diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/BehaviorBase.cc ./Behaviors/BehaviorBase.cc
--- ../Tekkotsu_2.4.1/Behaviors/BehaviorBase.cc	2005-07-07 18:33:51.000000000 -0400
+++ ./Behaviors/BehaviorBase.cc	2006-09-27 17:15:52.000000000 -0400
@@ -1,20 +1,18 @@
 #include "BehaviorBase.h"
 #include "Events/EventRouter.h"
 
-std::set<BehaviorBase*> BehaviorBase::registry;
-
 BehaviorBase::BehaviorBase(const std::string& name)
 	: ReferenceCounter(), EventListener(), started(false),
 	  instanceName(name), className(name)
 {
-	registry.insert(this);
+	getRegistryInstance().insert(this);
 }
 
 BehaviorBase::BehaviorBase(const std::string& classname, const std::string& instancename)
 	: ReferenceCounter(), EventListener(), started(false),
 	  instanceName(instancename), className(classname)
 {
-	registry.insert(this);
+	getRegistryInstance().insert(this);
 }
 
 
@@ -22,7 +20,7 @@
 	: ReferenceCounter(b), EventListener(b), started(b.started),
 	  instanceName(b.instanceName), className(b.className)
 {
-	registry.insert(this);
+	getRegistryInstance().insert(this);
 }
 
 BehaviorBase&
@@ -39,7 +37,7 @@
 	if(started)
 		std::cerr << "Behavior " << getName() << " deleted while running: use 'RemoveReference', not 'delete'" << std::endl;
 	erouter->removeListener(this);
-	registry.erase(this);
+	getRegistryInstance().erase(this);
 }
 
 void
@@ -56,12 +54,16 @@
 	//std::cout << getName() << " stopped " << this << std::endl;
 	if(started) {
 		started=false;
-		erouter->removeListener(this);
-		erouter->removeTimer(this);
+		erouter->remove(this);
 		RemoveReference();
 	}
 }
 
+std::set<BehaviorBase*>& BehaviorBase::getRegistryInstance() {
+	static std::set<BehaviorBase*> registry;
+	return registry;
+}
+
 /*! @file
  * @brief Implements BehaviorBase from which all Behaviors should inherit
  * @author ejt (Creator)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/BehaviorBase.h ./Behaviors/BehaviorBase.h
--- ../Tekkotsu_2.4.1/Behaviors/BehaviorBase.h	2005-04-23 14:32:59.000000000 -0400
+++ ./Behaviors/BehaviorBase.h	2006-10-03 18:09:40.000000000 -0400
@@ -8,19 +8,24 @@
 #include <set>
 
 //! The basis from which all other Behaviors should inherit
-/*! Makes use of ReferenceCounter so that behaviors can automatically delete themselves if
- *  wanted.
- *
- *  Make sure your own DoStart and DoStop call BehaviorBase::DoStart (or Stop) to allow
- *  the auto-deletion from reference counting... otherwise you'll get memory leaks if you
- *  rely on the reference counting.
+/*! 
+ *  For complex behaviors, it may be helpful to break aspects of the behaviors into independent 'states', and
+ *  use a state machine formalism to control them.  See StateNode and Transition for more information.
  *
- *  For an empty behavior boilerplate file to help you get started quickly, try
- *  <a href="http://cvs.tekkotsu.org/cgi-bin/viewcvs.cgi/Tekkotsu/project/templates/behavior.h?rev=HEAD&content-type=text/vnd.viewcvs-markup"><i>project</i><tt>/templates/behavior.h</tt></a>:
+ *  Quick-start boilerplate is included in the distribution: <a href="http://cvs.tekkotsu.org/cgi/viewcvs.cgi/Tekkotsu/project/templates/behavior.h?rev=HEAD&content-type=text/vnd.viewcvs-markup"><i>project</i><tt>/templates/behavior.h</tt></a>:
  * 
- *  But it would probably still be a good idea to go through the "<a
- *  href="../FirstBehavior.html">First Behavior</a>" tutorial to get a better idea of
- *  what's going on.
+ *  Tutorials:
+ *  - <a href="../FirstBehavior.html">Tekkotsu's "First Behavior" Tutorial</a>
+ *  - <a href="http://www.cs.cmu.edu/~dst/Tekkotsu/Tutorial/behaviors.shtml">David Touretzky's "Behaviors" 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>
+ *  
+ *  REMEMBER: If/when you override DoStart() / DoStop(), make sure that your own implementation calls BehaviorBase's implementation to allow
+ *  proper reference counting... otherwise you'll get memory leaks and other odd issues. (see boilerplate link above for example usage)
+ *
+ *  Also, if you instantiate a behavior on the stack instead of the heap (this is very rarely done), remember to call 
+ *  SetAutoDelete(false) (provided from the ReferenceCounter base class) -- don't want it to try to free memory
+ *  on the stack when the behavior is stopped!  (The stack limits the allocation of the behavior
+ *  to the current scope, which overrides the reference counting.)
  */
 class BehaviorBase : public ReferenceCounter, public EventListener {
 public:
@@ -74,9 +79,9 @@
 	//! Returns true if the behavior is currently running
 	virtual bool isActive() const { return started; }
 	
-	//! Allows read-only access to the set of currently instantiated behaviors
+	//! This read-only set allows us list all the currently instantiated behaviors
 	/*! Not all of these behaviors are necessarily active, this is everything that has been allocated and not yet deallocated */
-	static const std::set<BehaviorBase*>& getRegistry() { return registry; }
+	static const std::set<BehaviorBase*>& getRegistry() { return getRegistryInstance(); }
 
 	// Just some debugging stuff in stasis
 	/*	virtual void AddReference() {
@@ -91,6 +96,9 @@
 	*/
 	
 protected:
+	//! static function to provide well-defined initialization order
+	static std::set<BehaviorBase*>& getRegistryInstance();
+
 	//! constructor, @a name is used as both instance name and class name
 	explicit BehaviorBase(const std::string& name);
 	//! constructor, allows different initial values for class name and instance name
@@ -103,7 +111,6 @@
 	bool started; //!< true when the behavior is active
 	std::string instanceName; //!< holds the name of this instance of behavior
 	const std::string className; //!< holds the type of the subclass of this behavior as a string
-	static std::set<BehaviorBase*> registry; //!< allows us to keep track of all the current behaviors
 };
 
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controller.cc ./Behaviors/Controller.cc
--- ../Tekkotsu_2.4.1/Behaviors/Controller.cc	2005-06-01 01:47:44.000000000 -0400
+++ ./Behaviors/Controller.cc	2006-09-18 14:08:05.000000000 -0400
@@ -11,6 +11,9 @@
 #include "Shared/ERS220Info.h"
 #include "Shared/ERS7Info.h"
 #include "Shared/string_util.h"
+#ifndef PLATFORM_APERIOS
+#  include "local/sim/Simulator.h"
+#endif
 #include <sstream>
 
 Controller * Controller::theOneController=NULL;
@@ -28,11 +31,11 @@
 
 void Controller::DoStart() {
 	BehaviorBase::DoStart();
-	sndman->LoadFile(config->controller.select_snd);
-	sndman->LoadFile(config->controller.next_snd);
-	sndman->LoadFile(config->controller.prev_snd);
-	sndman->LoadFile(config->controller.read_snd);
-	sndman->LoadFile(config->controller.cancel_snd);
+	sndman->loadFile(config->controller.select_snd);
+	sndman->loadFile(config->controller.next_snd);
+	sndman->loadFile(config->controller.prev_snd);
+	sndman->loadFile(config->controller.read_snd);
+	sndman->loadFile(config->controller.cancel_snd);
 	erouter->addListener(this,EventBase::estopEGID);
 	// Turn on wireless
 	gui_comm=wireless->socket(SocketNS::SOCK_STREAM, 2048, 32000);
@@ -48,11 +51,11 @@
 }
 
 void Controller::DoStop() {
-	sndman->ReleaseFile(config->controller.select_snd);
-	sndman->ReleaseFile(config->controller.next_snd);
-	sndman->ReleaseFile(config->controller.prev_snd);
-	sndman->ReleaseFile(config->controller.read_snd);
-	sndman->ReleaseFile(config->controller.cancel_snd);
+	sndman->releaseFile(config->controller.select_snd);
+	sndman->releaseFile(config->controller.next_snd);
+	sndman->releaseFile(config->controller.prev_snd);
+	sndman->releaseFile(config->controller.read_snd);
+	sndman->releaseFile(config->controller.cancel_snd);
 	erouter->removeListener(this);
 	reset();
 	motman->removeMotion(display);
@@ -216,7 +219,7 @@
 
 	//pass a line at a time to the controller
 	while(s.size()>0) {
-		unsigned int endline=s.find('\n');
+		std::string::size_type endline=s.find('\n');
 		if(endline==std::string::npos) {
 			incomplete+=s;
 			return 0;
@@ -247,7 +250,7 @@
 
 	//pass a line at a time to the controller
 	while(s.size()>0) {
-		unsigned int endline=s.find('\n');
+		std::string::size_type endline=s.find('\n');
 		if(endline==std::string::npos) {
 			incomplete+=s;
 			return 0;
@@ -260,10 +263,18 @@
 			incomplete+=s.substr(0,endline);
 		
 		//is now complete
-		if(wireless->isConnected(theOneController->gui_comm->sock))
-			erouter->postEvent(new TextMsgEvent(incomplete));
-		else
-			theOneController->takeLine(incomplete); 
+		switch(config->main.consoleMode) {
+			case Config::main_config::CONTROLLER:
+				theOneController->takeLine(incomplete); break;
+			case Config::main_config::TEXTMSG:
+				erouter->postEvent(TextMsgEvent(incomplete,0)); break;
+			case Config::main_config::AUTO:
+				if(wireless->isConnected(theOneController->gui_comm->sock)) 	 
+					erouter->postEvent(TextMsgEvent(incomplete,0)); 	 
+				else
+					theOneController->takeLine(incomplete); 
+				break;
+		}
 		incomplete.erase();
 		s=s.substr(endline+1);
 	}
@@ -365,7 +376,7 @@
 			setNext(cmdstack.top()->doCancel());
 		} else if(args[0]=="!select") {
 		  if (args.size() == 1)
-			setNext(cmdstack.top()->doSelect());
+				setNext(cmdstack.top()->doSelect());
 		  else {
 		    select(root, args[1].c_str());
 		    refresh();
@@ -387,11 +398,66 @@
 				cmdstack.push(tmpstack.top());
 				tmpstack.pop();
 			}
+		} else if(args[0]=="!post") {
+			if(args.size()<4) {
+				serr->printf("Bad post command, need at least 3 arguments: generator source type [duration]\n");
+				return;
+			}
+			//parse generator id -- could be a generator name or a numeric value
+			int egid=0;
+			for(;egid<EventBase::numEGIDs && args[1]!=EventBase::EventGeneratorNames[egid];egid++) {}
+			if(egid==EventBase::numEGIDs) {
+				egid=atoi(args[1].c_str());
+				if(egid==0 && args[1]!="0") {
+					serr->printf("Bad event generator '%s'\n",args[1].c_str());
+					return;
+				}
+			}
+			//parse source id -- numeric value, unless egid is buttonEGID, in which case we can look up a button name
+			//(if you want to add support for other symbolic source types, this is where to do it)
+			unsigned int source;
+			if(egid==EventBase::buttonEGID) {
+				source=0;
+				for(;source<NumButtons && args[2]!=buttonNames[source];source++) {}
+				if(source==NumButtons) {
+					source=atoi(args[2].c_str());
+					if(source==0 && args[2]!="0") {
+						serr->printf("Invalid button name or index '%s'\n",args[2].c_str());
+						return;
+					}
+				}
+			} else {
+				source=atoi(args[2].c_str());
+			}
+			//parse type id -- numeric, name, or abbreviated name
+			int etid=0;
+			for(;etid<EventBase::numETIDs && args[3]!=EventBase::EventTypeNames[etid];etid++) {}
+			if(etid==EventBase::numETIDs) {
+				etid=0;
+				for(;etid<EventBase::numETIDs && args[3]!=EventBase::EventTypeAbbr[etid];etid++) {}
+				if(etid==EventBase::numETIDs) {
+					etid=atoi(args[3].c_str());
+					if(etid==0 && args[3]!="0") {
+						serr->printf("Bad event type '%s'\n",args[3].c_str());
+						return;
+					}
+				}
+			}
+			//duration field (optional, have to check args.size())
+			int dur=0;
+			if(args.size()>4)
+				dur=atoi(args[4].c_str());
+			//send event!
+			if(egid==EventBase::buttonEGID && isControlling)
+				erouter->removeTrapper(this);
+			erouter->postEvent((EventBase::EventGeneratorID_t)egid,source,(EventBase::EventTypeID_t)etid,dur);
+			if(egid==EventBase::buttonEGID && isControlling)
+				erouter->addTrapper(this,EventBase::buttonEGID);
 		} else if(args[0]=="!msg") {
 			if(offsets.size()>1)
-				erouter->postEvent(new TextMsgEvent(s.substr(offsets[1])));
+				erouter->postEvent(TextMsgEvent(s.substr(offsets[1]),0));
 			else
-				erouter->postEvent(new TextMsgEvent(""));
+				erouter->postEvent(TextMsgEvent("",0));
 		} else if(args[0]=="!hello") {
 			static unsigned int count=0;
 			count++;
@@ -417,8 +483,14 @@
 				}
 			refresh();
 		} else if(args[0]=="!set") {
-      setConfig(s.substr(offsets[1]).c_str());
-    } else
+			setConfig(s.substr(offsets[1]).c_str());
+		} else if(args[0]=="!sim") {
+#ifdef PLATFORM_APERIOS
+			serr->printf("!sim command invalid -- not running in simulator!\n");
+#else
+			Simulator::sendCommand(s.substr(offsets[1]));
+#endif
+		} else
 			setNext(cmdstack.top()->takeInput(s));
 	}
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controller.h ./Behaviors/Controller.h
--- ../Tekkotsu_2.4.1/Behaviors/Controller.h	2005-08-04 00:37:55.000000000 -0400
+++ ./Behaviors/Controller.h	2005-09-01 14:53:06.000000000 -0400
@@ -22,8 +22,9 @@
  *	- '<tt>!next</tt>' - calls ControlBase::doNextItem() of the current control
  *	- '<tt>!prev</tt>' - calls ControlBase::doPrevItem() of the current control
  *	- '<tt>!select</tt> [<i>item</i>]' - calls ControlBase::doSelect() of the current control, unless <i>item</i> is specified, in which case it is searched for, starting at the root.
- *	- '<tt>!cancel</tt>' - calls ControlBase::doCancel() of the current control
+ *	- '<tt>!cancel</tt>' - calls current ControlBase::doCancel(), indicates control should cease activity and return to parent (e.g. "Back" button)
  *	- '<tt>!dump_stack</tt>' - requests a dump of the current stack of submenus (useful if the GUI (re)connects and thus current robot state is unknown)
+ *  - '<tt>!post </tt><i>generator source type</i> [<i>duration</i>]' - posts an event of your choosing; <i>Generator</i> should be an entry in EventBase::EventGeneratorNames (e.g. timerEGID) or numeric value; <i>source</i> should be a numeric value (unless generator is buttonEGID, in which case it could be an entry from #buttonNames); <i>type</i> can be a numeric value, EventBase::EventTypeNames (e.g. <tt>activate</tt>), or EventBase::EventTypeAbbr (e.g. <tt>A</tt>); <i>duration</i>, if specified, gives the value for EventBase::duration
  *	- '<tt>!msg </tt><i>text</i>' - sends <i>text</i> out as a TextMsgEvent; also note that any text entered on the console port while a GUI is also connected will also be sent as a TextMsgEvent, without needing the !input.
  *  - '<tt>!root </tt><i>text</i>' - calls ControlBase::takeInput(<i>text</i>) on the root control
  *  - '<tt>!hello</tt>' - responds with '<tt>hello\\n</tt><i>count</i>\\n' where <i>count</i> is the number of times '<tt>!hello</tt>' has been sent.  Good for detecting first connection after boot vs. a reconnect.
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/BehaviorActivatorControl.h ./Behaviors/Controls/BehaviorActivatorControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/BehaviorActivatorControl.h	2003-09-25 11:26:10.000000000 -0400
+++ ./Behaviors/Controls/BehaviorActivatorControl.h	2006-09-16 02:28:06.000000000 -0400
@@ -8,7 +8,11 @@
 class BehaviorActivatorControl : public NullControl {
 public:
 	//! lets you tell it what action to perform
-	enum Mode_t { start, stop, toggle };
+	enum Mode_t {
+		start, //!< Passed to constructor, indicates this control should start the behavior when activated
+		stop,  //!< Passed to constructor, indicates this control should stop the behavior when activated
+		toggle //!< Passed to constructor, indicates this control should toggle the behavior when activated
+	};
 
 	//@{
 	//!constructors
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/BehaviorSwitchActivatorControl.h ./Behaviors/Controls/BehaviorSwitchActivatorControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/BehaviorSwitchActivatorControl.h	2003-09-25 11:26:10.000000000 -0400
+++ ./Behaviors/Controls/BehaviorSwitchActivatorControl.h	2006-09-16 02:28:06.000000000 -0400
@@ -9,7 +9,11 @@
 class BehaviorSwitchActivatorControl : public ControlBase {
 public:
 	//! lets you tell it what action to perform
-	enum Mode_t { start, stop, toggle };
+	enum Mode_t {
+		start, //!< Passed to constructor, indicates this control should start the behavior when activated
+		stop,  //!< Passed to constructor, indicates this control should stop the behavior when activated
+		toggle //!< Passed to constructor, indicates this control should toggle the behavior when activated
+	};
 
 	//!constructor
 	BehaviorSwitchActivatorControl(const std::string& n, BehaviorSwitchControlBase* bscb, Mode_t m=toggle) : ControlBase(n), behswitch(bscb), mode(m) {}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/BehaviorSwitchControl.h ./Behaviors/Controls/BehaviorSwitchControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/BehaviorSwitchControl.h	2005-06-29 18:02:58.000000000 -0400
+++ ./Behaviors/Controls/BehaviorSwitchControl.h	2006-09-01 14:21:20.000000000 -0400
@@ -7,6 +7,7 @@
 #include "Shared/ReferenceCounter.h"
 #include "Shared/Factory.h"
 #include "Shared/debuget.h"
+#include "Events/TextMsgEvent.h"
 
 //! Holds some utility classes and functions for BehaviorSwitchControl which shouldn't be stored in a templated class
 class BehaviorSwitchControlBase : public ControlBase {
@@ -20,9 +21,10 @@
 	 *  Pass NULL instead of one of these to get checkbox-style. */
 	class BehaviorGroup : public ReferenceCounter {
 	public:
-		BehaviorGroup() : curBehavior(NULL) { } //!< contructor
+		BehaviorGroup() : curBehavior(NULL), members() { } //!< contructor
 		~BehaviorGroup() { if(curBehavior!=NULL) curBehavior->DoStop(); } //!< destructor, will stop the current behavior if it was a one-shot
 		BehaviorBase * curBehavior; //!< pointer to current behavior
+		std::set<BehaviorSwitchControlBase*> members; //!< set of members of the group
 	private:
 		BehaviorGroup(const BehaviorGroup&); //!< shouldn't be called
 		BehaviorGroup operator=(const BehaviorGroup&); //!< shouldn't be called
@@ -31,17 +33,41 @@
 	//! constructor
 	BehaviorSwitchControlBase(const std::string& n, BehaviorBase* beh, BehaviorGroup* bg=NULL)
 		: ControlBase(n), behgrp(bg), mybeh(beh) {
-		if(behgrp!=NULL)
-			behgrp->AddReference();
-		if(mybeh!=NULL)
+		if(mybeh!=NULL) {
 			mybeh->AddReference();
+			mybeh->setName(n);
+			if(mybeh->isActive())
+				mybeh->AddReference();
+		}
+		if(behgrp!=NULL) {
+			behgrp->AddReference();
+			behgrp->members.insert(this);
+			if(mybeh!=NULL && mybeh->isActive()) {
+				if(behgrp->curBehavior!=NULL) {
+					behgrp->curBehavior->DoStop();
+					notifyGroupMembers();
+				}
+				behgrp->curBehavior=mybeh;
+			}
+		}
 	}
-	//! constructor
+	//! constructor, behavior must not be NULL
 	BehaviorSwitchControlBase(BehaviorBase* beh, BehaviorGroup* bg=NULL)
-		: ControlBase(), behgrp(bg), mybeh(beh) {
-		if(behgrp!=NULL)
-			behgrp->AddReference();
+		: ControlBase(beh->getName()), behgrp(bg), mybeh(beh) {
 		mybeh->AddReference();
+		if(mybeh->isActive())
+			mybeh->AddReference();
+		if(behgrp!=NULL) {
+			behgrp->AddReference();
+			behgrp->members.insert(this);
+			if(mybeh!=NULL && mybeh->isActive()) {
+				if(behgrp->curBehavior!=NULL) {
+					behgrp->curBehavior->DoStop();
+					notifyGroupMembers();
+				}
+				behgrp->curBehavior=mybeh;
+			}
+		}
 	}
 
 	//! destructor
@@ -50,6 +76,7 @@
 		if(mybeh!=NULL)
 			stop();
 		if(behgrp!=NULL) {
+			behgrp->members.erase(this);
 			behgrp->RemoveReference();
 			behgrp=NULL;
 		}
@@ -67,6 +94,15 @@
 	//! toggles the behavior
 	virtual BehaviorSwitchControlBase* toggle() { if(isRunning()) stopother(); else { stopother(); startmine(); } return this; }
 
+	virtual ControlBase * takeInput(const std::string& msg) {
+		if(options.size()>0)
+			return ControlBase::takeInput(msg);
+		if(!isRunning())
+			startmine();
+		mybeh->processEvent(TextMsgEvent(msg,1));
+		return NULL;
+	}
+	
 	//! tells the current behavior (if there is one) to stop then loads its own
 	/*! @return NULL unless there are submenus */
 	virtual ControlBase * activate(MotionManager::MC_ID display, Socket * gui) {
@@ -89,35 +125,46 @@
 		return "Class "+mybeh->getClassName()+": "+mybeh->getDescription();
 	}
 	
+	//! Returns true if the associated behavior is running
+	virtual bool isRunning() const {
+		if(mybeh==NULL) //not created or has been destroyed, definitely not running
+			return false;
+		// so, beh has been created (but may have been stopped by another in the group)
+		return mybeh->isActive(); //just check active flag (is valid object, we would have set it to NULL if we stopped it ourselves)
+	}
+	
 protected:
 	//! Stops the "other" guy's behavior - if ::behgrp is NULL, stops ourselves
 	virtual void stopother() {
 		if(behgrp==NULL) {
-			if(mybeh->isActive())
+			if(mybeh!=NULL && mybeh->isActive()) {
 				mybeh->DoStop();
+				behaviorStopped();
+			}
 		} else if(behgrp->curBehavior!=NULL) {
-			behgrp->curBehavior->DoStop();
+			if(behgrp->curBehavior->isActive()) {
+				behgrp->curBehavior->DoStop();
+				notifyGroupMembers();
+			}
 			behgrp->curBehavior=NULL;
 		}
 	}
-
+	
 	//! Starts our behavior
 	virtual void startmine() {
 		if(behgrp!=NULL)
 			behgrp->curBehavior=mybeh;
 		mybeh->DoStart();
 	}
-
-	//! Returns true if the associated behavior is running
-	virtual bool isRunning() const {
-		if(mybeh==NULL) //not created or has been destroyed, definitely not running
-			return false;
-		// so, beh has been created (but may have been stopped by another in the group)
-		if(behgrp==NULL) //no group
-			return mybeh->isActive(); //just check active flag (is valid object, we would have set it to NULL if we stopped it ourselves)
-		// so, we're in a group, someone else could have stopped us
-		return (behgrp->curBehavior==mybeh); //all we can see is if the current behavior is ours.  If it is, it'll be active
+	
+	//! updates other members in the group that the current behavior stopped -- do not call if behgrp is NULL
+	virtual void notifyGroupMembers() {
+		for(std::set<BehaviorSwitchControlBase*>::iterator it=behgrp->members.begin(); it!=behgrp->members.end(); ++it)
+			if((*it)->mybeh==behgrp->curBehavior)
+				(*it)->behaviorStopped();
 	}
+	//! called by notifyGroupMembers if #mybeh was destructed when stopped
+	virtual void behaviorStopped() {}
 
 	BehaviorGroup * behgrp; //!< the behavior group this belongs to.  Uses this to track the "current" behavior
 	BehaviorBase* mybeh; //!< used to store the behavior.  If retained and non-NULL, will be valid.  However, if not retained, only valid if equals behgrp->curBehavior
@@ -136,49 +183,34 @@
 public:
 	//! constructor, can use this to toggle a single behavior on and off
 	BehaviorSwitchControl(const std::string& n, bool retain=false)
-		: BehaviorSwitchControlBase(n,NULL,NULL), retained(retain)
+		: BehaviorSwitchControlBase(n,NULL,NULL), retained(retain), startref(NULL)
 	{}
 	//! constructor, if you want to use an already constructed behavior
 	BehaviorSwitchControl(B* beh, BehaviorGroup* bg=NULL)
-		: BehaviorSwitchControlBase(beh,bg), retained(true)
+		: BehaviorSwitchControlBase(beh,bg), retained(true), startref(NULL)
 	{}
 	//! constructor, if you want to use an already constructed behavior, but unretain it if it's stopped (if not retaining, will start @a beh if it's not already started)
 	BehaviorSwitchControl(const std::string& n, B* beh, BehaviorGroup* bg=NULL, bool retain=false)
-		: BehaviorSwitchControlBase(n,beh,bg), retained(retain)
+		: BehaviorSwitchControlBase(n,beh,bg), retained(retain), startref(NULL)
 	{
 		if(!retained) {
 			// have to make sure behavior is started to maintain invariants
 			if(!mybeh->isActive()) {
-				//keep reference from superclass's constructor in case mybeh stops itself right away
-				mybeh->DoStart();
-				bool stopped=!mybeh->isActive();
-				mybeh->RemoveReference(); //cancels reference from BehaviorSwitchControlBase's constructor
-				if(stopped)
-					mybeh=NULL;
-			} else
-				mybeh->RemoveReference(); //cancels reference from BehaviorSwitchControlBase's constructor
-		}
-		if(behgrp!=NULL) {
-			if(mybeh->isActive()) {
-				if(behgrp->curBehavior!=NULL)
-					behgrp->curBehavior->DoStop();
-				behgrp->curBehavior=mybeh;
-			} else if(!retained) {
-				if(behgrp->curBehavior!=NULL)
-					behgrp->curBehavior->DoStop();
-				behgrp->curBehavior=NULL;
+				startmine();
 			}
+			mybeh->RemoveReference(); //cancels reference from BehaviorSwitchControlBase's constructor
 		}
 	}
 	//! constructor, needs to know what group its in and whether to retain its behavior
 	BehaviorSwitchControl(const std::string& n, BehaviorGroup* bg, bool retain=false)
-		: BehaviorSwitchControlBase(n,NULL,bg), retained(retain)
+		: BehaviorSwitchControlBase(n,NULL,bg), retained(retain), startref(NULL)
 	{}
 	
 	//! destructor
 	virtual ~BehaviorSwitchControl() {
 		stop();
 		if(behgrp!=NULL) {
+			behgrp->members.erase(this);
 			behgrp->RemoveReference();
 			behgrp=NULL;
 		}
@@ -200,27 +232,8 @@
 			return BehaviorSwitchControlBase::getDescription();
 	}
 	
-
 protected:
 
-	virtual void stopother() {
-		if(behgrp==NULL) {
-			if(mybeh!=NULL) {
-				if(mybeh->isActive()) {
-					mybeh->DoStop();
-					if(!retained)
-						mybeh=NULL;
-				} else
-					ASSERT(retained,"null group, non-null not retained beh, not active, did you call inherited DoStart/DoStop in your Behavior?");
-			}
-		} else if(behgrp->curBehavior!=NULL) {
-			behgrp->curBehavior->DoStop();
-			if(behgrp->curBehavior==mybeh)
-				mybeh=NULL;
-			behgrp->curBehavior=NULL;
-		}
-	}
-
 	virtual void startmine() {
 		if(!retained) {
 			Al allocator;
@@ -238,17 +251,20 @@
 			if(behgrp!=NULL)
 				behgrp->curBehavior=mybeh;
 		}
-		mybeh->AddReference(); //temporary reference in case mybeh stops itself right away
+		startref=mybeh;
+		startref->AddReference();
 		mybeh->DoStart();
-		bool stopped=(!mybeh->isActive() && !retained);
-		mybeh->RemoveReference();
-		if(stopped) {
-			if(behgrp!=NULL && behgrp->curBehavior==mybeh)
-				behgrp->curBehavior=NULL;
-			mybeh=NULL;
-		}
 	}
 
+	//! adds a check to see if behavior has stopped itself -- if so, remove startref
+	virtual bool isRunning() const {
+		if(BehaviorSwitchControlBase::isRunning())
+			return true;
+		else if(startref!=NULL)
+			const_cast<BehaviorSwitchControl<B,Al>*>(this)->stopother();
+		return false;
+	}		
+	
 	//! Returns true if mybeh is pointing to a valid object
 	virtual bool isValid() const {
 		if(isRunning())
@@ -256,8 +272,19 @@
 		return retained;
 	}
 
-private:
+	virtual void behaviorStopped() {
+		if(!retained)
+			mybeh=NULL;
+		if(startref!=NULL) {
+			startref->RemoveReference();
+			startref=NULL;
+		}
+	}
+	
 	bool retained; //!< true if the behavior should be generated once and retained after DoStop.  Otherwise, a new one is generated each time it is started
+	BehaviorBase * startref; //!< true if a reference was added (and still current) from calling DoStart
+	
+private:
 	BehaviorSwitchControl(const BehaviorSwitchControl&); //!< shouldn't call this
 	BehaviorSwitchControl operator=(const BehaviorSwitchControl&); //!<shouldn't call this
 };
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/ControlBase.cc ./Behaviors/Controls/ControlBase.cc
--- ../Tekkotsu_2.4.1/Behaviors/Controls/ControlBase.cc	2005-06-01 01:47:44.000000000 -0400
+++ ./Behaviors/Controls/ControlBase.cc	2006-09-18 14:07:54.000000000 -0400
@@ -105,7 +105,7 @@
 	//		cout << "ControlBase::doSelect()" << endl;
 	//		cout << "cur==" << cur << endl;
 	if(hilights.size()==0) {
-		sndman->PlayFile(config->controller.select_snd);
+		sndman->playFile(config->controller.select_snd);
 		return this;
 	}
 	for(unsigned int i=0;i<hilights.size();i++) {
@@ -131,7 +131,7 @@
 				clearMenu();
 			doRewrite=false;
 		}
-		sndman->PlayFile(config->controller.select_snd);
+		sndman->playFile(config->controller.select_snd);
 		if(hilights.size()>1) {
 			options[cur]->activate(display_id,gui_comm);
 			options[cur]->deactivate();
@@ -154,7 +154,7 @@
 		cur=(cur+1)%options.size();
 	hilights.clear();
 	hilights.push_back(cur);
-	sndman->PlayFile(config->controller.next_snd);
+	sndman->playFile(config->controller.next_snd);
 	refresh();
 	//		cout << "cur==" << cur << endl;
 	return this;
@@ -172,14 +172,14 @@
 		cur=(cur+options.size()-1)%options.size();
 	hilights.clear();
 	hilights.push_back(cur);
-	sndman->PlayFile(config->controller.prev_snd);
+	sndman->playFile(config->controller.prev_snd);
 	refresh();
 	//		cout << "cur==" << cur << endl;
 	return this;
 }
 
 ControlBase * ControlBase::doCancel() {
-	sndman->PlayFile(config->controller.cancel_snd);
+	sndman->playFile(config->controller.cancel_snd);
 	return NULL;
 }
 
@@ -190,7 +190,7 @@
 		MMAccessor<LedMC> display(display_id);
 		display.mc()->cset(FaceLEDMask,.5);
 	}
-	sndman->PlayFile(config->controller.read_snd);
+	sndman->playFile(config->controller.read_snd);
 
 	//Just do one of the other two
 	if(gui_comm==NULL || !wireless->isConnected(gui_comm->sock)) {
@@ -373,9 +373,9 @@
 	float newavg=hilightsAvg();
 	if(avg!=-1 || newavg!=-1) {
 		if(avg<=newavg)
-			sndman->PlayFile(config->controller.next_snd);
+			sndman->playFile(config->controller.next_snd);
 		else
-			sndman->PlayFile(config->controller.prev_snd);
+			sndman->playFile(config->controller.prev_snd);
 	}
 	refresh();
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/EventLogger.cc ./Behaviors/Controls/EventLogger.cc
--- ../Tekkotsu_2.4.1/Behaviors/Controls/EventLogger.cc	2005-08-07 00:11:03.000000000 -0400
+++ ./Behaviors/Controls/EventLogger.cc	2006-09-18 14:07:54.000000000 -0400
@@ -8,7 +8,9 @@
 #include <sstream>
 #include "Sound/SoundManager.h"
 #include "Vision/FilterBankGenerator.h"
+#include "Vision/JPEGGenerator.h"
 #include "Shared/Base64.h"
+#include "Behaviors/StateNode.h"
 
 #include <libxml/xmlmemory.h>
 #include <libxml/parser.h>
@@ -16,8 +18,13 @@
 Socket* EventLogger::logSocket=NULL;
 unsigned int EventLogger::logSocketRefCount=0;
 int EventLogger::port=10080;
+EventLogger * EventLogger::theOne=NULL;
 
-EventLogger::EventLogger() : ControlBase("Event Logger","Allows you to see/log all of the un-trapped events as they are generated"), logfilePath(), logfile(), verbosity(0) {
+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() {
 	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));
@@ -27,21 +34,28 @@
 	pushSlot(new ControlBase("[X] Console Output","If selected, outputs events to the console"));
 	pushSlot(new StringInputControl("[ ] File Output","Please enter the filename to log to (in /ms/...)"));
 	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);
 		wireless->setDaemon(logSocket);
+		wireless->setReceiver(logSocket, callback);
 		wireless->listen(logSocket,port);
 	}
 	logSocketRefCount++;
 }
 
 EventLogger::~EventLogger() {
+	expected.clear();
+	while(!queuedEvents.empty())
+		queuedEvents.pop();
 	clearSlots();
 	if(--logSocketRefCount==0) {
 		wireless->setDaemon(logSocket,false);
 		wireless->close(logSocket);
 		logSocket=NULL;
 	}
+	if(theOne==this)
+		theOne=NULL;
 }
 
 ControlBase* EventLogger::doSelect() {
@@ -72,7 +86,7 @@
 				ans=options[cur];
 			}
 		}
-		sndman->PlayFile(config->controller.select_snd);
+		sndman->playFile(config->controller.select_snd);
 	}
 	if(ans==this)
 		refresh();
@@ -94,7 +108,7 @@
 		xmlNode * cur = xmlNewNode(NULL,(const xmlChar*)"");
 		xmlSetProp(cur,(const xmlChar*)"type",(const xmlChar*)"log");
 		xmlNode * desc = xmlNewNode(NULL,(const xmlChar*)"param");
-		event.SaveXML(cur);
+		event.saveXML(cur);
 		xmlAddChild(cur,desc);
 		xmlSetProp(desc,(const xmlChar*)"name",(const xmlChar*)"description");
 		xmlSetProp(desc,(const xmlChar*)"value",(const xmlChar*)event.getDescription(true,3).c_str());
@@ -116,21 +130,31 @@
 
 void EventLogger::logImage(FilterBankGenerator& fbg, unsigned int layer, unsigned int channel, const BehaviorBase* source/*=NULL*/) {
 	if(logSocket!=NULL && wireless->isConnected(logSocket->sock)) {
-		fbg.selectSaveImage(layer,channel);
-		unsigned int len=fbg.getBinSize();
-		char * binbuf=new char[len];
-		fbg.SaveBuffer(binbuf,len);
+
+		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());
-		snprintf(binbuf,len,"%d",get_time());
-		xmlSetProp(cur,(const xmlChar*)"time",(const xmlChar*)binbuf);
-		delete [] binbuf;
-		xmlNodeSetContent(cur,(const xmlChar*)b64buf.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);
@@ -230,6 +254,216 @@
 	}
 }
 
+
+void EventLogger::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);
+		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());
+
+		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);
+			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());
+			}
+			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());
+			}
+			indent(depth+1);
+			logSocket->printf("</transition>\n");
+		}
+
+		indent(depth);
+		logSocket->printf("</state>\n");
+	}
+}
+	
+bool EventLogger::isListening(const StateNode* n) {
+	while(n!=NULL) {
+		if(listen.find(n->getName())!=listen.end())
+			return true;
+		n=n->getParent();
+	}
+	return false;
+}
+
+void EventLogger::indent(unsigned int level) {
+	for(unsigned int i=0; i<level; i++)
+		logSocket->printf("  ");
+}
+
+const StateNode * EventLogger::find(const std::string& sname) {
+	const registry_t& registry=BehaviorBase::getRegistry();
+	for(registry_t::const_iterator it=registry.begin(); it!=registry.end(); it++) {
+		const StateNode * cur=dynamic_cast<const StateNode*>(*it);
+		if(cur!=NULL && cur->getName()==sname)
+			return cur;
+	}
+	//serr->printf("WARNING: EventLogger Could not find StateNode named `%s'\n",sname.c_str());
+	return NULL;
+}
+
+void EventLogger::runCommand(const std::string& s) {
+	if(s==std::string("list")) {
+		const registry_t& registry=BehaviorBase::getRegistry();
+		unsigned int numstate=0;
+		for(registry_t::const_iterator it=registry.begin(); it!=registry.end(); it++) {
+			const StateNode * cur=dynamic_cast<const StateNode*>(*it);
+			if(cur!=NULL)
+				numstate++;
+		}
+		logSocket->printf("%d\n",numstate);
+		for(registry_t::const_iterator it=registry.begin(); it!=registry.end(); it++) {
+			const StateNode * cur=dynamic_cast<const StateNode*>(*it);
+			if(cur!=NULL)
+				logSocket->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: EventLogger could not find \"%s\" for spidering\n",s.substr(7).c_str());
+			logSocket->printf("<model></model>\n");
+		} else {
+			logSocket->printf("<model>\n");
+			spider(n);
+			logSocket->printf("</model>\n");
+		}
+
+	} else if(s.find("listen ")==0) {
+		if(listen.size()==0) {
+			erouter->addListener(&smProcess,EventBase::stateMachineEGID);
+			erouter->addListener(&smProcess,EventBase::stateTransitionEGID);
+		}
+		listen.insert(s.substr(7));
+
+	} else if(s.find("ignore ")==0) {
+		listen.erase(s.substr(7));
+		if(listen.size()==0)
+			erouter->removeListener(&smProcess);
+
+	} else if(s=="clear") {
+		listen.clear();
+		erouter->removeListener(&smProcess);
+
+	} else {
+		serr->printf("EventLogger::runCommand() - bad message: '%s'\n",s.c_str());
+	}
+}
+
+// The command packet reassembly mechanism
+int EventLogger::callback(char *buf, int bytes) {
+	if(EventLogger::theOne==NULL)
+		return 0;
+	static std::string cmd;
+	for(int i=0; i<bytes; i++) {
+		if(buf[i]=='\n') {
+			EventLogger::theOne->runCommand(cmd);
+			cmd.clear();
+		} else if(buf[i]!='\r')
+			cmd+=buf[i];
+	}
+  return 0;
+}
+
+void EventLogger::processStateMachineEvent(const EventBase& event) {
+	if(!wireless->isConnected(logSocket->sock) || listen.size()==0)
+		return;
+
+	if(event.getGeneratorID()==EventBase::stateTransitionEGID) {
+		bool care=false;
+		const Transition * trans = reinterpret_cast<Transition*>(event.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(event);
+		} 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);
+			}
+		}
+
+	} else if(event.getGeneratorID()==EventBase::stateMachineEGID) {
+		if(event.getTypeID()==EventBase::statusETID)
+			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);
+				}
+			}
+		}
+
+	} else {
+		serr->printf("WARNING: Unknown event %s (%s)\n",event.getName().c_str(),event.getDescription().c_str());
+	}
+}
+
+
+
+
+
 /*! @file
  * @brief Describes EventLogger, which allows logging of events to the console or a file
  * @author ejt (Creator)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/EventLogger.h ./Behaviors/Controls/EventLogger.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/EventLogger.h	2005-06-01 01:47:44.000000000 -0400
+++ ./Behaviors/Controls/EventLogger.h	2006-09-16 02:28:06.000000000 -0400
@@ -5,15 +5,19 @@
 #include "ControlBase.h"
 #include "Events/EventListener.h"
 #include <fstream>
+#include <set>
+#include <queue>
 
 class FilterBankGenerator;
 class BehaviorBase;
+class StateNode;
 
 //! allows logging of events to the console or a file
 class EventLogger : public ControlBase, public EventListener {
 public:
 	//!constructor
 	EventLogger();
+	//!destructor
 	virtual ~EventLogger();
 
 	//!opens a custom (embedded) menu to toggle individual EGIDs
@@ -42,7 +46,21 @@
 	//! request that the desktop side take a picture with the webcam (if available)
 	static void logWebcam(const BehaviorBase* source=NULL);
 	
+	static int callback(char *buf, int bytes); //!< called by wireless when there's new data
+
 protected:
+	static EventLogger * theOne; //!< the instance which will handle network communication
+
+	//! a separate processEvent to distinguish between events requested for logging and events requested by a remote monitor
+	class StateMachineListener : public EventListener {
+		//! forwards any events received to EventLogger::theOne's EventLogger::processStateMachineEvent()
+		/*! EventLogger::runCommand() is responsible for maintaining which events this is listening to */
+		virtual void processEvent(const EventBase& event) {
+			EventLogger::theOne->processStateMachineEvent(event);
+		}
+	};
+	static class StateMachineListener smProcess; //!< handles state machine transitions if the Storyboard GUI (or other remote monitor) is listening for state machine events
+
 	virtual void clearSlots();
 
 	//!sets the status char of slot @a i to @a c
@@ -51,6 +69,26 @@
 	//!checks to see if logfilePath differs from the StringInputControl's value and switches it if it is
 	void checkLogFile();
 	
+	//! 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);
+
+	//! parses commands sent from callback()
+	void runCommand(const std::string& s);
+
+	//!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);
+
+	//!if there is a remote monitor listening for state machine transitions, this will send them over
+	/*!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);
+
 	//!address of the logfile, if any (empty string is no logfile)
 	std::string logfilePath;
 
@@ -68,6 +106,17 @@
 	
 	//!controls the level of verbosity - currently 0 through 2
 	unsigned int verbosity;
+
+	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
 };
 
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/FreeMemReportControl.cc ./Behaviors/Controls/FreeMemReportControl.cc
--- ../Tekkotsu_2.4.1/Behaviors/Controls/FreeMemReportControl.cc	2005-02-05 02:27:26.000000000 -0500
+++ ./Behaviors/Controls/FreeMemReportControl.cc	2006-09-25 19:26:56.000000000 -0400
@@ -37,7 +37,8 @@
 //! reports size of free memory - if this is below low_mem, also generates a warning
 void FreeMemReportControl::report() {
 	size_t freemem=freeMem();
-	sout->printf("%lu bytes free\n",(unsigned long)freemem);
+	sout->printf("%lu bytes free (%+ld)\n",(unsigned long)freemem,(long)(freemem-lastReport));
+	lastReport=freemem;
 	if(freemem<low_mem)
 		if(isWarning)
 			serr->printf("WARNING: Low memory: %lu\n",(unsigned long)freemem);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/FreeMemReportControl.h ./Behaviors/Controls/FreeMemReportControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/FreeMemReportControl.h	2004-11-10 20:45:35.000000000 -0500
+++ ./Behaviors/Controls/FreeMemReportControl.h	2006-09-25 19:26:56.000000000 -0400
@@ -13,9 +13,9 @@
 public:
 	//!@name Contructors/Destructors
 	//!contructor
-	FreeMemReportControl() : BehaviorBase("FreeMemReportControl"), ControlBase("Free Memory Report","Reports size of free memory, and monitors for low memory warning"), report_freq(-1U), low_mem(256), monitor_freq(1000), isWarning(false) {init();}
-	FreeMemReportControl(const std::string& n) : BehaviorBase("FreeMemReportControl"), ControlBase(n,"Reports size of free memory, and monitors for low memory warning"), report_freq(-1U), low_mem(256), monitor_freq(1000),isWarning(false) {init();}
-	FreeMemReportControl(const std::string& n, const std::string& d) : BehaviorBase("FreeMemReportControl"), ControlBase(n,d), report_freq(-1U), low_mem(256), monitor_freq(1000),isWarning(false) {init();}
+	FreeMemReportControl() : BehaviorBase("FreeMemReportControl"), ControlBase("Free Memory Report","Reports size of free memory, and monitors for low memory warning"), report_freq(-1U), low_mem(256), monitor_freq(1000), isWarning(false), lastReport() {init();}
+	FreeMemReportControl(const std::string& n) : BehaviorBase("FreeMemReportControl"), ControlBase(n,"Reports size of free memory, and monitors for low memory warning"), report_freq(-1U), low_mem(256), monitor_freq(1000),isWarning(false), lastReport() {init();}
+	FreeMemReportControl(const std::string& n, const std::string& d) : BehaviorBase("FreeMemReportControl"), ControlBase(n,d), report_freq(-1U), low_mem(256), monitor_freq(1000),isWarning(false), lastReport() {init();}
 	virtual ~FreeMemReportControl() { SetAutoDelete(false); DoStop(); clearSlots(); } //!< destructor
 	//@}
 
@@ -53,12 +53,14 @@
 		pushSlot(new ValueEditControl<int>("Report Frequency","Controls how often to generate free memory reports (in milliseconds)","Please enter milliseconds to wait between reports (-1 to stop)",&report_freq));
 		pushSlot(new ValueEditControl<unsigned int>("Low Memory Threshold","Controls when to start warning about low memory (in KB)","Please enter the new low memory warning threshold (in KB)",&low_mem));
 		pushSlot(new ValueEditControl<unsigned int>("Monitor Frequency","Controls how often to check for low memory (in milliseconds)","Please enter milliseconds to wait between low memory checks (-1 to stop)",&monitor_freq));
+		lastReport=freeMem();
 	}
 
 	int report_freq;  //!< how often to report memory size (in milliseconds - negative turns off, 0 is as often as possible)
 	unsigned int low_mem;      //!< threshold to trigger low memory warning (in kilobytes)
 	unsigned int monitor_freq; //!< how often to check for low memory (in milliseconds - -1U turns off, 0 is as often as possible)
 	bool isWarning;            //!< true we already know we're below threshold
+	size_t lastReport; //!< free memory at last report so we can report the difference
 };
 
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/LoadPostureControl.h ./Behaviors/Controls/LoadPostureControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/LoadPostureControl.h	2005-06-06 19:05:51.000000000 -0400
+++ ./Behaviors/Controls/LoadPostureControl.h	2006-09-18 14:07:54.000000000 -0400
@@ -23,6 +23,7 @@
 		setFilter("*.pos");
 	}
 	
+	//! destructor
 	virtual ~LoadPostureControl() {
 		erouter->removeListener(this);
 		motman->removeMotion(ledid);
@@ -53,7 +54,7 @@
 			runFile();
 		} else {
 			//we have to wait for the estop to be turned off
-			sndman->PlayFile("donkey.wav");
+			sndman->playFile("donkey.wav");
 			SharedObject<LedMC> led;
 			led->cset(FaceLEDMask,0);
 			led->cycle(BotLLEDMask,1000,3,0,0);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/LoadWalkControl.h ./Behaviors/Controls/LoadWalkControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/LoadWalkControl.h	2005-06-06 19:05:51.000000000 -0400
+++ ./Behaviors/Controls/LoadWalkControl.h	2006-09-09 00:32:17.000000000 -0400
@@ -37,8 +37,9 @@
 		if(walk==NULL)
 			serr->printf("Invalid walk for loading\n");
 		else {
-			walk->LoadFile(f.c_str());
-			motman->checkinMotion(id);
+			walk->loadFile(f.c_str());
+			if(id!=MotionManager::invalid_MC_ID)
+				motman->checkinMotion(id);
 		}
 		return NULL;
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/NetworkStatusControl.h ./Behaviors/Controls/NetworkStatusControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/NetworkStatusControl.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Behaviors/Controls/NetworkStatusControl.h	2005-10-25 17:25:33.000000000 -0400
@@ -43,11 +43,11 @@
 			pushSlot(new NullControl(tmp));
 			snprintf(tmp,TMP_SIZE,"noise: %d",msg.statistics.noise);
 			pushSlot(new NullControl(tmp));
-			snprintf(tmp,TMP_SIZE,"invalidIDCount: %d",msg.statistics.invalidIDCount);
+			snprintf(tmp,TMP_SIZE,"invalidIDCount: %u",(unsigned int)msg.statistics.invalidIDCount);
 			pushSlot(new NullControl(tmp));
-			snprintf(tmp,TMP_SIZE,"invalidEncCount: %d",msg.statistics.invalidEncCount);
+			snprintf(tmp,TMP_SIZE,"invalidEncCount: %u",(unsigned int)msg.statistics.invalidEncCount);
 			pushSlot(new NullControl(tmp));
-			snprintf(tmp,TMP_SIZE,"invalidMiscCount: %d",msg.statistics.invalidMiscCount);
+			snprintf(tmp,TMP_SIZE,"invalidMiscCount: %u",(unsigned int)msg.statistics.invalidMiscCount);
 			pushSlot(new NullControl(tmp));
 			MMAccessor<LedMC> leds_acc(display_id);
 			leds_acc->displayPercent(msg.statistics.signal/100.0,LedEngine::major,LedEngine::major);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/PlaySoundControl.h ./Behaviors/Controls/PlaySoundControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/PlaySoundControl.h	2005-06-06 19:05:51.000000000 -0400
+++ ./Behaviors/Controls/PlaySoundControl.h	2006-09-18 14:07:54.000000000 -0400
@@ -20,9 +20,9 @@
 protected:
 	//!does the actual loading of the MotionSequence
 	virtual ControlBase* selectedFile(const std::string& f) {
-		sndman->StopPlay();
+		sndman->stopPlay();
 		if(sndman)
-			sndman->PlayFile(f.c_str());
+			sndman->playFile(f.c_str());
 		return this;
 	}
 };
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/PostureEditor.cc ./Behaviors/Controls/PostureEditor.cc
--- ../Tekkotsu_2.4.1/Behaviors/Controls/PostureEditor.cc	2005-08-02 18:24:20.000000000 -0400
+++ ./Behaviors/Controls/PostureEditor.cc	2006-09-09 00:32:18.000000000 -0400
@@ -64,13 +64,14 @@
 PostureEditor::refresh() {
 	//cout << "refresh" << endl;
 	if(isEStopped()) {
+		processEvent(EventBase(EventBase::timerEGID,1,EventBase::statusETID,0));
 		erouter->addTimer(this,0,500);
 		options[0]=disabledLoadPose;
 	} else {
 		options[0]=loadPose;
 	}
 	if(loadPose->getLastInput().size()>0) {
-		pose.LoadFile(loadPose->getLastInput().c_str());
+		pose.loadFile(loadPose->getLastInput().c_str());
 		updatePose(moveTime);
 		loadPose->clearLastInput();
 	} else if(savePose->getLastInput().size()>0) {
@@ -78,7 +79,7 @@
 		std::string filename=savePose->getLastInput();
 		if(filename.find(".")==std::string::npos)
 			filename+=".pos";
-		pose.SaveFile(config->motion.makePath(filename).c_str());
+		pose.saveFile(config->motion.makePath(filename).c_str());
 		savePose->takeInput("");
 	} else {
 		updatePose(moveTime/2);
@@ -128,7 +129,8 @@
 			pose(i).value=state->outputs[i];
 		for(unsigned int i=LEDOffset+NumLEDs; i<NumOutputs; i++)
 			pose(i).value=state->outputs[i];
-		refresh();
+		if(e.getSourceID()==0) // source==1 indicates it's a forged event sent from refresh -- don't inf. recurse
+			refresh();
 	} else {
 		serr->printf("WARNING: PostureEditor unexpected event: %s\n",e.getName().c_str());
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/ProfilerCheckControl.h ./Behaviors/Controls/ProfilerCheckControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/ProfilerCheckControl.h	2004-11-11 15:34:59.000000000 -0500
+++ ./Behaviors/Controls/ProfilerCheckControl.h	2006-07-13 13:25:50.000000000 -0400
@@ -3,7 +3,7 @@
 #define INCLUDED_ProfilerCheckControl_h_
 
 #include "ControlBase.h"
-#include "Shared/WorldState.h"
+#include "Shared/Profiler.h"
 
 //! causes the WorldState::mainProfile and WorldState::motionProfile to display reports to #sout
 class ProfilerCheckControl : public ControlBase {
@@ -13,8 +13,9 @@
 
 	//! Prints a report to sout
 	virtual ControlBase * activate(MotionManager::MC_ID, Socket *) {
-		sout->printf("~~~ Main: ~~~\n%s",state->mainProfile.report().c_str());
-		sout->printf("~~~ Motion: ~~~\n%s",state->motionProfile.report().c_str());
+		sout->printf("~~~ Main: ~~~\n%s\n",mainProfiler==NULL?"Main profile unavailable":mainProfiler->report().c_str());
+		sout->printf("~~~ Motion: ~~~\n%s\n",motionProfiler==NULL?"Motion profile unavailable":motionProfiler->report().c_str());
+		sout->printf("~~~ Sound: ~~~\n%s\n",soundProfiler==NULL?"Sound profile unavailable":soundProfiler->report().c_str());
 		return NULL;
 	}
 };
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/RunSequenceControl.h ./Behaviors/Controls/RunSequenceControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/RunSequenceControl.h	2005-06-06 19:05:51.000000000 -0400
+++ ./Behaviors/Controls/RunSequenceControl.h	2006-09-18 14:07:54.000000000 -0400
@@ -34,6 +34,7 @@
 		setFilter("*.mot");
 	}
 
+	//! destructor
 	virtual ~RunSequenceControl() {
 		erouter->removeListener(this);
 		motman->removeMotion(ledid);
@@ -63,7 +64,7 @@
 			runFile();
 		} else {
 			//we have to wait for the estop to be turned off
-			sndman->PlayFile("donkey.wav");
+			sndman->playFile("donkey.wav");
 			SharedObject<LedMC> led;
 			led->cset(FaceLEDMask,0);
 			led->cycle(BotLLEDMask,1000,3,0,0);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/SavePostureControl.h ./Behaviors/Controls/SavePostureControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/SavePostureControl.h	2005-06-01 01:47:45.000000000 -0400
+++ ./Behaviors/Controls/SavePostureControl.h	2006-09-09 00:32:18.000000000 -0400
@@ -22,7 +22,7 @@
 			PostureEngine post;
 			post.takeSnapshot();
 			post.setWeights(1);
-			post.SaveFile(filename.c_str());
+			post.saveFile(filename.c_str());
 		}
 		return StringInputControl::takeInput(msg);
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/SaveWalkControl.h ./Behaviors/Controls/SaveWalkControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/SaveWalkControl.h	2005-06-01 01:47:45.000000000 -0400
+++ ./Behaviors/Controls/SaveWalkControl.h	2006-09-09 00:32:18.000000000 -0400
@@ -28,8 +28,9 @@
 			if(walk==NULL)
 				serr->printf("Invalid walk for saving\n");
 			else {
-				walk->SaveFile(filename.c_str());
-				motman->checkinMotion(id);
+				walk->saveFile(filename.c_str());
+				if(id!=MotionManager::invalid_MC_ID)
+					motman->checkinMotion(id);
 			}
 		}
 		return StringInputControl::takeInput(msg);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/SensorObserverControl.cc ./Behaviors/Controls/SensorObserverControl.cc
--- ../Tekkotsu_2.4.1/Behaviors/Controls/SensorObserverControl.cc	2005-06-01 01:47:45.000000000 -0400
+++ ./Behaviors/Controls/SensorObserverControl.cc	2006-10-02 18:11:38.000000000 -0400
@@ -62,7 +62,7 @@
 			ans=options[cur];
 		}
 	}
-	sndman->PlayFile(config->controller.select_snd);
+	sndman->playFile(config->controller.select_snd);
 	if(wasListening!=(numListeners>0)) {
 		if(numListeners>0)
 			erouter->addListener(this,EventBase::sensorEGID,SensorSourceID::UpdatedSID);
@@ -191,11 +191,11 @@
 	ControlBase::refresh();
 }
 void SensorObserverControl::RTViewControl::pause() {
-	erouter->removeListener(this);
+	erouter->removeTimer(this);
 	ControlBase::pause();
 }
 void SensorObserverControl::RTViewControl::deactivate() {
-	erouter->removeListener(this);
+	erouter->removeTimer(this);
 	ControlBase::deactivate();
 }
 /*! The change doesn't get picked up until next call to refresh() */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/ShutdownControl.cc ./Behaviors/Controls/ShutdownControl.cc
--- ../Tekkotsu_2.4.1/Behaviors/Controls/ShutdownControl.cc	2005-02-02 13:20:27.000000000 -0500
+++ ./Behaviors/Controls/ShutdownControl.cc	2005-08-31 17:55:12.000000000 -0400
@@ -1,12 +1,17 @@
 #include "ShutdownControl.h"
 #ifdef PLATFORM_APERIOS
 #  include <OPENR/OPENRAPI.h>
+#else
+#  include "local/sim/SharedGlobals.h"
 #endif
 
 ControlBase * ShutdownControl::doSelect()    {
 #ifdef PLATFORM_APERIOS
 	OBootCondition bc(0);
 	OPENR::Shutdown(bc);
+#else
+	if(globals!=NULL)
+		globals->signalShutdown();
 #endif
 	return NULL;
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/SimulatorAdvanceFrameControl.h ./Behaviors/Controls/SimulatorAdvanceFrameControl.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/SimulatorAdvanceFrameControl.h	2005-06-23 18:37:28.000000000 -0400
+++ ./Behaviors/Controls/SimulatorAdvanceFrameControl.h	2006-08-30 10:26:44.000000000 -0400
@@ -6,7 +6,7 @@
 #ifdef PLATFORM_APERIOS
 #  warning SimulatorAdvanceFrameControl is only useful when running in simulation!
 #else
-#  include "local/sim/Main.h"
+#  include "local/sim/Simulator.h"
 #endif
 
 //! Requests the next camera frame and sensor data, for use when running in simulation
@@ -32,23 +32,25 @@
 #ifndef PLATFORM_APERIOS
 
 	virtual ControlBase * activate(MotionManager::MC_ID disp_id, Socket * gui) {
-		Main::advanceVision();
-		Main::advanceSensor();
+		Simulator::sendCommand("advance");
 		return NullControl::activate(disp_id,gui);
 	}
 
 	virtual std::string getName() const {
-		if(Main::canManuallyAdvance())
+		if(canManuallyAdvance())
 			return NullControl::getName();
 		return "[Auto-Advancing]";
 	}
 
 	virtual std::string getDescription() const {
-		if(Main::canManuallyAdvance())
+		if(canManuallyAdvance())
 			return NullControl::getDescription();
 		return "Cannot manually advance when in realtime mode, or when AdvanceOnAccess is enabled";
 	}
 	
+protected:
+	bool canManuallyAdvance() const { return true; }
+	
 #endif
 
 };
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/WalkCalibration.cc ./Behaviors/Controls/WalkCalibration.cc
--- ../Tekkotsu_2.4.1/Behaviors/Controls/WalkCalibration.cc	2005-06-01 01:47:45.000000000 -0400
+++ ./Behaviors/Controls/WalkCalibration.cc	2006-09-18 14:07:54.000000000 -0400
@@ -220,12 +220,12 @@
 		if(hilights.size()==0)
 			return this;
 		if(options[hilights.front()]==measure) {
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			setupChoose();
 			refresh();
 			return this;
 		} else if(options[hilights.front()]==clear) {
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			setupClear();
 			refresh();
 			return this;
@@ -235,10 +235,10 @@
 	} else if(st==CLEAR) {
 		if(hilights.size()==0)
 			return this;
-		sndman->PlayFile(config->controller.select_snd);
+		sndman->playFile(config->controller.select_snd);
 		if(hilights.front()!=0) {
 			sout->printf("Clearing data...\n");
-			sndman->PlayFile(config->controller.cancel_snd);
+			sndman->playFile(config->controller.cancel_snd);
 			for(int i=0; i<NUM_SRC; i++) {
 				clearData(data[i]);
 				cnts[i]=0;
@@ -252,18 +252,18 @@
 			return this;
 		if(hilights.front()-2<NUM_SRC) {
 			curType=static_cast<dataSource>(hilights.front()-2);
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			setupReady();
 			refresh();
 			return this;
 		}
-		sndman->PlayFile(config->controller.cancel_snd);
+		sndman->playFile(config->controller.cancel_snd);
 		setupRoot();
 		refresh();
 		return this;
 	} else if(st==READY) {
 		if(hilights.size()==0 || options[hilights.front()]->getName()=="Go!") {
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			setupMoving();
 			refresh();
 			return this;
@@ -271,12 +271,12 @@
 		if(options[hilights.front()]==polar || options[hilights.front()]==rect) {
 			return ControlBase::doSelect();
 		}
-		sndman->PlayFile(config->controller.cancel_snd);
+		sndman->playFile(config->controller.cancel_snd);
 		setupChoose();
 		refresh();
 		return this;
 	} else {
-		sndman->PlayFile(config->controller.cancel_snd);
+		sndman->playFile(config->controller.cancel_snd);
 		setupChoose();
 		refresh();
 		return this;
@@ -287,7 +287,7 @@
 	if(st==MOVING) {
 		stopTime=e.getTimeStamp();
 		sout->printf("Ran for %g seconds\n",(stopTime-startTime)/1000.f);
-		sndman->PlayFile(config->controller.select_snd);
+		sndman->playFile(config->controller.select_snd);
 		setupReading1();
 		refresh();
 		if(curType!=5)
@@ -310,7 +310,7 @@
 				err("Invalid input: "+msg);
 				return doReadStdIn(std::string("Enter ")+getFirstMeasure(curType));
 			}
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			setupReading2();
 			refresh();
 			if(*end!='\0')
@@ -325,7 +325,7 @@
 				return doReadStdIn(std::string("Enter ")+getSecondMeasure(curType));
 			}
 			addSample();
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			setupReady();
 			refresh();
 			return this;
@@ -873,7 +873,7 @@
 		errmsg.push_back(str);
 		serr->printf("%s\n",str.c_str());
 		Controller::loadGUI("org.tekkotsu.mon.ControllerErr","msg",0,errmsg);
-		sndman->PlayFile(config->controller.error_snd);
+		sndman->playFile(config->controller.error_snd);
 		return;
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/WalkCalibration.h ./Behaviors/Controls/WalkCalibration.h
--- ../Tekkotsu_2.4.1/Behaviors/Controls/WalkCalibration.h	2005-02-02 13:47:23.000000000 -0500
+++ ./Behaviors/Controls/WalkCalibration.h	2006-09-16 16:11:49.000000000 -0400
@@ -44,25 +44,25 @@
 
 protected:
 	enum {
-		ROOT,
-		CHOOSE,
-		READY,
-		MOVING,
-		READING_1,
-		READING_2,
-		CLEAR,
+		ROOT,      //!< indicates the root menu is currently displayed (save/load data sets...)
+		CHOOSE,    //!< indicates the sample type selection is displayed
+		READY,     //!< waiting for user to indicate 0 point
+		MOVING,    //!< recording, waiting for the motion stop event
+		READING_1, //!< waiting for user to supply the first measurement coordinate
+		READING_2, //!< waiting for user to supply the second measurement coordinate
+		CLEAR,     //!< clear data confirmation menu
 	} st; //!< the currently active state
 
 	//! allows representation of the current sample type
 	enum dataSource {
-		fs,
-		fr,
-		sr,
-		br,
-		bs,
-		r,
-		NUM_SRC
-	} curType;
+		fs, //!< forward-sideways
+		fr, //!< forward-rotate
+		sr, //!< sideways-rotate
+		br, //!< backward-rotate
+		bs, //!< backward-sideways
+		r,  //!< pure rotation
+		NUM_SRC //!< number of data types
+	} curType; //!< the currently selected type of data being recorded	
 
 	static void loadData(const std::string& name, std::vector<float*>& data); //!< does the work of loading data sets
 	static void saveData(const std::string& name, const std::vector<float*>& data); //!< does the work of saving data sets
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Controls/WaypointWalkControl.cc ./Behaviors/Controls/WaypointWalkControl.cc
--- ../Tekkotsu_2.4.1/Behaviors/Controls/WaypointWalkControl.cc	2005-06-06 19:05:51.000000000 -0400
+++ ./Behaviors/Controls/WaypointWalkControl.cc	2006-09-18 14:07:54.000000000 -0400
@@ -120,23 +120,23 @@
 				startstopCtl->setDescription("Halt locomotion");
 				MMAccessor<WaypointWalkMC>(walk_id)->go();
 			}
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			return curctl;
 		} else if(curctl==loopCtl) {
 			MMAccessor<WaypointWalkMC>(walk_id)->setIsLooping(!loopCtl->getStatus());
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			return curctl;
 		} else if(curctl==addEgoWPCtl) {
 			MMAccessor<WaypointWalkMC>(walk_id)->addEgocentricWaypoint(0,0,false,true,.1);
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			return curctl;
 		} else if(curctl==addOffWPCtl) {
 			MMAccessor<WaypointWalkMC>(walk_id)->addOffsetWaypoint(0,0,false,true,.1);
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			return curctl;
 		} else if(curctl==addAbsWPCtl) {
 			MMAccessor<WaypointWalkMC>(walk_id)->addAbsoluteWaypoint(0,0,false,true,.1);
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			return curctl;
 		}
 	}
@@ -177,20 +177,20 @@
 		if(curctl==up) {
 			WaypointWalkMC::WaypointList_t& list=MMAccessor<WaypointWalkMC>(walk_id)->getWaypointList();
 			list.swap(list.prev(waypoint_id),waypoint_id);
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			return NULL;
 		} else if(curctl==down) {
 			WaypointWalkMC::WaypointList_t& list=MMAccessor<WaypointWalkMC>(walk_id)->getWaypointList();
 			list.swap(waypoint_id,list.next(waypoint_id));
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			return NULL;
 		} else if(curctl==del) {
 			MMAccessor<WaypointWalkMC>(walk_id)->getWaypointList().erase(waypoint_id);
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			return NULL;
 		} else if(curctl==set) {
 			MMAccessor<WaypointWalkMC>(walk_id)->setTargetWaypoint(waypoint_id);
-			sndman->PlayFile(config->controller.select_snd);
+			sndman->playFile(config->controller.select_snd);
 			return NULL;
 		}
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/AutoGetupBehavior.h ./Behaviors/Demos/AutoGetupBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/AutoGetupBehavior.h	2005-06-01 01:47:45.000000000 -0400
+++ ./Behaviors/Demos/AutoGetupBehavior.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,83 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_AutoGetupBehavior_h_
-#define INCLUDED_AutoGetupBehavior_h_
-
-#include "Behaviors/BehaviorBase.h"
-#include "Shared/WorldState.h"
-#include "Events/EventRouter.h"
-#include "IPC/SharedObject.h"
-#include "Motion/MotionManager.h"
-#include "Motion/MotionSequenceMC.h"
-#include "Shared/Config.h"
-#include "Sound/SoundManager.h"
-
-//! a little background behavior to keep the robot on its feet
-class AutoGetupBehavior : public BehaviorBase {
-public:
-	//! constructor
-	AutoGetupBehavior() : BehaviorBase("AutoGetupBehavior"), back(0), side(0), gamma(.9), sensitivity(.85*.85), waiting(false) {}
-	//! destructor
-	virtual ~AutoGetupBehavior() {}
-
-	//! Listens for the SensorSourceID::UpdatedSID
-	virtual void DoStart() {
-		BehaviorBase::DoStart();
-		erouter->addListener(this,EventBase::sensorEGID,SensorSourceID::UpdatedSID);
-	}
-	//! Stops listening for events
-	virtual void DoStop() {
-		erouter->removeListener(this);
-		BehaviorBase::DoStop();
-	}
-	//! Run appropriate motion script if the robot falls over
-	virtual void processEvent(const EventBase &event) {
-		if(event.getGeneratorID()==EventBase::motmanEGID) {
-			//previous attempt at getting up has completed
-			cout << "Getup complete" << endl;
-			erouter->removeListener(this,EventBase::motmanEGID);
-			waiting=false;
-			return;
-		}
-		back=back*gamma+(1-gamma)*state->sensors[BAccelOffset];
-		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;
-			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)
-			if(fabs(back)<fabs(side))
-				gu=config->motion.makePath("gu_side.mot");
-			else if(back<0)
-				gu=config->motion.makePath("gu_back.mot");
-			else
-				gu=config->motion.makePath("gu_front.mot");
-			SharedObject<MediumMotionSequenceMC> getup(gu.c_str());
-			MotionManager::MC_ID id=motman->addPrunableMotion(getup,MotionManager::kHighPriority);
-			erouter->addListener(this,EventBase::motmanEGID,id,EventBase::deactivateETID);
-			waiting=true;
-		}
-	}
-	static std::string getClassDescription() { return "Monitors gravity's influence on the accelerometers - if it seems the robot has fallen over, it runs appropriate getup script"; }
-	virtual std::string getDescription() const { return getClassDescription(); }
-
-protected:
-	float back;          //!< exponential average of backwards accel
-	float side;          //!< exponential average of sideways accel
-	float gamma;         //!< default 0.9, gamma parameter for exponential average of above
-	float sensitivity;   //!< default 0.85*0.85, squared threshold to consider having fallen over, use values 0-1
-	bool  waiting;       //!< true while we're waiting to hear from completion of MotionSequence, won't try again until this is cleared
-};
-
-/*! @file
- * @brief Defines AutoGetupBehavior, a little background behavior to keep the robot on its feet
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/BanditMachine.h ./Behaviors/Demos/BanditMachine.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/BanditMachine.h	2005-06-01 01:47:45.000000000 -0400
+++ ./Behaviors/Demos/BanditMachine.h	2006-09-18 14:07:57.000000000 -0400
@@ -6,6 +6,7 @@
 #include "Behaviors/Demos/StareAtBallBehavior.h"
 #include "IPC/SharedObject.h"
 #include "Motion/PostureMC.h"
+#include "Motion/MMAccessor.h"
 #include "Motion/MotionSequenceMC.h"
 #include "Motion/LedMC.h"
 #include "Behaviors/Transitions/TimeOutTrans.h"
@@ -13,200 +14,201 @@
 #include "Behaviors/Nodes/OutputNode.h"
 #include "Sound/SoundManager.h"
 #include "Shared/ProjectInterface.h"
+#include "Shared/WorldState.h"
 
 #include "Behaviors/Demos/karmedbandit.h"
 
 //! Plays K-armed bandit
 class BanditMachine : public StateNode {
 public:
-	//!constructor
-	BanditMachine()
-		: StateNode("BanditMachine","BanditMachine"), stare(NULL), start(NULL), liedown(MotionManager::invalid_MC_ID), bandit(2)
-	{
-		stare=new StareAtBallBehavior();
-		stare->AddReference();
-	}
-	//!constructor
-	BanditMachine(const char* n)
-		: StateNode("BanditMachine",n), stare(), start(NULL), liedown(MotionManager::invalid_MC_ID), bandit(2)
-	{
-		stare=new StareAtBallBehavior();
-		stare->AddReference();
-	}
-	//!destructor
-	virtual ~BanditMachine() {
-		stare->RemoveReference();
-	}
+  //!constructor
+  BanditMachine()
+    : StateNode("BanditMachine","BanditMachine"), stare(NULL), start(NULL), liedown(MotionManager::invalid_MC_ID), bandit(2)
+  {
+    stare=new StareAtBallBehavior();
+    stare->AddReference();
+  }
+  //!constructor
+  BanditMachine(const char* n)
+    : StateNode("BanditMachine",n), stare(), start(NULL), liedown(MotionManager::invalid_MC_ID), bandit(2)
+  {
+    stare=new StareAtBallBehavior();
+    stare->AddReference();
+  }
+  //!destructor
+  virtual ~BanditMachine() {
+    stare->RemoveReference();
+  }
 
-	static std::string getClassDescription() { return "Plays k-armed bandit with a computer"; }
-	virtual std::string getDescription() const { return getClassDescription(); }
+  static std::string getClassDescription() { return "Plays k-armed bandit with a computer"; }
+  virtual std::string getDescription() const { return getClassDescription(); }
 
-	virtual void setup() {
-		StateNode *wait=start=addNode(new WaitNode("Wait",bandit));
-		StateNode *left=addNode(new PressNode("Left",LFrLegOffset+KneeOffset));
-		StateNode *right=addNode(new PressNode("Right",RFrLegOffset+KneeOffset));
-		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));
-		wait->addTransition(new TimeOutTrans(decide,2000));
-		left->addTransition(new TimeOutTrans(recoverl,1500));
-		right->addTransition(new TimeOutTrans(recoverr,1500));
-		//		recover->addTransition(new TimeOutTrans(decide,500));
-		StateNode::setup();
-	}
+  virtual void setup() {
+    StateNode *wait=start=addNode(new WaitNode("Wait",bandit));
+    StateNode *left=addNode(new PressNode("Left",LFrLegOffset+KneeOffset));
+    StateNode *right=addNode(new PressNode("Right",RFrLegOffset+KneeOffset));
+    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));
+    wait->addTransition(new TimeOutTrans(decide,2000));
+    left->addTransition(new TimeOutTrans(recoverl,1500));
+    right->addTransition(new TimeOutTrans(recoverr,1500));
+    //		recover->addTransition(new TimeOutTrans(decide,500));
+    StateNode::setup();
+  }
 
-	virtual void DoStart() {
-		StateNode::DoStart();
-		stare->DoStart();
-		start->DoStart();
-		SharedObject<PostureMC> lie("liedown.pos");
-		lie->setOutputCmd(LFrLegOffset+RotatorOffset,.77);
-		lie->setOutputCmd(RFrLegOffset+RotatorOffset,.73);
-		lie->setOutputCmd(LFrLegOffset+KneeOffset,.6);
-		lie->setOutputCmd(RFrLegOffset+KneeOffset,.6);
-		liedown=motman->addPrunableMotion(lie);
-	}
+  virtual void DoStart() {
+    StateNode::DoStart();
+    stare->DoStart();
+    start->DoStart();
+    SharedObject<PostureMC> lie("liedown.pos");
+    lie->setOutputCmd(LFrLegOffset+RotatorOffset,.77);
+    lie->setOutputCmd(RFrLegOffset+RotatorOffset,.73);
+    lie->setOutputCmd(LFrLegOffset+KneeOffset,.6);
+    lie->setOutputCmd(RFrLegOffset+KneeOffset,.6);
+    liedown=motman->addPrunableMotion(lie);
+  }
 
-	virtual void DoStop() {
-		motman->removeMotion(liedown);
-		stare->DoStop();
-		StateNode::DoStop();
-	}
+  virtual void DoStop() {
+    motman->removeMotion(liedown);
+    stare->DoStop();
+    StateNode::DoStop();
+  }
 
 protected:
-	//! This node is used to move a paw down using a MotionSequenceMC
-	class PressNode : public StateNode {
-	public:
-		//! constructor
-		/*! @param n name of the node
-		 *  @param idx the joint index of the paw to move
-		 */
-		PressNode(const char* n, unsigned int idx) : StateNode("PressNode",n), press_id(MotionManager::invalid_MC_ID), index(idx) {
-			SharedObject<SmallMotionSequenceMC> press;
-			press->setTime(0);
-			press->setOutputCmd(idx,.6);
-			press->setTime(1);
-			press->setOutputCmd(idx,.6);
-			press->setTime(200);
-			press->setOutputCmd(idx,.3);
-			press->setTime(1500);
-			press->setOutputCmd(idx,outputRanges[idx][MinRange]);
-			press_id=motman->addPersistentMotion(press,MotionManager::kStdPriority+1);
-		}
-		//!destructor
-		virtual ~PressNode() {
-			motman->removeMotion(press_id);
-		}
-		virtual void DoStart() {
-			StateNode::DoStart();
-			MMAccessor<SmallMotionSequenceMC> press(press_id);
-			press->play();
-			press->setOutputCmd(index,.6);
-			//			press->setSpeed(1);
-		}
-		virtual void DoStop() {
-			MMAccessor<SmallMotionSequenceMC> press(press_id);
-			//			press->setSpeed(-1);
-			press->pause();
-			press->setTime(0);
-			StateNode::DoStop();
-		}
-	protected:
-		MotionManager::MC_ID press_id; //!< the MC_ID of the MotionSequenceMC being used to do the press
-		unsigned int index; //!< the joint index of the paw to move
-	};
+  //! This node is used to move a paw down using a MotionSequenceMC
+  class PressNode : public StateNode {
+  public:
+    //! constructor
+    /*! @param n name of the node
+     *  @param idx the joint index of the paw to move
+     */
+    PressNode(const char* n, unsigned int idx) : StateNode("PressNode",n), press_id(MotionManager::invalid_MC_ID), index(idx) {
+      SharedObject<SmallMotionSequenceMC> press;
+      press->setTime(0);
+      press->setOutputCmd(idx,.6);
+      press->setTime(1);
+      press->setOutputCmd(idx,.6);
+      press->setTime(200);
+      press->setOutputCmd(idx,.3);
+      press->setTime(1500);
+      press->setOutputCmd(idx,outputRanges[idx][MinRange]);
+      press_id=motman->addPersistentMotion(press,MotionManager::kStdPriority+1);
+    }
+    //!destructor
+    virtual ~PressNode() {
+      motman->removeMotion(press_id);
+    }
+    virtual void DoStart() {
+      StateNode::DoStart();
+      MMAccessor<SmallMotionSequenceMC> press(press_id);
+      press->play();
+      press->setOutputCmd(index,.6);
+      //			press->setSpeed(1);
+    }
+    virtual void DoStop() {
+      MMAccessor<SmallMotionSequenceMC> press(press_id);
+      //			press->setSpeed(-1);
+      press->pause();
+      press->setTime(0);
+      StateNode::DoStop();
+    }
+  protected:
+    MotionManager::MC_ID press_id; //!< the MC_ID of the MotionSequenceMC being used to do the press
+    unsigned int index; //!< the joint index of the paw to move
+  };
 
-	//! uses one of the algorithms in karmedbandit.h to decide which paw to press next
-	class DecideNode : public StateNode {
-	public:
-		//! constructor
-		/*! @param n name of the node
-		 *  @param bandito the decision making algorithm to use (look in karmedbandit.h)
-		 *  @param left the PressNode to go to if the left paw is chosen
-		 *  @param right the PressNode to go to if the right paw is chosen
-		 */
-		DecideNode(const char* n, karmedbanditExp3_1& bandito, StateNode* left, StateNode* right)
-			: StateNode("DecideNode",n), b(bandito), l(left), r(right)
-		{}
-		virtual void DoStart() {
-			StateNode::DoStart();
-			AddReference();
-			DoStop();
-			if(b.decide()==0) {
-				std::cout << "Left... " << std::flush;
-				l->DoStart();
-			} else {
-				std::cout << "Right... " << std::flush;
-				r->DoStart();
-			}
-			RemoveReference();
-		}
-	protected:
-		karmedbanditExp3_1& b; //!< the class implementing the k-armed bandit algorithm
-		StateNode* l; //!< the node to go to if the left paw is chosen
-		StateNode* r; //!< the node to go to if the right paw is chosen
-	private:
-		DecideNode(const DecideNode& node); //!< don't call this
-		DecideNode operator=(const DecideNode& node); //!< don't call this
-	};
+  //! uses one of the algorithms in karmedbandit.h to decide which paw to press next
+  class DecideNode : public StateNode {
+  public:
+    //! constructor
+    /*! @param n name of the node
+     *  @param bandito the decision making algorithm to use (look in karmedbandit.h)
+     *  @param left the PressNode to go to if the left paw is chosen
+     *  @param right the PressNode to go to if the right paw is chosen
+     */
+    DecideNode(const char* n, karmedbanditExp3_1& bandito, StateNode* left, StateNode* right)
+      : StateNode("DecideNode",n), b(bandito), l(left), r(right)
+    {}
+    virtual void DoStart() {
+      StateNode::DoStart();
+      AddReference();
+      DoStop();
+      if(b.decide()==0) {
+	std::cout << "Left... " << std::flush;
+	l->DoStart();
+      } else {
+	std::cout << "Right... " << std::flush;
+	r->DoStart();
+      }
+      RemoveReference();
+    }
+  protected:
+    karmedbanditExp3_1& b; //!< the class implementing the k-armed bandit algorithm
+    StateNode* l; //!< the node to go to if the left paw is chosen
+    StateNode* r; //!< the node to go to if the right paw is chosen
+  private:
+    DecideNode(const DecideNode& node); //!< don't call this
+    DecideNode operator=(const DecideNode& node); //!< don't call this
+  };
 	
-	//! Waits to see if a reward is received, lights up LEDs to let the user know
-	class WaitNode : public StateNode {
-	public:
-		//! constructor
-		/* @param n name to use for the node
-		 * @param bandito the class to pass the reward to (if it comes)
-		 */
-		WaitNode(const char* n, karmedbanditExp3_1& bandito)
-			: StateNode("WaitNode",n), b(bandito), reward(false), leds_id(MotionManager::invalid_MC_ID)
-		{
-			leds_id=motman->addPersistentMotion(SharedObject<LedMC>());
-		}
-		//! destructor
-		virtual ~WaitNode() {
-		  motman->removeMotion(leds_id);
-		}
-		virtual void DoStart() {
-			StateNode::DoStart();
-			erouter->addListener(this,EventBase::visObjEGID,ProjectInterface::visPinkBallSID);
-			erouter->addTimer(this,0,1000,false);
-			MMAccessor<LedMC> leds(leds_id);
-			leds->cflash(BotLLEDMask+BotRLEDMask,1,1000);
-		}
-		virtual void DoStop() {
-			erouter->removeListener(this);
-			b.reward(reward);
-			cout << endl;
-			reward=false;
-			StateNode::DoStop();
-		}
-		virtual void processEvent(const EventBase& event) {
-			if(event.getGeneratorID()==EventBase::timerEGID) {
-				sndman->PlayFile("whimper.wav");
-			} else {
-				sndman->PlayFile("yipper.wav");
-				reward=true;
-				MMAccessor<LedMC> leds(leds_id);
-				leds->cflash(MidLLEDMask+MidRLEDMask,1,100);
-			}
-			erouter->removeListener(this);
-		}
-	protected:
-		karmedbanditExp3_1& b; //!< the class implimenting a k-armed bandit algorithm to pass the reward back to
-		bool reward; //!< true if a reward was received
-		MotionManager::MC_ID leds_id; //!< MC_ID of a LedMC
-	};
+  //! Waits to see if a reward is received, lights up LEDs to let the user know
+  class WaitNode : public StateNode {
+  public:
+    //! constructor
+    /* @param n name to use for the node
+     * @param bandito the class to pass the reward to (if it comes)
+     */
+    WaitNode(const char* n, karmedbanditExp3_1& bandito)
+      : StateNode("WaitNode",n), b(bandito), reward(false), leds_id(MotionManager::invalid_MC_ID)
+    {
+      leds_id=motman->addPersistentMotion(SharedObject<LedMC>());
+    }
+    //! destructor
+    virtual ~WaitNode() {
+      motman->removeMotion(leds_id);
+    }
+    virtual void DoStart() {
+      StateNode::DoStart();
+      erouter->addListener(this,EventBase::visObjEGID,ProjectInterface::visPinkBallSID);
+      erouter->addTimer(this,0,1000,false);
+      MMAccessor<LedMC> leds(leds_id);
+      leds->cflash(BotLLEDMask+BotRLEDMask,1,1000);
+    }
+    virtual void DoStop() {
+      erouter->removeListener(this);
+      b.reward(reward);
+      cout << endl;
+      reward=false;
+      StateNode::DoStop();
+    }
+    virtual void processEvent(const EventBase& event) {
+      if(event.getGeneratorID()==EventBase::timerEGID) {
+	sndman->playFile("whimper.wav");
+      } else {
+	sndman->playFile("yipper.wav");
+	reward=true;
+	MMAccessor<LedMC> leds(leds_id);
+	leds->cflash(MidLLEDMask+MidRLEDMask,1,100);
+      }
+      erouter->removeListener(this);
+    }
+  protected:
+    karmedbanditExp3_1& b; //!< the class implimenting a k-armed bandit algorithm to pass the reward back to
+    bool reward; //!< true if a reward was received
+    MotionManager::MC_ID leds_id; //!< MC_ID of a LedMC
+  };
 
-	StareAtBallBehavior* stare; //!< active as long as we're in this state so it keeps an eye on the ball
-	StateNode* start; //!< used to start off by lying down before we start pressing buttons
-	MotionManager::MC_ID liedown; //!< a MotionSequence which will move the dog into a lying down posture
-	karmedbanditExp3_1 bandit; //!< algorithm to use in the k-armed bandit problem
+  StareAtBallBehavior* stare; //!< active as long as we're in this state so it keeps an eye on the ball
+  StateNode* start; //!< used to start off by lying down before we start pressing buttons
+  MotionManager::MC_ID liedown; //!< a MotionSequence which will move the dog into a lying down posture
+  karmedbanditExp3_1 bandit; //!< algorithm to use in the k-armed bandit problem
 
 private:
-	BanditMachine(const BanditMachine& node); //!< don't call this
-	BanditMachine operator=(const BanditMachine& node); //!< don't call this
+  BanditMachine(const BanditMachine& node); //!< don't call this
+  BanditMachine operator=(const BanditMachine& node); //!< don't call this
 };
 
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/BatteryMonitorBehavior.h ./Behaviors/Demos/BatteryMonitorBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/BatteryMonitorBehavior.h	2005-06-01 01:47:45.000000000 -0400
+++ ./Behaviors/Demos/BatteryMonitorBehavior.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,165 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_BatteryMonitorBehavior_h_
-#define INCLUDED_BatteryMonitorBehavior_h_
-
-#include "Behaviors/BehaviorBase.h"
-#include "Shared/debuget.h"
-#include "Shared/WorldState.h"
-#include "Events/EventRouter.h"
-#include "IPC/SharedObject.h"
-#include "Motion/MotionManager.h"
-#include "Motion/PostureMC.h"
-#include "Motion/LedMC.h"
-#include "Shared/ERS210Info.h"
-#include "Shared/ERS220Info.h"
-#include "Shared/ERS7Info.h"
-#include "Motion/MMAccessor.h"
-
-//! A background behavior which will monitor the power level and flip the ears when appropriate on a 210, or blink the headlight if a 220
-/*! Think of this as a simple example class.  For exercise, try using a MotionSequenceMC instead
- *  of switching the ears back manually using a PostureMC */
-class BatteryMonitorBehavior : public BehaviorBase {
-public:
-	static const unsigned int max_t=10000; //!< max time between ear flips when at "high power" mark
-	static const unsigned int high_power_p=20; //!< percent of 100 which is point at which to begin warning
-	static const unsigned int no_power_p=14; //!< percent of 100 at which power will fail (approximate!)
-
-	//! constructor
-	BatteryMonitorBehavior() : BehaviorBase("BatteryMonitorBehavior"), pose(NULL), pose_id(MotionManager::invalid_MC_ID), led_id(MotionManager::invalid_MC_ID) {}
-	//! destructor
-	virtual ~BatteryMonitorBehavior() {}
-
-	//! Listens for the PowerSourceID::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);
-		//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));
-	}
-	//! Stops listening for events
-	virtual void DoStop() {
-		if(pose!=NULL)
-			stopWarning();
-		erouter->removeListener(this);
-		BehaviorBase::DoStop();
-	}
-	//! Adds a BatteryMonitorMC to motman if power goes low
-	virtual void processEvent(const EventBase &event) {
-		if(event.getGeneratorID()==EventBase::powerEGID) {
-			//just check for low power status
-			bool shouldwarn=shouldWarn();
-			if(pose!=NULL && !shouldwarn)
-				stopWarning();
-			else if(pose==NULL && shouldwarn)
-				startWarning();
-		} else {
-			ASSERTRET(event.getGeneratorID()==EventBase::timerEGID,"Unrequested event "<<event.getName());
-			switch(event.getSourceID()) {
-			case 1: { // toggle the ears (signals low battery), show battery level on LEDs
-				ASSERTRET(pose!=NULL,"Extra timer 1");
-				setFlipper(true);
-				unsigned int flipdelay=calcFlipDelay();
-				// if we're just constantly flipping the ears, a slight change is needed so the battery
-				// level isn't obscuring the LED settings
-				if(flipdelay<=NumFrames*FrameTime) {
-					static bool on=false;
-					on=!on;
-					if(on) {
-						motman->setPriority(led_id,MotionManager::kEmergencyPriority+1);
-						MMAccessor<LedMC> led(led_id);
-						led->displayPercent(state->sensors[PowerRemainOffset],LedEngine::major,LedEngine::major);
-					} else
-						motman->setPriority(led_id,MotionManager::kIgnoredPriority);
-					erouter->addTimer(this,1,128+flipdelay,false);
-				} else {
-					motman->setPriority(led_id,MotionManager::kEmergencyPriority+1);
-					MMAccessor<LedMC> led(led_id);
-					led->displayPercent(state->sensors[PowerRemainOffset],LedEngine::major,LedEngine::major);
-					erouter->addTimer(this,2,128,false);
-				}
-			} break;
-			case 2: { // release ear until next flap, hide LEDs display
-				ASSERTRET(pose!=NULL,"Extra timer 1");
-				setFlipper(false);
-				motman->setPriority(led_id,MotionManager::kIgnoredPriority);
-				erouter->addTimer(this,1,calcFlipDelay(),false);
-			} break;
-			default:
-				ASSERTRET(false,"Unrequested timer " << event.getName());
-				break;
-			}
-		}
-	}
-	static std::string getClassDescription() { return "Reports the current battery status, and starts flicks the ears to warn when it gets too low"; }
-	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]; }
-
-protected:
-	//! adds a pose and a timer to get the ears flipping
-	void startWarning() {
-		serr->printf("LOW BATTERY\n");
-		pose_id=motman->addPersistentMotion(SharedObject<PostureMC>(),MotionManager::kEmergencyPriority+1);
-		pose=(PostureMC*)motman->peekMotion(pose_id);
-		SharedObject<LedMC> led;
-		led->displayPercent(state->sensors[PowerRemainOffset],LedEngine::major,LedEngine::major);
-		led_id=motman->addPersistentMotion(led,MotionManager::kEmergencyPriority+1);
-		setFlipper(true);
-		erouter->addTimer(this,2,128,false);
-	}
-	//! removes pose, in case battery magically charges
-	void stopWarning() {
-		serr->printf("BATTERY GOOD\n");
-		motman->removeMotion(pose_id);
-		motman->removeMotion(led_id);
-		led_id=pose_id=MotionManager::invalid_MC_ID;
-		pose=NULL;
-		erouter->removeTimer(this,1);
-		erouter->removeTimer(this,2);
-	}
-	//! makes the ears flip more rapidly as power declines.  Flips back and forth once every 15 seconds at 15%, down to flipping constantly at 5%.
-	unsigned int calcFlipDelay() {
-		const float high_power=high_power_p/100.0;
-		const float no_power=no_power_p/100.0;
-		float cur_power=state->sensors[PowerRemainOffset];
-		if(cur_power<no_power)
-			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
-	void setFlipper(bool set) {
-		if(state->robotDesign & WorldState::ERS210Mask)
-			for(unsigned int i=ERS210Info::EarOffset; i<ERS210Info::EarOffset+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++)
-				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
-	MotionManager::MC_ID led_id; //!< id of LedMC if we are currently warning, MotionManager::invalid_MC_ID otherwise
-
-private:
-	BatteryMonitorBehavior(const BatteryMonitorBehavior&); //!< don't copy behaviors
-	BatteryMonitorBehavior operator=(const BatteryMonitorBehavior&); //!< don't assign behaviors
-};
-
-/*! @file
- * @brief Defines BatteryMonitorBehavior, a background behavior to trigger BatteryMonitorMC to warn when the power is low
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/CameraBehavior.cc ./Behaviors/Demos/CameraBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Demos/CameraBehavior.cc	2005-08-05 17:55:43.000000000 -0400
+++ ./Behaviors/Demos/CameraBehavior.cc	2006-09-18 14:07:57.000000000 -0400
@@ -16,6 +16,7 @@
 #include "Vision/RawCameraGenerator.h"
 #include "Vision/InterleavedYUVGenerator.h"
 #include "Vision/JPEGGenerator.h"
+#include "Vision/PNGGenerator.h"
 
 #include <sys/types.h>
 #include <sys/stat.h>
@@ -33,7 +34,7 @@
 		camera_click.setSourceID(ERS7Info::HeadButOffset);
 	}
 	initIndex();
-	sndman->LoadFile("camera.wav");
+	sndman->loadFile("camera.wav");
 	ledID=motman->addPersistentMotion(SharedObject<LedMC>());
 	erouter->addListener(this,camera_click);
 	erouter->addListener(this,EventBase::textmsgEGID);
@@ -41,7 +42,7 @@
 
 void CameraBehavior::DoStop() {
 	erouter->removeListener(this);
-	sndman->ReleaseFile("camera.wav");
+	sndman->releaseFile("camera.wav");
 	motman->removeMotion(ledID);
 	BehaviorBase::DoStop();
 }
@@ -49,7 +50,7 @@
 	
 /*! The format used depends on the current config settings.  If JPEG
  *  is the current choice, then a JPEG file will be written.
- *  Otherwise, RawCameraGenerator::SaveFile() will be called.
+ *  Otherwise, RawCameraGenerator::saveFile() will be called.
  */
 void
 CameraBehavior::processEvent(const EventBase& e) {
@@ -78,19 +79,19 @@
 		if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_COLOR) {
 			FilterBankGenerator * gen=ProjectInterface::defInterleavedYUVGenerator; // just an alias for readability
 			gen->selectSaveImage(ProjectInterface::doubleLayer,InterleavedYUVGenerator::CHAN_YUV);
-			unsigned int len=gen->SaveFileStream(f);
+			unsigned int len=gen->saveFileStream(f);
 			if(len==0) {
 				serr->printf("Error saving file\n");
-				sndman->PlayFile(config->controller.error_snd);
+				sndman->playFile(config->controller.error_snd);
 				return;
 			}
 		} else if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_SINGLE_CHANNEL) {
 			FilterBankGenerator * gen=ProjectInterface::defRawCameraGenerator; // just an alias for readability
 			gen->selectSaveImage(ProjectInterface::doubleLayer,config->vision.rawcam_channel);
-			unsigned int len=gen->SaveFileStream(f);
+			unsigned int len=gen->saveFileStream(f);
 			if(len==0) {
 				serr->printf("Error saving file\n");
-				sndman->PlayFile(config->controller.error_snd);
+				sndman->playFile(config->controller.error_snd);
 				return;
 			}
 		}
@@ -122,7 +123,7 @@
 			unsigned int writ=fwrite(imgbuf,jpeg->getImageSize(ProjectInterface::doubleLayer,chan),1,f);
 			if(writ==0) {
 				serr->printf("Error saving file\n");
-				sndman->PlayFile(config->controller.error_snd);
+				sndman->playFile(config->controller.error_snd);
 				return;
 			}
 
@@ -131,9 +132,37 @@
 			
 			jpeg->setQuality(tmp_q);
 		}
-	}
-
 
+	} else if(config->vision.rawcam_compression==Config::vision_config::COMPRESS_PNG) {
+		//save a JPEG 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)
+			png=dynamic_cast<PNGGenerator*>(ProjectInterface::defColorPNGGenerator);
+		else if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_SINGLE_CHANNEL) {
+			png=dynamic_cast<PNGGenerator*>(ProjectInterface::defGrayscalePNGGenerator);
+			chan=config->vision.rawcam_channel;
+		}
+		if(png!=NULL) {
+			// open file
+			FILE * f=openNextFile(".png");
+			if(f==NULL) //error message already displayed in openNextFile()
+				return;
+			
+			//! write actual image data
+			unsigned char * imgbuf=png->getImage(ProjectInterface::doubleLayer,chan);
+			unsigned int writ=fwrite(imgbuf,png->getImageSize(ProjectInterface::doubleLayer,chan),1,f);
+			if(writ==0) {
+				serr->printf("Error saving file\n");
+				sndman->playFile(config->controller.error_snd);
+				return;
+			}
+			
+			// close file
+			fclose(f);
+		}
+	}
+	
 	{
 		MMAccessor<LedMC> leds(ledID);
 		leds->clear();
@@ -151,10 +180,10 @@
 	FILE * f=fopen(getNextName(ext).c_str(),"w+");
 	if(f==NULL) {
 		serr->printf("Error opening file\n");
-		sndman->PlayFile(config->controller.error_snd);
+		sndman->playFile(config->controller.error_snd);
 		return NULL;
 	}
-	sndman->PlayFile("camera.wav");
+	sndman->playFile("camera.wav");
 	return f;
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/DrawVisObjBoundBehavior.h ./Behaviors/Demos/DrawVisObjBoundBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/DrawVisObjBoundBehavior.h	2005-08-04 17:09:26.000000000 -0400
+++ ./Behaviors/Demos/DrawVisObjBoundBehavior.h	2006-06-30 12:37:03.000000000 -0400
@@ -52,9 +52,12 @@
 				chan=RawCameraGenerator::CHAN_Y;
 				color=255;
 			} else if(e.getGeneratorID()==EventBase::visSegmentEGID) {
-				layer=fbe.getNumLayers()-1-config->vision.rlecam_skip;
-				chan=config->vision.rlecam_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;
+				return;
 			}
 
 			//do the drawing
@@ -65,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.rlecam_compression==Config::vision_config::COMPRESS_RLE)
+			if(config->vision.segcam_compression==Config::vision_config::COMPRESS_RLE)
 				ProjectInterface::defRLEGenerator->invalidateCaches();
 			
 			drawn++;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/ExploreMachine.cc ./Behaviors/Demos/ExploreMachine.cc
--- ../Tekkotsu_2.4.1/Behaviors/Demos/ExploreMachine.cc	2004-12-03 19:10:38.000000000 -0500
+++ ./Behaviors/Demos/ExploreMachine.cc	2005-12-15 13:51:35.000000000 -0500
@@ -27,9 +27,9 @@
 
 	WalkNode * move=NULL;
 	addNode(move=new WalkNode(getName()+"::move",150,0,0));
-	move->setWalkID(walkid);
+	move->setMC(walkid);
 	start=addNode(turn=new WalkNode(getName()+"::turn",0,0,0.5f));
-	turn->setWalkID(walkid);
+	turn->setMC(walkid);
 
 	move->addTransition(new SmoothCompareTrans<float>(turn,&state->sensors[IRDistOffset],CompareTrans<float>::LT,350,EventBase(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID),.7));
 	turn->addTransition(new TimeOutTrans(move,2000));
@@ -42,7 +42,7 @@
 	StateNode::DoStart();
 	start->DoStart();
 	//erouter->addListener(this,EventBase::sensorEGID,SensorSourceID::UpdatedSID);
-	erouter->addListener(this,EventBase::stateMachineEGID,(unsigned int)turn,EventBase::activateETID);
+	erouter->addListener(this,EventBase::stateMachineEGID,(size_t)turn,EventBase::activateETID);
 }
 
 void ExploreMachine::DoStop() {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/ExploreMachine.h ./Behaviors/Demos/ExploreMachine.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/ExploreMachine.h	2005-01-24 17:23:46.000000000 -0500
+++ ./Behaviors/Demos/ExploreMachine.h	2005-12-15 13:51:36.000000000 -0500
@@ -3,6 +3,7 @@
 #define INCLUDED_ExploreMachine_h_
 
 #include "Behaviors/StateNode.h"
+#include "Behaviors/Nodes/WalkNode.h"
 #include "Motion/MotionManager.h"
 
 //! A state machine for exploring an environment (or searching for an object)
@@ -34,7 +35,7 @@
 
 protected:
 	StateNode * start; //!< the node to begin within on DoStart() (turn)
-	class WalkNode * turn; //!< walk node to use when turning
+	WalkNode * turn; //!< walk node to use when turning
 	MotionManager::MC_ID walkid; //!< we want to share a walk between turning and walking nodes
 
 private:
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/FlashIPAddrBehavior.cc ./Behaviors/Demos/FlashIPAddrBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Demos/FlashIPAddrBehavior.cc	2005-06-01 01:47:45.000000000 -0400
+++ ./Behaviors/Demos/FlashIPAddrBehavior.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,187 +0,0 @@
-#include "FlashIPAddrBehavior.h"
-
-#include "Events/EventRouter.h"
-#include "Motion/MMAccessor.h"
-#include "Motion/LedEngine.h"
-#include "Shared/WorldState.h"
-#include "Shared/Config.h"
-#include "Sound/SoundManager.h"
-#include "Wireless/Wireless.h"
-
-void FlashIPAddrBehavior::DoStart() {
-	BehaviorBase::DoStart(); // do this first
-	if(config->behaviors.flash_on_start) {
-		setupSequence();
-		loadSounds();
-		ms_id = motman->addPrunableMotion(ms,MotionManager::kEmergencyPriority+1);
-		erouter->addListener(this,EventBase::motmanEGID,ms_id,EventBase::deactivateETID);
-	}
-	erouter->addListener(this,EventBase::buttonEGID,button1);
-	erouter->addListener(this,EventBase::buttonEGID,button2);
-}
-
-void FlashIPAddrBehavior::DoStop() {
-	erouter->removeListener(this);
-	motman->removeMotion(ms_id);
-	ms_id=MotionManager::invalid_MC_ID;
-	releaseSounds();
-	BehaviorBase::DoStop(); // do this last
-}
-
-void FlashIPAddrBehavior::processEvent(const EventBase& e) {
-	if(e.getGeneratorID()==EventBase::timerEGID) {
-
-		if(e.getSourceID()==ACTIVATE_TIMER) {
-			//buttons have been held down long enough, time to run display
-			if(ms_id!=MotionManager::invalid_MC_ID) {
-				//there's already one running, have to check it out to clear it
-				MMAccessor<MSMC_t> ms_acc(ms_id);
-				setupSequence();
-			} else
-				setupSequence();
-			loadSounds();
-			ms_id = motman->addPrunableMotion(ms);
-			erouter->addListener(this,EventBase::motmanEGID,ms_id,EventBase::deactivateETID);
-				
-		} else { //its time to play a digit sound file
-			//the source id was set to correspond to an element of the sounds vector
-			if(e.getSourceID()>=sounds.size())
-				serr->printf("ERROR: %s received invalid timer event %s\n",getName().c_str(),e.getName().c_str());
-			else {
-				sndman->PlayFile(sounds[e.getSourceID()]);
-				if(e.getSourceID()==sounds.size()-1)
-					releaseSounds();
-			}
-				
-		}
-
-	} 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
-		if(e.getTypeID()==EventBase::activateETID) {
-			if(state->buttons[button1] && state->buttons[button2])
-				erouter->addTimer(this,ACTIVATE_TIMER,2000,false);
-		} else if(e.getTypeID()==EventBase::deactivateETID)
-			erouter->removeTimer(this,ACTIVATE_TIMER);
-
-	} else if(e.getGeneratorID()==EventBase::motmanEGID) {
-		// display has completed, mark it as such
-		if(e.getSourceID()!=ms_id)
-			serr->printf("WARNING: %s received event %s, doesn't match ms_id (%d)\n",getName().c_str(),e.getName().c_str(),ms_id);
-		ms_id=MotionManager::invalid_MC_ID;
-		erouter->removeListener(this,EventBase::motmanEGID);
-			
-	}
-}
-
-void FlashIPAddrBehavior::loadSounds() {
-	for(unsigned int i=0; i<sounds.size(); i++)
-		sndman->LoadFile(sounds[i]);
-}
-
-void FlashIPAddrBehavior::releaseSounds() {
-	for(unsigned int i=0; i<sounds.size(); i++)
-		sndman->ReleaseFile(sounds[i]);
-	sounds.clear();
-}
-
-void FlashIPAddrBehavior::setupSequence() {
-	const unsigned int DISP_TIME=600;
-	const unsigned int GROUP_TIME=500;
-	const unsigned int DOT_TIME=400;
-	const unsigned int FADE_TIME=1;
-	const unsigned int BLANK_TIME=100-FADE_TIME*2;
-	erouter->removeTimer(this);
-	ms->clear();
-	releaseSounds();
-	unsigned int a=wireless->getIPAddress();
-	unsigned int n=config->behaviors.flash_bytes;
-	if(n>4)
-		n=4;
-	LedEngine disp;
-	for(unsigned int i=n-1; i!=-1U; i--) {
-		unsigned int byte=(a>>(i*8))&0xFF;
-		unsigned int digits=1;
-		if(byte>=10)
-			digits++;
-		if(byte>=100)
-			digits++;
-		//cout << "byte " << i << " is " << byte << " -- " << digits << " digits" << endl;
-		//cout << "Setting LEDs: ";
-		for(unsigned int d=0; d<digits; d++) {
-			unsigned int digit=byte;
-			for(unsigned int j=d;j<digits-1;j++)
-				digit/=10;
-			digit-=(digit/10)*10;
-			disp.displayNumber(digit,LedEngine::onedigit);
-			std::string soundfile="numbers/";
-			soundfile+=(digit+'0');
-			soundfile+=".wav";
-			erouter->addTimer(this,sounds.size(),ms->getTime()+delay,false);
-			sounds.push_back(soundfile);
-			for(unsigned int j=0; j<NumLEDs; j++)
-				if(FaceLEDMask&(1<<j)) {
-					//if(disp.getValue(static_cast<LEDOffset_t>(LEDOffset+j)))
-					//cout << j << ' ';
-					ms->setOutputCmd(LEDOffset+j,disp.getValue(static_cast<LEDOffset_t>(LEDOffset+j)));
-				}
-			ms->advanceTime(DISP_TIME);
-			for(unsigned int j=0; j<NumLEDs; j++)
-				if(FaceLEDMask&(1<<j))
-					ms->setOutputCmd(LEDOffset+j,disp.getValue(static_cast<LEDOffset_t>(LEDOffset+j)));
-			ms->advanceTime(FADE_TIME);
-			for(unsigned int j=0; j<NumLEDs; j++)
-				if(FaceLEDMask&(1<<j))
-					ms->setOutputCmd(LEDOffset+j,0);
-			ms->advanceTime(BLANK_TIME);
-			if(d==digits-1)
-				ms->advanceTime(GROUP_TIME);
-			for(unsigned int j=0; j<NumLEDs; j++)
-				if(FaceLEDMask&(1<<j))
-					ms->setOutputCmd(LEDOffset+j,0);
-			ms->advanceTime(FADE_TIME);
-		}
-		//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) {
-				dot=LedEngine::ERS220numMasks[10];
-			} else if(state->robotDesign&WorldState::ERS7Mask) {
-				dot=LedEngine::ERS7numMasks[10];
-			}
-			erouter->addTimer(this,sounds.size(),ms->getTime()+delay,false);
-			sounds.push_back("numbers/dot.wav");
-			for(unsigned int j=0; j<NumLEDs; j++)
-				if(FaceLEDMask&(1<<j))
-					ms->setOutputCmd(LEDOffset+j,(dot>>j)&1);
-			ms->advanceTime(DOT_TIME);
-			for(unsigned int j=0; j<NumLEDs; j++)
-				if(FaceLEDMask&(1<<j))
-					ms->setOutputCmd(LEDOffset+j,(dot>>j)&1);
-			ms->advanceTime(FADE_TIME);
-			for(unsigned int j=0; j<NumLEDs; j++)
-				if(FaceLEDMask&(1<<j))
-					ms->setOutputCmd(LEDOffset+j,0);
-			ms->advanceTime(BLANK_TIME);
-			for(unsigned int j=0; j<NumLEDs; j++)
-				if(FaceLEDMask&(1<<j))
-					ms->setOutputCmd(LEDOffset+j,0);
-			ms->advanceTime(FADE_TIME);
-		}
-	}
-	ms->play();
-}
-
-
-/*! @file
- * @brief Implements FlashIPAddrBehavior, which displays IP address by flashing a series of numbers on the LED face panel
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/FlashIPAddrBehavior.h ./Behaviors/Demos/FlashIPAddrBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/FlashIPAddrBehavior.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Behaviors/Demos/FlashIPAddrBehavior.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,67 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_FlashIPAddrBehavior_h_
-#define INCLUDED_FlashIPAddrBehavior_h_
-
-#include "Behaviors/BehaviorBase.h"
-#include "Motion/MotionManager.h"
-#include "Motion/MotionSequenceMC.h"
-
-//! Displays IP address by speaking the digits and flashing a series of numbers on the LED face panel
-/*! Will only run the display on DoStart() if the flash_on_start
- *  config variable is set.  Otherwise you will need to hold down the
- *  buttons specified by #button1 and #button2 to trigger the display.
- *  Note that if the e-stop is active it will intercept the button
- *  events, so turn off e-stop first. */
-class FlashIPAddrBehavior : public BehaviorBase {
-public:
-	//! constructor
-	FlashIPAddrBehavior()
-		: BehaviorBase("FlashIPAddrBehavior"), sounds(), ms(), ms_id(MotionManager::invalid_MC_ID)
-	{}
-
-	virtual void DoStart(); //!< if the Config::behavior_config::flash_on_start flag is set, will setup and run
-	virtual void DoStop();  //!< halts any display which may be in progress
-
-	//! Receives button events, timers, and motman manager pruning notifications
-	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 ";
-		pre+=buttonNames[button1];
-		pre+=" and ";
-		pre+=buttonNames[button2];
-		pre+=" to trigger any time while running";
-		return pre;
-	}
-	virtual std::string getDescription() const { return getClassDescription(); }
-	
-protected:
-	typedef XLargeMotionSequenceMC MSMC_t; //!< used to flash the LEDs to report the IP address
-
-	void loadSounds();    //!< loads the numeric sounds into memory
-	void releaseSounds(); //!< releases the numeric sounds
-	void setupSequence(); //!< construct the motion sequence for flashing leds, request timers to play corresponding sound file
-
-	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
-	
-	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)
-	static const unsigned int delay=64; //!< time (in milliseconds) to expect #ms to be delayed before it actually starts
-	
-	SharedObject<MSMC_t> ms; //!< motion sequence used to control the LEDs
-	MotionManager::MC_ID ms_id; //!< id number of #ms
-};
-
-/*! @file
- * @brief Describes FlashIPAddrBehavior, which displays IP address by flashing a series of numbers on the LED face panel
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/FollowHeadBehavior.cc ./Behaviors/Demos/FollowHeadBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Demos/FollowHeadBehavior.cc	2004-11-10 20:45:36.000000000 -0500
+++ ./Behaviors/Demos/FollowHeadBehavior.cc	2006-09-05 16:30:21.000000000 -0400
@@ -53,7 +53,7 @@
 	} else if(e==head_release) {
 		cout << "release" << endl;
 		motman->addPrunableMotion(SharedObject<PIDMC>(HeadOffset,HeadOffset+NumHeadJoints,0));
-		erouter->addListener(this,clock);
+		erouter->addTimer(this,clock);
 
 	} else if(e==head_lock) {
 		cout << "lock" << endl;
@@ -61,7 +61,7 @@
 		for(unsigned int i=HeadOffset; i<HeadOffset+NumHeadJoints; i++)
 			motman->setOutput(NULL,i,state->outputs[i]); //doing this prevents the head from jerking back when you released it to where it was before you pressed the button
 		cout << state->outputs[HeadOffset+TiltOffset]/M_PI*180 << ' ' << state->outputs[HeadOffset+PanOffset]/M_PI*180 << ' ' << state->outputs[HeadOffset+RollOffset]/M_PI*180 << endl;
-		erouter->removeListener(this,clock);
+		erouter->removeTimer(this,clock.getSourceID());
 
 	} else {
 		ASSERT(false,"unprocessed event " << e.getName() << endl);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/GroundPlaneBehavior.h ./Behaviors/Demos/GroundPlaneBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/GroundPlaneBehavior.h	2004-12-22 20:47:06.000000000 -0500
+++ ./Behaviors/Demos/GroundPlaneBehavior.h	2006-03-03 18:08:39.000000000 -0500
@@ -61,7 +61,7 @@
 
 		} else if(e==head_release) {
 			motman->addPrunableMotion(SharedObject<PIDMC>(HeadOffset,HeadOffset+NumHeadJoints,0));
-			erouter->addListener(this,clock);
+			erouter->addTimer(this,clock);
 			processEvent(clock);
 		} else if(e==head_lock) {
 			motman->addPrunableMotion(SharedObject<PIDMC>(HeadOffset,HeadOffset+NumHeadJoints,1));
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/LEDCounterBehavior.h ./Behaviors/Demos/LEDCounterBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/LEDCounterBehavior.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Demos/LEDCounterBehavior.h	2006-02-02 15:08:12.000000000 -0500
@@ -0,0 +1,65 @@
+//-*-c++-*-
+#ifndef INCLUDED_LEDCounterBehavior_h_
+#define INCLUDED_LEDCounterBehavior_h_
+
+#include "Behaviors/BehaviorBase.h"
+#include "Events/EventRouter.h"
+#include "Motion/LedMC.h"
+#include "Motion/PostureMC.h"
+#include "Motion/MMAccessor.h"
+
+//! Counts with LEDs on back button presses
+class LEDCounterBehavior : public BehaviorBase {
+public:
+	LEDCounterBehavior()
+		: BehaviorBase("LEDCounterBehavior"),
+			inc(EventBase::buttonEGID,FrontBackButOffset,EventBase::activateETID),
+			dec(EventBase::buttonEGID,RearBackButOffset,EventBase::activateETID),
+			sw(EventBase::buttonEGID,MiddleBackButOffset,EventBase::activateETID),
+			style(LedEngine::onedigit), cnt(0), led_id(MotionManager::invalid_MC_ID) {}
+	virtual void DoStart() {
+		BehaviorBase::DoStart();
+		erouter->addListener(this,inc);
+		erouter->addListener(this,dec);
+		erouter->addListener(this,sw);
+		led_id=motman->addPersistentMotion(SharedObject<LedMC>());
+		motman->addPrunableMotion(SharedObject<PostureMC>("stand.pos"));
+	}
+	virtual void DoStop() {
+		motman->removeMotion(led_id);
+		erouter->removeListener(this);
+		BehaviorBase::DoStop();
+	}
+	virtual void processEvent(const EventBase& e) {
+		if(e==inc) {
+			MMAccessor<LedMC>(led_id)->displayNumber(++cnt,style);
+		} else if(e==dec) {
+			MMAccessor<LedMC>(led_id)->displayNumber(--cnt,style);
+		} else if(e==sw) {
+			style = (style==LedEngine::onedigit ? LedEngine::twodigit : LedEngine::onedigit);
+			MMAccessor<LedMC>(led_id)->displayNumber(cnt,style);
+		}			
+	}
+
+	static std::string getClassDescription() { return "Counts with LEDs on back button presses"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+
+protected:
+	EventBase inc,dec,sw;
+	LedEngine::numStyle_t style;
+	int cnt;
+	MotionManager::MC_ID led_id;
+};
+
+/*! @file
+ * @brief Defines LEDCounterBehavior, which counts with LEDs on back button presses
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/LogTestMachine.h ./Behaviors/Demos/LogTestMachine.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/LogTestMachine.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Demos/LogTestMachine.h	2006-09-18 14:07:57.000000000 -0400
@@ -0,0 +1,147 @@
+//-*-c++-*-
+#ifndef INCLUDED_LogTestMachine_h_
+#define INCLUDED_LogTestMachine_h_
+
+#include "Behaviors/StateNode.h"
+#include "Behaviors/Nodes/LedNode.h"
+#include "Behaviors/Controls/EventLogger.h"
+#include "Shared/ProjectInterface.h"
+#include "Behaviors/Transitions/TextMsgTrans.h"
+#include "Behaviors/Transitions/NullTrans.h"
+#include "Vision/JPEGGenerator.h"
+
+//! a class for testing the image logging facilities
+class ImageLogTestNode : public LedNode {
+public:
+	//!constructor
+	ImageLogTestNode(std::string name, int n)
+		: LedNode("ImageLogTestNode",name)
+	{
+		getMC()->displayNumber(n,LedEngine::onedigit);
+	}
+	virtual void DoStart() {
+		LedNode::DoStart();
+		EventLogger::logImage(*ProjectInterface::defColorJPEGGenerator,ProjectInterface::fullLayer,0,this);
+		sndman->playFile("camera.wav");
+	}
+};
+
+//! a class for testing the text message logging facilities
+class MessageLogTestNode : public LedNode {
+public:
+	//!constructor
+	MessageLogTestNode(std::string name, int n)
+		: LedNode("MessageLogTestNode",name)
+	{
+		getMC()->displayNumber(n,LedEngine::onedigit);
+	}
+	virtual void DoStart() {
+		LedNode::DoStart();
+		EventLogger::logMessage("Hello World!",this); //icon and placement arguments also available
+	}
+};
+
+//! a class for testing the external camera request facilities
+class WebcamLogTestNode : public LedNode {
+public:
+	//!constructor
+	WebcamLogTestNode(std::string name, int n)
+		: LedNode("WebcamLogTestNode",name)
+	{
+		getMC()->displayNumber(n,LedEngine::onedigit);
+	}
+	virtual void DoStart() {
+		LedNode::DoStart();
+		EventLogger::logWebcam(this);
+	}
+};
+
+
+//! tests different methods of the state machine viewer logging facilities
+class LogTestMachine : public StateNode {
+
+	// ****************************
+	// ******* CONSTRUCTORS *******
+	// ****************************
+public:
+	//! default constructor, use type name as instance name
+	LogTestMachine()
+		: StateNode("LogTestMachine","LogTestMachine"), start(NULL)
+	{}
+
+	//! constructor, take an instance name
+	LogTestMachine(const std::string& nm)
+		: StateNode("LogTestMachine",nm), start(NULL)
+	{}
+
+protected:
+  //! constructor for subclasses (which would need to provide a different class name)
+  LogTestMachine(const std::string &class_name, const std::string &node_name)
+    : StateNode(class_name,node_name), start(NULL)
+	{}
+	
+	
+	// ****************************
+	// ********* METHODS **********
+	// ****************************
+public:
+	virtual void setup() {
+		StateNode::setup(); 
+
+		//setup sub-nodes
+		start=addNode(new StateNode("Waiting"));
+		ImageLogTestNode * img_node=new ImageLogTestNode("Image",1); addNode(img_node);
+		MessageLogTestNode * msg_node=new MessageLogTestNode("Message",2); addNode(msg_node);
+		WebcamLogTestNode * webcam_node=new WebcamLogTestNode("Webcam",3); addNode(webcam_node);
+
+		//link with transitions
+		start->addTransition(new TextMsgTrans(img_node,"image"));
+		start->addTransition(new TextMsgTrans(msg_node,"message"));
+		start->addTransition(new TextMsgTrans(webcam_node,"webcam"));
+		img_node->addTransition(new NullTrans(start));
+		msg_node->addTransition(new NullTrans(start));
+		webcam_node->addTransition(new NullTrans(start));
+	}
+
+	virtual void DoStart() {
+		StateNode::DoStart(); // do this first (required)
+		start->DoStart();
+	}
+
+	static std::string getClassDescription() { return "Allows testing of various EventLogger facilities via text message events"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+
+
+	// ****************************
+	// ********* MEMBERS **********
+	// ****************************
+protected:
+	StateNode * start; //!< the subnode to begin within on DoStart()
+
+
+	// ****************************
+	// ********** OTHER ***********
+	// ****************************
+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)
+	LogTestMachine(const LogTestMachine&); //!< don't call (copy constructor)
+	LogTestMachine& operator=(const LogTestMachine&); //!< don't call (assignment operator)
+};
+
+
+/*! @file
+ * @brief Defines LogTestMachine, which allows testing of various EventLogger facilities via text message events
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/LookAtPointBehavior.h ./Behaviors/Demos/LookAtPointBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/LookAtPointBehavior.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Demos/LookAtPointBehavior.h	2006-09-22 12:59:27.000000000 -0400
@@ -0,0 +1,91 @@
+//-*-c++-*-
+#ifndef INCLUDED_LookAtPointBehavior_h_
+#define INCLUDED_LookAtPointBehavior_h_
+
+#include "Behaviors/BehaviorBase.h"
+#include "Motion/HeadPointerMC.h"
+#include "Motion/Kinematics.h"
+#include "Motion/MotionManager.h"
+#include "Shared/newmat/newmat.h"
+
+//! A simple behavior to see how well LookAtPoint (inverse kinematics) is working
+//! You may want to uncomment cout's in HeadPointer::LooAtPoint before running Behavior
+class LookAtPointBehavior : public BehaviorBase {
+ public:
+  
+  LookAtPointBehavior() : 
+    BehaviorBase("LookAtPointBehavior"), 
+    pointer_id(MotionManager::invalid_MC_ID), gazePt(500,0,0) { srand(clock()); }
+
+  virtual void DoStart() {
+    cout << "LookAtPointBehavior:DoStart()\n";
+    BehaviorBase::DoStart();
+    pointer_id = motman->addPersistentMotion(SharedObject<HeadPointerMC>());
+    erouter->addListener(this, EventBase::motmanEGID, pointer_id, EventBase::statusETID);
+    erouter->addTimer(this, 0, 1000, false);
+  }
+  virtual void DoStop() {
+    motman->removeMotion(pointer_id);
+    erouter->removeListener(this);
+    BehaviorBase::DoStop();
+  }
+
+  virtual void processEvent(const EventBase& e) {
+    switch (e.getGeneratorID()) {
+    case EventBase::motmanEGID:
+      if (e.getSourceID() == pointer_id) {
+	erouter->addTimer(this, 0, 1000, false); // wait 1 sec for joints to stablize
+      }
+      break;
+    case EventBase::timerEGID:
+      if (e.getSourceID() == 0) {
+	NEWMAT::ColumnVector down=Kinematics::pack(state->sensors[BAccelOffset],
+						   -state->sensors[LAccelOffset],
+						   state->sensors[DAccelOffset]);
+	NEWMAT::ColumnVector p=kine->calculateGroundPlane(down);
+	
+	NEWMAT::ColumnVector ray(4); ray(1)=ray(2)=0; ray(3)=ray(4)=1;
+	NEWMAT::ColumnVector hit;
+	hit=kine->projectToPlane(CameraFrameOffset,ray,BaseFrameOffset,p,BaseFrameOffset);
+
+	NEWMAT::ColumnVector groundPt = Kinematics::pack(gazePt.coordX(),gazePt.coordY(),gazePt.coordZ());
+	NEWMAT::ColumnVector camPt = (kine->baseToJoint(CameraFrameOffset))*groundPt;
+	groundPt = kine->projectToPlane(CameraFrameOffset,camPt,BaseFrameOffset,p,BaseFrameOffset);
+	float theta = acos(camPt(3)/sqrt(camPt(1)*camPt(1)+camPt(2)*camPt(2)+camPt(3)*camPt(3)));
+	cout << "Result:\n Cam Center projected to GroundPlane: " << Point(hit(1),hit(2),hit(3)) << endl;
+	cout << " Gaze Point projected to GroundPlane: " << Point(groundPt(1),groundPt(2),groundPt(3)) << endl;
+	cout << " Gaze Point in CameraPlane: " << Point(camPt(1),camPt(2),camPt(3)) << endl;
+	cout << " theta: " << mathutils::rad2deg(theta) << " degrees\n";
+
+	gazePt.setCoords(rand()%1000-200, rand()%1000-500, rand()%400-200); //set next gaze point
+	erouter->addTimer(this, 1, 4000, false);
+      }
+      else {
+	cout << "\n\n\nLookAtPoint: " << gazePt << endl;
+	bool b = MMAccessor<HeadPointerMC>(pointer_id)->lookAtPoint(gazePt.coordX(), gazePt.coordY(), gazePt.coordZ());
+	cout << " => " << (b ? "Reachable" : "Unreachable") << endl;
+      }
+      break;
+    default:
+      cout << "LookAtPointBehavior::ProcessEvent(): unknown event\n";
+      break;
+    };
+  }
+  
+protected:
+  MotionManager::MC_ID pointer_id;
+  Point gazePt;
+};
+
+/*! @file
+* @brief Defines LookAtPointBehavior, moves the head through a series of gaze points and reports if each is reachable to test inverse kinematic's lookAtPoint
+* @author dst (Creator)
+*
+* $Author: ejt $
+* $Name: HEAD $
+* $Revision: 1.1 $
+* $State: Exp $
+* $Date: 2006/10/04 04:21:12 $
+*/
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/PaceTargetsMachine.cc ./Behaviors/Demos/PaceTargetsMachine.cc
--- ../Tekkotsu_2.4.1/Behaviors/Demos/PaceTargetsMachine.cc	2005-08-03 15:11:58.000000000 -0400
+++ ./Behaviors/Demos/PaceTargetsMachine.cc	2006-09-18 14:07:57.000000000 -0400
@@ -60,10 +60,10 @@
 	tmptrans->setSound("barkmed.wav");
 	
 	//preload the sounds so we don't pause on tranisitions
-	sndman->LoadFile("cutey.wav");
-	sndman->LoadFile("barkmed.wav");
-	sndman->LoadFile("whimper.wav");
-	sndman->LoadFile("fart.wav");
+	sndman->loadFile("cutey.wav");
+	sndman->loadFile("barkmed.wav");
+	sndman->loadFile("whimper.wav");
+	sndman->loadFile("fart.wav");
 
 	//starts out exploring
 	start=explGrp;
@@ -76,10 +76,10 @@
 
 void PaceTargetsMachine::teardown() {
 	//release the sounds
-	sndman->ReleaseFile("cutey.wav");
-	sndman->ReleaseFile("barkmed.wav");
-	sndman->ReleaseFile("whimper.wav");
-	sndman->ReleaseFile("fart.wav");
+	sndman->releaseFile("cutey.wav");
+	sndman->releaseFile("barkmed.wav");
+	sndman->releaseFile("whimper.wav");
+	sndman->releaseFile("fart.wav");
 	StateNode::teardown();
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/RegionTestBehavior.h ./Behaviors/Demos/RegionTestBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/RegionTestBehavior.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Demos/RegionTestBehavior.h	2006-02-07 14:45:00.000000000 -0500
@@ -0,0 +1,53 @@
+//-*-c++-*-
+#ifndef INCLUDED_RegionTestBehavior_h_
+#define INCLUDED_RegionTestBehavior_h_
+
+#include "Behaviors/BehaviorBase.h"
+#include "Events/EventRouter.h"
+#include "Shared/ProjectInterface.h"
+#include "Vision/RegionGenerator.h"
+#include "Vision/SegmentedColorGenerator.h"
+
+//! Outputs some basic region statistics regarding the current frame to the console (and then stops again)
+class RegionTestBehavior : public BehaviorBase {
+public:
+	//! constructor
+	RegionTestBehavior() : BehaviorBase("RegionTest") {}
+	
+	virtual void DoStart() {
+		BehaviorBase::DoStart(); //always do first
+		
+		//long line: get the regions from the default region generator		//have to cast it to the type actually returned by the generator in question (see documentation)		RegionGenerator::region_stats * regions=(RegionGenerator::region_stats*)ProjectInterface::defRegionGenerator->getImage(ProjectInterface::fullLayer,0);
+		unsigned int num_colors=ProjectInterface::defSegmentedColorGenerator->getNumColors();
+		
+		//do some processing on the regions		for(unsigned int i=0; i<num_colors; i++) {
+		
+			std::cout << "There are " << regions[i].num << " " << regions[i].name << " regions:" << std::endl;
+			
+			if(regions[i].num>0 && regions[i].list!=NULL) { //really only need to check one
+				//region list is sorted by size, so first entry (if list isn't empty) is the largest:
+				std::cout << "\tlargest region has area " << regions[i].list->area << std::endl;
+				//but you might prefer the total size of all regions of that color:				std::cout << "\ttotal area is " << regions[i].total_area << std::endl;
+			}		}
+		
+		//just do it once for the current frame at launch, now stop again
+		DoStop();
+	}
+
+	static std::string getClassDescription() { return "Outputs some basic region statistics regarding the current frame to the console (and then stops again)"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+	
+};
+
+/*! @file
+ * @brief Defines RegionTestBehavior, which outputs some basic region statistics to the console
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/SoundTestBehavior.h ./Behaviors/Demos/SoundTestBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/SoundTestBehavior.h	2005-06-01 01:47:45.000000000 -0400
+++ ./Behaviors/Demos/SoundTestBehavior.h	2006-09-18 14:07:57.000000000 -0400
@@ -43,18 +43,18 @@
 	virtual void DoStart() {
 		BehaviorBase::DoStart();
 		erouter->addListener(this,EventBase::buttonEGID);
-		sndman->LoadFile("yap.wav");
-		sndman->LoadFile("howl.wav");
-		sndman->LoadFile("whimper.wav");
+		sndman->loadFile("yap.wav");
+		sndman->loadFile("howl.wav");
+		sndman->loadFile("whimper.wav");
 	}
 
 	//! Release sounds we loaded in DoStart()
 	virtual void DoStop() {
 		BehaviorBase::DoStop();
 		erouter->removeListener(this);
-		sndman->ReleaseFile("howl.wav");
-		sndman->ReleaseFile("yap.wav");
-		sndman->ReleaseFile("whimper.wav");
+		sndman->releaseFile("howl.wav");
+		sndman->releaseFile("yap.wav");
+		sndman->releaseFile("whimper.wav");
 	}
 
 	//! Play the sound corresponding to the button
@@ -75,7 +75,7 @@
 				curplay=SoundManager::invalid_Play_ID;
 				endtime=0;
 			} else if(pauseWhileChin)
-				sndman->ResumePlay(curplay);
+				sndman->resumePlay(curplay);
 	}
 
 	//! returns name to system
@@ -89,20 +89,20 @@
 
 			// Just play the sound
 			// This is probably all you need how to do unless you want to get fancy
-			sndman->PlayFile(name);
+			sndman->playFile(name);
 
 		} else {
 
 			// Enqueue the sound - mainly useful if you have a set of sounds and want to play a song with them
 			if(curplay==SoundManager::invalid_Play_ID || !pauseWhileChin && get_time()>=endtime) {
 				//start a new chain, either this is the first or we already finished playing the chain
-				curplay=sndman->PlayFile(name);
+				curplay=sndman->playFile(name);
 				if(pauseWhileChin)
-					sndman->PausePlay(curplay);
+					sndman->pausePlay(curplay);
 			} else //add to existing chain
-				sndman->ChainFile(curplay,name);
-			endtime=sndman->GetRemainTime(curplay)+get_time()-SoundBufferTime;
-			//-SoundBufferTime to guarrantee ID validity, see SoundManager::GetRemainTime() documentation
+				sndman->chainFile(curplay,name);
+			endtime=sndman->getRemainTime(curplay)+get_time()-SoundBufferTime;
+			//-SoundBufferTime to guarrantee ID validity, see SoundManager::getRemainTime() documentation
 
 		}
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/StareAtBallBehavior.cc ./Behaviors/Demos/StareAtBallBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Demos/StareAtBallBehavior.cc	2005-06-01 01:47:45.000000000 -0400
+++ ./Behaviors/Demos/StareAtBallBehavior.cc	2006-09-26 17:47:00.000000000 -0400
@@ -3,6 +3,7 @@
 #include "Events/VisionObjectEvent.h"
 #include "Shared/WorldState.h"
 #include "Motion/HeadPointerMC.h"
+#include "Motion/MMAccessor.h"
 #include "Shared/ProjectInterface.h"
 
 //! Converts degrees to radians
@@ -22,33 +23,29 @@
 
 //this could be cleaned up event-wise (only use a timer when out of view)
 void StareAtBallBehavior::processEvent(const EventBase& event) {
-	/*if(event.getSourceID()==ProjectInterface::visBlueBallSID) {
-		cout << "BLUE" << endl;
-		} else if(event.getSourceID()==ProjectInterface::visPinkBallSID) {
-		cout << "PINK" << endl;
-		}
-	*/
-
-	static float horiz=0,vert=0;
+	float horiz=0,vert=0;
 	if(event.getGeneratorID()==EventBase::visObjEGID && event.getTypeID()==EventBase::statusETID) {
-		horiz=static_cast<const VisionObjectEvent*>(&event)->getCenterX();
-		vert=static_cast<const VisionObjectEvent*>(&event)->getCenterY();
+		const VisionObjectEvent& objev=static_cast<const VisionObjectEvent&>(event);
+		horiz=objev.getCenterX();
+		vert=objev.getCenterY();
 	}
 
 	//cout << horiz << ' ' << vert << endl;
 
-	// Very simple visual servoing control -- move the head in the direction of the target
+	// 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;
-	HeadPointerMC * headpointer= (HeadPointerMC*)motman->checkoutMotion(headpointer_id);
-#ifdef TGT_ERS7
-	//on an ers-7, we want to set the nod joint to look up, 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);
-#endif
-	motman->checkinMotion(headpointer_id);
+	
+	// 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) {
+		//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);
+	}
 }
 			
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/TestBehaviors.cc ./Behaviors/Demos/TestBehaviors.cc
--- ../Tekkotsu_2.4.1/Behaviors/Demos/TestBehaviors.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Demos/TestBehaviors.cc	2006-09-18 14:07:57.000000000 -0400
@@ -0,0 +1,53 @@
+#include "TestBehaviors.h"
+#include "Vision/PNGGenerator.h"
+#include "Sound/SoundManager.h"
+#include <errno.h>
+
+//better to put this here instead of the header
+using namespace std; 
+
+void SaveImagePyramidBehavior::saveImage(unsigned int layer, unsigned int chan, const std::string& name) {
+	const unsigned int MAXPATH=128;
+	char fname[MAXPATH];
+	snprintf(fname,MAXPATH,name.c_str(),layer);
+	FILE * f=fopen(fname,"w+");
+	if(f==NULL) {
+		int err=errno;
+		serr->printf("Error opening file %s: %s\n",fname,strerror(err));
+		sndman->playFile(config->controller.error_snd);
+		return;
+	}
+	PNGGenerator * gen=dynamic_cast<PNGGenerator*>(ProjectInterface::defGrayscalePNGGenerator);
+	unsigned char * img=gen->getImage(layer,chan);
+	if(!gen->getImageCached(layer,chan)) {
+		serr->printf("A PNG encoding error occurred whiel saving file %s\n",fname);
+		sndman->playFile(config->controller.error_snd);
+		//return;
+	}
+	unsigned int size=gen->getImageSize(layer,chan);
+	unsigned int writ=fwrite(img,size,1,f);
+	if(writ==0) {
+		int err=errno;
+		serr->printf("Error saving file %s: %s\n",fname,strerror(err));
+		sndman->playFile(config->controller.error_snd);
+		return;
+	}
+	if(fclose(f)!=0) {
+		int err=errno;
+		serr->printf("Error closing file %s: %s\n",fname,strerror(err));
+		sndman->playFile(config->controller.error_snd);
+		return;
+	}
+	sout->printf("Saved %s\n",fname);
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/TestBehaviors.h ./Behaviors/Demos/TestBehaviors.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/TestBehaviors.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Demos/TestBehaviors.h	2006-09-05 15:40:07.000000000 -0400
@@ -0,0 +1,107 @@
+//-*-c++-*-
+#ifndef INCLUDED_TestBehaviors_h_
+#define INCLUDED_TestBehaviors_h_
+
+#include "Behaviors/BehaviorBase.h"
+#include "Events/EventRouter.h"
+#include "Events/TextMsgEvent.h"
+#include "Motion/MotionManager.h"
+#include "Motion/PostureMC.h"
+#include "Shared/ProjectInterface.h"
+#include "Vision/RawCameraGenerator.h"
+#include "Shared/Config.h"
+
+//! Adds a MotionCommand and then immediately removes it again
+class InstantMotionTestBehavior : public BehaviorBase {
+public:
+	InstantMotionTestBehavior() : BehaviorBase("InstantMotionTestBehavior") {} //!< constructor
+	virtual void DoStart() { BehaviorBase::DoStart(); motman->removeMotion(motman->addPersistentMotion(SharedObject<PostureMC>())); DoStop(); }
+	static std::string getClassDescription() { return "Adds a MotionCommand and then immediately removes it again"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+};
+
+//! When started, busy loops for 3 seconds and then stops
+class BusyLoopTestBehavior : public BehaviorBase {
+public:
+	BusyLoopTestBehavior() : BehaviorBase("BusyLoopTestBehavior") {} //!< constructor
+	virtual void DoStart() { BehaviorBase::DoStart(); unsigned int t=get_time(); while(get_time()-t<3000) {} DoStop(); }
+	static std::string getClassDescription() { return "When started, busy loops for 3 seconds and then stops"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+};
+
+//! Adds a MotionCommand which will busy loop for 3 seconds on its first update, and then autoprune
+class BusyMCTestBehavior : public BehaviorBase {
+	//! on first updateOutputs, blocks for 3 seconds, then autoprunes on second update
+	class BusyMC : public MotionCommand {
+		bool hasRun;
+	public:
+		BusyMC() : MotionCommand(), hasRun(false) {} //!< constructor
+		virtual int updateOutputs() {unsigned int t=get_time(); while(get_time()-t<3000) {} hasRun=true; return 0; }
+		virtual int isDirty() { return true; }
+		virtual int isAlive() { return !hasRun; }
+	};
+public:
+	BusyMCTestBehavior() : BehaviorBase("BusyMCTestBehavior") {} //!< constructor
+	virtual void DoStart() { BehaviorBase::DoStart(); motman->addPrunableMotion(SharedObject<BusyMC>()); DoStop(); }
+	static std::string getClassDescription() { return "Adds a MotionCommand which will busy loop for 3 seconds on its first update, and then autoprune"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+};
+
+//! Stops itself after a second via timer event
+class SuicidalBehavior : public BehaviorBase {
+public:
+	SuicidalBehavior() : BehaviorBase("SuicidalBehavior") {} //!< constructor
+	~SuicidalBehavior() { std::cout << getName() << " destructed" << 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"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+};
+
+//! Echos any text message events received to the console (doesn't add a listener, relies on direct BehaviorSwitchControl passing)
+class EchoTextBehavior : public BehaviorBase {
+public:
+	EchoTextBehavior() : BehaviorBase("EchoTextBehavior") {} //!< constructor
+	virtual void processEvent(const EventBase& event) { if(const TextMsgEvent* tev=dynamic_cast<const TextMsgEvent*>(&event)) std::cout << tev->getText() << std::endl; else std::cout << getName() << " got a non-TextMsgEvent" << std::endl; }
+	static std::string getClassDescription() { return "Echos any text message events received to the console (doesn't add a listener, relies on direct BehaviorSwitchControl passing)"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+};
+
+//! Saves all images currently provided by the hardware to a series of PNG files on the memory stick
+/*! Handy for examining the different channels/resolution levels provided by the system, all based on the same input */
+class SaveImagePyramidBehavior : public BehaviorBase {
+public:
+	SaveImagePyramidBehavior() : BehaviorBase("SaveImagePyramidBehavior") {} //!< constructor
+	virtual void DoStart() { BehaviorBase::DoStart(); erouter->addListener(this,EventBase::textmsgEGID); }
+	virtual void processEvent(const EventBase& event) {
+		if(const TextMsgEvent* tev=dynamic_cast<const TextMsgEvent*>(&event)) {
+			std::string prefix=config->portPath(tev->getText().substr(0,4));
+			saveImage(ProjectInterface::doubleLayer,RawCameraGenerator::CHAN_Y,prefix+"%dy.png");
+			for(unsigned int layer=ProjectInterface::fullLayer; layer>=ProjectInterface::quarterLayer; layer--) {
+				saveImage(layer,RawCameraGenerator::CHAN_Y,prefix+"%dy.png");
+				saveImage(layer,RawCameraGenerator::CHAN_U,prefix+"%du.png");
+				saveImage(layer,RawCameraGenerator::CHAN_V,prefix+"%dv.png");
+				saveImage(layer,RawCameraGenerator::CHAN_Y_DX,prefix+"%ddx.png");
+				saveImage(layer,RawCameraGenerator::CHAN_Y_DY,prefix+"%ddy.png");
+				saveImage(layer,RawCameraGenerator::CHAN_Y_DXDY,prefix+"%ddxy.png");
+			}
+		} else std::cout << getName() << " got a non-TextMsgEvent" << std::endl;
+	}
+	static std::string getClassDescription() { return "Saves all images currently provided by the hardware to a series of PNG files on the memory stick"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+protected:
+	void saveImage(unsigned int layer, unsigned int chan, const std::string& name);
+};
+
+/*! @file
+ * @brief A collection of small test behaviors (some would call them unit tests)
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/WallTestBehavior.cc ./Behaviors/Demos/WallTestBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Demos/WallTestBehavior.cc	2005-06-01 01:47:45.000000000 -0400
+++ ./Behaviors/Demos/WallTestBehavior.cc	2006-07-13 13:25:50.000000000 -0400
@@ -7,6 +7,7 @@
 #include "Shared/Config.h"
 #include "Shared/WorldState.h"
 #include "Shared/newmat/newmatio.h"
+#include "Shared/TimeET.h"
 #include <fstream>
 
 void
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Demos/WorldStateVelDaemon.h ./Behaviors/Demos/WorldStateVelDaemon.h
--- ../Tekkotsu_2.4.1/Behaviors/Demos/WorldStateVelDaemon.h	2005-06-29 18:00:03.000000000 -0400
+++ ./Behaviors/Demos/WorldStateVelDaemon.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,95 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_WorldStateVelDaemon_h_
-#define INCLUDED_WorldStateVelDaemon_h_
-
-#include "Behaviors/BehaviorBase.h"
-#include "Events/EventRouter.h"
-#include "Events/LocomotionEvent.h"
-#include "Shared/WorldState.h"
-#include "Events/EventTrapper.h"
-
-//! Listens for LocomotionEvents and updates the velocity fields of WorldState
-/*! If we get multiple ways of locomoting, this would be a good place
- *  to manage them to determine the actual final velocity.
- *
- *  Right now it'll correctly handle one (or more i suppose) e-stops
- *  with a single other locomotor.  But if there's two active
- *  locomotors, I dunno how to handle that.
- */
-class WorldStateVelDaemon : public BehaviorBase, public EventTrapper {
-public:
-	//! constructor
-	WorldStateVelDaemon() : BehaviorBase("WorldStateVelDaemon"), estopTime(1), old_x(0), old_y(0), old_a(0) {}
-
-	virtual void DoStart() {
-		BehaviorBase::DoStart(); // do this first
-		erouter->addTrapper(this,EventBase::locomotionEGID);
-		erouter->addListener(this,EventBase::estopEGID);
-	}
-
-	virtual void DoStop() {
-		erouter->removeListener(this);
-		erouter->removeTrapper(this);
-		BehaviorBase::DoStop(); // do this last
-	}
-
-	//! traps locomotion events - will filter them out if currently in EStop
-	virtual bool trapEvent(const EventBase& e) {
-		const LocomotionEvent& le=dynamic_cast<const LocomotionEvent&>(e);
-		old_x=le.x;
-		old_y=le.y;
-		old_a=le.a;
-		if(!estopTime) {
-			state->vel_x=le.x;
-			state->vel_y=le.y;
-			state->vel_a=le.a;
-			state->vel_time=le.getTimeStamp();
-			return false;
-		}
-		return true;
-	}
-
-	virtual void processEvent(const EventBase& e) {
-		if(e.getTypeID()==EventBase::deactivateETID) {
-			if(estopTime) {
-				estopTime=0;
-				LocomotionEvent *le = new LocomotionEvent(EventBase::locomotionEGID,e.getSourceID(),EventBase::statusETID,e.getTimeStamp()-state->vel_time);
-				le->setXYA(old_x,old_y,old_a);
-				erouter->postEvent(le);
-			}
-		} else {
-			if(!estopTime) {
-				float older_x=old_x;
-				float older_y=old_y;
-				float older_a=old_a;
-				erouter->postEvent(new LocomotionEvent(EventBase::locomotionEGID,e.getSourceID(),EventBase::statusETID,e.getTimeStamp()-state->vel_time));
-				estopTime=e.getTimeStamp();
-				old_x=older_x;
-				old_y=older_y;
-				old_a=older_a;
-			}
-		}
-	}
-
-	static std::string getClassDescription() { return "Keeps the WorldState's velocity fields up to date"; }
-	virtual std::string getDescription() const { return getClassDescription(); }
-	
-protected:
-	unsigned int estopTime; //!< time estop activation was received
-	float old_x; //!< current velocity of underlying locomotor
-	float old_y; //!< current velocity of underlying locomotor
-	float old_a; //!< current velocity of underlying locomotor
-};
-
-/*! @file
- * @brief Defines WorldStateVelDaemon, which listens for LocomotionEvents and updates the velocity fields of WorldState
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/Aibo3DControllerBehavior.cc ./Behaviors/Mon/Aibo3DControllerBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Mon/Aibo3DControllerBehavior.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Mon/Aibo3DControllerBehavior.cc	2006-08-03 18:58:39.000000000 -0400
@@ -0,0 +1,35 @@
+#include "Aibo3DControllerBehavior.h"
+#include "Behaviors/Controls/BehaviorSwitchControl.h"
+
+BehaviorSwitchControlBase* Aibo3DControllerBehavior::stateSerializerControl=NULL;
+
+void Aibo3DControllerBehavior::DoStart() {
+	// Behavior startup
+	BehaviorBase::DoStart();
+	
+	launchedSerializer=false;
+	if(stateSerializerControl!=NULL) {
+		if(!stateSerializerControl->isRunning()) {
+			stateSerializerControl->start();
+			launchedSerializer=true;
+		}
+		// open gui
+		/*		std::vector<std::string> tmp;
+		tmp.push_back("Aibo3D Load Instructions");
+		tmp.push_back("To load Aibo3D, you will need to install java3d\nand then run Tekkotsu/tools/aibo3d/");
+		tmp.back()+=getGUIType();
+		Controller::loadGUI("ControllerMsg","LoadAibo3d",getPort(),tmp);*/
+	}
+	
+	Controller::loadGUI(getGUIType(),getGUIType(),getPort());
+}
+
+void Aibo3DControllerBehavior::DoStop() {
+	Controller::closeGUI(getGUIType());
+	if(launchedSerializer && stateSerializerControl!=NULL) {
+		stateSerializerControl->stop();
+	}
+	// Total behavior stop
+	BehaviorBase::DoStop();
+}
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/Aibo3DControllerBehavior.h ./Behaviors/Mon/Aibo3DControllerBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Mon/Aibo3DControllerBehavior.h	2004-11-10 20:45:36.000000000 -0500
+++ ./Behaviors/Mon/Aibo3DControllerBehavior.h	2006-09-16 02:28:07.000000000 -0400
@@ -13,119 +13,46 @@
 #include "Behaviors/Controller.h"
 #include "Shared/WorldState.h"
 
-//! gets input from the GUI
-int aibo3dcontrollercmd_callback(char *buf, int bytes);
-class Aibo3DControllerBehavior;
 
-//! so aibo3dcontrollercmd_callback knows where to send the input from the GUI
-Aibo3DControllerBehavior *aibo3dControllerBehavior = NULL;
+class BehaviorSwitchControlBase;
+class Aibo3DControllerBehavior;
 
-  
 //! Listens to aibo3d control commands coming in from the command port.
 class Aibo3DControllerBehavior : public BehaviorBase {
- protected:
-	MotionManager::MC_ID rcontrol_id; //!< remote controller motion command's id
- 
-	//! The input command stream socket
-	Socket *cmdsock;
-
-  float val[NumPIDJoints]; //!< the value to use for each of the PID joints
-  char *fbuf;  //!< alias to val
-  unsigned int pos; //!< a counter to know when we've gotten 4 frames
-
  private:
 	Aibo3DControllerBehavior(const Aibo3DControllerBehavior&); //!< don't call
 	Aibo3DControllerBehavior operator=(const Aibo3DControllerBehavior&); //!< don't call
-
+	//! so we can start the serializer behavior if it's not already running
+	static BehaviorSwitchControlBase* stateSerializerControl;
+	//! if true, indicates we launched the WorldState serializer, so we should stop it again if we stop
+	bool launchedSerializer;
+	
  public:
 	//! constructor
-	Aibo3DControllerBehavior() :
-	  BehaviorBase("Aibo3DControllerBehavior"),
-	  rcontrol_id(MotionManager::invalid_MC_ID),
-	  cmdsock(NULL),
-    fbuf((char*)val), pos(0)
-	{ aibo3dControllerBehavior = this; }
+	Aibo3DControllerBehavior() : BehaviorBase("Aibo3DControllerBehavior"),launchedSerializer(false) { }
 	//! destructor
-	virtual ~Aibo3DControllerBehavior() { aibo3dControllerBehavior = NULL; }
-
-	//! processes input from the GUI
-  int registerData(char *buf, int bytes) {
-    int read=0;
-    while (read<bytes) {
-      fbuf[pos]=buf[read];
-			pos++;
-			read++;
-      if (pos==NumPIDJoints*sizeof(float)) {
-				updateRC();
-				pos=0;
-			}
-    }
-    return read;
-  }
+	virtual ~Aibo3DControllerBehavior() { }
 
-	//! sends the new joint commands to the motion command
-	void updateRC() {
-		RemoteControllerMC *rcontrol = (RemoteControllerMC*)motman->checkoutMotion(rcontrol_id);
-		for (unsigned int i=0; i<NumPIDJoints; i++)
-			rcontrol->cmds[i]=val[i];
-		rcontrol->setDirty();
-		motman->checkinMotion(rcontrol_id);
-	}
+	virtual void DoStart();
+	virtual void DoStop();
 	
-	virtual void DoStart() {
-		// Behavior startup
-		BehaviorBase::DoStart();
-		for(unsigned int i=0; i<NumPIDJoints; i++)
-			val[i]=state->outputs[i];
-		// Enable remote control stream
-		rcontrol_id = motman->addPersistentMotion(SharedObject<RemoteControllerMC>());
-		updateRC();
-		// Turn on wireless
-		cmdsock=wireless->socket(SocketNS::SOCK_STREAM, 2048, 2048);
-		wireless->setReceiver(cmdsock->sock, aibo3dcontrollercmd_callback);
-		wireless->setDaemon(cmdsock,true);
-		wireless->listen(cmdsock->sock, config->main.aibo3d_port);
-		// open gui
-		/*		std::vector<std::string> tmp;
-					tmp.push_back("Aibo3D Load Instructions");
-					tmp.push_back("To load Aibo3D, you will need to install java3d\nand then run Tekkotsu/tools/aibo3d/");
-					tmp.back()+=getGUIType();
-					Controller::loadGUI("ControllerMsg","LoadAibo3d",getPort(),tmp);*/
-		Controller::loadGUI(getGUIType(),getGUIType(),getPort());
-	}
-
-	virtual void DoStop() {
-		Controller::closeGUI(getGUIType());
-		// Close socket; turn wireless off
-		wireless->setDaemon(cmdsock,false);
-		wireless->close(cmdsock);
-		// Disable remote control
-		motman->removeMotion(rcontrol_id);
-		// Total behavior stop
-		BehaviorBase::DoStop();
-	}
-
 	//! returns string corresponding to the Java GUI which should be launched
-	virtual std::string getGUIType() const { return "org.tekkotsu.aibo3d.Aibo3DPick"; }
+	virtual std::string getGUIType() const { return "org.tekkotsu.aibo3d.Aibo3D"; }
 	//! returns port number the Java GUI should connect to
-	virtual unsigned int getPort() const { return config->main.aibo3d_port; }
+	virtual unsigned int getPort() const { return config->main.wsjoints_port; }
 
 	static std::string getClassDescription() { 
-		char tmp[20];
-		sprintf(tmp,"%d",config->main.aibo3d_port);
-		return std::string("Listens to aibo3d control commands coming in from port ")+tmp;
+		return "Launches a WorldStateSerializer and asks gui to load Aibo3D GUI";
+		//char tmp[20];
+		//sprintf(tmp,"%d",config->main.aibo3d_port);
+		//return std::string("Listens to aibo3d control commands coming in from port ")+tmp;
 	}
 	virtual std::string getDescription() const { return getClassDescription(); }
 
+	//! sets the BehaviorSwitchControlBase which should be used to activate the serialization of WorldState data for the Aibo3D client to read
+	static void setSerializerControl(BehaviorSwitchControlBase* ctrl) { stateSerializerControl=ctrl; }
 };
 
-
-int aibo3dcontrollercmd_callback(char *buf, int bytes) {
-  if (aibo3dControllerBehavior!=NULL)
-    return aibo3dControllerBehavior->registerData(buf, bytes);
-  return 0;
-}
-
 /*! @file
  * @brief Defines Aibo3DControllerBehavior, which listens to commands from the Aibo3D gui and shows current state
  * @author alokl (Creator)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/CameraStreamBehavior.cc ./Behaviors/Mon/CameraStreamBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Mon/CameraStreamBehavior.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Mon/CameraStreamBehavior.cc	2006-09-09 00:32:27.000000000 -0400
@@ -0,0 +1,103 @@
+#include "CameraStreamBehavior.h"
+#include "Wireless/Socket.h"
+#include "Motion/PostureEngine.h"
+#include "Events/EventRouter.h"
+#include "Shared/LoadSave.h"
+#include "Shared/Config.h"
+#include "Shared/WorldState.h"
+
+#if DEBUG
+void CameraStreamBehavior::processEvent(const EventBase& e) {
+	ASSERTRET(e.getGeneratorID()==EventBase::sensorEGID,"unexpected event");
+#else
+void CameraStreamBehavior::processEvent(const EventBase& /*e*/) {
+#endif
+		sendSensors();
+}
+
+int CameraStreamBehavior::receiveData(char* data, unsigned int len) {
+	std::string s(data,len);
+	//cout << "Console Received: " << s << endl;
+
+	static std::string incomplete;
+
+	//pass a line at a time to the controller
+	while(s.size()>0) {
+		std::string::size_type endline=s.find('\n');
+		if(endline==std::string::npos) {
+			incomplete+=s;
+			return 0;
+		}
+
+		//strip a \r\n or a \n
+		if(endline>0 && s[endline-1]=='\r')
+			incomplete+=s.substr(0,endline-1);
+		else
+			incomplete+=s.substr(0,endline);
+		
+		//is now complete
+		if(incomplete=="refreshSensors") {
+			sendSensors();
+		} else if(incomplete=="startSensors") {
+			if(sensorListeners++ == 0)
+				erouter->addListener(this,EventBase::sensorEGID);
+		} else if(incomplete=="stopSensors") {
+			if(sensorListeners==0)
+				serr->printf("WARNING: %s sensor listener underflow",getName().c_str());
+			else if(--sensorListeners == 0)
+				erouter->removeListener(this,EventBase::sensorEGID);
+		}
+		incomplete.erase();
+		s=s.substr(endline+1);
+	}
+	return 0;
+}
+
+void CameraStreamBehavior::sendSensors() {
+  if ((state->lastSensorUpdateTime - lastProcessedTime) < config->main.worldState_interval) // not enough time has gone by
+    return;
+  lastProcessedTime = state->lastSensorUpdateTime;
+
+	ASSERT(LoadSave::stringpad==sizeof(unsigned int)+sizeof(char),"LoadSave::encode(string) format has changed?");
+	PostureEngine pose;
+	pose.takeSnapshot();
+	pose.setWeights(1);
+	pose.setSaveFormat(true,state);
+	unsigned int len=pose.getBinSize()+LoadSave::stringpad;
+	byte* buf=curSocket->getWriteBuffer(len);
+	if(buf==NULL) {
+		serr->printf("Unable to serialize sensor data for camera image -- network overflow");
+		return;
+	}
+	unsigned int used;
+	if((used=pose.saveBuffer((char*)buf+sizeof(unsigned int),len-LoadSave::stringpad))==0) {
+		cerr << "An error occured during sensor serialization" << endl;
+		curSocket->write(0);
+		return;
+	}
+	if(used!=len-LoadSave::stringpad-1)
+		std::cout << "Warning: used==" << used << " len==" << len << std::endl;
+	//add the LoadSave fields (prepend length, append '\0')
+	len=LoadSave::encode(used,reinterpret_cast<char*>(buf),LoadSave::getSerializedSize(used));
+	if(len==0) {
+		cerr << "An error occured during serialization of buffer length" << endl;
+		curSocket->write(0);
+		return;
+	}
+	buf[used+sizeof(used)]='\0';
+	curSocket->write(used+LoadSave::stringpad);
+	//std::cout << "Sent sensors " << used << std::endl;
+}
+
+
+
+/*! @file
+ * @brief Defines CameraStreamBehavior, which is the base class for camera streaming communication classes, handles upstream communication
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/CameraStreamBehavior.h ./Behaviors/Mon/CameraStreamBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Mon/CameraStreamBehavior.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Mon/CameraStreamBehavior.h	2006-03-03 10:33:05.000000000 -0500
@@ -0,0 +1,68 @@
+//-*-c++-*-
+#ifndef INCLUDED_CameraStreamBehavior_h_
+#define INCLUDED_CameraStreamBehavior_h_
+
+#include "Behaviors/BehaviorBase.h"
+
+class Socket;
+
+//! Base class for camera streaming communication classes, handles upstream communication
+/*! This class isn't meant to be run directly -- it just provides common functionality for its subclasses. */
+class CameraStreamBehavior : public BehaviorBase {
+public:
+
+	virtual void processEvent(const EventBase& e);
+
+	static std::string getClassDescription() { return "Base class for camera streaming communication classes, handles upstream communication"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+	
+	int receiveData(char* data, unsigned int len); //!< called when new data is available (currently, only to toggle sensor sending)
+	
+	void sendSensors(); //!< causes current sensor values to be sent through #curSocket (along with video data)
+
+protected:
+	//! constructor, protected because you're not intended to instantiate this directly
+	/*! @param name the name of the instance and the class
+	 *  @param s the subclass's socket, a reference is stored so CameraStreamBehavior will always have access to the current socket */
+	CameraStreamBehavior(const std::string& name, Socket*& s)
+		: BehaviorBase(name), curSocket(s), sensorListeners(0), lastProcessedTime(0)
+	{}
+	//! constructor, protected because you're not intended to instantiate this directly
+	/*! @param classname the name of the class type
+	 *  @param name the name of the instance
+	 *  @param s the subclass's socket, a reference is stored so CameraStreamBehavior will always have access to the current socket */
+	CameraStreamBehavior(const std::string& classname, const std::string& name, Socket*& s)
+		: BehaviorBase(classname,name), curSocket(s), sensorListeners(0), lastProcessedTime(0)
+	{}
+
+	//! the socket over which to send updates
+	Socket*& curSocket;
+
+	//! number of times startSensors has been sent, minus number of times stopSensors has been sent
+	unsigned int sensorListeners;
+
+	//! timestamp of last sensor update sent
+	unsigned int lastProcessedTime;
+
+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)
+	CameraStreamBehavior(const CameraStreamBehavior&); //!< don't call (copy constructor)
+	CameraStreamBehavior& operator=(const CameraStreamBehavior&); //!< don't call (assignment operator)
+};
+
+/*! @file
+ * @brief Defines CameraStreamBehavior, which is the base class for camera streaming communication classes, handles upstream communication
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/EchoBehavior.h ./Behaviors/Mon/EchoBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Mon/EchoBehavior.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Behaviors/Mon/EchoBehavior.h	2006-09-16 02:28:07.000000000 -0400
@@ -9,7 +9,7 @@
 class EchoBehavior : public BehaviorBase {
 public:
 	static EchoBehavior * theOne; //!< the singleton object (only one of these objects can be active at a time or they would conflict over ports)
-	static unsigned short port; //! the port to listen on for incoming UDP and TCP connections
+	static unsigned short port; //!< the port to listen on for incoming UDP and TCP connections
 	static int server_callbackT(char *buf, int bytes); //!< called by wireless when there's new data
 	static int client_callbackT(char *buf, int bytes); //!< called by wireless when there's new data
 	static int server_callbackU(char *buf, int bytes); //!< called by wireless when there's new data
@@ -27,6 +27,7 @@
 				route[i][i]=true;				
 			}
 	}
+	//! destructor
 	~EchoBehavior() { theOne=NULL; }
 
 	virtual void DoStart();
@@ -41,6 +42,7 @@
 	virtual std::string getDescription() const { return getClassDescription(); }
 
 protected:
+	//! indicates one of the available data sinks: combinations of client/server and TCP/UDP
 	enum routeIndex_t {
 		STCP=0,  //!< server TCP
 		SUDP, //!< server UDP
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/HeadPointControllerBehavior.cc ./Behaviors/Mon/HeadPointControllerBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Mon/HeadPointControllerBehavior.cc	2005-06-10 15:18:59.000000000 -0400
+++ ./Behaviors/Mon/HeadPointControllerBehavior.cc	2006-09-10 13:00:43.000000000 -0400
@@ -6,18 +6,22 @@
 HeadPointControllerBehavior* HeadPointControllerBehavior::theOne = NULL;
 
 void HeadPointControllerBehavior::runCommand(unsigned char *command) {
-	// First, turn off the stop-if-no-heartbeat timer
-	erouter->removeTimer(this);
-
 	// Extract the command parameter
 	float param;
 	unsigned char *paramp = (unsigned char *) &param;
 
+#if defined(BYTE_ORDER) && BYTE_ORDER==BIG_ENDIAN
+	paramp[0] = command[4];
+	paramp[1] = command[3];
+	paramp[2] = command[2];
+	paramp[3] = command[1];
+#else
 	paramp[0] = command[1];
 	paramp[1] = command[2];
 	paramp[2] = command[3];
 	paramp[3] = command[4];
-
+#endif
+	
 	// Find out what type of command this is
 	switch(command[0]) {
 	case CMD_tilt:
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/HeadPointControllerBehavior.h ./Behaviors/Mon/HeadPointControllerBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Mon/HeadPointControllerBehavior.h	2005-06-10 15:18:59.000000000 -0400
+++ ./Behaviors/Mon/HeadPointControllerBehavior.h	2005-09-13 18:10:36.000000000 -0400
@@ -11,6 +11,17 @@
 #include "Shared/Config.h"
 
 //! Listens to control commands coming in from the command port for remotely controlling the head
+/*! The communication protocol is a very simple binary format, shared
+ *  with WalkControllerBehavior.  Each command is sent as a 5-byte
+ *  group.  The first byte is a command selector, and the following 4
+ *  bytes are a floating point argument:
+ *
+ *  - <@c char: command indicator>
+ *  - <@c float: value>
+ *  
+ *  The valid values for command indicator are given by #CMD_tilt,
+ *  #CMD_pan, or #CMD_roll ('t', 'p', or 'r' respectively).
+ */  
 class HeadPointControllerBehavior : public BehaviorBase {
 
  public:	
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/MicrophoneServer.h ./Behaviors/Mon/MicrophoneServer.h
--- ../Tekkotsu_2.4.1/Behaviors/Mon/MicrophoneServer.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Behaviors/Mon/MicrophoneServer.h	2006-09-16 13:32:38.000000000 -0400
@@ -16,23 +16,28 @@
 		virtual void DoStop();
 		virtual void processEvent(const EventBase& event);
 		
+		//! makes Aperios-specific call to set microphone mode
 		static bool SetMicrophoneUnidirectional(bool unidirectional);
+		//! makes Aperios-specific call to set microphone mode
 		static bool SetMicrophoneAlcEnabled(bool enabled);
 		
 	private:
+		//! max transmission buffer size for #socket
 		static const unsigned int SEND_BUFFER_SIZE = 2048 + 16;
 	
 		MicrophoneServer(); //!< constructor
 		MicrophoneServer(const MicrophoneServer& rhs); //!< don't call
 		MicrophoneServer& operator=(const MicrophoneServer& rhs); //!< don't call
-		static MicrophoneServer* instance;
+		static MicrophoneServer* instance; //!< global instance of the server
 		
+		//! returns size of a "frame" at the given sampling rate and resolution
 		unsigned int GetResampledFrameSize(
 			unsigned int samplesSize,
 			unsigned int newSampleRate,
 			unsigned int newSampleBits,
 			bool newStereo);
 		
+		//! performs sampling to a specified rate and resolution, stores into @a newSamples (which you must allocate)
 		unsigned int ResampleFrame(
 			const char* samples,
 			unsigned int samplesSize,
@@ -42,8 +47,10 @@
 			void* newSamples,
 			unsigned int newSamplesSize);
 		
+		//! aperios specific identifier for microphone access
 		static const char* const MIC_LOCATOR;
 		
+		//! socket for communication
 		class Socket *socket;
 		
 		//! writes @a value to @a dst and advances @a dst
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/RawCamBehavior.cc ./Behaviors/Mon/RawCamBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Mon/RawCamBehavior.cc	2005-07-29 14:35:05.000000000 -0400
+++ ./Behaviors/Mon/RawCamBehavior.cc	2006-09-14 14:57:03.000000000 -0400
@@ -7,35 +7,19 @@
 #include "Behaviors/Controller.h"
 #include "Shared/ProjectInterface.h"
 
+RawCamBehavior* RawCamBehavior::theOne=NULL;
+
 RawCamBehavior::RawCamBehavior()
-	: BehaviorBase("RawCamBehavior"), visRaw(NULL), packet(NULL), cur(NULL), avail(0), max_buf(0), lastProcessedTime(0)
-{}
+	: CameraStreamBehavior("RawCamBehavior",visRaw), visRaw(NULL), packet(NULL), cur(NULL), avail(0), max_buf(0), lastProcessedTime(0)
+{
+	ASSERT(theOne==NULL,"there was already a RawCamBehavior running!");
+	theOne=this;
+}
 
 void
 RawCamBehavior::DoStart() {
 	BehaviorBase::DoStart();
-	std::vector<std::string> args;
-	args.push_back("raw");
-	char port[50];
-	snprintf(port,50,"%d",config->vision.rawcam_port);
-	args.push_back(port);
-	if(config->vision.rawcam_transport==0) {
-		max_buf=UDP_WIRELESS_BUFFER_SIZE;
-		visRaw=wireless->socket(SocketNS::SOCK_DGRAM, 1024, max_buf);
-		args.push_back("udp");
-	} else if(config->vision.rawcam_transport==1) {
-		max_buf=TCP_WIRELESS_BUFFER_SIZE;
-		visRaw=wireless->socket(SocketNS::SOCK_STREAM, 1024, max_buf);
-		wireless->setDaemon(visRaw,true);
-		args.push_back("tcp");
-	} else {
-		serr->printf("ERROR: Invalid Config::vision.rawcam_transport: %d\n",config->vision.rawcam_transport);
-		return;
-	}
-	wireless->listen(visRaw,config->vision.rawcam_port);
-	
-	Controller::loadGUI("org.tekkotsu.mon.VisionGUI","RawVisionGUI",config->vision.rawcam_port,args);
-
+	setupServer();
 	erouter->addListener(this,EventBase::visRawCameraEGID,ProjectInterface::visRawCameraSID,EventBase::deactivateETID);
 	erouter->addListener(this,EventBase::visJPEGEGID,ProjectInterface::visColorJPEGSID,EventBase::deactivateETID);
 	erouter->addListener(this,EventBase::visJPEGEGID,ProjectInterface::visGrayscaleJPEGSID,EventBase::deactivateETID);
@@ -44,14 +28,7 @@
 void
 RawCamBehavior::DoStop() {
 	erouter->removeListener(this);
-	if(wireless->isConnected(visRaw->sock))
-		sendCloseConnectionPacket();
-	Controller::closeGUI("RawVisionGUI");
-
-	// this could be considered a bug in our wireless - if we don't setDaemon(...,false)
-	// it will try to listen again even though we explicitly closed the server socket...
-	wireless->setDaemon(visRaw,false);
-	wireless->close(visRaw->sock);
+	closeServer();
 	BehaviorBase::DoStop();
 }
 
@@ -59,24 +36,57 @@
 RawCamBehavior::processEvent(const EventBase& e) {
 	if(!wireless->isConnected(visRaw->sock))
 		return;
-	const FilterBankEvent* fbke=dynamic_cast<const FilterBankEvent*>(&e);
-	ASSERTRET(fbke!=NULL,"unexpected event");
-	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_transport==0 && visRaw->getTransport()==SocketNS::SOCK_STREAM
+		 || config->vision.rawcam_transport==1 && visRaw->getTransport()==SocketNS::SOCK_DGRAM) {
+		//reset the socket
+		closeServer();
+		setupServer();
 		return;
-		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) {
-		bool succ=writeColor(*fbke);
-		ASSERTRET(succ,"serialization failed");
-	} else if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_SINGLE_CHANNEL) {
-		bool succ=writeSingleChannel(*fbke);
-		ASSERTRET(succ,"serialization failed");
-	} else {
-		serr->printf("%s: Bad rawcam_encoding setting\n",getName().c_str());
+	}
+	try {
+		const FilterBankEvent* fbke=dynamic_cast<const FilterBankEvent*>(&e);
+		if(fbke==NULL) {
+			CameraStreamBehavior::processEvent(e);
+			return;
+		}
+		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)
+			return;
+			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(!writeColor(*fbke)) {
+				if(packet) { //packet was opened, need to close it
+					cur=packet; // don't send anything
+					closePacket();
+				}
+				//error message should already be printed in writeColor
+				//ASSERTRET(false,"serialization failed");
+			}
+		} else if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_SINGLE_CHANNEL) {
+			if(!writeSingleChannel(*fbke)) {
+				if(packet) { //packet was opened, need to close it
+					cur=packet; // don't send anything
+					closePacket();
+				}
+				//error message should already be printed in writeSingleChannel
+				//ASSERTRET(false,"serialization failed");
+			}
+		} else {
+			serr->printf("%s: Bad rawcam_encoding setting\n",getName().c_str());
+		}
+	} catch(...) {
+		if(packet) { //packet was opened, need to close it
+			cur=packet; // don't send anything
+			closePacket();
+		}
+		// typically this is a per-frame recurring error, so let's just stop now
+		serr->printf("%s: exception generated during image serialization, stopping stream.\n",getName().c_str());
+		DoStop();
+		throw;
 	}
 }
 
@@ -115,6 +125,44 @@
 	return getSourceLayer(RawCameraGenerator::CHAN_V,numLayers);
 }
 
+void
+RawCamBehavior::closeServer() {
+	if(wireless->isConnected(visRaw->sock))
+		sendCloseConnectionPacket();
+	Controller::closeGUI("RawVisionGUI");
+	
+	// this could be considered a bug in our wireless - if we don't setDaemon(...,false)
+	// it will try to listen again even though we explicitly closed the server socket...
+	wireless->setDaemon(visRaw,false);
+	wireless->close(visRaw->sock);
+}
+
+void
+RawCamBehavior::setupServer() {
+	std::vector<std::string> args;
+	args.push_back("raw");
+	char port[50];
+	snprintf(port,50,"%d",config->vision.rawcam_port);
+	args.push_back(port);
+	if(config->vision.rawcam_transport==0) {
+		max_buf=UDP_WIRELESS_BUFFER_SIZE;
+		visRaw=wireless->socket(SocketNS::SOCK_DGRAM, 1024, max_buf);
+		args.push_back("udp");
+	} else if(config->vision.rawcam_transport==1) {
+		max_buf=TCP_WIRELESS_BUFFER_SIZE;
+		visRaw=wireless->socket(SocketNS::SOCK_STREAM, 1024, max_buf);
+		args.push_back("tcp");
+	} else {
+		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);
+	
+	Controller::loadGUI("org.tekkotsu.mon.VisionGUI","RawVisionGUI",config->vision.rawcam_port,args);
+}
+
 bool
 RawCamBehavior::openPacket(FilterBankGenerator& fbkgen, unsigned int time, unsigned int layer) {
 	if(packet!=NULL)
@@ -124,31 +172,16 @@
 	ASSERT(cur==NULL,"cur non-NULL");
 	cur=NULL;
 	char * buf=packet=(char*)visRaw->getWriteBuffer(avail);
-	ASSERTRETVAL(packet!=NULL,"could not get buffer",false);
+	ASSERTRETVAL(packet!=NULL,"dropped frame, network bandwidth is saturated (reduce frame rate or size)",false);
 	
-	unsigned int used;
-	used=LoadSave::encode("TekkotsuImage",buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(config->vision.rawcam_encoding,buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(config->vision.rawcam_compression,buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
+	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;;
 
-	used=LoadSave::encode(fbkgen.getWidth(layer),buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(fbkgen.getHeight(layer),buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(time,buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(fbkgen.getFrameNumber(),buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
+	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;;
+	if(!LoadSave::encodeInc(time,buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;;
+	if(!LoadSave::encodeInc(fbkgen.getFrameNumber(),buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;;
 
 	cur=buf;
 	return true;
@@ -167,38 +200,22 @@
 			if(const JPEGGenerator* jgen=dynamic_cast<const JPEGGenerator*>(&fbkgen))
 				if(jgen->getCurrentSourceFormat()==JPEGGenerator::SRC_COLOR)
 					return true;
-			unsigned int used=0;
 			openPacket(fbkgen,e.getTimeStamp(),uv_layer);
-			ASSERTRETVAL(cur!=NULL,"header failed",false);
+			if(cur==NULL) //error should have been displayed by openPacket
+				return false;
 			
-			used=LoadSave::encode("FbkImage",cur,avail);
-			ASSERTRETVAL(used!=0,"save blank image failed",false);
-			avail-=used; cur+=used;
-			used=LoadSave::encode(0,cur,avail);
-			ASSERTRETVAL(used!=0,"save blank image failed",false);
-			avail-=used; cur+=used;
-			used=LoadSave::encode(0,cur,avail);
-			ASSERTRETVAL(used!=0,"save blank image failed",false);
-			avail-=used; cur+=used;
-			used=LoadSave::encode(-1,cur,avail);
-			ASSERTRETVAL(used!=0,"save blank image failed",false);
-			avail-=used; cur+=used;
-			used=LoadSave::encode(RawCameraGenerator::CHAN_Y,cur,avail);
-			ASSERTRETVAL(used!=0,"save blank image failed",false);
-			avail-=used; cur+=used;
-			used=LoadSave::encode("blank",cur,avail);
-			ASSERTRETVAL(used!=0,"save blank image failed",false);
-			avail-=used; cur+=used;
+			if(!LoadSave::encodeInc("FbkImage",cur,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;;
+			if(!LoadSave::encodeInc(0,cur,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;;
+			if(!LoadSave::encodeInc(0,cur,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;;
+			if(!LoadSave::encodeInc(-1,cur,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;;
+			if(!LoadSave::encodeInc(RawCameraGenerator::CHAN_Y,cur,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;;
+			if(!LoadSave::encodeInc("blank",cur,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;;
 
 			fbkgen.selectSaveImage(uv_layer,RawCameraGenerator::CHAN_U);
-			used=fbkgen.SaveBuffer(cur,avail);
-			ASSERTRETVAL(used!=0,"save image failed",false);
-			avail-=used; cur+=used;
+			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);
-			used=fbkgen.SaveBuffer(cur,avail);
-			ASSERTRETVAL(used!=0,"save image failed",false);
-			avail-=used; cur+=used;
+			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();
 		}
@@ -215,68 +232,51 @@
 		if(config->vision.rawcam_compression!=Config::vision_config::COMPRESS_JPEG)
 			return true;
 		if(jgen->getCurrentSourceFormat()==JPEGGenerator::SRC_COLOR && big_layer-small_layer<2) {
-			unsigned int used=0;
 			openPacket(fbkgen,e.getTimeStamp(),big_layer);
-			ASSERTRETVAL(cur!=NULL,"header failed",false);
+			if(cur==NULL) //error should have been displayed by openPacket
+				return false;
 			
 			fbkgen.selectSaveImage(big_layer,0);
-			used=fbkgen.SaveBuffer(cur,avail);
-			ASSERTRETVAL(used!=0,"save image failed",false);
-			avail-=used; cur+=used;
+			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) {
-			unsigned int used=0;
 			bool opened=openPacket(fbkgen,e.getTimeStamp(),big_layer);
-			ASSERTRETVAL(cur!=NULL,"header failed",false);
+			if(cur==NULL) //error should have been displayed by openPacket
+				return false;
 			
 			if(big_layer==y_layer) {
 				fbkgen.selectSaveImage(y_layer,RawCameraGenerator::CHAN_Y);
-				used=fbkgen.SaveBuffer(cur,avail);
-				ASSERTRETVAL(used!=0,"save image failed",false);
-				avail-=used; cur+=used;
+				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);
-				used=fbkgen.SaveBuffer(cur,avail);
-				ASSERTRETVAL(used!=0,"save image failed",false);
-				avail-=used; cur+=used;
-			
+				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);
-				used=fbkgen.SaveBuffer(cur,avail);
-				ASSERTRETVAL(used!=0,"save image failed",false);
-				avail-=used; cur+=used;
+				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)
 				closePacket();
 		}
 	} else {
-		unsigned int used=0;
 		bool opened=false;
 		
 		if(config->vision.rawcam_compression==Config::vision_config::COMPRESS_NONE || big_layer-small_layer>=2 && big_layer==uv_layer) {
 			opened=openPacket(fbkgen,e.getTimeStamp(),big_layer);
-			ASSERTRETVAL(cur!=NULL,"header failed",false);
-			
+			if(cur==NULL) //error should have been displayed by openPacket
+				return false;
 			fbkgen.selectSaveImage(y_layer,RawCameraGenerator::CHAN_Y);
-			used=fbkgen.SaveBuffer(cur,avail);
-			ASSERTRETVAL(used!=0,"save image failed",false);
-			avail-=used; cur+=used;
+			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) {
 			opened=openPacket(fbkgen,e.getTimeStamp(),big_layer);
-			ASSERTRETVAL(cur!=NULL,"header failed",false);
-			
+			if(cur==NULL) //error should have been displayed by openPacket
+				return false;
 			fbkgen.selectSaveImage(uv_layer,RawCameraGenerator::CHAN_U);
-			used=fbkgen.SaveBuffer(cur,avail);
-			ASSERTRETVAL(used!=0,"save image failed",false);
-			avail-=used; cur+=used;
-			
+			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);
-			used=fbkgen.SaveBuffer(cur,avail);
-			ASSERTRETVAL(used!=0,"save image failed",false);
-			avail-=used; cur+=used;
+			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)
@@ -297,14 +297,12 @@
 					return true;
 			unsigned int layer=fbkgen.getNumLayers()-1-config->vision.rawcam_y_skip;
 			
-			unsigned int used=0;
 			openPacket(fbkgen,e.getTimeStamp(),layer);
-			ASSERTRETVAL(cur!=NULL,"header failed",false);
+			if(cur==NULL) //error should have been displayed by openPacket
+				return false;
 			
 			fbkgen.selectSaveImage(layer,config->vision.rawcam_channel);
-			used=fbkgen.SaveBuffer(cur,avail);
-			ASSERTRETVAL(used!=0,"save image failed",false);
-			avail-=used; cur+=used;
+			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();
 		}
@@ -334,9 +332,13 @@
 	char msg[]="CloseConnection";
 	unsigned int len=strlen(msg)+LoadSave::stringpad;
 	char * buf = (char*)visRaw->getWriteBuffer(len);
-	ASSERTRETVAL(buf!=NULL,"Could not get buffer for closing packet",false);
+	if(buf==NULL) {
+		std::cerr << "Could not get buffer for closing packet" << std::endl;
+		return false;
+	}
 	unsigned int used=LoadSave::encode(msg,buf,len);
-	ASSERTRETVAL(used!=0,"Could not write close packet",false);
+	if(used==0)
+		std::cerr << "Could not write close packet" << std::endl;
 	visRaw->write(used);
 	return true;
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/RawCamBehavior.h ./Behaviors/Mon/RawCamBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Mon/RawCamBehavior.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Behaviors/Mon/RawCamBehavior.h	2006-09-16 13:32:38.000000000 -0400
@@ -2,7 +2,7 @@
 #ifndef INCLUDED_RawCamBehavior_h_
 #define INCLUDED_RawCamBehavior_h_
 
-#include "Behaviors/BehaviorBase.h"
+#include "CameraStreamBehavior.h"
 #include "Shared/Config.h"
 
 class Socket;
@@ -38,10 +38,13 @@
  *  in the AIBO's byte order (little endian).  Strings are encoded using
  *  the LoadSave::encode(char*,unsigned int, unsigned int) method.
  */ 
-class RawCamBehavior : public BehaviorBase {
+class RawCamBehavior : public CameraStreamBehavior {
 public:
 	//! constructor
 	RawCamBehavior();
+	
+	//! destructor
+	~RawCamBehavior() { theOne=NULL; }
 
 	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)
 	static const unsigned int UDP_WIRELESS_BUFFER_SIZE=64*1024; //!< 64KB is the max udp packet size
@@ -63,8 +66,15 @@
 	static unsigned int getSourceYLayer(unsigned int numLayers); //!< returns the layer which will be used out of the source, based on current ::config settings (i.e. compression, skip, etc)
 	static unsigned int getSourceULayer(unsigned int numLayers); //!< returns the layer which will be used out of the source, based on current ::config settings (i.e. compression, skip, etc)
 	static unsigned int getSourceVLayer(unsigned int numLayers); //!< returns the layer which will be used out of the source, based on current ::config settings (i.e. compression, skip, etc)
-	
+
 protected:
+	static RawCamBehavior* theOne; //!< global instance of RawCamBehavior acting as server
+	//! function for network data to be sent to -- forwards to #theOne's receiveData()
+	static int networkCallback(char* buf, int bytes) { return theOne->receiveData(buf,bytes); }
+
+	void closeServer(); //!<tear down the server socket (#visRaw)
+	void setupServer(); //!<setup the server socket (#visRaw)
+	
 	//! opens a new packet, writes header info; returns true if open, false if otherwise open (check cur==NULL for error)
 	/*! see the class documentation for RawCamBehavior for the protocol documentation */
 	bool openPacket(FilterBankGenerator& fbkgen, unsigned int time, unsigned int layer);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/RegionCamBehavior.cc ./Behaviors/Mon/RegionCamBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Mon/RegionCamBehavior.cc	2005-08-05 15:44:22.000000000 -0400
+++ ./Behaviors/Mon/RegionCamBehavior.cc	2006-09-09 00:32:29.000000000 -0400
@@ -15,7 +15,49 @@
 void
 RegionCamBehavior::DoStart() {
 	BehaviorBase::DoStart();
+	setupServer();
+	erouter->addListener(this,EventBase::visRegionEGID,ProjectInterface::visRegionSID,EventBase::deactivateETID);
+}
+
+void
+RegionCamBehavior::DoStop() {
+	erouter->removeListener(this);
+	closeServer();
+	BehaviorBase::DoStop();
+}
+
+void
+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) {
+		closeServer();
+		setupServer();
+		return;
+	}
+	const FilterBankEvent* fbke=dynamic_cast<const FilterBankEvent*>(&e);
+	ASSERTRET(fbke!=NULL,"unexpected event");
+#if DEBUG
+	bool succ=writeRegions(*fbke);
+	ASSERTRET(succ,"serialization failed");
+#else
+	writeRegions(*fbke);
+#endif
+}
+
+void
+RegionCamBehavior::closeServer() {
+	Controller::closeGUI("RegionVisionGUI");
 	
+	// this could be considered a bug in our wireless - if we don't setDaemon(...,false)
+	// it will try to listen again even though we explicitly closed the server socket...
+	wireless->setDaemon(visRegion,false);
+	wireless->close(visRegion->sock);
+}
+
+void
+RegionCamBehavior::setupServer() {
 	std::vector<std::string> args;
 	args.push_back("reg"); 
 	char port[50];
@@ -36,30 +78,6 @@
 	}
 	wireless->listen(visRegion,config->vision.region_port);
 	Controller::loadGUI("org.tekkotsu.mon.VisionGUI","RegionVisionGUI",config->vision.region_port,args);
-
-	erouter->addListener(this,EventBase::visRegionEGID,ProjectInterface::visRegionSID);
-}
-
-void
-RegionCamBehavior::DoStop() {
-	erouter->removeListener(this);
-	Controller::closeGUI("RegionVisionGUI");
-
-	// this could be considered a bug in our wireless - if we don't setDaemon(...,false)
-	// it will try to listen again even though we explicitly closed the server socket...
-	wireless->setDaemon(visRegion,false);
-	wireless->close(visRegion->sock);
-	BehaviorBase::DoStop();
-}
-
-void
-RegionCamBehavior::processEvent(const EventBase& e) {
-	if(!wireless->isConnected(visRegion->sock))
-		return;
-	const FilterBankEvent* fbke=dynamic_cast<const FilterBankEvent*>(&e);
-	ASSERTRET(fbke!=NULL,"unexpected event");
-		bool succ=writeRegions(*fbke);
-		ASSERTRET(succ,"serialization failed");
 }
 
 bool
@@ -73,29 +91,14 @@
 	char * buf=packet=(char*)visRegion->getWriteBuffer(avail);
 	ASSERTRETVAL(packet!=NULL,"could not get buffer",false);
 	
-	unsigned int used;
-	used=LoadSave::encode("TekkotsuImage",buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(Config::vision_config::ENCODE_SINGLE_CHANNEL,buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(Config::vision_config::COMPRESS_RLE,buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
+	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;;
 
-	used=LoadSave::encode(fbkgen.getWidth(layer),buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(fbkgen.getHeight(layer),buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(time,buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(fbkgen.getFrameNumber(),buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
+	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;;
+	if(!LoadSave::encodeInc(time,buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;;
+	if(!LoadSave::encodeInc(fbkgen.getFrameNumber(),buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;;
 
 	cur=buf;
 	return true;
@@ -106,22 +109,18 @@
 	FilterBankGenerator& fbkgen=*e.getSource();
 
 	unsigned int layer=fbkgen.getNumLayers()-1-config->vision.regioncam_skip;
-	unsigned int used=0;
 	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.rlecam_channel);
-	used=regGen->SaveBuffer(cur,avail);
-	ASSERTRETVAL(used!=0,"save region image failed",false);
-	avail-=used; cur+=used;
+	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)
 	ASSERTRETVAL(seg!=NULL,"The source of RegionGenerator's source is not a SegmentedColorGenerator - how do i know what the colors are?",false);
-	if(0==(used=seg->encodeColors(cur,avail))) return false;
-	avail-=used; cur+=used;
+	if(!seg->encodeColorsInc(cur,avail)) return false;
 
 	closePacket();
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/RegionCamBehavior.h ./Behaviors/Mon/RegionCamBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Mon/RegionCamBehavior.h	2005-08-05 15:44:22.000000000 -0400
+++ ./Behaviors/Mon/RegionCamBehavior.h	2006-09-16 13:32:38.000000000 -0400
@@ -27,12 +27,15 @@
 
 	static std::string getClassDescription() {
 		char tmp[20];
-		sprintf(tmp,"%d",config->vision.rle_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(); }
 	
 protected:
+	void closeServer(); //!<tear down the server socket (#visRegion)
+	void setupServer(); //!<setup the server socket (#visRegion)
+	
 	//! opens a new packet, writes header info; returns true if open, false if otherwise open (check cur==NULL for error)
 	/*! see the class documentation for RegionCamBehavior for the protocol documentation */
 	bool openPacket(FilterBankGenerator& fbkgen, unsigned int time, unsigned int layer); 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/SegCamBehavior.cc ./Behaviors/Mon/SegCamBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Mon/SegCamBehavior.cc	2005-07-29 14:35:04.000000000 -0400
+++ ./Behaviors/Mon/SegCamBehavior.cc	2006-09-14 14:57:03.000000000 -0400
@@ -7,37 +7,19 @@
 #include "Vision/SegmentedColorGenerator.h"
 #include "Vision/RLEGenerator.h"
 
+SegCamBehavior* SegCamBehavior::theOne=NULL;
+
 SegCamBehavior::SegCamBehavior()
-	: BehaviorBase("SegCamBehavior"), visRLE(NULL), packet(NULL), cur(NULL), avail(0), max_buf(0), lastProcessedTime(0)
+	: CameraStreamBehavior("SegCamBehavior",visRLE), visRLE(NULL), packet(NULL), cur(NULL), avail(0), max_buf(0), lastProcessedTime(0)
 {
+	ASSERT(theOne==NULL,"there was already a SegCamBehavior running!");
+	theOne=this;
 }
 
 void
 SegCamBehavior::DoStart() {
 	BehaviorBase::DoStart();
-	
-	std::vector<std::string> args;
-	args.push_back("rle");
-	char port[50];
-	snprintf(port,50,"%d",config->vision.rle_port);
-	args.push_back(port);
-	if(config->vision.rle_transport==0) {
-		max_buf=UDP_WIRELESS_BUFFER_SIZE;
-		visRLE=wireless->socket(SocketNS::SOCK_DGRAM, 1024, max_buf);
-		args.push_back("udp");
-	} else if(config->vision.rle_transport==1) {
-		max_buf=TCP_WIRELESS_BUFFER_SIZE;
-		visRLE=wireless->socket(SocketNS::SOCK_STREAM, 1024, max_buf);
-		wireless->setDaemon(visRLE,true);
-		args.push_back("tcp");
-	} else {
-		serr->printf("ERROR: Invalid Config::vision.rle_transport: %d\n",config->vision.rle_transport);
-		return;
-	}
-	wireless->listen(visRLE,config->vision.rle_port);
-
-	Controller::loadGUI("org.tekkotsu.mon.VisionGUI","SegVisionGUI",config->vision.rle_port,args);
-
+	setupServer();
 	erouter->addListener(this,EventBase::visSegmentEGID,ProjectInterface::visSegmentSID,EventBase::deactivateETID);
 	erouter->addListener(this,EventBase::visRLEEGID,ProjectInterface::visRLESID,EventBase::deactivateETID);
 }
@@ -45,33 +27,96 @@
 void
 SegCamBehavior::DoStop() {
 	erouter->removeListener(this);
+	closeServer();
+	BehaviorBase::DoStop();
+}
+
+void
+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) {
+		closeServer();
+		setupServer();
+		return;
+	}
+	try {
+		const FilterBankEvent* fbke=dynamic_cast<const FilterBankEvent*>(&e);
+		if(fbke==NULL) {
+			CameraStreamBehavior::processEvent(e);
+			return;
+		}
+		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(!writeSeg(*fbke)) {
+				if(packet!=NULL) {
+					cur=packet;
+					closePacket();
+				}
+				//error message should already have been reported
+				//ASSERTRET(succ,"serialization failed");
+			}
+		}
+		if(config->vision.segcam_compression==Config::vision_config::COMPRESS_RLE && e.getGeneratorID()==EventBase::visRLEEGID) {
+			if(!writeRLE(*fbke)) {
+				if(packet!=NULL) {
+					cur=packet;
+					closePacket();
+				}
+				//error message should already have been reported
+				//ASSERTRET(succ,"serialization failed");
+			}
+		}
+	} catch(...) {
+		if(packet!=NULL) {
+			cur=packet;
+			closePacket();
+		}
+		// typically this is a per-frame recurring error, so let's just stop now
+		serr->printf("%s: exception generated during image serialization, stopping stream.\n",getName().c_str());
+		DoStop();
+		throw;
+	}
+}
+
+void
+SegCamBehavior::closeServer() {
 	if(wireless->isConnected(visRLE->sock))
 		sendCloseConnectionPacket();
 	Controller::closeGUI("SegVisionGUI");
-
+	
 	// this could be considered a bug in our wireless - if we don't setDaemon(...,false)
 	// it will try to listen again even though we explicitly closed the server socket...
 	wireless->setDaemon(visRLE,false);
 	wireless->close(visRLE->sock);
-	BehaviorBase::DoStop();
 }
 
 void
-SegCamBehavior::processEvent(const EventBase& e) {
-	if(!wireless->isConnected(visRLE->sock))
+SegCamBehavior::setupServer() {
+	std::vector<std::string> args;
+	args.push_back("rle");
+	char port[50];
+	snprintf(port,50,"%d",config->vision.segcam_port);
+	args.push_back(port);
+	if(config->vision.segcam_transport==0) {
+		max_buf=UDP_WIRELESS_BUFFER_SIZE;
+		visRLE=wireless->socket(SocketNS::SOCK_DGRAM, 1024, max_buf);
+		args.push_back("udp");
+	} else if(config->vision.segcam_transport==1) {
+		max_buf=TCP_WIRELESS_BUFFER_SIZE;
+		visRLE=wireless->socket(SocketNS::SOCK_STREAM, 1024, max_buf);
+		args.push_back("tcp");
+	} else {
+		serr->printf("ERROR: Invalid Config::vision.segcam_transport: %d\n",config->vision.segcam_transport);
 		return;
-	const FilterBankEvent* fbke=dynamic_cast<const FilterBankEvent*>(&e);
-	ASSERTRET(fbke!=NULL,"unexpected event");
-	if ((get_time() - lastProcessedTime) < config->vision.rle_interval) // not enough time has gone by
-	  return;
-	if(config->vision.rlecam_compression==Config::vision_config::COMPRESS_NONE && e.getGeneratorID()==EventBase::visSegmentEGID) {
-		bool succ=writeSeg(*fbke);
-		ASSERTRET(succ,"serialization failed");
-	}
-	if(config->vision.rlecam_compression==Config::vision_config::COMPRESS_RLE && e.getGeneratorID()==EventBase::visRLEEGID) {
-		bool succ=writeRLE(*fbke);
-		ASSERTRET(succ,"serialization failed");
 	}
+	wireless->setDaemon(visRLE,true);
+	wireless->setReceiver(visRLE,networkCallback);
+	wireless->listen(visRLE,config->vision.segcam_port);
+	
+	Controller::loadGUI("org.tekkotsu.mon.VisionGUI","SegVisionGUI",config->vision.segcam_port,args);
 }
 
 bool
@@ -83,31 +128,16 @@
 	ASSERT(cur==NULL,"cur non-NULL");
 	cur=NULL;
 	char * buf=packet=(char*)visRLE->getWriteBuffer(avail);
-	ASSERTRETVAL(packet!=NULL,"could not get buffer",false);
+	ASSERTRETVAL(packet!=NULL,"dropped frame, network bandwidth is saturated (reduce frame rate or size)",false);
 	
-	unsigned int used;
-	used=LoadSave::encode("TekkotsuImage",buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(Config::vision_config::ENCODE_SINGLE_CHANNEL,buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(Config::vision_config::COMPRESS_RLE,buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
+	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;;
 
-	used=LoadSave::encode(fbkgen.getWidth(layer),buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(fbkgen.getHeight(layer),buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(time,buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
-	used=LoadSave::encode(fbkgen.getFrameNumber(),buf,avail);
-	ASSERTRETVAL(used!=0,"ran out of space",false);
-	avail-=used; buf+=used;
+	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;;
+	if(!LoadSave::encodeInc(time,buf,avail,"ran out of space %s:%u\n",__FILE__,__LINE__)) return false;;
+	if(!LoadSave::encodeInc(fbkgen.getFrameNumber(),buf,avail,"ran out of space %s:%u\n",__FILE__,__LINE__)) return false;;
 
 	cur=buf;
 	return true;
@@ -117,24 +147,21 @@
 SegCamBehavior::writeRLE(const FilterBankEvent& e) {
 	FilterBankGenerator& fbkgen=*e.getSource();
 
-	unsigned int layer=fbkgen.getNumLayers()-1-config->vision.rlecam_skip;
-	unsigned int used=0;
+	unsigned int layer=fbkgen.getNumLayers()-1-config->vision.segcam_skip;
 	openPacket(fbkgen,e.getTimeStamp(),layer);
-	ASSERTRETVAL(cur!=NULL,"header failed",false);
+	if(cur==NULL) //error should have been displayed by openPacket
+		return false;
 	
 	RLEGenerator * rle = dynamic_cast<RLEGenerator*>(&fbkgen);
 	ASSERTRETVAL(rle!=NULL,"fbkgen isn't an RLEGenerator",false);
 
-	rle->selectSaveImage(layer,config->vision.rlecam_channel);
-	used=rle->SaveBuffer(cur,avail);
-	ASSERTRETVAL(used!=0,"save rle image failed",false);
-	avail-=used; cur+=used;
+	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());
 	ASSERTRETVAL(seg!=NULL,"RLE's source is not a SegmentedColorGenerator - how do i know what the colors are?",false);
-	if(0==(used=seg->encodeColors(cur,avail))) return false;
-	avail-=used; cur+=used;
+	if(!seg->encodeColorsInc(cur,avail)) return false;
 
 	closePacket();
 
@@ -145,15 +172,13 @@
 SegCamBehavior::writeSeg(const FilterBankEvent& e) {
 	FilterBankGenerator& fbkgen=*e.getSource();
 
-	unsigned int layer=fbkgen.getNumLayers()-1-config->vision.rlecam_skip;
-	unsigned int used=0;
+	unsigned int layer=fbkgen.getNumLayers()-1-config->vision.segcam_skip;
 	openPacket(fbkgen,e.getTimeStamp(),layer);
-	ASSERTRETVAL(cur!=NULL,"header failed",false);
+	if(cur==NULL) //error should have been displayed by openPacket
+		return false;
 	
-	fbkgen.selectSaveImage(layer,config->vision.rlecam_channel);
-	used=fbkgen.SaveBuffer(cur,avail);
-	ASSERTRETVAL(used!=0,"save seg image failed",false);
-	avail-=used; cur+=used;
+	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();
 
@@ -175,9 +200,13 @@
 	char msg[]="CloseConnection";
 	unsigned int len=strlen(msg)+LoadSave::stringpad;
 	char * buf = (char*)visRLE->getWriteBuffer(len);
-	ASSERTRETVAL(buf!=NULL,"Could not get buffer for closing packet",false);
+	if(buf==NULL) {
+		std::cerr << "Could not get buffer for closing packet" << std::endl;
+		return false;
+	}
 	unsigned int used=LoadSave::encode(msg,buf,len);
-	ASSERTRETVAL(used!=0,"Could not write close packet",false);
+	if(used==0)
+		std::cerr << "Could not write close packet" << std::endl;
 	visRLE->write(used);
 	return true;
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/SegCamBehavior.h ./Behaviors/Mon/SegCamBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Mon/SegCamBehavior.h	2005-07-29 14:35:05.000000000 -0400
+++ ./Behaviors/Mon/SegCamBehavior.h	2006-09-16 16:11:50.000000000 -0400
@@ -2,7 +2,7 @@
 #ifndef INCLUDED_SegCamBehavior_h_
 #define INCLUDED_SegCamBehavior_h_
 
-#include "Behaviors/BehaviorBase.h"
+#include "CameraStreamBehavior.h"
 #include "Shared/Config.h"
 
 class Socket;
@@ -55,11 +55,14 @@
  *  in the AIBO's byte order (little endian).  Strings are encoded using
  *  the LoadSave::encode(char*,unsigned int, unsigned int) method.
  */ 
-class SegCamBehavior : public BehaviorBase {
+class SegCamBehavior : public CameraStreamBehavior {
 public:
 	//! constructor
 	SegCamBehavior();
 
+	//! destructor
+	~SegCamBehavior() { theOne=NULL; }
+
 	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
 	static const unsigned int UDP_WIRELESS_BUFFER_SIZE=64*1024; //!< 64KB is the max udp packet size
 
@@ -71,12 +74,19 @@
 
 	static std::string getClassDescription() {
 		char tmp[20];
-		snprintf(tmp,20,"%d",config->vision.rle_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(); }
 	
 protected:
+	static SegCamBehavior* theOne; //!< global instance of SegCamBehavior acting as server
+	//! function for network data to be sent to -- forwards to #theOne's receiveData()
+	static int networkCallback(char* buf, int bytes) { return theOne->receiveData(buf,bytes); }
+	
+	void closeServer(); //!<tear down the server socket (#visRLE)
+	void setupServer(); //!<setup the server socket (#visRLE	)
+	
 	//! opens a new packet, writes header info; returns true if open, false if otherwise open (check cur==NULL for error)
 	/*! see the class documentation for SegCamBehavior for the protocol documentation */
 	bool openPacket(FilterBankGenerator& fbkgen, unsigned int time, unsigned int layer); 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/SpeakerServer.cc ./Behaviors/Mon/SpeakerServer.cc
--- ../Tekkotsu_2.4.1/Behaviors/Mon/SpeakerServer.cc	2004-11-12 17:07:39.000000000 -0500
+++ ./Behaviors/Mon/SpeakerServer.cc	2006-09-18 14:08:07.000000000 -0400
@@ -58,7 +58,7 @@
 		socket = 0;
 	}
 	
-	sndman->StopPlay(channel);
+	sndman->stopPlay(channel);
 	channel = SoundManager::invalid_Play_ID;
 	
 	packet.samples->SetCapacity(0);
@@ -216,17 +216,17 @@
 		
 void SpeakerServer::QueueFrame(const char* samples, int samplesSize) {
 	if (channel != SoundManager::invalid_Play_ID) {
-		const int remainingTime = sndman->GetRemainTime(channel) - RobotInfo::SoundBufferTime;
+		const int remainingTime = sndman->getRemainTime(channel) - RobotInfo::SoundBufferTime;
 		if (remainingTime > (int) config->sound.streaming.speaker_max_delay) {
 			// Queue too long
-			sndman->StopPlay(channel);
+			sndman->stopPlay(channel);
 			channel = SoundManager::invalid_Play_ID;
 		} else if (remainingTime < 0) {
 			// Queue underrun
 		} else {
 			// Try queueing
 			SoundManager::Play_ID newChannel =
-				sndman->ChainBuffer(channel, samples, (int) samplesSize);
+				sndman->chainBuffer(channel, samples, (int) samplesSize);
 			if (newChannel != SoundManager::invalid_Play_ID) {
 				channel = newChannel;
 				return;
@@ -235,7 +235,7 @@
 	}
 	
 	// Start a new channel
-	channel = sndman->PlayBuffer(samples, samplesSize);
+	channel = sndman->playBuffer(samples, samplesSize);
 }
 
 const void* SpeakerServer::ResampleForSpeaker(
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/SpeakerServer.h ./Behaviors/Mon/SpeakerServer.h
--- ../Tekkotsu_2.4.1/Behaviors/Mon/SpeakerServer.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Behaviors/Mon/SpeakerServer.h	2006-09-16 16:11:50.000000000 -0400
@@ -8,33 +8,36 @@
 //! Plays streamed audio via the speaker
 class SpeakerServer : public BehaviorBase {
 	public:
-		static SpeakerServer* GetInstance();
-		virtual ~SpeakerServer();
+		static SpeakerServer* GetInstance(); //!< returns global #instance
+		virtual ~SpeakerServer(); //!< destructor
 		
 		virtual void DoStart();
 		virtual void DoStop();
 		
+		//! registered by DoStart() to be called by networking module with incoming data
 		static int socket_callback(char *buf, int size);
 	
 	private:
-		SpeakerServer();
+		SpeakerServer(); //!< constructor
 		SpeakerServer(const SpeakerServer& rhs); //!< don't call
 		SpeakerServer& operator=(const SpeakerServer& rhs); //!< don't call
-		static SpeakerServer* instance;
+		static SpeakerServer* instance; //!< global instance of the server (only ever want to have one of these)
 		
-		int GotSocketData(char* data, int dataSize);
-		class Socket *socket;
+		int GotSocketData(char* data, int dataSize); //!< should be called with new sound data from the network
+		class Socket *socket; //!< network communications socket for receiving sound data
+		//! returns the next sizeof(short) bytes from @a buf as a short
 		static short GetShort(const void* buf) { short result; memcpy(&result, buf, sizeof(short)); return result; }
 		
-		static const int MAX_PACKET_SIZE = 1024 * 1024;
-		static const int RECEIVE_BUFFER_SIZE = 2048;
+		static const int MAX_PACKET_SIZE = 1024 * 1024; //!< maximum size of sound buffer to send to system
+		static const int RECEIVE_BUFFER_SIZE = 2048; //!< maximum network packet size to accept
 	
+		//! stores information about current sound buffer
 		class Packet {
 			public:
-				Packet();
-				virtual ~Packet(); 
+				Packet(); //!< constructor
+				virtual ~Packet(); //!< destructor
 				
-				class Buffer* header;
+				class Buffer* header; 
 				int size;
 				int type;
 				bool skipped;
@@ -55,7 +58,11 @@
 		class Buffer* resampled;
 		
 		void AddPacket(
-			const void* samples, int samplesSize, int sampleRate, byte sampleBits);
+			const void* samples,
+			int samplesSize,
+			int sampleRate,
+			byte sampleBits);
+		
 		const void* ResampleForSpeaker(
 			const void* samples,
 			int samplesSize,
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/SpiderMachineBehavior.cc ./Behaviors/Mon/SpiderMachineBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Mon/SpiderMachineBehavior.cc	2005-06-01 01:47:45.000000000 -0400
+++ ./Behaviors/Mon/SpiderMachineBehavior.cc	2006-02-21 00:27:13.000000000 -0500
@@ -163,7 +163,7 @@
 }
 
 const StateNode * SpiderMachineBehavior::find(const std::string& name) {
-	for(registry_t::const_iterator it=registry.begin(); it!=registry.end(); it++) {
+	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;
@@ -175,13 +175,13 @@
 void SpiderMachineBehavior::runCommand(const std::string& s) {
 	if(s==std::string("list")) {
 		unsigned int numstate=0;
-		for(registry_t::const_iterator it=registry.begin(); it!=registry.end(); it++) {
+		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=registry.begin(); it!=registry.end(); it++) {
+		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());
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/UPennWalkControllerBehavior.cc ./Behaviors/Mon/UPennWalkControllerBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Mon/UPennWalkControllerBehavior.cc	2005-06-01 01:47:46.000000000 -0400
+++ ./Behaviors/Mon/UPennWalkControllerBehavior.cc	2006-09-18 14:08:07.000000000 -0400
@@ -45,19 +45,19 @@
 		cout << "MECHA: hey, reprogram this button!" << endl;
 		break;
 	case CMD_opt5:
-		sndman->PlayFile("howl.wav");
+		sndman->playFile("howl.wav");
 		break;
 	case CMD_opt6:
-		sndman->PlayFile("yap.wav");
+		sndman->playFile("yap.wav");
 		break;
 	case CMD_opt7:
-		sndman->PlayFile("whimper.wav");
+		sndman->playFile("whimper.wav");
 		break;
 	case CMD_opt8:
-		sndman->PlayFile("growl.wav");
+		sndman->playFile("growl.wav");
 		break;
 	case CMD_opt9:
-		sndman->PlayFile("barkmed.wav");
+		sndman->playFile("barkmed.wav");
 		break;
 		// The options button commands.
 	default:
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/WMMonitorBehavior.cc ./Behaviors/Mon/WMMonitorBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Mon/WMMonitorBehavior.cc	2004-04-16 16:17:22.000000000 -0400
+++ ./Behaviors/Mon/WMMonitorBehavior.cc	2005-11-08 16:36:08.000000000 -0500
@@ -60,7 +60,7 @@
 WMitem_base*
 WMMonitorBehavior::find (std::string& s) {
   WMregistry* wmreg=&GlobalWM;
-  unsigned int pos=s.find('.');
+  std::string::size_type pos=s.find('.');
   while (pos!=std::string::npos) {
     bool changed=false;
     std::string subreg=s.substr(0, pos);
@@ -126,7 +126,7 @@
                                                                                 
   //pass a line at a time to the controller
   while(s.size()>0) {
-    unsigned int endline=s.find('\n');
+    std::string::size_type endline=s.find('\n');
     if(endline==std::string::npos) {
       incomplete+=s;
       return 0;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/WalkControllerBehavior.cc ./Behaviors/Mon/WalkControllerBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Mon/WalkControllerBehavior.cc	2005-06-01 01:47:46.000000000 -0400
+++ ./Behaviors/Mon/WalkControllerBehavior.cc	2006-09-18 14:08:07.000000000 -0400
@@ -14,10 +14,17 @@
 	float param;
 	unsigned char *paramp = (unsigned char *) &param;
 
+#if defined(BYTE_ORDER) && BYTE_ORDER==BIG_ENDIAN
+	paramp[0] = command[4];
+	paramp[1] = command[3];
+	paramp[2] = command[2];
+	paramp[3] = command[1];
+#else
 	paramp[0] = command[1];
 	paramp[1] = command[2];
 	paramp[2] = command[3];
 	paramp[3] = command[4];
+#endif
 
 	// Find out what type of command this is
 	switch(command[0]) {
@@ -45,19 +52,19 @@
 		cout << "MECHA: hey, reprogram this button!" << endl;
 		break;
 	case CMD_opt5:
-		sndman->PlayFile("howl.wav");
+		sndman->playFile("howl.wav");
 		break;
 	case CMD_opt6:
-		sndman->PlayFile("yap.wav");
+		sndman->playFile("yap.wav");
 		break;
 	case CMD_opt7:
-		sndman->PlayFile("whimper.wav");
+		sndman->playFile("whimper.wav");
 		break;
 	case CMD_opt8:
-		sndman->PlayFile("growl.wav");
+		sndman->playFile("growl.wav");
 		break;
 	case CMD_opt9:
-		sndman->PlayFile("barkmed.wav");
+		sndman->playFile("barkmed.wav");
 		break;
 		// The options button commands.
 	default:
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/WalkControllerBehavior.h ./Behaviors/Mon/WalkControllerBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Mon/WalkControllerBehavior.h	2004-11-10 20:45:36.000000000 -0500
+++ ./Behaviors/Mon/WalkControllerBehavior.h	2005-09-13 18:10:36.000000000 -0400
@@ -13,6 +13,18 @@
 #include "Shared/Config.h"
 
 //! 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
+ *  with HeadPointControllerBehavior.  Each command is sent as a
+ *  5-byte group.  The first byte is a command selector, and the
+ *  following 4 bytes are a floating point argument:
+ *
+ *  - <@c char: command indicator>
+ *  - <@c float: value>
+ *  
+ *  The valid values for command indicator are given by #CMD_fwd,
+ *  #CMD_roto, or #CMD_side ('f', 'r', or 's' respectively).  Others
+ *  are listed below, but are not currently used.
+ */  
 class WalkControllerBehavior : public BehaviorBase {
 
  public:	
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/WorldStateSerializerBehavior.cc ./Behaviors/Mon/WorldStateSerializerBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Mon/WorldStateSerializerBehavior.cc	2005-02-21 03:05:57.000000000 -0500
+++ ./Behaviors/Mon/WorldStateSerializerBehavior.cc	2006-09-19 18:51:38.000000000 -0400
@@ -2,63 +2,131 @@
 #include "Shared/WorldState.h"
 #include "Wireless/Wireless.h"
 #include "Shared/Config.h"
+#include "Behaviors/Controller.h"
 #include "Events/EventRouter.h"
+#include "Shared/LoadSave.h"
 
 WorldStateSerializerBehavior::WorldStateSerializerBehavior()
-	: BehaviorBase("WorldStateSerializerBehavior"), wsJoints(NULL), wsPIDs(NULL), lastProcessedTime(0)
+: BehaviorBase("WorldStateSerializerBehavior"), wsJoints(NULL), wsPIDs(NULL), lastProcessedTime(0)
 {
-	wsJoints=wireless->socket(SocketNS::SOCK_STREAM, 1024, 2048);
-  wireless->setDaemon(wsJoints);
-  wireless->listen(wsJoints, config->main.wsjoints_port);
-  wsPIDs=wireless->socket(SocketNS::SOCK_STREAM, 1024, 2048);
-  wireless->setDaemon(wsPIDs);
-	wireless->listen(wsPIDs, config->main.wspids_port);
 }
 
 void WorldStateSerializerBehavior::DoStart() {
 	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
+	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
+	wireless->setDaemon(wsJoints);
+	wireless->listen(wsJoints, config->main.wsjoints_port);
+		
+	Controller::loadGUI(getGUIType(),getGUIType(),getPort());
+	
 	erouter->addListener(this,EventBase::sensorEGID);
 }
 
 void WorldStateSerializerBehavior::DoStop() {
 	erouter->removeListener(this);
+	
+	Controller::closeGUI(getGUIType());
+	
+	wireless->setDaemon(wsJoints,false);
+	wireless->close(wsJoints);
+	wireless->setDaemon(wsPIDs,false);
+	wireless->close(wsPIDs);
+	
 	BehaviorBase::DoStop(); // do this last
 }
 
 void WorldStateSerializerBehavior::processEvent(const EventBase& e) {
-  if ((e.getTimeStamp() - lastProcessedTime) < config->main.worldState_interval) // not enough time has gone by
-    return;
-  lastProcessedTime = e.getTimeStamp();
-  char *buf=(char*)wsPIDs->getWriteBuffer((NumPIDJoints*3)*sizeof(float)+2*sizeof(unsigned int));
-  if (buf) {
-    encode(&buf,state->lastSensorUpdateTime);
-		encode(&buf,NumPIDJoints);
-    encode(&buf,state->pids,NumPIDJoints*3);
-    wsPIDs->write((NumPIDJoints*3)*sizeof(float)+2*sizeof(unsigned int));
-  }
-  
-  buf=(char*)wsJoints->getWriteBuffer((NumPIDJoints*2+NumSensors+NumButtons)*sizeof(float)+4*sizeof(unsigned int));
-  if (buf) {
-    encode(&buf,state->lastSensorUpdateTime);
-		encode(&buf,NumPIDJoints);
-    encode(&buf,&state->outputs[PIDJointOffset], NumPIDJoints);
-		encode(&buf,NumSensors);
-    encode(&buf,state->sensors,NumSensors);
-		encode(&buf,NumButtons);
-    encode(&buf,state->buttons,NumButtons);
-    encode(&buf,state->pidduties,NumPIDJoints);
-    wsJoints->write((NumPIDJoints*2+NumSensors+NumButtons)*sizeof(float)+4*sizeof(unsigned int));
-  }
+	const size_t transmitPIDSize=(NumPIDJoints*3)*LoadSave::getSerializedSize<float>()+2*LoadSave::getSerializedSize<unsigned int>();
+	if ((e.getTimeStamp() - lastProcessedTime) < config->main.worldState_interval) // not enough time has gone by
+		return;
+	lastProcessedTime = e.getTimeStamp();
+	char *buf=(char*)wsPIDs->getWriteBuffer(transmitPIDSize);
+	if(buf==NULL) {
+		if(wireless->isConnected(wsPIDs->sock))
+			std::cout << "WorldStateSerializer dropped pid at " << e.getTimeStamp() << std::endl;
+	} else {
+#if LOADSAVE_SWAPBYTES
+		// if we need to swap bytes, need to use this slightly slower method
+		unsigned int remain=transmitPIDSize;
+		LoadSave::encodeInc(state->lastSensorUpdateTime,buf,remain);
+		LoadSave::encodeInc(NumPIDJoints,buf,remain);
+		for(unsigned int i=0; i<NumPIDJoints; ++i)
+			for(unsigned int j=0; j<3; ++j)
+				LoadSave::encodeInc(state->pids[i][j],buf,remain);
+		ASSERT(remain==0,"buffer remains");
+		wsPIDs->write(transmitPIDSize-remain);
+#else
+		// this is the original version, doesn't handle byte swapping, but faster
+		copy(&buf,state->lastSensorUpdateTime);
+		copy(&buf,NumPIDJoints);
+		copy(&buf,state->pids,NumPIDJoints*3);
+		wsPIDs->write(transmitPIDSize);
+#endif
+	}
+	
+	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;
+	//std::cout << "transmitting at " << e.getTimeStamp() << " with " << (wsJoints->getAvailableSendSize() / float(transmitJointsSize)) << std::endl;
+	buf=(char*)wsJoints->getWriteBuffer(transmitJointsSize);
+	if(buf==NULL) {
+		if(wireless->isConnected(wsJoints->sock))
+			std::cout << "WorldStateSerializer dropped state at " << e.getTimeStamp() << std::endl;
+	} else {
+#if LOADSAVE_SWAPBYTES
+		// if we need to swap bytes, need to use this slightly slower method
+		unsigned int remain=transmitJointsSize;
+		memcpy(buf,RobotName,robotNameLen);
+		buf+=robotNameLen; remain-=robotNameLen;
+		LoadSave::encodeInc(state->lastSensorUpdateTime,buf,remain);
+		LoadSave::encodeInc(state->frameNumber,buf,remain);
+		LoadSave::encodeInc(NumOutputs,buf,remain);
+		for(unsigned int i=0; i<NumOutputs; ++i)
+			LoadSave::encodeInc(state->outputs[i],buf,remain);
+		LoadSave::encodeInc(NumSensors,buf,remain);
+		for(unsigned int i=0; i<NumSensors; ++i)
+			LoadSave::encodeInc(state->sensors[i],buf,remain);
+		LoadSave::encodeInc(NumButtons,buf,remain);
+		for(unsigned int i=0; i<NumButtons; ++i)
+			LoadSave::encodeInc(state->buttons[i],buf,remain);
+		LoadSave::encodeInc(NumPIDJoints,buf,remain);
+		for(unsigned int i=0; i<NumPIDJoints; ++i)
+			LoadSave::encodeInc(state->pidduties[i],buf,remain);
+		ASSERT(remain==0,"buffer remains");
+		wsJoints->write(transmitJointsSize-remain);
+#else
+		// this is the original version, doesn't handle byte swapping, but faster
+		copy(&buf,RobotName,robotNameLen);
+		copy(&buf,state->lastSensorUpdateTime);
+		copy(&buf,state->frameNumber);
+		copy(&buf,NumOutputs);
+		copy(&buf,state->outputs,NumOutputs);
+		copy(&buf,NumSensors);
+		copy(&buf,state->sensors,NumSensors);
+		copy(&buf,NumButtons);
+		copy(&buf,state->buttons,NumButtons);
+		copy(&buf,NumPIDJoints);
+		copy(&buf,state->pidduties,NumPIDJoints);
+		wsJoints->write(transmitJointsSize);
+#endif
+	}
 }
 
 
 /*! @file
- * @brief Implements WorldStateSerializer, which copies WorldState into a buffer for transmission over the network
- * @author alokl (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
+* @brief Implements WorldStateSerializer, which copies WorldState into a buffer for transmission over the network
+* @author alokl (Creator)
+*
+* $Author: ejt $
+* $Name: HEAD $
+* $Revision: 1.1 $
+* $State: Exp $
+* $Date: 2006/10/04 04:21:12 $
+*/
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Mon/WorldStateSerializerBehavior.h ./Behaviors/Mon/WorldStateSerializerBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Mon/WorldStateSerializerBehavior.h	2005-02-21 03:05:57.000000000 -0500
+++ ./Behaviors/Mon/WorldStateSerializerBehavior.h	2006-09-09 19:28:59.000000000 -0400
@@ -13,23 +13,26 @@
  *  of values.
  *
  *  Protocol:
+ *  - <@c char[]: modelName> (null terminated character array)
  *  - <@c unsigned @c int: timestamp>
- *  - <@c unsigned @c int: ::NumPIDJoints>
- *  - for each <i>i</i> of ::NumPIDJoints:
- *    - <@c float: position of joint <i>i</i>>
+ *  - <@c unsigned @c int: framenumber>
+ *  - <@c unsigned @c int: ::NumOutputs>
+ *  - for each <i>i</i> of ::NumOutputs:
+ *    - <@c float: position of output <i>i</i>>
  *  - <@c unsigned @c int: ::NumSensors>
  *  - for each <i>i</i> of ::NumSensors:
  *    - <@c float: value of sensor <i>i</i>>
  *  - <@c unsigned @c int: ::NumButtons>
  *  - for each <i>i</i> of ::NumButtons:
  *    - <@c float: value of button <i>i</i>>
+ *  - <@c unsigned @c int: ::NumPIDJoints>
  *  - for each <i>i</i> of ::NumPIDJoints:
  *    - <@c float: duty cycle of joint <i>i</i>>
  * */
 class WorldStateSerializerBehavior : public BehaviorBase {
 public:
-  WorldStateSerializerBehavior(); //!< constructor
-
+	WorldStateSerializerBehavior(); //!< constructor
+	
 	virtual void DoStart(); //!< starts listening for sensor update events
 	virtual void DoStop(); //!< stops listening for events
 	virtual void processEvent(const EventBase& e); //!< core functionality - performs serialization, sends to sockets
@@ -39,31 +42,36 @@
 		return tmp;
 	}
 	virtual std::string getDescription() const { return getClassDescription(); }
-
+	
+	//! returns string corresponding to the Java GUI which should be launched
+	virtual std::string getGUIType() const { return "org.tekkotsu.mon.WorldStateRecordGUI"; }
+	//! returns port number the Java GUI should connect to
+	virtual unsigned int getPort() const { return config->main.wsjoints_port; }
+	
 protected:
-	//! writes @a value to @a dst and advances @a dst
-  template<class T>
-  inline static void encode(char **dst, const T& value) {
-    memcpy(*dst, &value, sizeof(T));
-		// it'd be nice to use network byte order, but we'll save the aibo extra work
-		//hostToNetwork(*dst, (char *)&value, sizeof(T));
-    (*dst) += sizeof(T);
-  }
-
-	//! writes @a length bytes from @a src to @a dst
-  template<class T>
-  inline static void encode(char **dst, const T * src, int num) {
-    memcpy(*dst, src, num*sizeof(T));
-    (*dst) += num*sizeof(T);
-  }
+	//! writes @a value to @a dst and advances @a dst by 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& value) {
+		memcpy(*dst, &value, sizeof(T));
+		(*dst) += sizeof(T);
+	}
 
-  Socket *wsJoints; //!< socket for sending current joint data
-  Socket *wsPIDs; //!< socket for sending current PID info
-  unsigned int lastProcessedTime; //!< the time that the last event was processed
+	//! 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) {
+		memcpy(*dst, src, num*sizeof(T));
+		(*dst) += num*sizeof(T);
+	}
 
+	Socket *wsJoints; //!< socket for sending current joint data
+	Socket *wsPIDs; //!< socket for sending current PID info
+	unsigned int lastProcessedTime; //!< the time that the last event was processed
+	
 private:
-  WorldStateSerializerBehavior(const WorldStateSerializerBehavior&); //!< don't call
-  WorldStateSerializerBehavior& operator= (const WorldStateSerializerBehavior&); //!< don't call
+	WorldStateSerializerBehavior(const WorldStateSerializerBehavior&); //!< don't call
+	WorldStateSerializerBehavior& operator= (const WorldStateSerializerBehavior&); //!< don't call
 };
 
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Nodes/HeadPointerNode.h ./Behaviors/Nodes/HeadPointerNode.h
--- ../Tekkotsu_2.4.1/Behaviors/Nodes/HeadPointerNode.h	2005-01-24 17:23:50.000000000 -0500
+++ ./Behaviors/Nodes/HeadPointerNode.h	2006-09-27 16:10:27.000000000 -0400
@@ -2,64 +2,42 @@
 #ifndef INCLUDED_HeadPointerNode_h_
 #define INCLUDED_HeadPointerNode_h_
 
-#include "Behaviors/StateNode.h"
-#include "Events/EventRouter.h"
+#include "MCNode.h"
 #include "Motion/HeadPointerMC.h"
 
-//! A simple StateNode that executes a LedMC motion command and throws a status event upon completion
-class HeadPointerNode : public StateNode {
-protected:
-  SharedObject<HeadPointerMC> head_mc;    //!< MotionCommand used by this node
-  MotionManager::MC_ID head_id;  //!< id number for the MotionCommand
-
-public:
-  //! constructor
-  HeadPointerNode(const std::string & nodename="HeadPointerNode") : 
-    StateNode("HeadPointerNode",nodename), head_mc(), head_id(MotionManager::invalid_MC_ID) {}
-
-  //! activate the node
-  virtual void DoStart() {
-    head_id = motman->addPersistentMotion(head_mc);
-    erouter->addListener(this,EventBase::motmanEGID,head_id,EventBase::statusETID);
-    StateNode::DoStart();  // don't activate transitions until our listener has been added
-  }
-
-  //! deactivate the node
-  virtual void DoStop() {
-    motman->removeMotion(head_id);
-    head_id = MotionManager::invalid_MC_ID;
-    erouter->removeListener(this);
-    StateNode::DoStop();
-  }
-
-  //! receive motmanEGID status event and throw stateMachineEGID status event
-  virtual void processEvent(const EventBase&) {
-		postCompletionEvent();
-  }
-
-  //! reveal the MotionCommand
-  SharedObject<HeadPointerMC>& getMC() { return head_mc; }
-
-  //! reveal the MC_ID
-  MotionManager::MC_ID& getMC_ID() { return head_id; }
-
-protected:
-  //! constructor
-  HeadPointerNode(const std::string &classname, const std::string &nodename) : 
-    StateNode(classname,nodename), head_mc(), head_id(MotionManager::invalid_MC_ID) {}
+// You don't actually need to declare extern strings in order to use
+// MCNode, but it's nice...  If you left the name and description
+// off, it would substitute MCNode's default values, but that would
+// yield rather ambiguous debugging output
 
+//!default name for HeadPointerNode's (have to instantiate a variable in order to use as a template argument)
+/*! instantiation will be placed in MCNode.cc (instead of HeadPointerNode.cc) to avoid file bloat */
+extern const char defHeadPointerNodeName[];
+//!default description for HeadPointerNode's (have to instantiate a variable in order to use as a template argument)
+/*! instantiation will be placed in MCNode.cc (instead of HeadPointerNode.cc) to avoid file bloat */
+extern const char defHeadPointerNodeDesc[];
 
+//! A simple StateNode that executes a HeadPointerMC motion command
+class HeadPointerNode : public MCNode<HeadPointerMC,defHeadPointerNodeName,defHeadPointerNodeDesc,true> {
+public:
+	//! default constructor, use type name as instance name
+	HeadPointerNode() : MCNode<HeadPointerMC,defHeadPointerNodeName,defHeadPointerNodeDesc,true>() {}
+	
+	//! constructor, take an instance name
+	HeadPointerNode(const std::string& nm) : MCNode<HeadPointerMC,defHeadPointerNodeName,defHeadPointerNodeDesc,true>(nm) {}
 };
 
+
 /*! @file
  * @brief Defines HeadPointerNode, a simple StateNode that runs a HeadPointerMC motion command and throws a status event upon completion
  * @author dst (Creator)
+ * @author ejt (Rewrote using MCNode)
  *
  * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
  * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
+ * $Date: 2006/10/04 04:21:12 $
  */
 
 #endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Nodes/LedNode.h ./Behaviors/Nodes/LedNode.h
--- ../Tekkotsu_2.4.1/Behaviors/Nodes/LedNode.h	2005-06-01 01:47:46.000000000 -0400
+++ ./Behaviors/Nodes/LedNode.h	2006-09-16 13:32:38.000000000 -0400
@@ -2,53 +2,39 @@
 #ifndef INCLUDED_LedNode_h_
 #define INCLUDED_LedNode_h_
 
-#include "Behaviors/StateNode.h"
-#include "Events/EventRouter.h"
+#include "MCNode.h"
 #include "Motion/LedMC.h"
 
 //! A simple StateNode that executes a LedMC motion command and throws a status event upon completion
-class LedNode : public StateNode {
-protected:
-  SharedObject<LedMC> leds_mc;    //!< MotionCommand used by this node
-  MotionManager::MC_ID leds_id;  //!< id number for the MotionCommand
-
+/*! Extends MCNode slightly so that each time the LedMC is accessed, any flash commands are reset.
+ *  This allows a flash to be triggered each time the node starts */
+class LedNode : public MCNode<LedMC> {
 public:
-  //! constructor
-  LedNode(std::string nodename="LedNode") : 
-    StateNode("LedNode",nodename), leds_mc(), leds_id(MotionManager::invalid_MC_ID) {}
-
-  //! activate the node
-  virtual void DoStart() {
-    leds_id = motman->addPersistentMotion(leds_mc);
-    erouter->addListener(this,EventBase::motmanEGID,leds_id,EventBase::statusETID);
-    StateNode::DoStart();  // don't activate transitions until our listener has been added
-  }
-
-  //! deactivate the node
-  virtual void DoStop() {
-    motman->removeMotion(leds_id);
-    leds_id = MotionManager::invalid_MC_ID;
-    erouter->removeListener(this);
-    StateNode::DoStop();
-  }
-
-  //! receive motmanEGID status event and throw stateMachineEGID status event
-  virtual void processEvent(const EventBase&) {
-		postCompletionEvent();
-  }
-
-  //! reveal the MotionCommand
-  SharedObject<LedMC>& getMC() { return leds_mc; }
-
-  //! reveal the MC_ID
-  MotionManager::MC_ID& getMC_ID() { return leds_id; }
-
+	//! default constructor, use type name as instance name
+	LedNode() : MCNode<LedMC>("LedNode","LedNode"), lastAccess(0) {}
+	
+	//! constructor, take an instance name
+	LedNode(const std::string& nm) : MCNode<LedMC>("LedNode",nm), lastAccess(0) {}
+	
+	static std::string getClassDescription() { return "Displays a pattern on the LEDs for as long as the state is active"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+	
 protected:
-  //! constructor
-  LedNode(const std::string &classname, const std::string &nodename) : 
-    StateNode(classname,nodename), leds_mc(), leds_id(MotionManager::invalid_MC_ID) {}
-
-
+	//! constructor for subclasses (which would need to provide a different class name)
+	LedNode(const std::string &class_name, const std::string &node_name) : MCNode<LedMC>(class_name,node_name), lastAccess(0) {}
+	
+	//! extends MCNode implementation so that each time the LedMC is accessed, any flash commands are reset.
+	virtual SharedObject<LedMC>& getPrivateMC() {
+		unsigned int curtime=get_time();
+		bool isFirstCreation=(mc==NULL);
+		SharedObject<LedMC>& l=MCNode<LedMC>::getPrivateMC();
+		if(!isFirstCreation)
+			l->extendFlash(curtime-lastAccess);
+		lastAccess=curtime;
+		return l;
+	}
+	
+	unsigned int lastAccess; //!< stores time of last call to getPrivateMC()
 };
 
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Nodes/MCNode.cc ./Behaviors/Nodes/MCNode.cc
--- ../Tekkotsu_2.4.1/Behaviors/Nodes/MCNode.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Nodes/MCNode.cc	2006-09-27 16:10:27.000000000 -0400
@@ -0,0 +1,70 @@
+#include "MCNode.h"
+#include "Events/EventRouter.h"
+
+const char MCNodeBase::defName[]="MCNode";
+const char MCNodeBase::defDesc[]="A generic wrapper for any MotionCommand";
+
+// These externs are declared in their respective header files, but
+// 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 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.";
+
+
+void MCNodeBase::DoStart() {
+	StateNode::DoStart(); // do this first (required)
+	if(mc_id==MotionManager::invalid_MC_ID)
+		mc_id = motman->addPersistentMotion(getPrivateMC());
+	else
+		motman->setPriority(mc_id,MotionManager::kStdPriority);
+	erouter->addListener(this,EventBase::motmanEGID,mc_id,EventBase::statusETID);
+}
+
+void MCNodeBase::processEvent(const EventBase& /*e*/) {
+	if(mcCompletes)
+		postCompletionEvent();
+}
+
+void MCNodeBase::DoStop() {
+	erouter->removeListener(this); //generally a good idea, unsubscribe all
+	if(hasPrivateMC()) {
+		motman->removeMotion(mc_id);
+		mc_id=MotionManager::invalid_MC_ID;
+	} else if(mc_id!=MotionManager::invalid_MC_ID) {
+		motman->setPriority(mc_id,MotionManager::kIgnoredPriority);
+	}
+	StateNode::DoStop(); // do this last (required)
+}
+
+void MCNodeBase::setMC(MotionManager::MC_ID mcid) {
+	if(hasPrivateMC()) {
+		if(mc_id!=MotionManager::invalid_MC_ID)
+			motman->removeMotion(mc_id);
+		delete mc;
+		mc=NULL;
+	}
+	mc_id=mcid;
+}
+
+
+/*! @file
+ * @brief Implement's MCNode's default name and description strings (the class is templated, so everything else has to go in the header)
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Nodes/MCNode.h ./Behaviors/Nodes/MCNode.h
--- ../Tekkotsu_2.4.1/Behaviors/Nodes/MCNode.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Nodes/MCNode.h	2006-09-27 16:12:37.000000000 -0400
@@ -0,0 +1,128 @@
+//-*-c++-*-
+#ifndef INCLUDED_MCNode_h_
+#define INCLUDED_MCNode_h_
+
+#include "Behaviors/StateNode.h"
+#include "Motion/MotionManager.h"
+#include "Motion/MMAccessor.h"
+
+//! Common parent class for all the templated MCNode, which is what you want to instantiate.
+class MCNodeBase : public StateNode {
+public:
+	static const char defName[]; //!< the default name for MCNodes -- can be overridden via MCNode's template arguments
+	static const char defDesc[]; //!< the default description for MCNodes -- can be overridden via MCNode's template arguments
+
+	//! destructor, free #mc
+	virtual ~MCNodeBase() { delete mc; }
+	
+	//! Adds the motion command to the motion manager, add a listener for the motion's completion event
+	virtual void DoStart();
+	
+	//! Assumes the event is a completion event from the motion, throws a corresponding state node completion event
+	virtual void processEvent(const EventBase& /*e*/);
+	
+	//! Removes the motion command from the motion manager if it was our own creation
+	virtual void DoStop();	
+	
+	//! Allows you to assign a previously created motion, which might be shared among several MCNodes
+	/*! If this node already has an #mc, then it will be freed, removing from MotionManager if necessary */
+	virtual void setMC(MotionManager::MC_ID mcid);
+	
+	//! reveal the MC_ID; if the motion isn't currently active, returns MotionManager::invalid_MC_ID
+	virtual MotionManager::MC_ID getMC_ID() { return mc_id; }
+	
+	static std::string getClassDescription() { return defName; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+	
+protected:
+	//! constructor for subclasses (which would need to provide a different class name)
+	MCNodeBase(const std::string &class_name, const std::string &node_name, bool expectCompletion=true)
+		: StateNode(class_name,node_name), mc(NULL), mc_id(MotionManager::invalid_MC_ID), mcCompletes(expectCompletion)
+	{}
+	
+	//! returns reference to #mc or a new SharedObject<T> if #mc is currently NULL (so it will always return a valid value)
+	/*! if a particular motion command needs some initial setup besides the default constructor,
+	 *  overriding this function is a good opportunity to do so */
+	virtual SharedObjectBase& getPrivateMC()=0;
+
+	//! returns true if the motion command being used was created internally via getPrivateMC()
+	virtual bool hasPrivateMC() { return mc!=NULL; }
+
+	SharedObjectBase* mc;    //!< MotionCommand used by this node (may be NULL if sharing the MC with other nodes)
+	MotionManager::MC_ID mc_id;  //!< id number for the MotionCommand
+	bool mcCompletes; //!< if true, will post a completion when the underlying MotionCommand posts a status
+
+private:
+	MCNodeBase(const MCNodeBase&); //!< don't call (copy constructor)
+	MCNodeBase& operator=(const MCNodeBase&); //!< don't call (assignment operator)
+};
+
+//! A generic wrapper for any MotionCommand, note that some functions are provided by the MCNodeBase common base class, namely MCNodeBase::setMC() and MCNodeBase::getMC_ID()
+template<class T, const char* mcName=MCNodeBase::defName, const char* mcDesc=MCNodeBase::defDesc, bool completes=true>
+class MCNode : public MCNodeBase {
+public:
+	//! default constructor, use type name as instance name
+	MCNode()
+		: MCNodeBase(mcName,mcName,completes)
+	{}
+	
+	//! constructor, take an instance name
+	MCNode(const std::string& nm)
+		: MCNodeBase(mcName,nm,completes)
+	{}
+	
+	//! destructor
+	virtual ~MCNode() {}
+	
+	//! reveal the MotionCommand through an MMAccessor
+	/*! This is a no-op if the motion command hasn't been added to motion manager yet, and enforces mutual exclusion if it has */
+	virtual MMAccessor<T> getMC();
+	
+	static std::string getClassDescription() { return mcDesc; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+
+protected:
+	//! constructor for subclasses (which would need to provide a different class name)
+	MCNode(const std::string &class_name, const std::string &node_name)
+		: MCNodeBase(class_name,node_name)
+	{}
+	
+	virtual SharedObject<T>& getPrivateMC();
+};
+
+
+// ****************************
+// ******* IMPLEMENTATION *******
+// ****************************
+
+template<class T, const char* mcName, const char* mcDesc, bool completes>
+MMAccessor<T> MCNode<T,mcName,mcDesc,completes>::getMC() {
+	if(mc_id==MotionManager::invalid_MC_ID) {
+		// motion hasn't been added to motion manager yet
+		return MMAccessor<T>(*getPrivateMC());
+	} else {
+		// motion has been added to motion manager, check it out
+		return MMAccessor<T>(mc_id);
+	}
+}
+
+template<class T, const char* mcName, const char* mcDesc, bool completes>
+SharedObject<T>& MCNode<T,mcName,mcDesc,completes>::getPrivateMC() {
+	if(mc==NULL)
+		mc=new SharedObject<T>;
+	return dynamic_cast<SharedObject<T>&>(*mc);
+}
+
+
+/*! @file
+ * @brief Defines MCNode, which provides generic wrapper for any MotionCommand
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Nodes/MotionSequenceNode.h ./Behaviors/Nodes/MotionSequenceNode.h
--- ../Tekkotsu_2.4.1/Behaviors/Nodes/MotionSequenceNode.h	2005-01-27 15:08:15.000000000 -0500
+++ ./Behaviors/Nodes/MotionSequenceNode.h	2006-09-09 00:32:33.000000000 -0400
@@ -109,7 +109,7 @@
 		} else {
 			MMAccessor<MotionSequenceMC<SIZE> > ms(msid);
 			ms->clear();
-			ms->LoadFile(file.c_str());
+			ms->loadFile(file.c_str());
 			ms->setTime(1);
 		}
 		filename=file;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Nodes/PlayMotionSequenceNode.h ./Behaviors/Nodes/PlayMotionSequenceNode.h
--- ../Tekkotsu_2.4.1/Behaviors/Nodes/PlayMotionSequenceNode.h	2005-01-21 17:50:37.000000000 -0500
+++ ./Behaviors/Nodes/PlayMotionSequenceNode.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,27 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_PlayMotionSequenceNode_h_
-#define INCLUDED_PlayMotionSequenceNode_h_
-
-#warning PlayMotionSequenceNode has been deprecated, please use MotionSequenceNode instead.
-
-#include "MotionSequenceNode.h"
-typedef TinyMotionSequenceNode TinyPlayMotionSequenceNode; //!< @deprecated, use MotionSequenceNode directly
-typedef SmallMotionSequenceNode SmallPlayMotionSequenceNode; //!< @deprecated, use MotionSequenceNode directly
-typedef MediumMotionSequenceNode MediumPlayMotionSequenceNode; //!< @deprecated, use MotionSequenceNode directly
-typedef LargeMotionSequenceNode LargePlayMotionSequenceNode; //!< @deprecated, use MotionSequenceNode directly
-typedef XLargeMotionSequenceNode XLargePlayMotionSequenceNode; //!< @deprecated, use MotionSequenceNode directly
-
-
-/*! @file
- * @brief Deprecated version of MotionSequenceNode
- * @deprecated use MotionSequenceNode
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Nodes/SoundNode.h ./Behaviors/Nodes/SoundNode.h
--- ../Tekkotsu_2.4.1/Behaviors/Nodes/SoundNode.h	2005-06-01 01:47:46.000000000 -0400
+++ ./Behaviors/Nodes/SoundNode.h	2006-09-18 14:07:59.000000000 -0400
@@ -9,7 +9,7 @@
 //! A simple StateNode that plays a sound upon startup and throws a status event on completion
 /*! Doesn't automatically preload the sound buffer - if you want the sound file
  *  to be preloaded, you'll have to make the
- *  SoundManager::LoadFile() / SoundManager::ReleaseFile() calls yourself.
+ *  SoundManager::loadFile() / SoundManager::releaseFile() calls yourself.
  *  
  *  By default, sound playback will continue even after this node has been deactivated.
  *  If this is not the behavior you desire, set the #autostop flag (through setAutoStop())
@@ -33,7 +33,7 @@
   virtual void DoStart() {
     StateNode::DoStart();  // don't activate transitions until our listener has been added
 		if(filename.size()>0) {
-			curplay_id = sndman->PlayFile(filename);
+			curplay_id = sndman->playFile(filename);
 			erouter->addListener(this,EventBase::audioEGID,curplay_id,EventBase::deactivateETID);
 		}
   }
@@ -41,7 +41,7 @@
   //! deactivate the node, doesn't stop the sound playback unless the #autostop flag has been set
   virtual void DoStop() {
 		if(autostop)
-			StopPlay();
+			stopPlay();
     erouter->removeListener(this);
     StateNode::DoStop();
   }
@@ -53,8 +53,8 @@
   }
 
   //! interrupts playing of the current sound
-  void StopPlay() {
-    sndman->StopPlay(curplay_id);
+  void stopPlay() {
+    sndman->stopPlay(curplay_id);
     curplay_id = SoundManager::invalid_Play_ID;
   }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Nodes/TailWagNode.h ./Behaviors/Nodes/TailWagNode.h
--- ../Tekkotsu_2.4.1/Behaviors/Nodes/TailWagNode.h	2005-01-24 17:23:50.000000000 -0500
+++ ./Behaviors/Nodes/TailWagNode.h	2006-09-27 16:10:27.000000000 -0400
@@ -2,48 +2,29 @@
 #ifndef INCLUDED_TailWagNode_h_
 #define INCLUDED_TailWagNode_h_
 
-#include "Behaviors/StateNode.h"
-#include "Events/EventRouter.h"
+#include "MCNode.h"
 #include "Motion/TailWagMC.h"
 
-//! A simple StateNode that executes a TailWagMC motion command
-class TailWagNode : public StateNode {
-protected:
-  SharedObject<TailWagMC> tail_mc;    //!< MotionCommand used by this node
-  MotionManager::MC_ID tail_id;  //!< id number for the MotionCommand
-
-public:
-  //! constructor
-  TailWagNode(std::string nodename="TailWagNode") : 
-    StateNode("TailWagNode",nodename), tail_mc(), tail_id(MotionManager::invalid_MC_ID) {}
-
-  //! activate the node
-  virtual void DoStart() {
-    StateNode::DoStart();
-    tail_id = motman->addPersistentMotion(tail_mc);
-    erouter->addListener(this,EventBase::motmanEGID,tail_id,EventBase::statusETID);
-  }
-
-  //! deactivate the node
-  virtual void DoStop() {
-    motman->removeMotion(tail_id);
-    tail_id = MotionManager::invalid_MC_ID;
-    erouter->removeListener(this);
-    StateNode::DoStop();
-  }
-
-  //! receive motmanEGID status event and throw stateMachineEGID status event - this doesn't ever actually happen for a TailWagMC, but just for completeness...
-  virtual void processEvent(const EventBase&) {
-		postCompletionEvent();
-  }
-
-  //! reveal the MotionCommand itself, use getMC_ID() instead if this node isActive().
-  SharedObject<TailWagMC>& getMC() { return tail_mc; }
-
-  //! reveal the MC_ID
-  MotionManager::MC_ID& getMC_ID() { return tail_id; }
+// You don't actually need to declare extern strings in order to use
+// MCNode, but it's nice...  If you left the name and description
+// off, it would substitute MCNode's default values, but that would
+// yield rather ambiguous debugging output
 
+//!default name for TailWagNode'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 defTailWagNodeName[];
+//!default description for TailWagNode'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 defTailWagNodeDesc[];
 
+//! A simple StateNode that executes a TailWagMC motion command
+class TailWagNode : public MCNode<TailWagMC,defTailWagNodeName,defTailWagNodeDesc,false> {
+public:
+	//! default constructor, use type name as instance name
+	TailWagNode() : MCNode<TailWagMC,defTailWagNodeName,defTailWagNodeDesc,false>() {}
+	
+	//! constructor, take an instance name
+	TailWagNode(const std::string& nm) : MCNode<TailWagMC,defTailWagNodeName,defTailWagNodeDesc,false>(nm) {}
 };
 
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Nodes/WalkNode.h ./Behaviors/Nodes/WalkNode.h
--- ../Tekkotsu_2.4.1/Behaviors/Nodes/WalkNode.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Behaviors/Nodes/WalkNode.h	2006-09-27 16:10:27.000000000 -0400
@@ -2,15 +2,23 @@
 #ifndef INCLUDED_WalkNode_h_
 #define INCLUDED_WalkNode_h_
 
-#include "Behaviors/StateNode.h"
+#include "MCNode.h"
 #include "Motion/MotionManager.h"
 #include "Motion/WalkMC.h"
 #include "Motion/MMAccessor.h"
 #include "Events/LocomotionEvent.h"
 #include "Events/EventRouter.h"
 
-//! A StateNode for walking in a direction
-class WalkNode : public StateNode {
+//!default name for WalkEngineNode'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 defWalkNodeName[];
+//!default description for WalkEngineNode'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 defWalkNodeDesc[];
+
+//! A StateNode for walking in a direction, use the template parameter to specify a custom walk MC, or use the ::WalkNode typedef to accept the "default" walk
+template<typename W, const char* mcName=defWalkNodeName, const char* mcDesc=defWalkNodeDesc>
+class WalkEngineNode : public MCNode<W,mcName,mcDesc> {
 public:
 	//! lets us interpret values as either distances or velocities
   enum WalkMode_t {
@@ -20,247 +28,128 @@
 
 public:
 	//!constructor
-	WalkNode()
-	  : StateNode("WalkNode"), walkid(MotionManager::invalid_MC_ID), walkidIsMine(true), x(0), y(0), a(0), n(-1), walkMode()
+	WalkEngineNode()
+	  : MCNode<W,mcName,mcDesc>(), x(0), y(0), a(0), n(-1), walkMode()
 	{}
 
 	//!constructor, positive @a yvel is counter-clockwise from above (to match coordinate system), assumes velocity
-	WalkNode(float xvel, float yvel, float avel)
-	  : StateNode("WalkNode"), walkid(MotionManager::invalid_MC_ID), walkidIsMine(true), x(xvel), y(yvel), a(avel), n(-1), walkMode(VelocityWalkMode)
+	WalkEngineNode(float xvel, float yvel, float avel)
+	  : MCNode<W,mcName,mcDesc>(), x(xvel), y(yvel), a(avel), n(-1), walkMode(VelocityWalkMode)
 	{}
 
 	//!constructor, positive @a yvel is counter-clockwise from above (to match coordinate system), assumes distance
-	WalkNode(float xvel, float yvel, float avel, int steps)
-	  : StateNode("WalkNode"), walkid(MotionManager::invalid_MC_ID), walkidIsMine(true), x(xvel), y(yvel), a(avel), n(steps), walkMode(DistanceWalkMode)
+	WalkEngineNode(float xdist, float ydist, float adist, int steps)
+	  : MCNode<W,mcName,mcDesc>(), x(xdist), y(ydist), a(adist), n(steps), walkMode(DistanceWalkMode)
 	{}
 
 	//!constructor, positive @a yvel is counter-clockwise from above (to match coordinate system), assumes velocity
-	WalkNode(const std::string& name, float xvel, float yvel, float avel)
-	  : StateNode("WalkNode",name), walkid(MotionManager::invalid_MC_ID), walkidIsMine(true), x(xvel), y(yvel), a(avel), n(-1), walkMode(VelocityWalkMode)
+	WalkEngineNode(const std::string& name, float xvel, float yvel, float avel)
+	  : MCNode<W,mcName,mcDesc>(name), x(xvel), y(yvel), a(avel), n(-1), walkMode(VelocityWalkMode)
 	{}
 
 	//!constructor, positive @a yvel is counter-clockwise from above (to match coordinate system), assumes distance
-	WalkNode(const std::string& name, float xvel, float yvel, float avel, int steps)
-	  : StateNode("WalkNode",name), walkid(MotionManager::invalid_MC_ID), walkidIsMine(true), x(xvel), y(yvel), a(avel), n(steps), walkMode(DistanceWalkMode)
+	WalkEngineNode(const std::string& name, float xdist, float ydist, float adist, int steps)
+	  : MCNode<W,mcName,mcDesc>(name), x(xdist), y(ydist), a(adist), n(steps), walkMode(DistanceWalkMode)
 	{}
 
-	//!destructor, check if we need to call our teardown
-	~WalkNode() {
-	  if(issetup)
-	    teardown();
-	}
+	//!destructor
+	~WalkEngineNode() {}
 
 	//! sets the velocity of the walk
-	void setDisplacement(float xd, float yd, float ad, int np = -1) {
-	  //cout << "SET_DISPLACEMENT" << endl;
-	  //updateWalk(xd,yd,ad,np,false);
-	  storeValues(xd, yd, ad, np, DistanceWalkMode);
+	/*! @param xdist x displacement (mm, positive is forward)
+	 *  @param ydist y displacement (mm, positive is left)
+	 *  @param adist angular displacement (rad, positive is counter-clockwise)
+	 *  @param steps how many steps to take to achieve displacement (velocity depends on walk's cycle time parameter) */
+	void setDisplacement(float xdist, float ydist, float adist, int steps = -1) {
+		storeValues(xdist, ydist, adist, steps, DistanceWalkMode);
 	}
 
 	//! sets the velocity of the walk
+	/*! @param xvel x velocity (mm/s, positive is forward)
+	 *  @param yvel y velocity (mm/s, positive is left)
+	 *  @param avel angular velocity (rad/s, positive is counter-clockwise)
+	 *  @param np how many steps to take at specified velocity (resulting distance depends on walk's cycle time parameter) */
 	void setVelocity(float xvel, float yvel, float avel, int np = -1) {
-	  //updateWalk(xvel,yvel,avel,np);
-	  storeValues(xvel, yvel, avel, np, VelocityWalkMode);
+		storeValues(xvel, yvel, avel, np, VelocityWalkMode);
 	}
 	
 	//! sets the velocity in x direction (positive is forward)
 	void setXVelocity(float xvel) { x=xvel; storeValues(xvel, y, a, n, VelocityWalkMode); }
 
 	//! returns the velocity in x direction (positive is forward)
-	float getXVelocity() { return x; }
-
-	//! sets the velocity in y direction (positive is forward)
+	float getX() { return x; }
+	
+	//! sets the velocity in y direction (positive is left)
 	void setYVelocity(float yvel) { y=yvel; storeValues(x, yvel, a, n, VelocityWalkMode); }
-
-	//! returns the velocity in y direction (positive is forward)
-	float getYVelocity() { return y; }
-
+	
+	//! returns the velocity in y direction (positive is left)
+	float getY() { return y; }
+	
 	//! sets the velocity of the turn, positive is counter-clockwise from above (to match coordinate system)
 	void setAVelocity(float avel) { a=avel; storeValues(x, y, avel, n, VelocityWalkMode); }
-
-	//! returns the velocity of the turn, positive is counter-clockwise from above (to match coordinate system)
-	float getAVelocity() { return a; }
+	
+	//! returns the velocity of the turn (positive is counter-clockwise from above (to match coordinate system))
+	float getA() { return a; }
+	
+	//! returns the number of steps being taken (not necessarily the number *remaining*)
+	int getSteps() { return n; }
 
 	virtual void DoStart() {
-		StateNode::DoStart();
-		if (walkid != MotionManager::invalid_MC_ID) {
-		  erouter->addListener(this, EventBase::locomotionEGID, walkid, EventBase::statusETID);
-		}
-
-	  updateWMC();
-	}
-
-	virtual void DoStop() {
-	  //added the 0
-	  //cout << "-----------WALK NODE: DoStop()" << endl;
-	  erouter->removeListener(this);
-	  if(walkid!=MotionManager::invalid_MC_ID) {
-	    MMAccessor<WalkMC> walk(walkid);
-	    walk->setTargetVelocity(0,0,0,0);
-	  }
-	  //updateWalk(0,0,0,0);
-	  StateNode::DoStop();
-	}
-
-        //! receive locomotionEGID status event and throw stateMachineEGID status event, ie a completion event
-        virtual void processEvent(const EventBase& e) {
-	  //cout << "PROCESSING WALK EVENTS" << endl;
-	  if (e.getGeneratorID() == EventBase::locomotionEGID) {
-	    const LocomotionEvent le = *reinterpret_cast<const LocomotionEvent*>(&e);
-	    //cout << "LE description: " << le.getDescription() << endl;
-	    //cout << "LE X: " << le.x << " = 0? " << (le.x == 0) << endl;
-	    //cout << "LE Y: " << le.y << " = 0? " << (le.y == 0) << endl;
-	    //cout << "LE A: " << le.a << " = 0? " << (le.a == 0) << endl;
-	    if (le.x == 0 && le.y == 0 && le.a == 0) {
-	      //cout << "Posting Completion Event for Walk." << endl;
-	      postCompletionEvent();
-	    }
-	  }
-        }
-
-
-	//! removes #walkid if #walkidIsMine
-	virtual void teardown() {
-		if(walkidIsMine) {
-			motman->removeMotion(walkid);
-			walkid=MotionManager::invalid_MC_ID;
-		}
-		StateNode::teardown();
-	}
-
-	//! use this to force the WalkNode to use a shared WalkMC - set to MotionManager::invalid_MC_ID to reset to internally generated walk
-	virtual void setWalkID(MotionManager::MC_ID id) {
-		if(walkidIsMine) {
-			motman->removeMotion(walkid);
-			walkid=MotionManager::invalid_MC_ID;
-		}
-		erouter->removeListener(this, EventBase::locomotionEGID);
-		walkid=id;
-		walkidIsMine=(id==MotionManager::invalid_MC_ID);
-		erouter->addListener(this, EventBase::locomotionEGID, walkid, EventBase::statusETID);
+		MCNode<W,mcName,mcDesc>::DoStart();
+		updateWMC();
 	}
 
-	//! use this to access the WalkMC that the WalkNode is using
-	virtual MotionManager::MC_ID getWalkID() { return walkid; }
-
-	//! returns true if #walkid was created (and will be destroyed) by this WalkNode - false if assigned by setWalkID()
-	virtual bool ownsWalkID() { return walkidIsMine; }
-
 protected:
+	//!constructor, positive @a yvel is counter-clockwise from above (to match coordinate system), assumes velocity
+	WalkEngineNode(const std::string& className, const std::string& instanceName, float xvel, float yvel, float avel)
+	: MCNode<W,mcName,mcDesc>(className,instanceName), x(xvel), y(yvel), a(avel), n(-1), walkMode(VelocityWalkMode)
+	{}
+	
+	//!constructor, positive @a yvel is counter-clockwise from above (to match coordinate system), assumes distance
+	WalkEngineNode(const std::string& className, const std::string& instanceName, float xdist, float ydist, float adist, int steps)
+	: MCNode<W,mcName,mcDesc>(className,instanceName), x(xdist), y(ydist), a(adist), n(steps), walkMode(DistanceWalkMode)
+	{}
+
 	//! stores the values and if active, calls updateWMC()
-  void storeValues(float xp, float yp, float ap, int np, WalkMode_t wmode) {
-    x = xp;
-    y = yp;
-    a = ap;
-    n = np;
-    walkMode = wmode;
+	void storeValues(float xp, float yp, float ap, int np, WalkMode_t wmode) {
+		x = xp;
+		y = yp;
+		a = ap;
+		n = np;
+		walkMode = wmode;
 
-    if (isActive()) {
-      updateWMC();
-    }
-  }
+		if(MCNode<W,mcName,mcDesc>::isActive())
+			updateWMC();
+	}
 
 	//! makes the appropriate calls on the WalkMC
-  void updateWMC() {
-    if(walkid==MotionManager::invalid_MC_ID) {
-      SharedObject<WalkMC> walk;
-      MotionManager::MC_ID id = motman->addPersistentMotion(walk);
-      setWalkID(id);
-      walkidIsMine=true;
-    }
-    MMAccessor<WalkMC> walk(walkid);
-    switch(walkMode) {
-    case VelocityWalkMode:
-      walk->setTargetVelocity(x,y,a,n);
-      break;
-    case DistanceWalkMode:
-      walk->setTargetDisplacement(x,y,a,n); // WalkMC will calculate velocities.
-      break;
-    default:
-      std::cout << "Unknown Walk Mode" << std::endl;
-      break;
-    }
-  }
-
-  /*
-  void updateWMC() {
-    if(walkid==MotionManager::invalid_MC_ID) {
-      SharedObject<WalkMC> walk;
-      switch(walkMode) {
-      case VelocityWalkMode:
-	walk->setTargetVelocity(x,y,a,n);
-	break;
-      case DistanceWalkMode:
-	walk->setTargetDisplacement(x,y,a,n); // WalkMC will calculate velocities.
-	break;
-      default:
-	cout << "Unknown Walk Mode" << endl;
-	break;
-      }
-      MotionManager::MC_ID id = motman->addPersistentMotion(walk);
-      setWalkID(id);
-      walkidIsMine=true;
-    } else {
-      MMAccessor<WalkMC> walk(walkid);
-      switch(walkMode) {
-      case VelocityWalkMode:
-	walk->setTargetVelocity(x,y,a,n);
-	break;
-      case DistanceWalkMode:
-	walk->setTargetDisplacement(x,y,a,n); // WalkMC will calculate velocities.
-	break;
-      default:
-	cout << "Unknown Walk Mode" << endl;
-	break;
-      }
-    }
-  }
-  */
-
-  /*
-	//!if the walk is invalid, create; then set xya
-	void updateWalk(float xp, float yp, float ap, int np=-1, bool isVelocity=true) {
-	  cout << "NNNNNNNNNPPPPPPPPP: " << np << endl;
-	  vector3d velocities;
-	  if(walkid==MotionManager::invalid_MC_ID) {
-	    SharedObject<WalkMC> walk;
-	    if (isVelocity)
-	      walk->setTargetVelocity(xp,yp,ap,np);
-	    else
-	      walk->setTargetDisplacement(xp,yp,ap,np); // WalkMC will calculate velocities.
-	    velocities = walk->getCurVelocity();
-	    MotionManager::MC_ID id = motman->addPersistentMotion(walk);
-	    setWalkID(id);
-	    walkidIsMine=true;
-	  } else {
-	    MMAccessor<WalkMC> walk(walkid);
-	    if (isVelocity)
-	      walk->setTargetVelocity(xp,yp,ap,np);
-	    else
-	      walk->setTargetDisplacement(xp,yp,ap,np); // WalkMC will calculate velocities.
-
-	    velocities = walk->getCurVelocity();  // extract the velocities WalkMC calculated
-	  }
-	  
-	  x = velocities.x;
-	  y = velocities.y;
-	  a = velocities.z;
-	  n = np;
+	void updateWMC() {
+		MMAccessor<W> walk = MCNode<W,mcName,mcDesc>::getMC();
+		switch(walkMode) {
+		case VelocityWalkMode:
+			walk->setTargetVelocity(x,y,a,n);
+			break;
+		case DistanceWalkMode:
+			walk->setTargetDisplacement(x,y,a,n); // WalkMC will calculate velocities.
+			break;
+		default:
+			std::cout << "Unknown Walk Mode" << std::endl;
+			break;
+		}
 	}
-  */
 
-	MotionManager::MC_ID walkid; //!< the current WalkMC
-	bool walkidIsMine; //!< true if the walk was created in updateWalk (instead of assigned externally)
 	float x; //!< velocity in x direction (positive is forward), or distance if #walkMode is DistanceWalkMode
 	float y; //!< velocity in y direction (positive is dog's left), or distance if #walkMode is DistanceWalkMode
 	float a; //!< velocity of the turn, positive is counter-clockwise from above (to match coordinate system), or distance if #walkMode is DistanceWalkMode
 	int n; //!< number of steps (-1 means walk forever)
-
-  WalkMode_t walkMode; //!< the current interpretation of #x, #y, and #a
+	WalkMode_t walkMode; //!< the current interpretation of #x, #y, and #a
 };
 
+//! the prototypical WalkNode, using a WalkMC
+typedef WalkEngineNode<WalkMC> WalkNode;
+
 /*! @file
- * @brief Describes WalkNode, a  StateNode for walking in a direction
+ * @brief Describes WalkEngineNode,  a StateNode for walking in a direction; use the template parameter to specify a custom walk MC, or use the WalkNode typedef to accept the "default" walk
  * @author ejt (Creator)
  *
  * $Author: ejt $
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Nodes/WalkToTargetNode.h ./Behaviors/Nodes/WalkToTargetNode.h
--- ../Tekkotsu_2.4.1/Behaviors/Nodes/WalkToTargetNode.h	2004-12-08 14:05:50.000000000 -0500
+++ ./Behaviors/Nodes/WalkToTargetNode.h	2005-12-15 13:51:27.000000000 -0500
@@ -26,7 +26,7 @@
 	static std::string getClassDescription() { return "walks towards a visual target, using some basic logic for moving the head to track it"; }
 	virtual std::string getDescription() const { return getClassDescription(); }
 
-	//uses head to watch ball, walks towards it
+	//! uses head to watch ball, walks towards it
 	virtual void processEvent(const EventBase& event);
 	
 	virtual Transition* newDefaultLostTrans(StateNode* dest);  //!< returns a suggested transition for detecting "lost" condition, but you don't have to use it
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/README ./Behaviors/README
--- ../Tekkotsu_2.4.1/Behaviors/README	2003-03-01 15:53:25.000000000 -0500
+++ ./Behaviors/README	2006-09-14 15:22:11.000000000 -0400
@@ -8,4 +8,7 @@
 
       Nodes - For finite state machines, we'll put general purpose nodes here.
 
+   Services - These are behaviors which provide a useful service during execution, not just
+              sample code.  For instance, automatic get up, battery monitoring, etc.
+
 Transitions - For finite state machines, we'll put general purpose transitions here.
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Services/AutoGetupBehavior.h ./Behaviors/Services/AutoGetupBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Services/AutoGetupBehavior.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Services/AutoGetupBehavior.h	2006-09-18 14:07:56.000000000 -0400
@@ -0,0 +1,83 @@
+//-*-c++-*-
+#ifndef INCLUDED_AutoGetupBehavior_h_
+#define INCLUDED_AutoGetupBehavior_h_
+
+#include "Behaviors/BehaviorBase.h"
+#include "Shared/WorldState.h"
+#include "Events/EventRouter.h"
+#include "IPC/SharedObject.h"
+#include "Motion/MotionManager.h"
+#include "Motion/MotionSequenceMC.h"
+#include "Shared/Config.h"
+#include "Sound/SoundManager.h"
+
+//! a little background behavior to keep the robot on its feet
+class AutoGetupBehavior : public BehaviorBase {
+public:
+	//! constructor
+	AutoGetupBehavior() : BehaviorBase("AutoGetupBehavior"), back(0), side(0), gamma(.9), sensitivity(.85*.85), waiting(false) {}
+	//! destructor
+	virtual ~AutoGetupBehavior() {}
+
+	//! Listens for the SensorSourceID::UpdatedSID
+	virtual void DoStart() {
+		BehaviorBase::DoStart();
+		erouter->addListener(this,EventBase::sensorEGID,SensorSourceID::UpdatedSID);
+	}
+	//! Stops listening for events
+	virtual void DoStop() {
+		erouter->removeListener(this);
+		BehaviorBase::DoStop();
+	}
+	//! Run appropriate motion script if the robot falls over
+	virtual void processEvent(const EventBase &event) {
+		if(event.getGeneratorID()==EventBase::motmanEGID) {
+			//previous attempt at getting up has completed
+			cout << "Getup complete" << endl;
+			erouter->removeListener(this,EventBase::motmanEGID);
+			waiting=false;
+			return;
+		}
+		back=back*gamma+(1-gamma)*state->sensors[BAccelOffset];
+		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;
+			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)
+			if(fabs(back)<fabs(side))
+				gu=config->motion.makePath("gu_side.mot");
+			else if(back<0)
+				gu=config->motion.makePath("gu_back.mot");
+			else
+				gu=config->motion.makePath("gu_front.mot");
+			SharedObject<MediumMotionSequenceMC> getup(gu.c_str());
+			MotionManager::MC_ID id=motman->addPrunableMotion(getup,MotionManager::kHighPriority);
+			erouter->addListener(this,EventBase::motmanEGID,id,EventBase::deactivateETID);
+			waiting=true;
+		}
+	}
+	static std::string getClassDescription() { return "Monitors gravity's influence on the accelerometers - if it seems the robot has fallen over, it runs appropriate getup script"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+
+protected:
+	float back;          //!< exponential average of backwards accel
+	float side;          //!< exponential average of sideways accel
+	float gamma;         //!< default 0.9, gamma parameter for exponential average of above
+	float sensitivity;   //!< default 0.85*0.85, squared threshold to consider having fallen over, use values 0-1
+	bool  waiting;       //!< true while we're waiting to hear from completion of MotionSequence, won't try again until this is cleared
+};
+
+/*! @file
+ * @brief Defines AutoGetupBehavior, a little background behavior to keep the robot on its feet
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Services/BatteryMonitorBehavior.h ./Behaviors/Services/BatteryMonitorBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Services/BatteryMonitorBehavior.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Services/BatteryMonitorBehavior.h	2006-09-14 15:14:03.000000000 -0400
@@ -0,0 +1,165 @@
+//-*-c++-*-
+#ifndef INCLUDED_BatteryMonitorBehavior_h_
+#define INCLUDED_BatteryMonitorBehavior_h_
+
+#include "Behaviors/BehaviorBase.h"
+#include "Shared/debuget.h"
+#include "Shared/WorldState.h"
+#include "Events/EventRouter.h"
+#include "IPC/SharedObject.h"
+#include "Motion/MotionManager.h"
+#include "Motion/PostureMC.h"
+#include "Motion/LedMC.h"
+#include "Shared/ERS210Info.h"
+#include "Shared/ERS220Info.h"
+#include "Shared/ERS7Info.h"
+#include "Motion/MMAccessor.h"
+
+//! A background behavior which will monitor the power level and flip the ears when appropriate on a 210, or blink the headlight if a 220
+/*! Think of this as a simple example class.  For exercise, try using a MotionSequenceMC instead
+ *  of switching the ears back manually using a PostureMC */
+class BatteryMonitorBehavior : public BehaviorBase {
+public:
+	static const unsigned int max_t=10000; //!< max time between ear flips when at "high power" mark
+	static const unsigned int high_power_p=20; //!< percent of 100 which is point at which to begin warning
+	static const unsigned int no_power_p=14; //!< percent of 100 at which power will fail (approximate!)
+
+	//! constructor
+	BatteryMonitorBehavior() : BehaviorBase("BatteryMonitorBehavior"), pose(NULL), pose_id(MotionManager::invalid_MC_ID), led_id(MotionManager::invalid_MC_ID) {}
+	//! destructor
+	virtual ~BatteryMonitorBehavior() {}
+
+	//! Listens for the PowerSourceID::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);
+		//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));
+	}
+	//! Stops listening for events
+	virtual void DoStop() {
+		if(pose!=NULL)
+			stopWarning();
+		erouter->removeListener(this);
+		BehaviorBase::DoStop();
+	}
+	//! Adds a BatteryMonitorMC to motman if power goes low
+	virtual void processEvent(const EventBase &event) {
+		if(event.getGeneratorID()==EventBase::powerEGID) {
+			//just check for low power status
+			bool shouldwarn=shouldWarn();
+			if(pose!=NULL && !shouldwarn)
+				stopWarning();
+			else if(pose==NULL && shouldwarn)
+				startWarning();
+		} else {
+			ASSERTRET(event.getGeneratorID()==EventBase::timerEGID,"Unrequested event "<<event.getName());
+			switch(event.getSourceID()) {
+			case 1: { // toggle the ears (signals low battery), show battery level on LEDs
+				ASSERTRET(pose!=NULL,"Extra timer 1");
+				setFlipper(true);
+				unsigned int flipdelay=calcFlipDelay();
+				// if we're just constantly flipping the ears, a slight change is needed so the battery
+				// level isn't obscuring the LED settings
+				if(flipdelay<=NumFrames*FrameTime) {
+					static bool on=false;
+					on=!on;
+					if(on) {
+						motman->setPriority(led_id,MotionManager::kEmergencyPriority+1);
+						MMAccessor<LedMC> led(led_id);
+						led->displayPercent(state->sensors[PowerRemainOffset],LedEngine::major,LedEngine::major);
+					} else
+						motman->setPriority(led_id,MotionManager::kIgnoredPriority);
+					erouter->addTimer(this,1,128+flipdelay,false);
+				} else {
+					motman->setPriority(led_id,MotionManager::kEmergencyPriority+1);
+					MMAccessor<LedMC> led(led_id);
+					led->displayPercent(state->sensors[PowerRemainOffset],LedEngine::major,LedEngine::major);
+					erouter->addTimer(this,2,128,false);
+				}
+			} break;
+			case 2: { // release ear until next flap, hide LEDs display
+				ASSERTRET(pose!=NULL,"Extra timer 1");
+				setFlipper(false);
+				motman->setPriority(led_id,MotionManager::kIgnoredPriority);
+				erouter->addTimer(this,1,calcFlipDelay(),false);
+			} break;
+			default:
+				ASSERTRET(false,"Unrequested timer " << event.getName());
+				break;
+			}
+		}
+	}
+	static std::string getClassDescription() { return "Reports the current battery status, and starts flicks the ears to warn when it gets too low"; }
+	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]; }
+
+protected:
+	//! adds a pose and a timer to get the ears flipping
+	void startWarning() {
+		serr->printf("LOW BATTERY\n");
+		pose_id=motman->addPersistentMotion(SharedObject<PostureMC>(),MotionManager::kEmergencyPriority+1);
+		pose=(PostureMC*)motman->peekMotion(pose_id);
+		SharedObject<LedMC> led;
+		led->displayPercent(state->sensors[PowerRemainOffset],LedEngine::major,LedEngine::major);
+		led_id=motman->addPersistentMotion(led,MotionManager::kEmergencyPriority+1);
+		setFlipper(true);
+		erouter->addTimer(this,2,128,false);
+	}
+	//! removes pose, in case battery magically charges
+	void stopWarning() {
+		serr->printf("BATTERY GOOD\n");
+		motman->removeMotion(pose_id);
+		motman->removeMotion(led_id);
+		led_id=pose_id=MotionManager::invalid_MC_ID;
+		pose=NULL;
+		erouter->removeTimer(this,1);
+		erouter->removeTimer(this,2);
+	}
+	//! makes the ears flip more rapidly as power declines.  Flips back and forth once every 15 seconds at 15%, down to flipping constantly at 5%.
+	unsigned int calcFlipDelay() {
+		const float high_power=high_power_p/100.0;
+		const float no_power=no_power_p/100.0;
+		float cur_power=state->sensors[PowerRemainOffset];
+		if(cur_power<no_power)
+			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
+	void setFlipper(bool set) {
+		if(state->robotDesign & WorldState::ERS210Mask)
+			for(unsigned int i=ERS210Info::EarOffset; i<ERS210Info::EarOffset+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++)
+				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
+	MotionManager::MC_ID led_id; //!< id of LedMC if we are currently warning, MotionManager::invalid_MC_ID otherwise
+
+private:
+	BatteryMonitorBehavior(const BatteryMonitorBehavior&); //!< don't copy behaviors
+	BatteryMonitorBehavior operator=(const BatteryMonitorBehavior&); //!< don't assign behaviors
+};
+
+/*! @file
+ * @brief Defines BatteryMonitorBehavior, a background behavior to trigger BatteryMonitorMC to warn when the power is low
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Services/FlashIPAddrBehavior.cc ./Behaviors/Services/FlashIPAddrBehavior.cc
--- ../Tekkotsu_2.4.1/Behaviors/Services/FlashIPAddrBehavior.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Services/FlashIPAddrBehavior.cc	2006-09-18 14:07:56.000000000 -0400
@@ -0,0 +1,187 @@
+#include "FlashIPAddrBehavior.h"
+
+#include "Events/EventRouter.h"
+#include "Motion/MMAccessor.h"
+#include "Motion/LedEngine.h"
+#include "Shared/WorldState.h"
+#include "Shared/Config.h"
+#include "Sound/SoundManager.h"
+#include "Wireless/Wireless.h"
+
+void FlashIPAddrBehavior::DoStart() {
+	BehaviorBase::DoStart(); // do this first
+	if(config->behaviors.flash_on_start) {
+		setupSequence();
+		loadSounds();
+		ms_id = motman->addPrunableMotion(ms,MotionManager::kEmergencyPriority+1);
+		erouter->addListener(this,EventBase::motmanEGID,ms_id,EventBase::deactivateETID);
+	}
+	erouter->addListener(this,EventBase::buttonEGID,button1);
+	erouter->addListener(this,EventBase::buttonEGID,button2);
+}
+
+void FlashIPAddrBehavior::DoStop() {
+	erouter->removeListener(this);
+	motman->removeMotion(ms_id);
+	ms_id=MotionManager::invalid_MC_ID;
+	releaseSounds();
+	BehaviorBase::DoStop(); // do this last
+}
+
+void FlashIPAddrBehavior::processEvent(const EventBase& e) {
+	if(e.getGeneratorID()==EventBase::timerEGID) {
+
+		if(e.getSourceID()==ACTIVATE_TIMER) {
+			//buttons have been held down long enough, time to run display
+			if(ms_id!=MotionManager::invalid_MC_ID) {
+				//there's already one running, have to check it out to clear it
+				MMAccessor<MSMC_t> ms_acc(ms_id);
+				setupSequence();
+			} else
+				setupSequence();
+			loadSounds();
+			ms_id = motman->addPrunableMotion(ms);
+			erouter->addListener(this,EventBase::motmanEGID,ms_id,EventBase::deactivateETID);
+				
+		} else { //its time to play a digit sound file
+			//the source id was set to correspond to an element of the sounds vector
+			if(e.getSourceID()>=sounds.size())
+				serr->printf("ERROR: %s received invalid timer event %s\n",getName().c_str(),e.getName().c_str());
+			else {
+				sndman->playFile(sounds[e.getSourceID()]);
+				if(e.getSourceID()==sounds.size()-1)
+					releaseSounds();
+			}
+				
+		}
+
+	} 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
+		if(e.getTypeID()==EventBase::activateETID) {
+			if(state->buttons[button1] && state->buttons[button2])
+				erouter->addTimer(this,ACTIVATE_TIMER,2000,false);
+		} else if(e.getTypeID()==EventBase::deactivateETID)
+			erouter->removeTimer(this,ACTIVATE_TIMER);
+
+	} else if(e.getGeneratorID()==EventBase::motmanEGID) {
+		// display has completed, mark it as such
+		if(e.getSourceID()!=ms_id)
+			serr->printf("WARNING: %s received event %s, doesn't match ms_id (%d)\n",getName().c_str(),e.getName().c_str(),ms_id);
+		ms_id=MotionManager::invalid_MC_ID;
+		erouter->removeListener(this,EventBase::motmanEGID);
+			
+	}
+}
+
+void FlashIPAddrBehavior::loadSounds() {
+	for(unsigned int i=0; i<sounds.size(); i++)
+		sndman->loadFile(sounds[i]);
+}
+
+void FlashIPAddrBehavior::releaseSounds() {
+	for(unsigned int i=0; i<sounds.size(); i++)
+		sndman->releaseFile(sounds[i]);
+	sounds.clear();
+}
+
+void FlashIPAddrBehavior::setupSequence() {
+	const unsigned int DISP_TIME=600;
+	const unsigned int GROUP_TIME=500;
+	const unsigned int DOT_TIME=400;
+	const unsigned int FADE_TIME=1;
+	const unsigned int BLANK_TIME=100-FADE_TIME*2;
+	erouter->removeTimer(this);
+	ms->clear();
+	releaseSounds();
+	unsigned int a=wireless->getIPAddress();
+	unsigned int n=config->behaviors.flash_bytes;
+	if(n>4)
+		n=4;
+	LedEngine disp;
+	for(unsigned int i=n-1; i!=-1U; i--) {
+		unsigned int byte=(a>>(i*8))&0xFF;
+		unsigned int digits=1;
+		if(byte>=10)
+			digits++;
+		if(byte>=100)
+			digits++;
+		//cout << "byte " << i << " is " << byte << " -- " << digits << " digits" << endl;
+		//cout << "Setting LEDs: ";
+		for(unsigned int d=0; d<digits; d++) {
+			unsigned int digit=byte;
+			for(unsigned int j=d;j<digits-1;j++)
+				digit/=10;
+			digit-=(digit/10)*10;
+			disp.displayNumber(digit,LedEngine::onedigit);
+			std::string soundfile="numbers/";
+			soundfile+=(digit+'0');
+			soundfile+=".wav";
+			erouter->addTimer(this,sounds.size(),ms->getTime()+delay,false);
+			sounds.push_back(soundfile);
+			for(unsigned int j=0; j<NumLEDs; j++)
+				if(FaceLEDMask&(1<<j)) {
+					//if(disp.getValue(static_cast<LEDOffset_t>(LEDOffset+j)))
+					//cout << j << ' ';
+					ms->setOutputCmd(LEDOffset+j,disp.getValue(static_cast<LEDOffset_t>(LEDOffset+j)));
+				}
+			ms->advanceTime(DISP_TIME);
+			for(unsigned int j=0; j<NumLEDs; j++)
+				if(FaceLEDMask&(1<<j))
+					ms->setOutputCmd(LEDOffset+j,disp.getValue(static_cast<LEDOffset_t>(LEDOffset+j)));
+			ms->advanceTime(FADE_TIME);
+			for(unsigned int j=0; j<NumLEDs; j++)
+				if(FaceLEDMask&(1<<j))
+					ms->setOutputCmd(LEDOffset+j,0);
+			ms->advanceTime(BLANK_TIME);
+			if(d==digits-1)
+				ms->advanceTime(GROUP_TIME);
+			for(unsigned int j=0; j<NumLEDs; j++)
+				if(FaceLEDMask&(1<<j))
+					ms->setOutputCmd(LEDOffset+j,0);
+			ms->advanceTime(FADE_TIME);
+		}
+		//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) {
+				dot=LedEngine::ERS220numMasks[10];
+			} else if(state->robotDesign&WorldState::ERS7Mask) {
+				dot=LedEngine::ERS7numMasks[10];
+			}
+			erouter->addTimer(this,sounds.size(),ms->getTime()+delay,false);
+			sounds.push_back("numbers/dot.wav");
+			for(unsigned int j=0; j<NumLEDs; j++)
+				if(FaceLEDMask&(1<<j))
+					ms->setOutputCmd(LEDOffset+j,(dot>>j)&1);
+			ms->advanceTime(DOT_TIME);
+			for(unsigned int j=0; j<NumLEDs; j++)
+				if(FaceLEDMask&(1<<j))
+					ms->setOutputCmd(LEDOffset+j,(dot>>j)&1);
+			ms->advanceTime(FADE_TIME);
+			for(unsigned int j=0; j<NumLEDs; j++)
+				if(FaceLEDMask&(1<<j))
+					ms->setOutputCmd(LEDOffset+j,0);
+			ms->advanceTime(BLANK_TIME);
+			for(unsigned int j=0; j<NumLEDs; j++)
+				if(FaceLEDMask&(1<<j))
+					ms->setOutputCmd(LEDOffset+j,0);
+			ms->advanceTime(FADE_TIME);
+		}
+	}
+	ms->play();
+}
+
+
+/*! @file
+ * @brief Implements FlashIPAddrBehavior, which displays IP address by flashing a series of numbers on the LED face panel
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Services/FlashIPAddrBehavior.h ./Behaviors/Services/FlashIPAddrBehavior.h
--- ../Tekkotsu_2.4.1/Behaviors/Services/FlashIPAddrBehavior.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Services/FlashIPAddrBehavior.h	2006-09-14 15:14:04.000000000 -0400
@@ -0,0 +1,67 @@
+//-*-c++-*-
+#ifndef INCLUDED_FlashIPAddrBehavior_h_
+#define INCLUDED_FlashIPAddrBehavior_h_
+
+#include "Behaviors/BehaviorBase.h"
+#include "Motion/MotionManager.h"
+#include "Motion/MotionSequenceMC.h"
+
+//! Displays IP address by speaking the digits and flashing a series of numbers on the LED face panel
+/*! Will only run the display on DoStart() if the flash_on_start
+ *  config variable is set.  Otherwise you will need to hold down the
+ *  buttons specified by #button1 and #button2 to trigger the display.
+ *  Note that if the e-stop is active it will intercept the button
+ *  events, so turn off e-stop first. */
+class FlashIPAddrBehavior : public BehaviorBase {
+public:
+	//! constructor
+	FlashIPAddrBehavior()
+		: BehaviorBase("FlashIPAddrBehavior"), sounds(), ms(), ms_id(MotionManager::invalid_MC_ID)
+	{}
+
+	virtual void DoStart(); //!< if the Config::behavior_config::flash_on_start flag is set, will setup and run
+	virtual void DoStop();  //!< halts any display which may be in progress
+
+	//! Receives button events, timers, and motman manager pruning notifications
+	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 ";
+		pre+=buttonNames[button1];
+		pre+=" and ";
+		pre+=buttonNames[button2];
+		pre+=" to trigger any time while running";
+		return pre;
+	}
+	virtual std::string getDescription() const { return getClassDescription(); }
+	
+protected:
+	typedef XLargeMotionSequenceMC MSMC_t; //!< used to flash the LEDs to report the IP address
+
+	void loadSounds();    //!< loads the numeric sounds into memory
+	void releaseSounds(); //!< releases the numeric sounds
+	void setupSequence(); //!< construct the motion sequence for flashing leds, request timers to play corresponding sound file
+
+	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
+	
+	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)
+	static const unsigned int delay=64; //!< time (in milliseconds) to expect #ms to be delayed before it actually starts
+	
+	SharedObject<MSMC_t> ms; //!< motion sequence used to control the LEDs
+	MotionManager::MC_ID ms_id; //!< id number of #ms
+};
+
+/*! @file
+ * @brief Describes FlashIPAddrBehavior, which displays IP address by flashing a series of numbers on the LED face panel
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Services/WorldStateVelDaemon.h ./Behaviors/Services/WorldStateVelDaemon.h
--- ../Tekkotsu_2.4.1/Behaviors/Services/WorldStateVelDaemon.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Services/WorldStateVelDaemon.h	2006-09-14 15:14:04.000000000 -0400
@@ -0,0 +1,95 @@
+//-*-c++-*-
+#ifndef INCLUDED_WorldStateVelDaemon_h_
+#define INCLUDED_WorldStateVelDaemon_h_
+
+#include "Behaviors/BehaviorBase.h"
+#include "Events/EventRouter.h"
+#include "Events/LocomotionEvent.h"
+#include "Shared/WorldState.h"
+#include "Events/EventTrapper.h"
+
+//! Listens for LocomotionEvents and updates the velocity fields of WorldState
+/*! If we get multiple ways of locomoting, this would be a good place
+ *  to manage them to determine the actual final velocity.
+ *
+ *  Right now it'll correctly handle one (or more i suppose) e-stops
+ *  with a single other locomotor.  But if there's two active
+ *  locomotors, I dunno how to handle that.
+ */
+class WorldStateVelDaemon : public BehaviorBase, public EventTrapper {
+public:
+	//! constructor
+	WorldStateVelDaemon() : BehaviorBase("WorldStateVelDaemon"), estopTime(1), old_x(0), old_y(0), old_a(0) {}
+
+	virtual void DoStart() {
+		BehaviorBase::DoStart(); // do this first
+		erouter->addTrapper(this,EventBase::locomotionEGID);
+		erouter->addListener(this,EventBase::estopEGID);
+	}
+
+	virtual void DoStop() {
+		erouter->removeListener(this);
+		erouter->removeTrapper(this);
+		BehaviorBase::DoStop(); // do this last
+	}
+
+	//! traps locomotion events - will filter them out if currently in EStop
+	virtual bool trapEvent(const EventBase& e) {
+		const LocomotionEvent& le=dynamic_cast<const LocomotionEvent&>(e);
+		old_x=le.x;
+		old_y=le.y;
+		old_a=le.a;
+		if(!estopTime) {
+			state->vel_x=le.x;
+			state->vel_y=le.y;
+			state->vel_a=le.a;
+			state->vel_time=le.getTimeStamp();
+			return false;
+		}
+		return true;
+	}
+
+	virtual void processEvent(const EventBase& e) {
+		if(e.getTypeID()==EventBase::deactivateETID) {
+			if(estopTime) {
+				estopTime=0;
+				LocomotionEvent le(EventBase::locomotionEGID,e.getSourceID(),EventBase::statusETID,e.getTimeStamp()-state->vel_time);
+				le.setXYA(old_x,old_y,old_a);
+				erouter->postEvent(le);
+			}
+		} else {
+			if(!estopTime) {
+				float older_x=old_x;
+				float older_y=old_y;
+				float older_a=old_a;
+				erouter->postEvent(LocomotionEvent(EventBase::locomotionEGID,e.getSourceID(),EventBase::statusETID,e.getTimeStamp()-state->vel_time));
+				estopTime=e.getTimeStamp();
+				old_x=older_x;
+				old_y=older_y;
+				old_a=older_a;
+			}
+		}
+	}
+
+	static std::string getClassDescription() { return "Keeps the WorldState's velocity fields up to date"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+	
+protected:
+	unsigned int estopTime; //!< time estop activation was received
+	float old_x; //!< current velocity of underlying locomotor
+	float old_y; //!< current velocity of underlying locomotor
+	float old_a; //!< current velocity of underlying locomotor
+};
+
+/*! @file
+ * @brief Defines WorldStateVelDaemon, which listens for LocomotionEvents and updates the velocity fields of WorldState
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/StateNode.cc ./Behaviors/StateNode.cc
--- ../Tekkotsu_2.4.1/Behaviors/StateNode.cc	2005-04-15 17:30:55.000000000 -0400
+++ ./Behaviors/StateNode.cc	2005-11-08 16:36:06.000000000 -0500
@@ -79,15 +79,15 @@
 }
 
 void StateNode::postStartEvent() {
-	erouter->postEvent(EventBase::stateMachineEGID,reinterpret_cast<unsigned int>(this),EventBase::activateETID,0,getName(),1);
+	erouter->postEvent(EventBase::stateMachineEGID,reinterpret_cast<size_t>(this),EventBase::activateETID,0,getName(),1);
 }
 
 void StateNode::postCompletionEvent(float magnitude/*=0*/) {
-	erouter->postEvent(EventBase::stateMachineEGID,reinterpret_cast<unsigned int>(this),EventBase::statusETID,get_time()-startedTime,getName(),magnitude);
+	erouter->postEvent(EventBase::stateMachineEGID,reinterpret_cast<size_t>(this),EventBase::statusETID,get_time()-startedTime,getName(),magnitude);
 }
 
 void StateNode::postStopEvent() {
-	erouter->postEvent(EventBase::stateMachineEGID,reinterpret_cast<unsigned int>(this),EventBase::deactivateETID,get_time()-startedTime,getName(),0);
+	erouter->postEvent(EventBase::stateMachineEGID,reinterpret_cast<size_t>(this),EventBase::deactivateETID,get_time()-startedTime,getName(),0);
 }
 
 /*! @file 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/StateNode.h ./Behaviors/StateNode.h
--- ../Tekkotsu_2.4.1/Behaviors/StateNode.h	2005-08-07 00:11:02.000000000 -0400
+++ ./Behaviors/StateNode.h	2006-10-03 18:11:44.000000000 -0400
@@ -8,11 +8,21 @@
 #include <string>
 
 //! Recursive data structure - both a state machine controller as well as a node within a state machine itself
-/*! Override setup() to setup your own Transition and StateNode network.
- *  There are two StateNode templates in <a href="http://cvs.tekkotsu.org/cgi-bin/viewcvs.cgi/Tekkotsu/project/templates/"><i>project</i><tt>/templates/</tt></a>: <a href="http://cvs.tekkotsu.org/cgi-bin/viewcvs.cgi/Tekkotsu/project/templates/statenode.h?rev=HEAD&content-type=text/vnd.viewcvs-markup">statenode.h</a> and <a href="http://cvs.tekkotsu.org/cgi-bin/viewcvs.cgi/Tekkotsu/project/templates/statemachine.h?rev=HEAD&content-type=text/vnd.viewcvs-markup">statemachine.h</a>.
- *  statenode.h is meant for leaf nodes, which directly implement the execution of a task.
- *  statemachine.h is meant for nodes which contain a network of transitions and subnodes, which together solve the task.
-*/
+/*!
+ *  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.
+ *
+ *  You can override setup to create a sub-network, as well as overriding DoStart and DoStop, in the same class.
+ *  
+ *  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.
+ *  - <a href="http://cvs.tekkotsu.org/cgi/viewcvs.cgi/Tekkotsu/project/templates/statemachine.h?rev=HEAD&content-type=text/vnd.viewcvs-markup">statemachine.h</a>
+ *    is intended for nodes which contain a network of transitions and subnodes, which together solve the task.
+ */
 class StateNode  : public BehaviorBase {
 public:
 	//!constructor, pass a name to use
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Transition.cc ./Behaviors/Transition.cc
--- ../Tekkotsu_2.4.1/Behaviors/Transition.cc	2005-08-03 14:47:58.000000000 -0400
+++ ./Behaviors/Transition.cc	2006-09-18 14:08:05.000000000 -0400
@@ -10,9 +10,9 @@
 	AddReference(); //just in case a side effect of this transition is to dereference the transition, we don't want to be deleted while still transitioning
 
 	if(sound.size()!=0)
-		sndman->PlayFile(sound);
+		sndman->playFile(sound);
 
-	erouter->postEvent(EventBase::stateTransitionEGID,reinterpret_cast<int>(this),EventBase::statusETID,0,getName(),1);
+	erouter->postEvent(EventBase::stateTransitionEGID,reinterpret_cast<size_t>(this),EventBase::statusETID,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...
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Transition.h ./Behaviors/Transition.h
--- ../Tekkotsu_2.4.1/Behaviors/Transition.h	2005-08-07 00:11:02.000000000 -0400
+++ ./Behaviors/Transition.h	2006-10-03 17:08:20.000000000 -0400
@@ -32,7 +32,7 @@
  *  depending whether the source was added to the transition or the
  *  transition was added to the source.  Confusing?  Exactly.
  *
- *  A template file is available at <a href="http://cvs.tekkotsu.org/cgi-bin/viewcvs.cgi/Tekkotsu/project/templates/transition.h?rev=HEAD&content-type=text/vnd.viewcvs-markup"><i>project</i><tt>/templates/transition.h</tt></a>,
+ *  A template file is available at <a href="http://cvs.tekkotsu.org/cgi/viewcvs.cgi/Tekkotsu/project/templates/transition.h?rev=HEAD&content-type=text/vnd.viewcvs-markup"><i>project</i><tt>/templates/transition.h</tt></a>,
  *  which will help you get moving faster.
  */
 class Transition : public BehaviorBase {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Transitions/RandomTrans.cc ./Behaviors/Transitions/RandomTrans.cc
--- ../Tekkotsu_2.4.1/Behaviors/Transitions/RandomTrans.cc	2005-06-01 01:47:46.000000000 -0400
+++ ./Behaviors/Transitions/RandomTrans.cc	2006-09-18 14:08:04.000000000 -0400
@@ -34,7 +34,7 @@
 void RandomTrans::fire() {
   AddReference(); // for safety
   if ( sound.size()!=0 )
-    sndman->PlayFile(sound);
+    sndman->playFile(sound);
 
   for(size_t i=0; i<srcs.size(); i++)
     if(srcs[i]->isActive())  // don't deactivate a non-active node
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Behaviors/Transitions/SignalTrans.h ./Behaviors/Transitions/SignalTrans.h
--- ../Tekkotsu_2.4.1/Behaviors/Transitions/SignalTrans.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Behaviors/Transitions/SignalTrans.h	2006-09-16 16:11:51.000000000 -0400
@@ -0,0 +1,51 @@
+//-*-c++-*-
+#ifndef INCLUDED_SignalTrans_h_
+#define INCLUDED_SignalTrans_h_
+
+#include "Behaviors/Transition.h"
+#include "Events/DataEvent.h"
+#include "Events/EventRouter.h"
+
+//! causes a transition if a DataEvent from stateSignalEGID occurs with a specific value
+/*! This allows a state node to signal a transition to another state
+ *  in a clean symbolic way.  Only the transition itself needs to
+ *  know the address of the destination node.
+ */
+
+template<class T>
+class SignalTrans : public Transition {
+public:
+  //! Constructor
+  SignalTrans(StateNode *destination, const T &value) :
+    Transition("SignalTrans",destination), val(value)
+  { }
+
+  //! Constructor
+  SignalTrans(const std::string &name, StateNode *destination, const T &value) :
+    Transition("SignalTrans",name,destination), val(value)
+  { }
+
+  virtual void DoStart() {
+    Transition::DoStart();
+    for ( std::vector<StateNode*>::const_iterator it = srcs.begin(); it != srcs.end(); it++ )
+      erouter->addListener(this,EventBase::stateSignalEGID,(unsigned int)*it);
+  }
+
+  virtual void processEvent(const EventBase &event) {
+    const DataEvent<T> &d_event = dynamic_cast<const DataEvent<T>&>(event);
+    if ( d_event.getData() == val )
+      fire();
+  }
+
+protected:
+  //! Constructor
+  SignalTrans(const std::string &classname, const std::string &instancename,
+	      StateNode *destination, const T &value) :
+    Transition(classname,instancename,destination,value)
+  { }
+
+  T val; //!< value to compare against
+
+};
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/AgentData.cc ./DualCoding/AgentData.cc
--- ../Tekkotsu_2.4.1/DualCoding/AgentData.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/AgentData.cc	2006-05-19 13:14:59.000000000 -0400
@@ -0,0 +1,135 @@
+//-*-c++-*-
+
+#include <vector>
+#include <iostream>
+#include <math.h>
+
+#include "BaseData.h"    // superclass
+#include "Point.h"       // Point data member
+#include "Measures.h"    // coordinate_t; AngPi data member
+#include "ShapeTypes.h"  // agentDataType
+
+#include "SketchSpace.h"
+#include "Sketch.h"
+#include "ShapeSpace.h"  // required by DATASTUFF_CC
+#include "ShapeRoot.h"   // required by DATASTUFF_CC
+
+#include "AgentData.h"
+#include "ShapeAgent.h"
+
+namespace DualCoding {
+
+DATASTUFF_CC(AgentData);
+
+AgentData::AgentData(ShapeSpace& _space, const Point &c) 
+  : BaseData(_space,agentDataType), center_pt(c), orientation_pt(c), orientation(0)
+{ mobile = true; }
+  
+AgentData::AgentData(const AgentData& otherData)
+  : BaseData(otherData), 
+    center_pt(otherData.center_pt), 
+    orientation_pt(otherData.orientation_pt),
+    orientation(otherData.orientation)
+{ mobile = true; }
+
+bool AgentData::isMatchFor(const ShapeRoot&) const {
+  return false;
+}
+
+//! Print information about this shape. (Virtual in BaseData.)
+void
+AgentData::printParams() const {
+	cout << "Type = " << getTypeName();
+	cout << "Shape ID = " << getId() << endl;
+	cout << "Parent ID = " << getParentId() << endl;
+
+	// Print critical points.
+	cout << endl;
+	cout << "center{" << getCentroid().coords(1) << ", " << getCentroid().coords(2) << "}" << endl;
+		
+	cout << "orientation = " << orientation << endl;
+	//cout << "color = " << getColor() << endl;
+	printf("color = %d %d %d\n",getColor().red,getColor().green,getColor().blue);
+
+	cout << "mobile = " << isMobile() << endl;
+	cout << "viewable = " << isViewable() << endl;
+}
+
+
+//! Transformations. (Virtual in BaseData.)
+void AgentData::applyTransform(const NEWMAT::Matrix& Tmat) {
+  //  cout << "AgentData::applyTransform: " << getId() << endl;
+  //  cout << Tmat << endl;
+  center_pt.applyTransform(Tmat);
+  orientation_pt.applyTransform(Tmat);
+  orientation = orientation - (AngTwoPi)atan2(Tmat(1,2),Tmat(1,1));
+  //  updateOrientation();
+}
+
+//! Functions to set properties.
+//{
+void
+AgentData::setOrientation(AngTwoPi _orientation) {
+  orientation = _orientation;
+  orientation_pt.setCoords(getCentroid().coords(1) + 0.5*cos(orientation),
+			   getCentroid().coords(2) + 0.5*sin(orientation));
+  deleteRendering();
+}
+//}
+
+void AgentData::updateOrientation() {
+  Point heading = orientation_pt-center_pt;
+  orientation = atan2(heading.coordY(),heading.coordX());
+}
+
+void AgentData::projectToGround(const NEWMAT::Matrix& camToBase,
+				const NEWMAT::ColumnVector& groundplane) {
+  center_pt.projectToGround(camToBase,groundplane);
+  orientation_pt.projectToGround(camToBase,groundplane);
+  updateOrientation();
+}
+
+bool AgentData::updateParams(const ShapeRoot& other, bool force) {
+  if (isMatchFor(other) || force) {
+    const AgentData& other_agent = ShapeRootTypeConst(other,AgentData).getData();
+    int other_conf = other_agent.getConfidence();
+    if (other_conf <= 0)
+      return true;
+    center_pt = (center_pt*confidence + other_agent.getCentroid()*other_conf) / (confidence+other_conf);
+    orientation = orientation*((orientation_t)confidence/(confidence+other_conf))
+      + other_agent.getOrientation()*((orientation_t)confidence/(confidence+other_conf));
+    return true;
+  }
+  return false;
+}
+
+//! Render into a sketch space and return reference. (Private.)
+Sketch<bool>* AgentData::render() const {
+	Sketch<bool>* draw_result =
+	  new Sketch<bool>(space->getDualSpace(), "render("+getName()+")");
+	draw_result = 0;
+
+	// JJW This does not take orientation into account.
+	// should probably take principal axis into account later on
+	int cx = int(getCentroid().coords(1));
+	int cy = int(getCentroid().coords(2));
+	
+	// Sure the agent rendering is terribly inefficient, but it works
+	const float a = 2.0;
+	const float b = 2.0;
+	const float x_skip = atan(1/(0.5*a)); // minimum x-diff w/o gaps 
+	for(float x = (cx-a); x<(cx+a); x+=x_skip) {
+		float y_y0_sq = (b*b) * (1 - (x-cx)*(x-cx)/(a*a));
+		if(y_y0_sq > 0) {
+			int y_bot = cy + (int)(sqrt(y_y0_sq));
+			int y_top = cy - (int)(sqrt(y_y0_sq));
+			(*draw_result)((int)x,y_bot) = true;
+			(*draw_result)((int)x,y_top) = true;
+		}
+	}
+	(*draw_result)(cx-(int)a, cy) = true; // fill in "holes" at ends
+	(*draw_result)(cx+(int)a, cy) = true;
+	return draw_result;
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/AgentData.h ./DualCoding/AgentData.h
--- ../Tekkotsu_2.4.1/DualCoding/AgentData.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/AgentData.h	2006-10-03 19:23:00.000000000 -0400
@@ -0,0 +1,80 @@
+//-*-c++-*-
+#ifndef _AGENTDATA_H_
+#define _AGENTDATA_H_
+
+#include "BaseData.h"    // superclass
+#include "Point.h"       // Point data member
+#include "Measures.h"    // coordinate_t; AngPi data member
+#include "ShapeTypes.h"  // agentDataType
+
+namespace DualCoding {
+
+class ShapeRoot;
+class SketchSpace;
+template<typename T> class Sketch;
+
+class AgentData : public BaseData {
+private:
+  Point center_pt;
+  Point orientation_pt;
+  AngTwoPi orientation;
+
+public:
+  //! Constructor
+  AgentData(ShapeSpace& _space, const Point &c);
+  
+  //! Copy constructor
+  AgentData(const AgentData& otherData);
+  
+  static ShapeType_t getStaticType() { return agentDataType; }
+
+  // =========================================
+  // BEGIN FUNCTIONS
+  // =========================================
+  
+  DATASTUFF_H(AgentData);
+  
+  //! Centroid. (Virtual in BaseData.)
+  Point getCentroid() const { return center_pt; }
+  
+  //! Match agents based on their parameters.  (Virtual in BaseData.)
+  virtual bool isMatchFor(const ShapeRoot& other) const;
+  
+  //! Print information about this shape. (Virtual in BaseData.)
+  virtual void printParams() const;
+  
+  virtual bool updateParams(const ShapeRoot& other, bool force=false);
+  
+  virtual void projectToGround(const NEWMAT::Matrix& camToBase,
+			       const NEWMAT::ColumnVector& groundplane);
+  
+  //! Transformations. (Virtual in BaseData.)
+  virtual void applyTransform(const NEWMAT::Matrix& Tmat);
+  
+
+  virtual unsigned short getDimension() const { return 3; }  
+
+  AngTwoPi getOrientation() const { return orientation; }
+  
+protected:
+  //! Updates orientation according to @param orientation_pt
+  void updateOrientation();
+  
+private:
+  friend class MapBuilder;
+  //! Functions to set property values.
+  //@{
+  void setOrientation(AngTwoPi _orientation); //!< Don't call this; use MapBuilder::setAgent()
+  void setCentroidPt(const Point &otherPt) { center_pt.setCoords(otherPt); }  //!< Don't call this; use MapBuilder::setAgent()
+  //@}
+
+  //! Render into a sketch space and return reference.
+  virtual Sketch<bool>* render() const;
+
+  AgentData& operator=(const AgentData&); //!< don't call
+  
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/BaseData.cc ./DualCoding/BaseData.cc
--- ../Tekkotsu_2.4.1/DualCoding/BaseData.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/BaseData.cc	2006-08-10 23:20:22.000000000 -0400
@@ -0,0 +1,190 @@
+#include "Macrodefs.h"
+#include "Measures.h"
+
+#include "Sketch.h"   // this must precede references to Sketch
+#include "BaseData.h"
+#include "ShapeRoot.h"
+#include "ShapePoint.h"
+#include "SketchDataRoot.h"
+#include "ShapeSpace.h"
+
+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)) {}
+
+BoundingBox::BoundingBox(const std::vector<ShapeRoot> &vec) :
+  xmin(0), ymin(0), xmax(0), ymax(0) {
+  if ( vec.size() > 0 ) {
+    *this = vec[0]->getBoundingBox();
+    for ( size_t i = 1; i<vec.size(); i++ )
+      *this = BoundingBox(*this,vec[i]->getBoundingBox());
+  }
+}
+
+std::ostream& operator<< (std::ostream& out, const BoundingBox &b) {
+  out << "BoundingBox(" << b.xmin << "," << b.ymin << ","
+      << b.xmax << "," << b.ymax << ")";
+  return out;
+}
+
+
+BaseData::BaseData(ShapeSpace& _space, ShapeType_t _type, int _parentId) :
+  space(&_space), name(data_name(_type)), type(_type), 
+  id(0), parentId(_parentId), lastMatchId(0),
+  refcount(0), viewable(true),
+  color_rgb((ProjectInterface::getNumColors() != -1U) ? ProjectInterface::getColorRGB(1) : rgb(0,0,255)), // color 0 is invalid, so use color 1 as default, or blue if colors aren't loaded yet
+  confidence(1),
+  mobile(false),
+  rendering_sketch(NULL)
+{};
+
+
+  /*
+BaseData::BaseData(ShapeType_t _type, int _parentId) :
+  space(NULL), name(data_name(_type)), type(_type), 
+  id(0), parentId(_parentId), lastMatchId(0),
+  refcount(0), viewable(true),
+  color_rgb(ProjectInterface::defSegmentedColorGenerator?ProjectInterface::getColorRGB(1):rgb(0,0,255)), // color 0 is invalid, so use color 1 as default, or blue if colors aren't loaded yet
+  confidence(1),
+  mobile(false),
+  rendering_sketch(NULL)
+{};
+  */
+    
+BaseData::BaseData(const BaseData& other)
+  : space(other.space), name(other.name), type(other.type),
+    id(0), parentId(other.parentId), lastMatchId(other.lastMatchId),
+    refcount(0), viewable(other.viewable),
+    color_rgb(other.color_rgb),
+    confidence(other.confidence),
+    mobile(other.mobile),
+    rendering_sketch(NULL)
+{
+  //  cout << "copied BaseData: parentID " << parentId << " <-> " << other.parentId << endl;
+};
+
+
+BaseData::~BaseData(void) { 
+  if ( rendering_sketch != NULL )
+    delete rendering_sketch;
+}
+
+Shape<PointData> BaseData::getCentroidPtShape() const {
+  PointData *pt = new PointData(*space,getCentroid());
+  pt->inheritFrom(*this);
+  return Shape<PointData>(pt);
+}
+
+BaseData& BaseData::operator=(const BaseData& other) {
+  // assumes &other =? this check is done by the sub class using BaseData::operator=
+  //  if (&other == this)
+  //    return *this;
+
+  space = other.space ? &(*other.space) : NULL;
+  name = other.name;
+  type = other.type;	
+  id = other.id;
+  parentId = other.parentId;
+  lastMatchId = other.lastMatchId;
+  refcount = other.refcount;
+  viewable = other.viewable;
+  color_rgb = other.color_rgb;
+  confidence = other.confidence;
+  mobile = other.mobile;  
+  rendering_sketch = other.rendering_sketch ? &(*rendering_sketch) : NULL;
+  return *this;
+}
+
+void BaseData::inheritFrom(const BaseData &parent) {   // used by leftPtShape, etc.
+  setParentId(parent.getViewableId());
+  setColor(parent.getColor());
+}
+
+void BaseData::inheritFrom(const ShapeRoot &parent) {
+  setParentId(parent->getViewableId());
+  setColor(parent->getColor());
+}
+
+void BaseData::inheritFrom(const SketchDataRoot &parent) {
+  setParentId(parent.getViewableId());
+  setColor(parent.getColor());
+}
+
+void BaseData::V(std::string const &_name) {
+  setViewable(true);
+  if ( !_name.empty() ) setName(_name);
+}
+
+void BaseData::N(std::string const &_name) {
+  setViewable(false);
+  if ( !_name.empty() ) setName(_name);
+}
+
+ReferenceFrameType_t BaseData::getRefFrameType() const {
+  return space->getRefFrameType(); }
+
+
+//!Type.
+//{
+//! Get shape type name.
+const char* BaseData::getTypeName() const { return data_name(type); }
+
+//! Test the shape type.
+bool BaseData::isType(ShapeType_t this_type) const { return this_type == type; }
+
+//! Test that two shapes are of same type.
+bool BaseData::isSameTypeAs(const ShapeRoot& other) const {
+	return((bool)(isType(other->type))); }
+
+
+bool BaseData::isSameColorAs(const ShapeRoot& other) const {
+  return getColor() == other->getColor(); }
+
+void BaseData::setColor(string const &color_name) {
+  setColor(ProjectInterface::getColorRGB(color_name));
+}
+
+void BaseData::setColor(rgb new_color) {
+  color_rgb = new_color;
+  if ( rendering_sketch != NULL )
+    (*rendering_sketch)->setColor(new_color);
+}
+
+
+bool BaseData::isMobile() const { return mobile; }
+
+void BaseData::setMobile(bool _mobile) { mobile = _mobile; }
+
+void BaseData::deleteRendering() {
+  delete rendering_sketch;
+  rendering_sketch = NULL;
+}
+
+Sketch<bool>& BaseData::getRendering() {
+  if ( rendering_sketch != NULL )
+    return *rendering_sketch;
+  rendering_sketch = render();
+  (*rendering_sketch)->setColor(getColor());
+  (*rendering_sketch)->setParentId(id);
+  (*rendering_sketch)->setName("render("+getName()+")");
+  return *rendering_sketch;
+}
+
+
+void BaseData::increaseConfidence(int n, int maxConfidence) {
+  confidence += n;
+  if ( maxConfidence > 0 )
+    confidence = min(confidence, maxConfidence);
+}
+  
+void BaseData::increaseConfidence(const BaseData& other, int maxConfidence) {
+  increaseConfidence(other.getConfidence() > 0 ? other.getConfidence()+1 : 2, maxConfidence);
+}
+  
+void BaseData::increaseConfidence(const ShapeRoot& other, int maxConfidence) { 
+  increaseConfidence(other.getData(), maxConfidence);
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/BaseData.h ./DualCoding/BaseData.h
--- ../Tekkotsu_2.4.1/DualCoding/BaseData.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/BaseData.h	2006-08-10 23:20:22.000000000 -0400
@@ -0,0 +1,225 @@
+//-*-c++-*-
+#ifndef _BASEDATA_H_
+#define _BASEDATA_H_
+
+#include <vector>
+#include <iostream>
+#include <string>
+#include "Wireless/Socket.h" // needed for sout
+
+#include "Macrodefs.h"
+#include "Measures.h"
+#include "Point.h"
+#include "Shared/newmat/newmat.h"
+#include "Motion/Kinematics.h"
+#include "ShapeTypes.h"
+#include "Vision/colors.h"
+
+namespace DualCoding {
+
+class Point;
+class PointData;
+class SketchSpace;
+template<typename T> class Sketch;
+class ShapeRoot;
+class SketchDataRoot;
+template<typename T> class Shape;
+
+class BoundingBox {
+public:
+  coordinate_t xmin, ymin, xmax, ymax;
+
+  BoundingBox(coordinate_t _xmin, coordinate_t _ymin, coordinate_t _xmax, coordinate_t _ymax) :
+	 xmin(_xmin), ymin(_ymin), xmax(_xmax), ymax(_ymax) {}
+
+  BoundingBox() : xmin(0), ymin(0), xmax(0), ymax(0) {}
+
+  BoundingBox(const Point &p) :
+    xmin(p.coordX()), ymin(p.coordY()), xmax(p.coordX()), ymax(p.coordY()) {}
+
+  BoundingBox(const BoundingBox &b1, const BoundingBox &b2);
+
+  BoundingBox(const std::vector<ShapeRoot> &vec);
+
+};
+
+std::ostream& operator<< (std::ostream& out, const BoundingBox &b);
+
+class BaseData {
+public:
+  friend class ShapeRoot;
+  friend class ShapeSpace;
+  
+protected:
+  ShapeSpace *space;
+  std::string name;
+  ShapeType_t type;	
+  int id;
+  int parentId;
+  int lastMatchId;      //!< Id of the shape in the preceding space that gave rise to or was matched to this one.
+  int refcount;
+  bool viewable;
+  rgb color_rgb;
+  
+  int confidence;       //!< Confidence that this shape exists and isn't noise.
+  bool mobile;		//!< True if this shape can move in the world
+  
+  Sketch<bool>* rendering_sketch;
+
+public:
+  //! Constructor
+  BaseData(ShapeSpace& _space, ShapeType_t typeval, int _parentId=0);
+
+  //! Copy constructor
+  BaseData(const BaseData& otherData);
+  
+  // BaseData(ShapeType_t typeval, int _parentID=0);
+
+  //! Destructor.
+  virtual ~BaseData(void);
+
+  virtual BaseData* clone(void) const = 0;
+  
+  ShapeSpace& getSpace() const { return *space; }
+  ReferenceFrameType_t getRefFrameType() const;
+
+  int getId() const { return id; }
+  int getParentId() const { return parentId; }
+  void setParentId(int _pid) { parentId = _pid; }
+
+  bool isViewable() const { return viewable; }
+  void setViewable(bool _viewable) { viewable = _viewable; }
+
+  int getViewableId() const {
+    if ( viewable )
+      return id;
+    else
+      return parentId;
+  }
+  
+  void inheritFrom(const BaseData &parent);
+  void inheritFrom(const ShapeRoot &parent);
+  void inheritFrom(const SketchDataRoot &parent);
+
+  int getLastMatchId() const { return lastMatchId; }
+  void setLastMatchId(int _lmid) { lastMatchId = _lmid; }
+
+  const std::string& getName() const { return name; }
+  void setName(const std::string& _name) { name = _name; }
+  
+  void V(std::string const &_name="");
+  void N(std::string const &_name="");
+  
+  virtual BoundingBox getBoundingBox() const { return BoundingBox(); }
+
+  //! Confidence.
+  //@{
+  virtual int getConfidence() const { return confidence; } //!< returns confidence of Data. Reimpletemnted in PolygonData
+
+  void increaseConfidence(int n=1, int maxConfidence=-1);
+  void increaseConfidence(const BaseData& other, int maxConfidence=-1);
+  void increaseConfidence(const ShapeRoot& other, int maxConfidence=-1);
+
+  void decreaseConfidence() { confidence--; }
+  void setConfidence(const BaseData& other) { confidence = other.getConfidence(); }
+  //@}
+  
+  //! Type.
+  //@{
+  //! Get the shape type.
+  virtual ShapeType_t getType() const=0;
+  const char* getTypeName() const;
+  
+  //! Test the shape type.
+  bool isType(ShapeType_t this_type) const;
+  
+  //! Test if shape types are the same.
+  bool isSameTypeAs(const ShapeRoot& other) const;
+  //@}
+  
+  
+  //! Color.
+  //@{
+  //! Get the color.
+  rgb getColor() const { return color_rgb; }
+  
+  //! Set shape and rendering sketch color.
+  //@{
+  void setColor(std::string const &color_name);
+  void setColor(rgb new_color);
+  //@}
+
+  //! Test if shape colors are the same.
+  bool isSameColorAs(const ShapeRoot& other) const;
+  
+  //@}
+  
+  //! Shapes match if their coordinates agree.  DOES NOT Assume type and color already checked.
+  virtual bool isMatchFor(const ShapeRoot& other) const = 0;
+
+  //! Combine two shapes by taking weighted average depending on confidence level.
+  //  virtual void mergeWith(const ShapeRoot& other) = 0;
+
+  //! Shapes are admissible to the local map if they're large enough not to be noise.
+  virtual bool isAdmissible() const { return true; }
+
+  //! Update shape parameters after matching to another shape.
+  virtual bool updateParams(const ShapeRoot& other, bool forceUpdate=false) = 0;
+
+  //! returns if a point is inside the shape or not. Reimplemented by EllipseData, SphereData, PolygonData
+  virtual bool isInside(const Point&) const { return false; }
+
+  virtual unsigned short getDimension() const = 0;
+
+  //! Mobility
+  //@{
+  bool isMobile() const;
+  void setMobile(bool mobility);
+  //@}
+  
+  void deleteRendering();
+
+  //! return the centroid of the shape in point format
+  virtual Point getCentroid() const=0;
+
+  virtual Shape<PointData> getCentroidPtShape() const;
+  
+  //! Prints information about this shape.
+  virtual void printParams() const=0;
+  
+  //! Apply a transformation matrix to the shape.
+  virtual void applyTransform(const NEWMAT::Matrix& Tmat)=0;
+  
+  //! Project to ground plane using given matrix
+  virtual void projectToGround(const NEWMAT::Matrix& camToBase,
+			       const NEWMAT::ColumnVector& groundplane)=0;
+  
+  //! Update properties of the shape derived from endpoints or other basic parameters.
+  //  virtual void update_derived_properties() {}
+  
+  //! Rendering.
+  //@{
+  //! Returns a pointer to the rendering associated with the ShapeRoot object.
+  //! If no such rendering exists, it is created.
+  Sketch<bool>& getRendering();
+  
+  //! Render into a sketch space.
+  virtual Sketch<bool>* render() const=0;
+  //@}
+
+  //! Copy operator. Assumes "&other =? this" check is done by the sub class calling this operator
+  BaseData& operator=(const BaseData& other); 
+};
+
+#define DATASTUFF_H(T) \
+  virtual ShapeType_t getType() const { return getStaticType(); } \
+  virtual BaseData* clone() const; \
+  Shape<T> copy() const;
+
+#define DATASTUFF_CC(T) \
+  BaseData* T::clone() const { return new T(*this); } \
+  Shape<T> T::copy() const { return Shape<T>((T*)clone()); }
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/BlobData.cc ./DualCoding/BlobData.cc
--- ../Tekkotsu_2.4.1/DualCoding/BlobData.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/BlobData.cc	2006-08-02 17:27:14.000000000 -0400
@@ -0,0 +1,912 @@
+//-*-c++-*-
+#include <iostream>
+#include <vector>
+
+#include "Vision/cmvision.h"
+
+#include "SketchSpace.h"
+#include "Sketch.h"
+#include "ShapeSpace.h"
+#include "ShapeRoot.h"
+
+#include "BlobData.h"
+#include "LineData.h"  // for drawline2d
+#include "ShapeBlob.h"
+#include "visops.h"
+#include "Region.h"
+#include "ShapeLine.h"
+#include "ShapePoint.h"
+
+#include "BrickOps.h" 
+
+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) :
+  BaseData(_space, getStaticType()),
+  topLeft(_topLeft), topRight(_topRight),
+  bottomLeft(_bottomLeft), bottomRight(_bottomRight),
+  area(_area), runvec(_runvec), orientation(_orientation)
+{
+  setColor(_rgbvalue);
+}
+      
+DATASTUFF_CC(BlobData);
+
+//! return the centroid of the shape in point format
+Point BlobData::getCentroid() const {
+  return Point((topLeft.coords + topRight.coords + bottomLeft.coords + bottomRight.coords) / 4,
+	       getRefFrameType());
+}
+  
+void BlobData::printParams() const {
+  cout << "Blob"
+       << " tl=" << topLeft.coords
+       << " tr=" << topRight.coords
+       << " bl=" << bottomLeft.coords
+       << " br=" << bottomRight.coords
+       << " area=" << area
+       << endl;
+}
+
+Sketch<bool>* BlobData::render() const {
+  SketchSpace &SkS = space->getDualSpace();
+  Sketch<bool>* result = new Sketch<bool>(SkS, "render("+getName()+")");
+  *result = false;
+  switch ( orientation ) {
+  case groundplane:
+    if ( space->getRefFrameType() == camcentric ) {
+      for ( std::vector<BlobData::run>::const_iterator it = runvec.begin();
+	    it != runvec.end(); it++ ) {
+	const BlobData::run &r = *it;
+	int const xstop = r.x + r.width;
+	for ( int xi=r.x; xi<xstop; xi++ )
+	  (*result)(xi, r.y) = true;
+      }
+    } else {
+      NEWMAT::ColumnVector tl(topLeft.getCoords()), tr(topRight.getCoords()),
+	bl(bottomLeft.getCoords()), br(bottomRight.getCoords());
+      SkS.applyTmat(tl); SkS.applyTmat(tr); SkS.applyTmat(bl); SkS.applyTmat(br);
+      LineData::drawline2d(*result, (int)tl(1), (int)tl(2), (int)tr(1), (int)tr(2));
+      LineData::drawline2d(*result, (int)tr(1), (int)tr(2), (int)br(1), (int)br(2));
+      LineData::drawline2d(*result, (int)br(1), (int)br(2), (int)bl(1), (int)bl(2));
+      LineData::drawline2d(*result, (int)bl(1), (int)bl(2), (int)tl(1), (int)tl(2));
+    }
+    break;
+  case pillar:
+  case pinata:
+    cout << "BlobData::render() : Can't yet render blobs in pillar/pinata 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::projectToGround(const NEWMAT::Matrix& camToBase,
+			       const NEWMAT::ColumnVector& gndplane) {
+  switch ( orientation ) {
+  case groundplane:
+    topLeft.projectToGround(camToBase,gndplane);
+    topRight.projectToGround(camToBase,gndplane);
+    bottomLeft.projectToGround(camToBase,gndplane);
+    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);
+    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();
+}
+  */
+
+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
+    break;
+  }
+}
+
+bool BlobData::isMatchFor(const ShapeRoot& other) const {
+  if (!(isSameTypeAs(other) && isSameColorAs(other)))
+    return false;
+  else {
+    const Shape<BlobData>& other_blob = ShapeRootTypeConst(other,BlobData);
+    float dist = getCentroid().distanceFrom(other_blob->getCentroid());
+    return dist < 2*sqrt(area);
+  }
+}
+
+bool BlobData::updateParams(const ShapeRoot& other, bool forceUpdate) {
+  const Shape<BlobData>& other_blob = ShapeRootTypeConst(other,BlobData);
+  int other_conf = other_blob->confidence;
+  if (other_conf <= 0) {
+    if (forceUpdate)
+      other_conf = 1;
+    else
+      return false;
+  }
+  confidence += other_conf;
+  const int sumconf = confidence + other_conf;
+  topLeft = (topLeft*confidence + other_blob->topLeft*other_conf) / sumconf;
+  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;
+  update_derived_properties();
+  return true;
+}
+
+std::vector<Shape<BlobData> >
+BlobData::extractBlobs(const Sketch<bool> &sketch, 
+		       const set<int>& colors, int minarea,
+		       BlobData::BlobOrientation_t orient, 
+		       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());
+  for ( std::vector<Shape<BlobData> >::iterator it = result.begin();
+	it != result.end(); it++ )
+    (*it)->setColor(rgbvalue);
+  return result;
+}
+
+std::vector<Shape<BlobData> > 
+BlobData::extractBlobs(const Sketch<bool> &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);
+}
+  
+
+std::vector<Shape<BlobData> >
+BlobData::extractBlobs(const Sketch<uchar> &sketch, 
+		       const set<int>& colors, int minarea,
+		       BlobData::BlobOrientation_t orient, int maxblobs) {
+  int parent = sketch->getId();
+  uchar *pixels = &((*sketch.pixels)[0]);
+
+  // convert pixel array to RLE
+  int const maxRuns = (sketch.width * sketch.height) / 8;
+  CMVision::run<uchar> *rle_buffer = new CMVision::run<uchar>[maxRuns];
+  unsigned int const numRuns = CMVision::EncodeRuns(rle_buffer, pixels, sketch.width, sketch.height, maxRuns);
+
+  // convert RLE to region list
+  CMVision::ConnectComponents(rle_buffer,numRuns);
+  int const maxRegions = (sketch.width * sketch.height) / 16;   // formula from RegionGenerator.h
+  CMVision::region *regions = new CMVision::region[maxRegions];
+  unsigned int numRegions = CMVision::ExtractRegions(regions, maxRegions, rle_buffer, numRuns);
+  unsigned int const numColors = ProjectInterface::getNumColors();
+  CMVision::color_class_state *ccs = new CMVision::color_class_state[numColors];
+  unsigned int const maxArea = CMVision::SeparateRegions(ccs, numColors, regions, numRegions);
+  CMVision::SortRegions(ccs, numColors, maxArea);
+  CMVision::MergeRegions(ccs, int(numColors), rle_buffer);
+
+  // extract blobs from region list
+  std::vector<Shape<BlobData> > result(20);
+  result.clear();
+  ShapeSpace &ShS = sketch->getSpace().getDualSpace();
+  //  for ( size_t color=1; color < numColors; color++ ) {
+  for (set<int>::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;
+    if ( list_head != NULL ) {
+      //      const rgb rgbvalue = ProjectInterface::getColorRGB(color);
+      const rgb rgbvalue = ProjectInterface::getColorRGB(*it);
+      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);
+	blobdat->setParentId(parent);
+	result.push_back(Shape<BlobData>(blobdat));
+      }
+    }
+  }
+  delete[] ccs;
+  delete[] regions;
+  delete[] rle_buffer;
+  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 rgb rgbvalue) {
+  int const x1 = reg.x1;
+  int const y1 = reg.y1;
+  int const x2 = reg.x2;
+  int const y2 = reg.y2;
+  // Count the number of runs so we can allocate a vector of the right size.
+  // The first run might be numbered 0, so we must use -1 as end of list indicator.
+  int numruns = 0;
+  for (int runidx = reg.run_start; runidx != -1; 
+       runidx = rle_buff[runidx].next ? rle_buff[runidx].next : -1)
+    ++numruns;
+  std::vector<BlobData::run> runvec(numruns);
+  runvec.clear();
+  // now fill in the run vector
+  for (int runidx = reg.run_start; runidx != -1; 
+       runidx = rle_buff[runidx].next ? rle_buff[runidx].next : -1) {
+    const CMVision::run<uchar> &this_run = rle_buff[runidx];
+    runvec.push_back(BlobData::run(this_run.x, this_run.y, this_run.width));
+  }
+  if ( space.getRefFrameType() == camcentric )
+    return new BlobData(space,
+			Point(x1,y1),Point(x2,y1),
+			Point(x1,y2),Point(x2,y2),
+			reg.area, runvec, orient, rgbvalue);
+  else
+    return new BlobData(space,
+			Point(x2,y2),Point(x1,y2),
+			Point(x2,y1),Point(x1,y1),
+		      reg.area, runvec, orient, rgbvalue);
+}
+
+
+
+
+
+
+  // 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
+    for (unsigned int i=0; i<fitCorners.size(); i++){
+      NEW_SHAPE(fitline, LineData, LineData(*space, fitCorners[i], fitCorners[(i+1)%nExpected]));
+      fitline->setParentId(getViewableId());
+    }
+
+    // Handling off-screen bricks:
+    // If our fit of corners is close to the edge of the image,
+    // re-try fitting 3 or 5 corners to the brick
+    bool onEdge = false;
+    int width = space->getDualSpace().getWidth();
+    int height = space->getDualSpace().getHeight();
+    for (unsigned int i=0; i<nExpected; i++) {
+      if (fitCorners[i].coordX() < 5 || fitCorners[i].coordX() > width - 5 ||
+	  fitCorners[i].coordY() < 5 || fitCorners[i].coordY() > height - 5) {
+	onEdge = true;
+	break;
+      }
+    }
+    if (onEdge && nExpected == 4) {
+      std::vector<int> outsideCandidates;
+      for (unsigned int i=0; i<nExpected; i++) {
+	if (candidates[i].coordX() < 5 || candidates[i].coordX() > width - 5 ||
+	    candidates[i].coordY() < 5 || candidates[i].coordY() > height - 5) {
+	  outsideCandidates.push_back(i);
+	}
+      }
+
+
+      std::vector<Point> candidates3(candidates), candidates5;
+
+      if (outsideCandidates.size() == 0) {
+	std::cout<<"Err? final points are near the edge, but the candidates aren't?"<<std::endl;
+      }
+      
+      // If just one candidate is outside the scene, 
+      // try removing it for 3 points
+      // and adding the points where it crosses the border of the image for 5 points
+      if (outsideCandidates.size() == 1) {
+	int outC = outsideCandidates[0];
+	candidates3.erase(candidates3.begin() + outC);
+      
+	Point p1, p2;
+	if (candidates[outC].coordX() < 5) {
+	  p1.setCoords(0,0);
+	  p2.setCoords(0,height);
+	}
+	else if (candidates[outC].coordX() > width - 5) {
+	  p1.setCoords(width,0);
+	  p2.setCoords(width,height);
+	}
+	else if (candidates[outC].coordY() < 5) {
+	  p1.setCoords(0,0);
+	  p2.setCoords(width,0);
+	}
+	else {
+	  p1.setCoords(0,height);
+	  p2.setCoords(width,height);
+	}
+	LineData edgeLine(*space, p1,p2);
+	LineData l1(*space, candidates[(outC+3)%4], candidates[outC]);
+	LineData l2(*space, candidates[(outC+1)%4], candidates[outC]);
+	candidates5.push_back(candidates[(outC+3)%4]);
+	candidates5.push_back(l1.intersectionWithLine(edgeLine));
+	candidates5.push_back(l2.intersectionWithLine(edgeLine));
+	candidates5.push_back(candidates[(outC+1)%4]);
+	candidates5.push_back(candidates[(outC+2)%4]);
+      }
+      
+      if (outsideCandidates.size() == 2) {
+	Point betweenOutside = (candidates[outsideCandidates[0]] + candidates[outsideCandidates[1]])/2;
+	candidates3[outsideCandidates[0]].setCoords(betweenOutside);
+	candidates3.erase(candidates3.begin() + outsideCandidates[1]);
+	
+	int dC = outsideCandidates[1] - outsideCandidates[0];
+	int c1 = outsideCandidates[1];
+	candidates5.push_back(candidates[outsideCandidates[0]]);
+	candidates5.push_back(betweenOutside);
+	candidates5.push_back(candidates[outsideCandidates[1]]);
+	candidates5.push_back(candidates[(c1+dC)%4]);
+	candidates5.push_back(candidates[(c1+2*dC)%4]);
+      }
+      
+      if (outsideCandidates.size() > 2) {
+	// Not gonna get very good points out of this, probably
+      }
+    
+      float value3, value5;
+      for (unsigned int i=0; i<candidates3.size(); i++) {
+	NEW_SHAPE(candidate3, PointData, PointData(*space, candidates3[i]));
+	candidate3->setParentId(getViewableId());
+      }
+      for (unsigned int i=0; i<candidates5.size(); i++) {
+	NEW_SHAPE(candidate5, PointData, PointData(*space, candidates5[i]));
+	candidate5->setParentId(getViewableId());
+      }
+      std::vector<Point> fitcorners3 = findCornersShapeFit(3, candidates3, value3);
+      std::vector<Point> fitcorners5 = findCornersShapeFit(5, candidates5, value5);
+      for (unsigned int i=0; i<fitcorners3.size(); i++) {
+	NEW_SHAPE(fit3, PointData, PointData(*space, fitcorners3[i]));
+	fit3->setParentId(getViewableId());
+      }
+      for (unsigned int i=0; i<fitcorners5.size(); i++) {
+	NEW_SHAPE(fit5, PointData, PointData(*space, fitcorners5[i]));
+	fit5->setParentId(getViewableId());
+      }
+    }
+
+    // right now just take the corners from quadrilateral fitting
+    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
+    /* 
+    const float MIN_BOUNDING_SCORE = .75;
+
+    float derivScore = -1, diagScore = -1;
+
+    std::vector<Point> derivCorners = findCornersDerivative();
+
+    if (derivCorners.size() == nExpected) {
+
+      derivScore = getBoundingQuadrilateralInteriorPointRatio(derivCorners);
+      std::cout<<"Derivative score for ("<<getViewableId()<<") = "<<derivScore<<std::endl;
+      if (derivScore > MIN_BOUNDING_SCORE) {
+	return derivCorners;
+      }
+    }
+    
+    std::vector<Point> diagCorners = findCornersDiagonal();
+
+    if (diagCorners.size() == nExpected) {
+      diagScore = getBoundingQuadrilateralInteriorPointRatio(diagCorners);
+      std::cout<<"Diagonal score for ("<<getViewableId()<<") = "<<diagScore<<std::endl;
+      if (diagScore > derivScore) {
+	return diagCorners;
+      }
+      else if (derivScore > .5) {
+	return derivCorners;
+      }
+    }
+
+    // can we integrate sets of incomplete / overcomplete points?
+
+    std::vector<Point> result;
+
+    return result;
+    */
+  }
+
+
+  /*
+   * Derivative approach to finding the corners of the blobs. 
+   * Computes the distance from the center to the edge in a circle around the blob
+   * Takes a couple derivatives, and looks for peaks.
+   *
+   * Works well on big shapes, poorly on small ones
+   * Doesn't make any guarantees as to how many points are returned. 
+   */
+  std::vector<Point> BlobData::findCornersDerivative()
+  {
+    std::vector<Point> corners;
+
+    float radius = sqrt((topRight.coordX()-topLeft.coordX())*(topRight.coordX()-topLeft.coordX()) + 
+			(bottomLeft.coordY()-topLeft.coordY())*(bottomLeft.coordY()-topLeft.coordY()))/2 + 1;
+    int len = (int)(2*M_PI*radius + 1);
+    float distances[len];
+    Point points[len];
+    Point centroid = getCentroid();
+    NEW_SKETCH(rendering, bool, getRendering());
+    
+    int i=0, maxi = 0;
+
+    maxi = findRadialDistancesFromPoint(centroid, radius, rendering, distances, points);
+    float gdist[len], ddist[len], d2dist[len], d3dist[len];
+    applyGaussian(distances, gdist, len);
+    takeDerivative(gdist, ddist, len);
+    takeDerivative(ddist, d2dist, len);
+    takeDerivative(d2dist, d3dist, len);
+
+    drawHist(gdist, len, rendering);
+    drawHist(ddist, len, rendering);
+    drawHist(d2dist, len, rendering);
+    
+
+    // Corners are negative peaks in the second derivative of the distance from the center
+    // Zero-crossings in the first derivative should work, but we want to capture contour changes that 
+    // don't necessarily cross zero (steep increase -> shallow increase could be a corner)
+
+    const float MIN_D2 = 5.0;
+
+    float curmin = -MIN_D2;
+    int curi = -1;
+    int curonpeak = 0;
+    for (i=0; i<len; i++) {
+      if (d2dist[i]  < curmin) {
+	curmin = d2dist[i];
+	curi = i;
+	curonpeak = 1;
+      }
+      else if (curonpeak) {
+	if (d2dist[i] > -MIN_D2 || (d3dist[i-1] > 0 && d3dist[i] <= 0)) {
+	  curonpeak = 0;
+	  curmin = -MIN_D2;
+	  corners.push_back(points[curi]);
+	  NEW_SHAPE(cornerpoint, PointData, Shape<PointData>(*space, points[curi])); 
+	  cornerpoint->setParentId(rendering->getViewableId());
+	} 
+      }
+    }
+
+
+    // Normalize returned corners to counter-clock-wise order;
+    vector<Point> reversedCorners;
+    for (i=corners.size()-1; i>=0; i--){
+      reversedCorners.push_back(corners[i]);
+    }
+
+    return reversedCorners;
+  }
+
+
+  /*
+   * Diagonal approach to finding corners
+   * ad-hoc heuristic works well for normal parallelograms 
+   *
+   * fails on trapezoids and triangles, and where nCorners != 4. 
+   *
+   *
+   * Computes radial distance from the center like the derivative method
+   * Finds the peak in distance (furthest point is once corner)
+   * Finds the peak in the opposite region (another corner)
+   * 
+   * At this point it can draw the diagonal. The breakdown occurs when 
+   * it thinks it has a diagonal at this point but it isn't an actual diagonal
+   *
+   * Then split the quadrilateral into two triangles, and the furthest points from the 
+   * diagonal are the two remaining corners. 
+   */
+  std::vector<Point> BlobData::findCornersDiagonal()
+  {
+    std::vector<Point> corners;
+
+    float radius = sqrt((topRight.coordX()-topLeft.coordX())*(topRight.coordX()-topLeft.coordX()) + 
+			(bottomLeft.coordY()-topLeft.coordY())*(bottomLeft.coordY()-topLeft.coordY()))/2 + 1;
+    int len = (int)(2*M_PI*radius + 1);
+    float distances[len];
+    Point points[len];
+    Point centroid = getCentroid();
+    NEW_SKETCH(rendering, bool, getRendering());
+    
+    int i=0;
+    int maxi = 0, origmaxi = 0;
+    bool stillmax = false;
+
+    maxi = findRadialDistancesFromPoint(centroid, radius, rendering, distances, points);
+
+    // Find second max
+    int maxi2 = 0;
+    float max2 = 0;
+    stillmax = false;
+    origmaxi = -1;
+    for (i=0; i<len; i++) {
+      if (distances[i] >= max2 && 
+	  abs(i-maxi) > len*3/8 && 
+	  abs(i-maxi) < len*5/8) {
+	if (distances[i] > max2) {
+	  maxi2 = i;
+	  max2 = distances[i];
+	  origmaxi = maxi2;
+	  stillmax = true;
+	}
+	else if (stillmax){
+	  maxi2 = (origmaxi+i)/2;
+	}
+      }
+      else {
+	stillmax = false;
+      }
+    }
+    
+    corners.push_back(points[maxi]);
+    corners.push_back(points[maxi2]);
+    std::cout<<"Corners: ("<<corners[0].coordX()<<","<<corners[0].coordY()<<")  ("<<
+      corners[1].coordX()<<","<<corners[1].coordY()<<")\n";
+
+    // Get the regions on either side of the line made by the two corners
+    // The most distant points in those regions are the other two corners
+    NEW_SHAPE(diag, LineData, Shape<LineData>(*space, corners[0], corners[1]));
+    diag->firstPt().setActive(false);
+    diag->secondPt().setActive(false);
+    diag->setParentId(rendering->getViewableId());
+
+    NEW_SKETCH_N(filled, bool, visops::topHalfPlane(diag));
+    NEW_SKETCH(side1, bool, filled & rendering);
+    NEW_SKETCH(side2, bool, !filled & rendering);
+    
+    const float MIN_PT_DIST = 3.0;
+
+    Point pt3 = (Region::extractRegion(side1)).mostDistantPtFrom(diag.getData());
+    Point pt4 = (Region::extractRegion(side2)).mostDistantPtFrom(diag.getData());
+    if (diag->perpendicularDistanceFrom(pt3) > MIN_PT_DIST)
+      corners.push_back(pt3);
+    if (diag->perpendicularDistanceFrom(pt4) > MIN_PT_DIST)
+      corners.push_back(pt4);
+    
+
+    // Sort the corners into order going around the brick
+    std::vector<Point> resultCorners;
+    std::vector<float> angles;
+
+    float ta;
+    Point tp;
+    for (i=0; i<(int)corners.size(); i++) {
+      Point di = corners[i] - centroid;
+      angles.push_back(atan2(di.coordY(), di.coordX()));
+      resultCorners.push_back(corners[i]);
+      for (int j=i-1; j>=0; j--) {
+	if (angles[j+1] > angles[j]) {
+	  ta = angles[j];
+	  angles[j] = angles[j+1];
+	  angles[j+1] = ta;
+	  tp = resultCorners[j];
+	  resultCorners[j] = resultCorners[j+1];
+	  resultCorners[j+1] = tp;
+	}
+	else{
+	  break;
+	}
+      }
+    }
+
+    NEW_SHAPE(cornerline1, LineData, Shape<LineData>(*space, resultCorners[0], resultCorners[1])); 
+    cornerline1->setParentId(rendering->getViewableId());
+    if (resultCorners.size() > 3) {
+      NEW_SHAPE(cornerline2, LineData, Shape<LineData>(*space, resultCorners[2], resultCorners[3]));
+      cornerline2->setParentId(rendering->getViewableId());
+    }
+    
+     return resultCorners;
+  }
+
+
+
+
+
+  // find corners by fitting a quadrilateral to the blob
+  //
+  // Its expecting a set of candidate points that are roughly aligned with one set of edges and are
+  // significantly wider than the blob itself. 
+  // It contracts the candidate points to form a rough bounding box, 
+  // then does simulated annealing on random perturbations of the end points to get a good fit
+  //
+  // Potential quadrilateral fits are scored by maximizing the number of edge points of the blob that 
+  // lie under one of the lines, and minimizing the total area. 
+  // A fixed minimum edge length constraint is also enforced. 
+  std::vector<Point> BlobData::findCornersShapeFit(unsigned int ncorners, std::vector<Point>& candidates, 
+						   float &bestValue)
+  { 
+    NEW_SKETCH(rendering, bool, getRendering());
+
+    std::vector<Point> bestPoints(ncorners), curTest(ncorners);
+    float bestScore;
+    int bestEdgeCount;
+    std::vector<std::vector<Point> > testPoints;
+    std::vector<float> testScores;
+    std::vector<int> testEdgeCounts;
+
+    if (candidates.size() == ncorners) {
+      for (unsigned int i=0; i<ncorners; i++) {
+	bestPoints[i].setCoords(candidates[i]);
+	curTest[i].setCoords(candidates[i]);
+      }
+    }
+    else {
+      std::cout<<"Warning: incorrect number of candidates provided"<<std::endl;
+      return bestPoints;
+    }
+
+    NEW_SKETCH_N(nsum, uchar, visops::neighborSum(getRendering()));
+    NEW_SKETCH(borderPixels, bool, nsum > 0 & nsum < 8 & getRendering());
+    int edgeTotal = 0;
+    for (unsigned int x=0; x<borderPixels->getWidth(); x++) {
+      borderPixels(x,0) = 0;
+      borderPixels(x,borderPixels->getHeight() - 1) = 0;
+    }
+    for (unsigned int y=0; y<borderPixels->getHeight(); y++) {
+      borderPixels(0,y) = 0;
+      borderPixels(borderPixels->getWidth() - 1, y) = 0;
+    }
+    for (unsigned int i=0; i<borderPixels->getNumPixels(); i++) {
+      if (borderPixels->at(i))
+	edgeTotal++;
+    }
+
+    bestScore = getBoundingQuadrilateralScore(*this, bestPoints, borderPixels, bestEdgeCount, *space);
+
+    int testCount = 0, testEdgeCount;
+    Point dp;
+    float dpDist, testRatio;
+    bool hasMoved;
+
+    float annealingScalar = 1.0;
+    bool doingRandomMovement = false;
+    const float ANNEALING_CAP = 25.0;
+    const float WEIGHT_SCALAR = .2;
+    
+    const float MIN_DISTANCE = 10.0;
+    const float MIN_BOUNDING_RATIO = 0.8;
+
+    int iterationCount = 0, annealingStart = 0;
+    // Right now it just keeps going until the annealing weight gets to a set threshold
+    // Should probably be improved by checking the quality of the fit at intervals
+    // especially if the points have stopped moving
+    while (annealingScalar < ANNEALING_CAP) {
+
+      hasMoved = false;
+      
+      // Test each corner in succession
+      for (unsigned int i=0; i<ncorners; i++) {
+
+	testScores.clear();
+	testPoints.clear();
+	testEdgeCounts.clear();
+	testCount = 0;
+	// Try moving the corner toward or away from either adjacent corner by 1 pixel
+	// Only look at moving toward adjacent corners until we start doing random movement
+
+	for (unsigned int j=0; j<ncorners; j++)
+	  curTest[j].setCoords(bestPoints[j]);
+	dp.setCoords(curTest[(i+1)%ncorners] - curTest[i]);
+	dpDist = curTest[i].distanceFrom(curTest[(i+1)%ncorners]);
+	// Don't allow corners to get too close to each other
+	if (dpDist > MIN_DISTANCE) {
+
+	  dp/=dpDist;
+	  curTest[i]+=dp;
+	  testRatio = getBoundingQuadrilateralInteriorPointRatio(*this, curTest, *space);
+	  if (testRatio > MIN_BOUNDING_RATIO) {
+	    testScores.push_back(getBoundingQuadrilateralScore(*this, curTest, borderPixels, 
+							       testEdgeCount, *space));
+	    testPoints.push_back(curTest);
+	    testEdgeCounts.push_back(testEdgeCount);
+	    testCount++;
+	  }
+
+	  // Look outward too if we're in the annealing stage
+	  if (doingRandomMovement) {
+	    curTest[i].setCoords(bestPoints[i]);
+	    curTest[i]-=dp;
+	    testRatio = getBoundingQuadrilateralInteriorPointRatio(*this, curTest, *space);
+	    if (testRatio > MIN_BOUNDING_RATIO) {
+	      testScores.push_back(getBoundingQuadrilateralScore(*this, curTest, borderPixels, 
+								 testEdgeCount, *space));
+	      testPoints.push_back(curTest);
+	      testEdgeCounts.push_back(testEdgeCount);
+	      testCount++;
+	    }
+
+	  }
+	  
+	}
+
+	curTest[i].setCoords(bestPoints[i]);
+	dp.setCoords(curTest[(i+ncorners-1)%ncorners] - curTest[i]);
+	dpDist = curTest[i].distanceFrom(curTest[(i+ncorners-1)%ncorners]);
+	// Don't allow corners to get too close to each other
+	if (dpDist > MIN_DISTANCE) {
+
+	  dp/=dpDist;
+	  curTest[i]+=dp;
+	  testRatio = getBoundingQuadrilateralInteriorPointRatio(*this, curTest, *space);
+	  if (testRatio > MIN_BOUNDING_RATIO) {
+	    testScores.push_back(getBoundingQuadrilateralScore(*this, curTest, borderPixels, 
+							       testEdgeCount, *space));
+	    testPoints.push_back(curTest);
+	    testEdgeCounts.push_back(testEdgeCount);
+	    testCount++;
+	  }
+
+	  // Look outward too if we're in the annealing stage
+	  if (doingRandomMovement) {
+	    curTest[i].setCoords(bestPoints[i]);
+	    curTest[i]-=dp;
+	    testRatio = getBoundingQuadrilateralInteriorPointRatio(*this, curTest, *space);
+	    if (testRatio > MIN_BOUNDING_RATIO) {
+	      testScores.push_back(getBoundingQuadrilateralScore(*this, curTest, borderPixels, 
+								 testEdgeCount, *space));
+	      testPoints.push_back(curTest);
+	      testEdgeCounts.push_back(testEdgeCount);
+	      testCount++;
+	    }
+	  }
+	  
+	}
+	
+
+	testScores.push_back(bestScore);
+	testPoints.push_back(bestPoints);
+	testEdgeCounts.push_back(bestEdgeCount);
+	testCount++;
+
+	int move = -1;
+	if (doingRandomMovement) {
+	  move = pickMove(testScores, annealingScalar);
+	}
+	else {
+	  move = 0;
+	  for (int j=0; j<testCount; j++) {
+	    if (testScores[j] < testScores[move])
+	      move = j;
+	  }
+	  if (move != testCount-1) {
+	    hasMoved = true;
+	  }
+	}
+
+	if (move < 0 || move >= testCount)
+	  std::cout<<"Hmm, picked a bad move somewhere ("<<move<<")\n";
+	else {
+	  bestPoints[i].setCoords(testPoints[move][i]);
+	  bestScore = testScores[move];
+	  bestEdgeCount = testEdgeCounts[move];
+	}
+
+      }
+
+      // Increase the weight proportional to how much of the edges are covered
+      // Only increase it if we're at the annealing stage though. 
+      if (doingRandomMovement) {
+	annealingScalar += bestEdgeCount*WEIGHT_SCALAR/edgeTotal;
+      }
+      else if (!hasMoved) {
+	doingRandomMovement = true;
+
+	// debug output
+	annealingStart = iterationCount;
+	for (unsigned int z=0; z<ncorners; z++) {
+	  NEW_SHAPE(preannealing, PointData, PointData(*space, bestPoints[z]));
+	  preannealing->setParentId(borderPixels->getViewableId());
+	}
+      }
+
+      iterationCount++;
+      if (iterationCount > 500) {
+	std::cout<<"Warning, annealing stopped by max iteration count\n"<<std::endl;
+	break;
+      }
+      
+    }
+
+    std::cout<<"Shape fit took "<<iterationCount<<" iterations ("<<iterationCount - annealingStart<<" of annealing)\n";
+    bestValue = bestScore;
+    return bestPoints;
+
+  }
+
+
+// Comparison predicates
+
+bool BlobData::areaLessThan::operator() (const Shape<BlobData> &b1, const Shape<BlobData> &b2) const {
+      return b1->getArea() < b2->getArea();
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/BlobData.h ./DualCoding/BlobData.h
--- ../Tekkotsu_2.4.1/DualCoding/BlobData.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/BlobData.h	2006-07-21 13:57:44.000000000 -0400
@@ -0,0 +1,149 @@
+//-*-c++-*-
+#ifndef _BLOBDATA_H_
+#define _BLOBDATA_H_
+
+#include <vector>
+#include <set>
+#include <iostream>
+#include <string>
+
+#include "Shared/newmat/newmat.h"
+#include "Vision/cmv_types.h"
+
+#include "BaseData.h"      // superclass
+#include "Point.h"          // Point data member
+#include "ShapeTypes.h"   // blobDataType
+#include "ShapeFuns.h"
+
+namespace DualCoding {
+
+class ShapeRoot;
+template<typename T> class Sketch;
+
+//! Blob shapes, described by bounding boxes and an optional list of runs.
+
+class BlobData : public BaseData {
+ public:
+
+  // Bounding quadrilateral; may not be square when projected to world space.
+  Point topLeft, topRight, bottomLeft, bottomRight;
+
+  float area;
+
+  struct run {
+  public:
+    unsigned short int x, y, width;
+    run() : x(0), y(0), width(0) {}
+    run(unsigned short int _x, unsigned short int _y, unsigned short int _width) :
+      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;
+
+ 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);
+
+  static ShapeType_t getStaticType() { return blobDataType; }
+
+  DATASTUFF_H(BlobData);
+
+  friend class Shape<BlobData>;
+
+  //! return the centroid of the shape in point format
+  virtual Point getCentroid() const;
+  
+  //! Area of the blob
+  float getArea() { return area; }
+
+  //! Print information about this shape.
+  virtual void printParams() const;
+
+  //! Transformations. (Virtual in BaseData.)
+  virtual void applyTransform(const NEWMAT::Matrix& Tmat);
+  
+  //! Project to ground
+  //  virtual void projectToGround(int xres, int yres, const NEWMAT::ColumnVector& groundplane);
+  virtual void projectToGround(const NEWMAT::Matrix& camToBase,
+			       const NEWMAT::ColumnVector& groundplane);
+
+  //! Update derived properties
+  virtual void update_derived_properties();
+
+  //! Match blobs based on their parameters.  (Virtual in BaseData.)
+  virtual bool isMatchFor(const ShapeRoot& other) const;
+
+  virtual bool updateParams(const ShapeRoot& other, bool forceUpdate=false);
+
+  virtual unsigned short getDimension() const { return (orientation==groundplane) ? 2 : 3; }
+
+
+  //! 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, 
+	       int maxblobs=50); 
+
+  //! Import blobs 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,
+	       int maxblobs=50);
+  static std::vector<Shape<BlobData> >
+  extractBlobs(const Sketch<CMVision::uchar> &sketch, int minarea=0,
+	       BlobData::BlobOrientation_t orient=BlobData::groundplane,
+	       int maxblobs=50);
+
+  static BlobData* 
+  new_blob(ShapeSpace& space,
+	   const CMVision::region &reg, 
+	   const CMVision::run<CMVision::uchar> *rle_buff,
+	   const BlobData::BlobOrientation_t orient,
+	   const rgb rgbvalue);
+
+  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> {
+  public:
+    bool operator() (const Shape<BlobData> &b1, const Shape<BlobData> &b2) const;
+  };
+
+private:
+  //! Render into a sketch space and return reference. (Private.)
+  virtual Sketch<bool>* render() const;
+
+  BlobData& operator=(const BlobData&); //!< don't call
+
+};
+
+} // namespace
+
+#endif // BLOBDATA_H_
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/BrickData.cc ./DualCoding/BrickData.cc
--- ../Tekkotsu_2.4.1/DualCoding/BrickData.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/BrickData.cc	2006-09-23 23:45:20.000000000 -0400
@@ -0,0 +1,1167 @@
+//-*-c++-*-
+
+#include <iostream>
+#include <vector>
+
+#include "BaseData.h"    // superclass
+#include "Point.h"       // Point data member
+#include "ShapeTypes.h"  // brickDataType
+
+#include "SketchSpace.h"
+#include "Sketch.h"
+#include "visops.h"
+
+#include "ShapeSpace.h"  // required by DATASTUFF_CC
+#include "ShapeRoot.h"   // required by DATASTUFF_CC
+
+#include "BrickData.h"
+#include "ShapeBrick.h"
+#include "ShapePoint.h"
+#include "Region.h"
+
+
+namespace DualCoding {
+
+BrickData::BrickData(ShapeSpace& _space,
+		     const EndPoint &_GFL, const EndPoint &_GFR, 
+		     const EndPoint &_GBL, const EndPoint &_GBR, 
+		     const EndPoint &_TFL, const EndPoint &_TFR, 
+		     const EndPoint &_TBL, const EndPoint &_TBR) 
+  : BaseData(_space,brickDataType), 
+    GFL(_GFL), GFR(_GFR), GBL(_GBL), GBR(_GBR),
+    TFL(_TFL), TFR(_TFR), TBL(_TBL), TBR(_TBR),
+    centroid((GFL + GFR + GBL + GBR + TFL + TFR + TBL + TBR) / 8)
+{
+}
+
+  
+DATASTUFF_CC(BrickData);
+
+bool BrickData::isMatchFor(const ShapeRoot& other) const {
+  if (!(isSameTypeAs(other) && isSameColorAs(other)))
+    return false;
+  // const Shape<BrickData>& other_point = ShapeRootTypeConst(other,BrickData);
+  // float dist = the_point.distanceFrom(other_point->getCentroid());
+  float dist = 0;
+  return dist < 20; // *** DST hack
+}
+
+void BrickData::mergeWith(const ShapeRoot& other) {
+  const Shape<BrickData>& other_brick = ShapeRootTypeConst(other,BrickData);
+  if (other_brick->confidence <= 0)
+    return;
+  /*
+  const int other_conf = other_point->confidence;
+  confidence += other_conf;
+  the_point = (the_point*confidence + other_point->getCentroid()*other_conf) / (confidence+other_conf);*/
+}
+
+bool BrickData::updateParams(const ShapeRoot& other, bool) {
+  const Shape<BrickData>& other_brick = *static_cast<const Shape<BrickData>*>(&other);
+  //  ++confidence;
+  GFL = (GFL*(confidence-1) + other_brick->getGFL())/confidence;
+  GFR = (GFR*(confidence-1) + other_brick->getGFR())/confidence;
+  GBL = (GBL*(confidence-1) + other_brick->getGBL())/confidence;
+  GBR = (GBR*(confidence-1) + other_brick->getGBR())/confidence;
+  TFL = (TFL*(confidence-1) + other_brick->getTFL())/confidence;
+  TFR = (TFR*(confidence-1) + other_brick->getTFR())/confidence;
+  TBL = (TBL*(confidence-1) + other_brick->getTBL())/confidence;
+  TBR = (TBR*(confidence-1) + other_brick->getTBR())/confidence;
+  deleteRendering();
+  return true;
+}
+
+//! Print information about this shape. (Virtual in BaseData.)
+void
+BrickData::printParams() const {
+  cout << "Type = " << getTypeName();
+  cout << "Shape ID = " << getId() << endl;
+  cout << "Parent ID = " << getParentId() << endl;
+  
+  // Print critical points.
+  cout << endl;
+  //cout << "center{" << getCentroid().coordX() << ", " << getCentroid().coordY() << "}" << endl;
+  /* Didn't work initially... not sure why, didn't try too hard.
+    cout<<"GFL: "; GFL.printData(); cout<<endl;
+  cout<<"GFR: "; GFR.printData(); cout<<endl;
+  cout<<"GBL: "; GBL.printData(); cout<<endl;
+  cout<<"GBR: "; GBR.printData(); cout<<endl;
+  cout<<"TFL: "; TFL.printData(); cout<<endl;
+  cout<<"TFR: "; TFR.printData(); cout<<endl;
+  cout<<"TBL: "; TBL.printData(); cout<<endl;
+  cout<<"TBR: "; TBR.printData(); cout<<endl;*/
+  printf("color = %d %d %d\n",getColor().red,getColor().green,getColor().blue);
+  cout << "viewable = " << isViewable() << endl;
+}
+
+
+//! 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::projectToGround(const NEWMAT::Matrix& camToBase,
+				const NEWMAT::ColumnVector& groundplane) {
+  GFL.projectToGround(camToBase,groundplane);
+  GFR.projectToGround(camToBase,groundplane);
+  GBL.projectToGround(camToBase,groundplane);
+  GBR.projectToGround(camToBase,groundplane);
+
+  // Compute height at every corner except BL (because we didn't actually observe that corner)
+  float FLHeight, FRHeight, BRHeight;
+  TFL.projectToGround(camToBase,groundplane);
+  TFR.projectToGround(camToBase,groundplane);
+  TBR.projectToGround(camToBase,groundplane);
+  FLHeight = TFL.getHeightAbovePoint(GFL, groundplane);
+  FRHeight = TFR.getHeightAbovePoint(GFR, groundplane);
+  BRHeight = TBR.getHeightAbovePoint(GBR, groundplane);
+  float brickHeight = (FLHeight + FRHeight+ BRHeight) / 3.0;
+  TFL.setCoords(GFL.coordX(), GFL.coordY(), GFL.coordZ() + FLHeight);
+  TFR.setCoords(GFR.coordX(), GFR.coordY(), GFR.coordZ() + FRHeight);
+  TBL.setCoords(GBL.coordX(), GBL.coordY(), GBL.coordZ() + brickHeight);
+  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";
+
+}
+
+// ==================================================
+// BEGIN SKETCH MANIPULATION AND BRICK EXTRACTION CODE
+// ==================================================
+
+
+//! Brick extraction.
+
+
+//! Render into a sketch space and return reference. (Private.)
+Sketch<bool>* BrickData::render() const {
+  SketchSpace &renderspace = space->getDualSpace();
+  //int const width = renderspace.getWidth();
+  //int const height = renderspace.getHeight();
+  //float x1,y1,x2,y2;
+  Sketch<bool>* draw_result = 
+    new Sketch<bool>(renderspace, "render("+getName()+")");
+  (*draw_result)->setParentId(getViewableId());
+  (*draw_result)->setColor(getColor());
+  *draw_result = 0;
+  LineData GF(*space, GFL, GFR);
+  *draw_result = *draw_result & GF.getRendering();
+  LineData GL(*space, GFL, GBL);
+  *draw_result = *draw_result & GL.getRendering();
+  LineData GB(*space, GBL, GBR);
+  *draw_result = *draw_result & GB.getRendering();
+  LineData GR(*space, GBR, GFR);
+  *draw_result = *draw_result & GR.getRendering();
+  
+  return draw_result;
+}
+
+
+
+
+  // Old version of brick extraction
+  // Final version resides in extractBrick
+std::vector<Shape<BrickData> > BrickData::findBricks(ShapeSpace& ShS, std::vector<Shape<LineData> > lines)
+{
+  const float lengthConst = .3;
+  std::vector<Shape<LineData> > resultLines;
+  std::vector<Shape<BrickData> > resultBricks;
+  float longLength, shortLength;
+
+  if (lines.size() < 3)
+    {
+      return resultBricks;
+    }
+
+  lines = stable_sort(lines, not2(LineData::LengthLessThan()));
+
+  DO_SHAPEVEC(lines, LineData, l1, {
+    DO_SHAPENEXT(lines, LineData, l1, l2, {
+    if (l1->getLength() > l2->getLength()){
+      longLength = l1->getLength();
+      shortLength = l2->getLength();
+    }
+    else {
+      longLength = l2->getLength();
+      shortLength = l1->getLength();
+    }
+    if (LineData::ParallelTest()(l1,l2) && !LineData::ColinearTest()(l1,l2) && 
+	(shortLength / longLength > lengthConst)) {
+      DO_SHAPENEXT(lines, LineData, l2, l3, {
+	if (LineData::ParallelTest()(l1,l3) && 
+	    !LineData::ColinearTest()(l1,l3) &&
+	    LineData::ParallelTest()(l2,l3) && 
+	    !LineData::ColinearTest()(l2,l3) &&
+	    (l3->getLength() / longLength > lengthConst) && 
+	    (shortLength / l3->getLength() > lengthConst)) {
+	  NEW_SHAPE_N(l1_2, LineData,  new LineData(ShS, l1->leftPt(), l1->rightPt()));
+	  NEW_SHAPE_N(l2_2, LineData, new LineData(ShS, l2->leftPt(), l2->rightPt()));
+	  NEW_SHAPE_N(l3_2, LineData, new LineData(ShS, l3->leftPt(), l3->rightPt()));
+	  l1_2->setParentId(l1->getViewableId());
+	  l2_2->setParentId(l1->getViewableId());
+	  l3_2->setParentId(l1->getViewableId());
+	  resultLines.push_back(l1_2);
+	  resultLines.push_back(l2_2);
+	  resultLines.push_back(l3_2);
+	}
+      });
+    }
+    });
+  });
+	      
+  if (resultLines.size() < 3) {
+      return resultBricks;
+  }
+  
+  for (unsigned int i=0; i<resultLines.size(); i+=3)
+    {
+      const Shape<LineData>& final1 = ShapeRootTypeConst(resultLines[i+0],LineData);
+      const Shape<LineData>& final2 = ShapeRootTypeConst(resultLines[i+1],LineData);
+      const Shape<LineData>& final3 = ShapeRootTypeConst(resultLines[i+2],LineData);
+      /*cout<<"3 lines:"<<endl;
+	final1->printEnds();
+	final2->printEnds();
+	final3->printEnds();*/
+      
+      std::vector<Shape<LineData> > threeLines;
+      
+      if (final1->bottomPt().isBelow(final2->bottomPt(),camcentric))
+	{
+	  if (final1->bottomPt().isBelow(final3->bottomPt(),camcentric))
+	    {
+	      threeLines.push_back(final1);
+	      if (final2->bottomPt().isBelow(final3->bottomPt(),camcentric))
+		{
+		  threeLines.push_back(final2);
+		  threeLines.push_back(final3);
+		}
+	      else
+		{
+		  threeLines.push_back(final3);
+		  threeLines.push_back(final3);
+		}
+	    }
+	  else
+	    {
+	      threeLines.push_back(final3);
+	      threeLines.push_back(final1);
+	      threeLines.push_back(final2);
+	    }
+	}
+      else
+	{
+	  if (final2->bottomPt().isBelow(final3->bottomPt(),camcentric))
+	    {
+	      threeLines.push_back(final2);
+	      if (final1->bottomPt().isBelow(final3->bottomPt(),camcentric))
+		{
+		  threeLines.push_back(final1);
+		  threeLines.push_back(final3);
+		}
+	      else
+		{
+		  threeLines.push_back(final3);
+		  threeLines.push_back(final1);
+		}
+	    }
+	  else
+	    {
+	      threeLines.push_back(final3);
+	      threeLines.push_back(final2);
+	      threeLines.push_back(final1);
+	    }
+	}
+      const Shape<LineData> &bottom = ShapeRootTypeConst(threeLines[0], LineData);
+      const Shape<LineData> &mid = ShapeRootTypeConst(threeLines[1], LineData);
+      const Shape<LineData> &top = ShapeRootTypeConst(threeLines[2], LineData);
+      
+      /*cout<<"Sorted Lines: "<<endl;
+	bottom->printEnds();
+	mid->printEnds();
+	top->printEnds();*/
+      
+      Point gbl(top->leftPt()+(bottom->leftPt() - mid->leftPt()));
+      Point gbr(top->rightPt()+(bottom->rightPt() - mid->rightPt()));
+      Shape<BrickData> newBrick (ShS, (Point&)(bottom->leftPt()), (Point&)bottom->rightPt(), 
+				 gbl, gbr, 
+				 (Point&)mid->leftPt(), (Point&)mid->rightPt(), 
+				 (Point&)top->leftPt(), (Point&)top->rightPt());
+      
+      newBrick->setParentId(final1->getViewableId());
+
+      NEW_SHAPE(brickl1, LineData, Shape<LineData>(bottom.getData()));
+      NEW_SHAPE(brickl2, LineData, Shape<LineData>(mid.getData()));
+      NEW_SHAPE(brickl3, LineData, Shape<LineData>(top.getData()));
+
+      brickl1->setParentId(newBrick->getViewableId());
+      brickl2->setParentId(newBrick->getViewableId());
+      brickl3->setParentId(newBrick->getViewableId());
+      
+      resultBricks.push_back(newBrick);
+    }
+  
+  return resultBricks;
+}
+
+
+// Find bricks from 3 vectors of candidate blobs
+// Each vector is blobs of a different face color
+//
+// Also an old version. Final version is in extractBrick
+std::vector<Shape<BrickData> > BrickData::findBricksFromBlobs(ShapeSpace& ShS, 
+							      std::vector<Shape<BlobData> > blobs1,
+							      std::vector<Shape<BlobData> > blobs2,
+							      std::vector<Shape<BlobData> > blobs3) 
+{
+
+  const float distanceThresh = 10;
+
+  unsigned int i, i1, i2;
+  Shape<BlobData> blob1, blob2, blob3;
+
+  std::vector<Shape<BrickData> > resultBricks;
+
+  Point GFL, GFR, GBL, GBR, TFL, TFR, TBL, TBR;
+  Point c12,c13,c23;
+
+  std::vector<std::vector<Point> > corners1;
+  std::vector<std::vector<Point> > corners2;
+  std::vector<std::vector<Point> > corners3;
+  std::vector<bool> used1;
+  std::vector<bool> used2;
+  std::vector<bool> used3;
+  for (i=0; i<blobs1.size(); i++) { 
+    used1.push_back(false); 
+    corners1.push_back(blobs1[i]->findCornersDiagonal()); 
+  }
+  for (i=0; i<blobs2.size(); i++) { 
+    used2.push_back(false); 
+    corners2.push_back(blobs2[i]->findCornersDiagonal()); 
+  }
+  for (i=0; i<blobs3.size(); i++) { 
+    used3.push_back(false); 
+    corners3.push_back(blobs3[i]->findCornersDiagonal()); 
+  }
+
+  // Look for bricks with a good common edge between each pair of viable brick face colors
+  int used;
+  for (i1=0; i1<blobs1.size(); i1++){
+    for (i2=0; i2<blobs2.size();i2++){
+      if (!used1[i1] && !used2[i2]) {
+	used = addBrickWithTwoSides(ShS, corners1[i1], corners2[i2], corners3, 
+				    resultBricks, distanceThresh);
+	if (used>=0) {
+	  used1[i1] = true;
+	  used2[i2] = true;
+	  used3[used] = true;
+	  resultBricks[resultBricks.size()-1]->setParentId(blobs1[i1]->getViewableId());
+	}
+      }
+    }
+  }
+
+  for (i1=0; i1<blobs1.size(); i1++){
+    for (i2=0; i2<blobs3.size();i2++){
+      if (!used1[i1] && !used3[i2]) {
+	used = addBrickWithTwoSides(ShS, corners1[i1], corners3[i2], corners2, 
+				    resultBricks, distanceThresh);
+	if (used>=0) {
+	  used1[i1] = true;
+	  used3[i2] = true;
+	  used2[used] = true;
+	  resultBricks[resultBricks.size()-1]->setParentId(blobs1[i1]->getViewableId());
+	}
+      }
+    }
+  }
+
+  for (i1=0; i1<blobs3.size(); i1++){
+    for (i2=0; i2<blobs2.size();i2++){
+      if (!used3[i1] && !used2[i2]) {
+	used = addBrickWithTwoSides(ShS, corners3[i1], corners2[i2], corners1, 
+				    resultBricks, distanceThresh);
+	if (used>=0) {
+	  used3[i1] = true;
+	  used2[i2] = true;
+	  used1[used] = true;
+	  resultBricks[resultBricks.size()-1]->setParentId(blobs3[i1]->getViewableId());
+	}
+      }
+    }
+  }
+
+
+  return resultBricks;
+}
+
+
+// Subroutine for blob brick detection
+// If the two sides match, finds the third side that matches
+// Extrapolates all the points and adds the brick to the vector
+// returns the index of the third face, or -1 if no match is found
+//
+// subroutine for an old version
+int BrickData::addBrickWithTwoSides(ShapeSpace &ShS,
+				    std::vector<Point>& corners1, 
+				    std::vector<Point>& corners2, 
+				    std::vector<std::vector<Point> >& blobs3, 
+				    std::vector<Shape<BrickData> >& result, 
+				    float distanceThresh)
+{
+  unsigned int blobi;
+  int i1=-1,j1=-1, i2=-1, j2=-1;
+  for (int i=0; i<4 && i2<0; i++) {
+    for (int j=0; j<4 && j2<0; j++) {
+      if (corners1[i].distanceFrom(corners2[j]) < distanceThresh) {
+	if (corners1[(i+1)%4].distanceFrom(corners2[(j+3)%4]) < distanceThresh) {
+	  i1 = i;
+	  i2 = (i+1)%4;
+	  j1 = (j+3)%4;
+	  j2 = j;
+	}
+	else if (corners1[(i+3)%4].distanceFrom(corners2[(j+1)%4]) < distanceThresh) {
+	  i1 = (i+3)%4;
+	  i2 = i;
+	  j1 = j;
+	  j2 = (j+1)%4;
+	}
+	if (i2>=0) {
+	  // Two matching corners have been found: (i1,j2), (i2, j1)
+	  // Look for the third side
+	  bool found = false;
+	  Point center, mid1, mid2, mid3, c1, c2, c3;
+	  for (blobi=0; blobi<blobs3.size() && !found; blobi++) {
+	    for(int k=0; k<4 && !found; k++) {
+	      if (((blobs3[blobi][k].distanceFrom(corners1[i1]) < distanceThresh) +
+		   (blobs3[blobi][(k+1)%4].distanceFrom(corners1[(i1+3)%4]) < distanceThresh) +
+		   (blobs3[blobi][(k+3)%4].distanceFrom(corners2[(j2+1)%4]) < distanceThresh)) > 1) {
+		// (i1,j2, k) is the center
+		found = true;
+		mid1 = (corners1[i2]+corners2[j1])/2;
+		if (blobs3[blobi][k].distanceFrom(corners1[i1]) < distanceThresh) 
+		  center = (corners1[i1]+corners2[j2]+blobs3[blobi][k])/3;
+		else
+		  center = (corners1[i1]+corners2[j2])/2;
+		if (blobs3[blobi][(k+1)%4].distanceFrom(corners1[(i1+3)%4]) < distanceThresh)
+		  mid2 = (blobs3[blobi][(k+1)%4] + corners1[(i1+3)%4])/2;
+		else
+		  mid2 = corners1[(i1+3)%4];
+		if (blobs3[blobi][(k+3)%4].distanceFrom(corners2[(j2+1)%4]) < distanceThresh)
+		  mid3 = (blobs3[blobi][(k+3)%4] + corners2[(j2+1)%4])/2;
+		else
+		  mid3 = corners2[(j2+1)%4];
+		c1 = corners1[(i1+2)%4];
+		c2 = blobs3[blobi][(k+2)%4];
+		c3 = corners2[(j2+2)%4];
+	      }
+	      else if (((blobs3[blobi][k].distanceFrom(corners1[i2]) < distanceThresh) +
+		   (blobs3[blobi][(k+1)%4].distanceFrom(corners2[(j1+3)%4]) < distanceThresh) +
+		   (blobs3[blobi][(k+3)%4].distanceFrom(corners1[(i2+1)%4]) < distanceThresh)) > 1) {
+		// (i2, j1, k) is the center
+		found = true;
+		mid1 = (corners1[i1]+corners2[j2])/2;
+		if (blobs3[blobi][k].distanceFrom(corners1[i2]) < distanceThresh) 
+		  center = (corners1[i2]+corners2[j1]+blobs3[blobi][k])/3;
+		else
+		  center = (corners1[i2]+corners2[j1])/2;
+		if (blobs3[blobi][(k+1)%4].distanceFrom(corners2[(j1+3)%4]) < distanceThresh)
+		  mid2 = (blobs3[blobi][(k+1)%4] + corners2[(j1+3)%4])/2;
+		else
+		  mid2 = corners2[(j1+3)%4];
+		if (blobs3[blobi][(k+3)%4].distanceFrom(corners1[(i2+1)%4]) < distanceThresh)
+		  mid3 = (blobs3[blobi][(k+3)%4] + corners1[(i2+1)%4])/2;
+		else
+		  mid3 = corners1[(i2+1)%4];
+		c1 = corners2[(j1+2)%4];
+		c2 = blobs3[blobi][(k+2)%4];
+		c3 = corners1[(i2+2)%4];
+	      }
+	    }
+
+	  }
+
+	  if (found) {
+	    // Found a brick, figure out where the top / left / etc sides are
+
+	    // Debug shapes
+	    NEW_SHAPE(centerp, PointData, new PointData(ShS, center));
+	    NEW_SHAPE(mid1p, PointData, new PointData(ShS, mid1));
+	    NEW_SHAPE(mid2p, PointData, new PointData(ShS, mid2));
+	    NEW_SHAPE(mid3p, PointData, new PointData(ShS, mid3));
+	    NEW_SHAPE(c1p, PointData, new PointData(ShS, c1));
+	    NEW_SHAPE(c2p, PointData, new PointData(ShS, c2));
+	    NEW_SHAPE(c3p, PointData, new PointData(ShS, c3));
+	    centerp->setColor(rgb(150,0,255));
+	    mid1p->setColor(rgb(150,0,255));
+	    mid2p->setColor(rgb(150,0,255));
+	    mid3p->setColor(rgb(150,0,255));
+	    c1p->setColor(rgb(150,0,255));
+	    c2p->setColor(rgb(150,0,255));
+	    c3p->setColor(rgb(150,0,255));
+	    
+	    Point GFL, GFR, GBL, GBR, TFL, TFR, TBL, TBR;
+	    
+	    TFR = center;
+	    if (mid1.isBelow(center, camcentric) && mid1.isBelow(mid2, camcentric) && mid1.isBelow(mid3, camcentric)) {
+	      GFR = mid1;
+	      GBR = c1;
+	      if (mid2.isRightOf(mid3, camcentric)) {
+		TBR = mid2;
+		TBL = c2;
+		TFL = mid3;
+		GFL = c3;
+	      }
+	      else {
+		TBR = mid3;
+		TBL = c3;
+		TFL = mid2;
+		GFL = c2;
+	      }
+	    }
+	    else if (mid2.isBelow(center, camcentric) && mid2.isBelow(mid1, camcentric) && mid2.isBelow(mid3, camcentric)) {
+	      GFR = mid2;
+	      GBR = c2;
+	      if (mid1.isRightOf(mid3, camcentric)) {
+		TBR = mid1;
+		TBL = c1;
+		TFL = mid3;
+		GFL = c3;
+	      }
+	      else {
+		TBR = mid3;
+		TBL = c3;
+		TFL = mid1;
+		GFL = c1;
+	      }
+	    }
+	    else {
+	      GFR = mid3;
+	      GBR = c3;
+	      if (mid2.isRightOf(mid1, camcentric)) {
+		TBR = mid2;
+		TBL = c2;
+		TFL = mid1;
+		GFL = c1;
+	      }
+	      else {
+		TBR = mid1;
+		TBL = c1;
+		TFL = mid2;
+		GFL = c2;
+	      }
+	    }
+	    
+	    GBL = GFL + (TBL - TFL);
+
+	    Shape<BrickData> newBrick(ShS, GFL, GFR, GBL, GBR, TFL, TFR, TBL, TBR);
+	    result.push_back(newBrick);
+	    centerp->setParentId(newBrick->getViewableId());
+	    mid1p->setParentId(newBrick->getViewableId());
+	    mid2p->setParentId(newBrick->getViewableId());
+	    mid3p->setParentId(newBrick->getViewableId());
+	    c1p->setParentId(newBrick->getViewableId());
+	    c2p->setParentId(newBrick->getViewableId());
+	    c3p->setParentId(newBrick->getViewableId());
+	    return blobi;
+	  }
+	  else {
+	    // What do we do if we get two good faces and no third?
+	  }
+	  
+	}
+      }
+    }
+  }
+
+  return -1;
+
+}
+
+
+
+
+
+/* Unified brick extraction starting from 2 or 3 blobs, each of a different color 
+ *
+ *************    Final Version   ***************
+ *
+ * Checks the relative locations of the blobs (to ensure they are adjacent enough to 
+ * be part of the same brick)
+ *
+ * Computes the interior edge lines from the regions close to two faces.
+ *
+ * Computes the corners of each face individually. 
+ * This step is handled in blobData::findCorners
+ *
+ * Combine all the corner guesses together and extrapolate missing corners.
+ *
+ *
+ * Some helper functions can be found in BrickOps.h 
+ */
+Shape<BrickData> BrickData::extractBrick(ShapeSpace& space, vector<Shape<BlobData> > &blobs)
+{
+  unsigned int nblobs = blobs.size();
+  std::vector<Point> centroids;
+
+  ShapeRoot invalid;
+  if (nblobs > 3 || nblobs < 2) {
+    return ShapeRootType(invalid,BrickData);
+  }
+
+  for (unsigned int i=0; i<nblobs; i++) {
+    centroids.push_back(blobs[i]->getCentroid());
+  }
+
+  // Check inter-blob distance
+  // If any pair of blobs are too far apart, this set is invalid
+  for (unsigned int i=0; i<nblobs; i++) {
+    for (unsigned int j=i+1; j<nblobs; j++) {
+      if (centroids[i].distanceFrom(centroids[j]) >= 
+	  blobs[i]->topLeft.distanceFrom(centroids[i]) + 
+	  blobs[j]->topLeft.distanceFrom(centroids[j])){
+	return ShapeRootType(invalid,BrickData);	
+      }
+    }
+  }
+
+
+  // arbitrary face assignment, aligned as the brick is in camera space
+  // this will probably break down if the dog tilts its head
+  // 
+  // if we only have two faces, we're assuming only the top and "left" faces are visible
+  // always assume a top face is visible, becuase any shape without a top face is much more likely
+  // to be a pyramid than a tall brick
+  int top=-1, left=-1, right=-1;
+  
+  if (centroids[0].isAbove(centroids[1], camcentric)) {
+    top = 0;
+  }
+  else {
+    top = 1;
+  }
+  if (nblobs > 2 && centroids[2].isAbove(centroids[top], camcentric)) {
+    top = 2;
+  }
+
+  if ((top != 0 && centroids[0].isLeftOf(centroids[1], camcentric)) || top == 1) {
+    left = 0;
+  }
+  else {
+    left = 1;
+  }
+  if (nblobs>2 && top != 2 && centroids[2].isLeftOf(centroids[left], camcentric)) {
+    left = 2;
+  }
+
+  if (nblobs > 2) {
+    if (top != 0 && left != 0) {
+      right = 0;
+    }
+    else if (top != 1 && left != 1) {
+      right = 1;
+    }
+    else {
+      right = 2;
+    }
+  }
+
+  if (top == left || top == right || left == right){
+    std::cout<<"ERROR: Brick side misclassification!"<<std::endl;
+    return ShapeRootType(invalid,BrickData);	
+  }
+
+
+  // Compute two-blob boundary regions
+  // This is used to find the interior edges of the brick
+  // It is also used as a second check for inter-brick distance
+  const int INTERSECT_DIST = 5, MIN_REQUIRED_DIST = 2;
+  std::vector<Sketch<bool> > boundaries;
+  NEW_SKETCH_N(topEdist, uchar, visops::edist(blobs[top]->getRendering()));
+  NEW_SKETCH_N(leftEdist, uchar, visops::edist(blobs[left]->getRendering()));
+  NEW_SKETCH(tlsmall, bool, topEdist<MIN_REQUIRED_DIST & leftEdist<MIN_REQUIRED_DIST);
+  if (!tlsmall->max()){
+    return ShapeRootType(invalid,BrickData);	
+  }
+  NEW_SKETCH(tl, bool, topEdist<INTERSECT_DIST & leftEdist<INTERSECT_DIST);
+  rgb green_rgb(0,0,255);
+  tl->setColor(green_rgb);
+  boundaries.push_back(tl);
+
+  if (nblobs>2) {
+    NEW_SKETCH_N(rightEdist, uchar, visops::edist(blobs[right]->getRendering()));
+    NEW_SKETCH(trsmall, bool, topEdist<MIN_REQUIRED_DIST & rightEdist<MIN_REQUIRED_DIST);
+    if (!trsmall->max()){
+      return ShapeRootType(invalid,BrickData);
+    }	
+    NEW_SKETCH(tr, bool, topEdist<INTERSECT_DIST & rightEdist<INTERSECT_DIST);
+    tr->setColor(green_rgb);
+    boundaries.push_back(tr);
+
+    NEW_SKETCH(lrsmall, bool, leftEdist<MIN_REQUIRED_DIST & rightEdist<MIN_REQUIRED_DIST);
+    if (!lrsmall->max()){
+      return ShapeRootType(invalid,BrickData);
+    }	
+    NEW_SKETCH(lr, bool, leftEdist<INTERSECT_DIST & rightEdist<INTERSECT_DIST);
+    lr->setColor(green_rgb);
+    boundaries.push_back(lr);
+  }
+
+
+
+  // Begin gathering evidence for each point
+  // This should probably be augmented by an extra vector of confidences
+  std::vector<std::vector<Point> > points(8);
+
+  // Arbitrary corner / face assignemt (in cam space)
+  //
+  //      5------6
+  //     /   T  /|
+  //    /(4)   / 7
+  //   1------2 / <-- R
+  //   |  L   |/
+  //   0------3
+  //    
+
+
+  // Construct the interior lines
+  // Add their guesses to the appropriate points on the brick
+  NEW_SHAPE(tlline, LineData, LineData::extractLine(boundaries[0]));
+  Shape<LineData> trline, lrline;
+
+  if (right!=-1) {
+    trline = LineData::extractLine(boundaries[1]);
+    lrline = LineData::extractLine(boundaries[2]);
+
+    // shorten interior lines based on their intersections
+    bool on1=false, on2=false;
+    if (tlline.isValid() && trline.isValid()) {
+      Point isectPt = tlline->intersectionWithLine(trline, on1, on2);
+      if (on1) {
+	tlline->rightPt().setCoords(isectPt);
+      }
+      if (on2) {
+	trline->leftPt().setCoords(isectPt);
+      }
+    }
+
+    if (tlline.isValid() && lrline.isValid()) {
+      Point isectPt = tlline->intersectionWithLine(lrline, on1, on2);
+      if (on1) {
+	tlline->rightPt().setCoords(isectPt);
+      }
+      if (on2) {
+	lrline->topPt().setCoords(isectPt);
+      }
+    }
+
+    if (trline.isValid() && lrline.isValid()) {
+      Point isectPt = trline->intersectionWithLine(lrline, on1, on2);
+      if (on1) {
+	trline->leftPt().setCoords(isectPt);
+      }
+      if (on2) {
+	lrline->topPt().setCoords(isectPt);
+      }
+    }
+
+
+    if (trline.isValid()) {
+      points[2].push_back(trline->leftPt());
+      points[6].push_back(trline->rightPt());
+    }
+
+    if (lrline.isValid()) {
+      points[2].push_back(lrline->topPt());
+      points[3].push_back(lrline->bottomPt());
+    }
+  }
+
+  if (tlline.isValid()) {
+    points[1].push_back(tlline->leftPt());
+    points[2].push_back(tlline->rightPt());
+  }
+
+
+
+  // Extract the corners of the blob using the derivative approach
+  //
+  // corners are coming out of findCorners() in counter-clock-wise order around the blob
+  //  with unknown starting position
+  //
+  // the findCorners function in BlobData is the other important part of the algorithm
+  // Several different methods of corner extraction can be connected there. 
+  std::vector<Point> candidates;
+
+  // top face
+
+  // Compute an orthogonal bounding box from the top-left line
+  if (tlline.isValid()) {
+    if (trline.isValid() && trline->getLength() > tlline->getLength()) {
+      candidates = findOrthogonalBoundingBox(space, blobs[top], centroids[top], trline);
+    }
+    else {
+      candidates = findOrthogonalBoundingBox(space, blobs[top], centroids[top], tlline);      
+    }
+  }
+  else if (trline.isValid()) {
+    candidates = findOrthogonalBoundingBox(space, blobs[top], centroids[top], trline);
+  }
+  
+  float cornerValue; 
+
+  std::vector<Point> tcorners = blobs[top]->findCorners(4, candidates, cornerValue);
+
+  if (tcorners.size() == 4) {
+    
+    // Sort out which corner is which
+    // if there's a clear left-most corner, its corner 1
+    // if two corners are close in left-ness, then they should be 1 and 5
+    unsigned int leftCorner = 0;
+    for (unsigned int i=1; i<4; i++){
+      if (tcorners[i].isLeftOf(tcorners[leftCorner], camcentric)) {
+	leftCorner = i;
+      }
+    }
+    int closeCorner = -1;
+    float mostLeft = tcorners[leftCorner].coordX();
+    const int MAX_CLOSE_DIST = 5;
+    for (unsigned int i=0; i<4; i++) {
+      if (i != leftCorner && tcorners[i].coordX() - mostLeft < MAX_CLOSE_DIST) {
+	closeCorner = i;
+      }
+    }
+    
+    if (closeCorner != -1) {
+      // If 5 was actually left-most, switch leftCorner to 1
+      if ((unsigned int)closeCorner == (leftCorner+1)%4) {
+	leftCorner = closeCorner;
+      }
+      else if ((unsigned int)closeCorner != (leftCorner+3)%4) {
+	std::cout<<"WARNING, opposite corners are close together!"<<std::endl;
+      }
+    }
+    NEW_SHAPE(top1, PointData, PointData(space, tcorners[leftCorner]));
+    points[1].push_back(tcorners[leftCorner]);
+    points[2].push_back(tcorners[(leftCorner+1)%4]);
+    points[6].push_back(tcorners[(leftCorner+2)%4]);
+    points[5].push_back(tcorners[(leftCorner+3)%4]);
+
+  }
+  else {
+    // Some versions of findCorners don't always return 4 corners. 
+    // How to handle these cases is ambiguous at best. 
+  }
+
+  // repeat with other faces
+
+  // left face
+  candidates.clear();
+  if (tlline.isValid()) {
+    if (lrline.isValid() && lrline->getLength() > tlline->getLength()) {
+      candidates = findOrthogonalBoundingBox(space, blobs[left], centroids[left], lrline);
+    }
+    else {
+      candidates = findOrthogonalBoundingBox(space, blobs[left], centroids[left], tlline);      
+    }
+  }
+  else if (trline.isValid()) {
+    candidates = findOrthogonalBoundingBox(space, blobs[left], centroids[left], lrline);
+  }
+
+  for (unsigned int i=0; i<candidates.size(); i++) {
+    NEW_SHAPE(candidate, PointData, PointData(space, candidates[i]));
+    candidate->setParentId(blobs[left]->getViewableId());
+  }
+  std::vector<Point> lcorners = blobs[left]->findCorners(4, candidates, cornerValue);
+  if (lcorners.size() == 4) {
+    
+    // if there's a clear right-most corner, its corner 3
+    // if two corners are close in right-ness, then they should 3 and 2
+    unsigned int rightCorner = 0;
+    for (unsigned int i=1; i<4; i++){
+      if (lcorners[i].isRightOf(lcorners[rightCorner], camcentric)) {
+	rightCorner = i;
+      }
+    }
+    int closeCorner = -1;
+    float mostRight = lcorners[rightCorner].coordX();
+    const int MAX_CLOSE_DIST = 5;
+    for (unsigned int i=0; i<4; i++) {
+      if (i != rightCorner && mostRight - lcorners[i].coordX() < MAX_CLOSE_DIST) {
+	closeCorner = i;
+      }
+    }
+    
+    if (closeCorner != -1) {
+      // If 2 was actually right-most, switch rightCorner to 3
+      if ((unsigned int)closeCorner == (rightCorner+3)%4) {
+	rightCorner = closeCorner;
+      }
+      else if ((unsigned int)closeCorner != (rightCorner+1)%4) {
+	std::cout<<"WARNING, opposite corners are close together!"<<std::endl;
+      }
+    }
+    NEW_SHAPE(left2, PointData, PointData(space, lcorners[rightCorner]));
+    points[3].push_back(lcorners[rightCorner]);
+    points[2].push_back(lcorners[(rightCorner+1)%4]);
+    points[1].push_back(lcorners[(rightCorner+2)%4]);
+    points[0].push_back(lcorners[(rightCorner+3)%4]);
+
+  }
+  else {
+
+  }
+
+  // right face
+  if (right != -1) {
+
+    candidates.clear();
+    if (trline.isValid()) {
+      if (lrline.isValid() && lrline->getLength() > trline->getLength()) {
+	candidates = findOrthogonalBoundingBox(space, blobs[right], centroids[right], lrline);
+      }
+      else {
+	candidates = findOrthogonalBoundingBox(space, blobs[right], centroids[right], trline);      
+      }
+    }
+    else if (lrline.isValid()) {
+      candidates = findOrthogonalBoundingBox(space, blobs[right], centroids[right], lrline);
+    }
+
+    std::vector<Point> rcorners = blobs[right]->findCorners(4, candidates, cornerValue);
+    if (rcorners.size() == 4) {
+    
+      // if there's a clear bottom-most corner, its corner 3
+      // if two corners are close in bottom-ness, then they should 3 and 7
+      unsigned int bottomCorner = 0;
+      for (unsigned int i=1; i<4; i++){
+	if (rcorners[i].isBelow(rcorners[bottomCorner], camcentric)) {
+	  bottomCorner = i;
+	}
+      }
+      int closeCorner = -1;
+      float mostBottom = rcorners[bottomCorner].coordY();
+      const int MAX_CLOSE_DIST = 5;
+      for (unsigned int i=0; i<4; i++) {
+	if (i != bottomCorner && mostBottom - rcorners[i].coordY() < MAX_CLOSE_DIST) {
+	  closeCorner = i;
+	}
+      }
+    
+      if (closeCorner != -1) {
+	// If 7 was actually bottom-most, switch bottomCorner to 3
+	if ((unsigned int)closeCorner == (bottomCorner+3)%4) {
+	  bottomCorner = closeCorner;
+	}
+	else if ((unsigned int)closeCorner != (bottomCorner+1)%4) {
+	  std::cout<<"WARNING, opposite corners are close together!"<<std::endl;
+	}
+      }
+      NEW_SHAPE(right3, PointData, PointData(space,rcorners[bottomCorner]));
+      points[3].push_back(rcorners[bottomCorner]);
+      points[7].push_back(rcorners[(bottomCorner+1)%4]);
+      points[6].push_back(rcorners[(bottomCorner+2)%4]);
+      points[2].push_back(rcorners[(bottomCorner+3)%4]);
+
+    }
+  }
+
+
+  // If we have additional ways of extracting candidate corners, 
+  // add the corners they find to the vector of corners now.
+
+
+  // debug output
+  /*for (unsigned int i=0; i<8; i++){
+    for (unsigned int j=0; j<points[i].size(); j++) {
+      NEW_SHAPE(corner, PointData, PointData(space, points[i][j]));
+      char name[10];
+      sprintf(name, "corner%d%d",i,j);
+      corner->setName(name);
+    }
+    }*/
+
+
+  // Now merge all our candidate points to get the final brick
+
+  vector<Point> finalCorners(8);
+
+  // for now just average corners together to get the last corners
+  // should at least weight the average based on confidence
+  // could also do statistics
+  // produce a final confidence based on the std. deviation
+
+  // if we didn't get the center point of the brick then we don't have a shot
+  // top-left line also is pretty critical, 
+  // though I probably should re-work below to work in the case where top and right only work well
+  if (points[2].size()==0 || points[1].size()==0){
+    return ShapeRootType(invalid,BrickData);    
+  }
+
+  Point empty(0,0);
+
+
+  // Lots of cases for which corners are visible and extrapolating the others
+
+  for (unsigned int i=0; i<8; i++) {
+    finalCorners[i] = empty;
+    for (unsigned int j=0; j<points[i].size(); j++) {
+      finalCorners[i]+=points[i][j];
+    }
+    if (points[i].size() > 0) {
+      finalCorners[i]/=points[i].size();
+    }
+  }
+
+  if (points[3].size()==0){
+    // These should be easier cases
+    return ShapeRootType(invalid,BrickData);        
+  }
+
+  if (points[6].size() == 0) {
+    // If we have the top left line but not corner 6, infer corner 6 from the thickness of the top side
+    if (tlline.isValid()) {
+      NEW_SKETCH_N(topRendering, bool, blobs[top]->getRendering());
+      Point topPt = (Region::extractRegion(topRendering)).mostDistantPtFrom(tlline.getData());
+      NEW_SHAPE(intersectLine, LineData, LineData(space, topPt, tlline->getThetaNorm()));
+      Point intersectPoint = intersectLine->intersectionWithLine(tlline);
+      // lower confidence result
+      finalCorners[6] = topPt+finalCorners[2]-intersectPoint;
+    }
+    // can also use right left line and the right side, but the top side is more likely to be good
+    else {
+      return ShapeRootType(invalid,BrickData);        
+    }
+ }
+
+  if (points[0].size() == 0) {
+    finalCorners[0] = finalCorners[3] + finalCorners[1]-finalCorners[2];
+  }
+
+  if (points[5].size() == 0) {
+    finalCorners[5] = finalCorners[6] + finalCorners[1]-finalCorners[2];
+  }
+
+  if (points[7].size() == 0) {
+    finalCorners[7] = finalCorners[3] + finalCorners[6]-finalCorners[2];
+  }
+
+  finalCorners[4] = finalCorners[5] + finalCorners[7] - finalCorners[6] +
+    finalCorners[5] + finalCorners[0] - finalCorners[1] +
+    finalCorners[0] + finalCorners[7] - finalCorners[3];
+  finalCorners[4]/=3.0;
+
+  // left == front for generalized brick
+  NEW_SHAPE(returnbrick, BrickData, new BrickData(space, 
+						  finalCorners[0], finalCorners[3],
+						  finalCorners[4], finalCorners[7],
+						  finalCorners[1], finalCorners[2],
+						  finalCorners[5], finalCorners[6]));
+  return returnbrick;
+    
+}
+
+
+
+  // Generates a wide bounding box around the blob from a parallel line along one edge
+  // This bounding box will be used as a starting point for the quadrilateral-fitting algorithm
+  // 
+  // Generates 4 points based on the line, centroid of the blob, and parameters for extending the bounds
+  // Then sorts the points into counter-clockwise order to satisfy the ordering constraints to make other 
+  // extrapolations possible. 
+vector<Point> BrickData::findOrthogonalBoundingBox(ShapeSpace& space, Shape<BlobData> blob, Point centroid, Shape<LineData> parallel)
+{
+  const float PARALLEL_EXTEND_FACTOR = .6, ORTHO_EXTEND_FACTOR = .6;
+
+  vector<Point> candidates;
+  LineData candidate1(space, parallel->end1Pt(), parallel->end2Pt());
+
+  //candidate1.setEndPts(parallel->end1Pt(), parallel->end2Pt());
+  Point parallelExtend(candidate1.end2Pt() - candidate1.end1Pt());
+  parallelExtend *= PARALLEL_EXTEND_FACTOR;
+  LineData ortho(space, centroid, candidate1.getThetaNorm());
+  Point orthoIsect = candidate1.intersectionWithLine(ortho);
+  Point candidate2Offset = (centroid - orthoIsect) * 2.0;
+  Point orthoExtend = candidate2Offset * ORTHO_EXTEND_FACTOR;
+
+  LineData candidate2(space, candidate1.end1Pt() + candidate2Offset + orthoExtend - parallelExtend,
+		      candidate1.end2Pt() + candidate2Offset + orthoExtend + parallelExtend);
+  candidate1.setEndPts(candidate1.end1Pt() - orthoExtend - parallelExtend,
+		       candidate1.end2Pt() - orthoExtend + parallelExtend);
+  candidates.push_back(candidate1.leftPt());
+  candidates.push_back(candidate1.rightPt());
+  candidates.push_back(candidate2.rightPt());
+  candidates.push_back(candidate2.leftPt());
+
+  // debug output
+  for (unsigned int i=0; i<candidates.size(); i++) {
+    NEW_SHAPE_N(candidate, PointData, PointData(space, candidates[i]));
+    candidate->setParentId(blob->getViewableId());
+  }
+
+  // order counter-clockwise around the blob before returning
+  Point centerPoint = (candidates[0] + candidates[1] + candidates[2] + candidates[3]) / 4.0;
+  vector<float> centerAngles;
+  for (unsigned int i=0; i<candidates.size(); i++) {
+    NEW_SHAPE_N(centerLine, LineData, LineData(space, centerPoint, candidates[i]));
+    centerLine->setParentId(blob->getViewableId());
+    centerAngles.push_back(atan2(centerLine->end2Pt().coordY() - centerLine->end1Pt().coordY(),
+				 centerLine->end2Pt().coordX() - centerLine->end1Pt().coordX()));
+  }
+
+
+  vector<Point> orderedPoints;
+  
+  int maxi = 0, mini = 0;
+  float maxAng = centerAngles[0];
+  float minAng = maxAng;
+  
+  for (unsigned int i=1; i<candidates.size(); i++) {
+    if (centerAngles[i] > maxAng) {
+      maxAng = centerAngles[i];
+      maxi = i;
+    }
+    if (centerAngles[i] < minAng) {
+      minAng = centerAngles[i];
+      mini = i;
+    }
+       
+  }
+
+  orderedPoints.push_back(candidates[maxi]);
+  
+  float lastMax = maxAng;
+  for (unsigned int i=1; i<candidates.size(); i++) {
+    maxi = mini;
+    maxAng = minAng;
+    for (unsigned int j=0; j<candidates.size(); j++) {
+      float curAng = centerAngles[j];
+      if (curAng > maxAng && curAng < lastMax) {
+	maxi = j;
+	maxAng = curAng;
+      }
+    }
+    orderedPoints.push_back(candidates[maxi]);
+    lastMax = maxAng;
+  }
+  
+  // debug output
+  for (unsigned int i=0; i<candidates.size(); i++) {
+    NEW_SHAPE(orderedcandidate, PointData, PointData(space, orderedPoints[i]));
+    orderedcandidate->setParentId(blob->getViewableId());
+  }
+
+  return orderedPoints;
+}
+
+
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/BrickData.h ./DualCoding/BrickData.h
--- ../Tekkotsu_2.4.1/DualCoding/BrickData.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/BrickData.h	2006-07-21 13:57:45.000000000 -0400
@@ -0,0 +1,115 @@
+//-*-c++-*-
+#ifndef _BRICKDATA_H_
+#define _BRICKDATA_H_
+
+#include <vector>
+#include <iostream>
+#include <string>
+
+#include "Shared/newmat/newmat.h"
+
+#include "BaseData.h"    // superclass
+#include "Point.h"       // Point data members
+#include "ShapeTypes.h"  // brickDataType
+
+#include "LineData.h"
+#include "ShapeLine.h"
+#include "ShapeBlob.h"
+
+namespace DualCoding {
+
+class ShapeRoot;
+class SketchSpace;
+template<typename T> class Sketch;
+
+class BrickData : public BaseData {
+private:
+  // T=Top, G=Ground, F=front, B=back, L=left, R=right
+  EndPoint GFL;
+  EndPoint GFR;
+  EndPoint GBL;
+  EndPoint GBR;
+  EndPoint TFL;
+  EndPoint TFR;
+  EndPoint TBL;
+  EndPoint TBR;
+
+  Point centroid;
+
+public:
+
+  //! Constructor
+  BrickData(ShapeSpace& _space,
+	    const EndPoint &GFL, const EndPoint &GFR, const EndPoint &GBL, const EndPoint &GBR, 
+	    const EndPoint &TFL, const EndPoint &TFR, const EndPoint &TBL, const EndPoint &TBR);
+
+  //! Copy constructor
+  //BrickData(BrickData& otherBrick);
+
+  static ShapeType_t getStaticType() { return brickDataType; }
+  DATASTUFF_H(BrickData);
+  
+  //! Centroid. (Virtual in BaseData.)
+  Point getCentroid() const { return centroid; } 
+  
+  EndPoint getGFL() {return GFL;}
+  EndPoint getGFR() {return GFR;}
+  EndPoint getGBL() {return GBL;}
+  EndPoint getGBR() {return GBR;}
+  EndPoint getTFL() {return TFL;}
+  EndPoint getTFR() {return TFR;}
+  EndPoint getTBL() {return TBL;}
+  EndPoint getTBR() {return TBR;}
+  
+  //! Match bricks based on their parameters.  (Virtual in BaseData.)
+  virtual bool isMatchFor(const ShapeRoot& other) const;
+
+  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);
+  
+  //! Project to ground
+  virtual void projectToGround(const NEWMAT::Matrix& camToBase,
+			       const NEWMAT::ColumnVector& groundplane);
+
+  virtual unsigned short getDimension() const { return 3; }
+
+  //! Extraction.
+  static std::vector<Shape<BrickData> > findBricks(ShapeSpace& ShS, std::vector<Shape<LineData> > lines);
+
+  static std::vector<Shape<BrickData> > findBricksFromBlobs(ShapeSpace& ShS, 
+							    std::vector<Shape<BlobData> > blobs1,
+							    std::vector<Shape<BlobData> > blobs2,
+							    std::vector<Shape<BlobData> > blobs3);
+
+  static Shape<BrickData> extractBrick(ShapeSpace& space, vector<Shape<BlobData> > &blobs);
+    
+  static 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;
+
+
+  static int addBrickWithTwoSides(ShapeSpace& ShS,
+				  std::vector<Point>& corners1, 
+				  std::vector<Point>& corners2, 
+				  std::vector<std::vector<Point> >& blobs3, 
+				  std::vector<Shape<BrickData> >& result, 
+				  float distanceThresh);
+
+  //@}
+
+  BrickData& operator=(const BrickData&); //!< don't call
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/BrickOps.cc ./DualCoding/BrickOps.cc
--- ../Tekkotsu_2.4.1/DualCoding/BrickOps.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/BrickOps.cc	2006-08-10 23:19:53.000000000 -0400
@@ -0,0 +1,418 @@
+#include "BrickOps.h"
+#include "visops.h"
+
+namespace DualCoding {
+
+  /* Begin functionality for distance-from-center methods of finding the corners of a blob*/
+
+
+  /* Find the point at which the given line hits the edge of the rendered region */
+  Point findEdgePoint(Point start, Point end, Sketch<bool>& rendering) 
+  {
+    int gap_tolerance=2;
+
+    float startx = start.coordX();
+    float starty = start.coordY();
+    float dx = end.coordX() - startx;
+    float dy = end.coordY() - starty;
+
+    float dist = sqrt(dx*dx + dy*dy);
+    dx = dx/dist;
+    dy = dy/dist;
+    int maxi=0, gap=0;
+    int x,y;
+    for (int i=0; i<dist; i++) {
+      x = (int)(startx+i*dx);
+      y = (int)(starty+i*dy);
+      if (rendering(x,y)) {
+	maxi = i;
+	gap = 0;
+      }
+      else 
+	gap++;
+      if (gap>gap_tolerance)
+	break;
+    }
+    float fx = startx+maxi*dx;
+    float fy = starty+maxi*dy;
+    Point result(fx,fy);
+    return result;
+  }
+
+
+  /* 
+   * Finds the edge points of the region by drawing lines out from the center to the edges
+   * Points and distances returned are indexed by angle, so some overlap is possible. 
+   * The return value is the index of the most distant point. 
+   */
+  int findRadialDistancesFromPoint(Point center, float radius, 
+					     Sketch<bool>& rendering,
+					     float distances[],
+					     Point points[])
+  {
+    NEW_SKETCH(circle, bool, visops::zeros(rendering));
+
+    int maxi = 0, origmaxi = 0;
+    float max = -1;
+    bool stillmax = false;
+    Point edge;
+    for (int i=0; i<2*M_PI*radius; i++){
+      float x = center.coordX()+radius*cos(i/radius);
+      float y = center.coordY()+radius*sin(i/radius);
+      if (x<0) x = 0; 
+      else if (x>=rendering->getWidth()) x = rendering->getWidth()-1;
+      if (y<0) y = 0;
+      else if (y>=rendering->getHeight()) y = rendering->getHeight()-1;
+      edge.setCoords(x,y,0);
+      circle->at((int)(edge.coordX()), (int)(edge.coordY())) = 1;
+      points[i] = findEdgePoint(center,edge, rendering);
+      distances[i] = points[i].distanceFrom(center);
+      if (distances[i] > max) {
+	max = distances[i];
+	maxi = i;
+	origmaxi = i;
+	stillmax = true;
+      }
+      else if (distances[i] == max && stillmax) {
+	maxi = (origmaxi + i) / 2;
+      }
+      else {
+	stillmax = false;
+      }
+      
+    }
+
+    return maxi;
+  }
+
+
+  /*
+   * Takes the derivative of the x array, returned in dx
+   */
+  void takeDerivative(float x[], float dx[], int len) 
+  {
+    for (int i=0; i<len; i++) {
+      dx[i] = x[(i+1)%len]+x[(i+2)%len]-x[(i-1+len)%len]-x[(i-2+len)%len];
+    }
+  }
+
+  // Applies a "gaussian" to x, returned in gx
+  // very lazy implementation
+  // "gaussian" == averaging
+  void applyGaussian(float x[], float gx[], int len)
+  {
+    int smooth_n = 5;
+    float smooth_x = .2;
+    for (int i=0; i<len; i++) {
+      gx[i] = 0;
+      for (int j=0; j<smooth_n; j++) {
+	gx[i]+=x[(i+len+j-smooth_n/2)%len]*smooth_x;
+      }
+    }
+  }
+
+
+  /*
+   * Draws a histogram of the array, to be viewed like a normal sketch. 
+   * Purely for debugging / presentation output. 
+   */
+  void drawHist(float distances[], unsigned int len, Sketch<bool>& parent) 
+  {
+    float xscale = 1;
+    if (len > parent->getWidth() - 20) xscale = (parent->getWidth()-20)/(1.0*len);
+    float ymax = 0;
+    for (unsigned int i=0; i<len; i++)
+      ymax = max(ymax,abs(distances[i]));
+    int const yscale = 2;
+    ymax *= yscale; // scale up the histogram
+    int const maxheight = 70;
+    float const yshrink =  (ymax > maxheight) ? maxheight/ymax : 1.0;
+    // Draw a histogram
+    NEW_SKETCH(hist,bool, visops::zeros(parent));
+    for(unsigned int i=0; i<len; i++) {
+      if (distances[i] > 0) {
+	for (unsigned int j=0; j<yscale*distances[i]; j++) {
+	  hist->at((int)(i*xscale+10), (int)(maxheight - j*yshrink + 5)) = 1;		
+	}
+      }
+      else {
+	for (int j=-1; j>yscale*distances[i]; j--) {
+	  hist->at((int)(i*xscale+10), (int)(maxheight - j*yshrink + 5)) = 1;		
+	}
+      }
+    }
+
+    hist->at(5,(int)(maxheight*(1-yshrink)+5)) = 1;
+    hist->at(5,(int)(maxheight*(1+yshrink)+5)) = 1;
+    hist->at(203,(int)(maxheight*(1-yshrink)+5)) = 1;
+    hist->at(203,(int)(maxheight*(1+yshrink)+5)) = 1;
+
+  }
+
+
+  /* Helper functions for finding corners by fitting a quadrilateral to a blob */
+
+
+  /*
+   * Gets the score of the given set of corners as a fit to the blob. 
+   * 
+   * The score is a combination of the area of the quadrilateral and the number of edge pixels
+   * that its lines lie on. 
+   *
+   * A lower score is better, scores can go negative
+   */
+  float getBoundingQuadrilateralScore(BlobData &blob, vector<Point>& corners, 
+				      Sketch<bool> edgeImage, 
+				      int& borderCount, ShapeSpace &space)
+  {
+    const float EDGE_SCALAR = 50;
+
+    borderCount = countBorderPixelFit(blob, corners, edgeImage, space);
+    return getQuadrilateralArea(corners) - EDGE_SCALAR*borderCount;
+  }
+
+
+
+  /*
+   * assuming a convex quadrilateral
+   * splits the quadrilateral into n-2 triangles and uses the
+   * edge-length method to find the area of each triangle:
+   * s = perimeter / 2
+   * area = sqrt(s*(s-a)(s-b)(s-c))
+   */
+  float getQuadrilateralArea(vector<Point>& corners) 
+  {
+    float totalArea = 0;
+    for (unsigned int i=2; i<corners.size(); i++) {
+      float e1 = corners[0].distanceFrom(corners[i-1]);
+      float e2 = corners[i-1].distanceFrom(corners[i]);
+      float diag = corners[0].distanceFrom(corners[i]);
+      float s1 = (e1+e2+diag)/2.0;
+      totalArea += sqrt(s1*(s1-e1)*(s1-e2)*(s1-diag));
+    }
+    
+    return totalArea;
+  }
+
+  
+  /*
+   * Computes the percentage of the blob points that are inside the quadrilateral
+   *
+   * A point is inside if it is on the same side of each line as one of the opposite corners
+   * This is assuming a convex quadrilateral
+   */
+  float getBoundingQuadrilateralInteriorPointRatio(BlobData &blob, 
+						   vector<Point>& corners, 
+						   ShapeSpace &space)
+  {
+    int ncorners = corners.size();
+
+    vector<LineData> lines;
+    for (int i=0; i<ncorners; i++) {
+      lines.push_back(LineData(space,corners[(i+1)%ncorners], corners[(i+2)%ncorners]));
+    }
+
+    int totalInside = 0;
+    int totalPixelArea = 0;
+
+    for ( std::vector<BlobData::run>::const_iterator it = blob.runvec.begin();
+	  it != blob.runvec.end(); it++ ) {
+      const BlobData::run &r = *it;
+      int const xstop = r.x + r.width;
+
+      totalPixelArea += r.width;
+
+      Point p1(r.x,r.y);
+      Point p2(xstop, r.y);
+      
+      // Check if the endpoints are inside the polygon
+      bool pt1Inside = true, pt2Inside = true;
+      for (int i=0; i<ncorners; i++) {
+	if (!lines[i].pointsOnSameSide(p1,corners[i])) {
+	  pt1Inside = false;
+	  break;
+	}
+      }
+      for (int i=0; i<ncorners; i++) {
+	if (!lines[i].pointsOnSameSide(p2,corners[i])) {
+	  pt2Inside = false;
+	  break;
+	}
+      }
+
+      // if the whole run is inside, we can just add the whole run and move on
+      if (pt1Inside) {
+	if (pt2Inside) {
+	  totalInside += r.width;
+	}
+	else {
+	  // If one end of the run is inside the quadrilateral, walk along it until you enter
+	  // This could be made faster with a binary search
+	  // It could also be made faster by just checking the lines that the other endpoint was outside of
+	  totalInside++;
+	  for (int x=xstop-1; x>r.x; x--) {
+	    Point p(x,r.y);
+	    bool ptInside = true;
+	    for (int i=0; i<ncorners; i++) {
+	      if (!lines[i].pointsOnSameSide(p,corners[i])) {
+		ptInside = false;
+		break;
+	      }
+	    }
+	    if (ptInside) {
+	      totalInside+=x-r.x;
+	      break;
+	    }
+	  }
+	}
+      }
+      else {
+	// Same case as above, with the other endpoint
+	if (pt2Inside) {
+	  totalInside++;
+	  for (int x=r.x+1; x<xstop; x++) {
+	    Point p(x,r.y);
+	    bool ptInside = true;
+	    for (int i=0; i<ncorners; i++) {
+	      if (!lines[i].pointsOnSameSide(p,corners[i])) {
+		ptInside = false;
+		break;
+	      }
+	    }
+	    if (ptInside) {
+	      totalInside+=xstop-x;
+	      break;
+	    }
+	  }
+	}
+	else {
+	  // If both endpoints are outside, we still need to check the whole run.
+	  bool beenInside = false;
+	  int xstart = xstop;
+	  for (int x=r.x+1; x<xstop; x++) {
+	    Point p(x,r.y);
+	    bool ptInside = true;
+	    for (int i=0; i<ncorners; i++) {
+	      if (!lines[i].pointsOnSameSide(p,corners[i])) {
+		ptInside = false;
+		break;
+	      }
+	    }
+	    if (ptInside) {
+	      xstart = x;
+	      beenInside = true;
+	      break;
+	    }
+	  }
+	  if (beenInside) {
+	    for (int x=xstop-1; x>=xstart; x--) {
+	      Point p(x,r.y);
+	      bool ptInside = true;
+	      for (int i=0; i<ncorners; i++) {
+		if (!lines[i].pointsOnSameSide(p,corners[i])) {
+		  ptInside = false;
+		  break;
+		}
+	      }
+	      if (ptInside) {
+		totalInside+=x-xstart+1;
+		break;
+	      }
+	    }
+	  }
+	}
+      }
+  
+    }
+  
+    
+    return totalInside*1.0/totalPixelArea;
+  }
+
+
+  /*
+   * Counts the number of border pixels of the blob that lie udner one of the lines
+   */
+  int countBorderPixelFit(BlobData &blob, const vector<Point> &corners, 
+			  Sketch<bool> edges, ShapeSpace &space)
+  {
+    int ncorners = corners.size();
+
+    vector<LineData> lines;
+    vector<float> dx, dy;
+    for (int i=0; i<ncorners; i++) {
+      lines.push_back(LineData(space, corners[(i+1)%ncorners], corners[(i+2)%ncorners]));
+    }
+
+    int count = 0;
+
+    for (int x=max((int)blob.topLeft.coordX()-5,0); x<=min((int)blob.topRight.coordX()+5,edges.width); x++) {
+      for (int y=max((int)blob.topLeft.coordY()-5,0); y<=min((int)blob.bottomRight.coordY()+5,edges.height); y++) {
+	if (edges(x,y)) {
+	  Point p(x,y);
+	  bool onLine = false;
+	  for (int i=0; i<ncorners; i++) {
+	    if (lines[i].pointOnLine(p)) {
+	      onLine = true;
+	      break;
+	    }
+	  }
+	  if (onLine)
+	    count++;
+	}
+      }
+    }
+    
+    return count;
+  }
+
+
+  /*
+   * Probabilistically pick the next move based on the scores
+   * Lower is better for the score
+   */
+  int pickMove(vector<float> scores, float weight) 
+  {
+    unsigned int i;
+    float min = scores[0], max = scores[0];
+    for (i=1; i<scores.size(); i++) {
+      if (scores[i] < min)
+	min = scores[i];
+      else if (scores[i] > max)
+	max = scores[i];
+    }
+    
+    max -= min;
+    for (i=0; i<scores.size(); i++) {
+      scores[i]-=min;
+      if (max > 0) {
+	scores[i]*=weight/max;
+      }
+    }
+
+    vector<float> exps;
+    float expsum = 0;
+    for (i=0; i<scores.size(); i++) {
+      float curexp = exp(-scores[i]);
+      exps.push_back(curexp);
+      expsum+=curexp;
+    }
+
+    for (i=0; i<scores.size(); i++) {
+      exps[i]/=expsum;
+    }    
+
+    float randval = (rand()%1000000)/1000000.0;
+
+    for (i=0; i<scores.size(); i++) {
+      randval -= exps[i];
+      if (randval <= 0)
+	return i;
+    }
+
+    return -1;
+  }
+
+
+} // namespace
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/BrickOps.h ./DualCoding/BrickOps.h
--- ../Tekkotsu_2.4.1/DualCoding/BrickOps.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/BrickOps.h	2006-08-10 23:19:53.000000000 -0400
@@ -0,0 +1,43 @@
+//-*-c++-*-
+#ifndef _BRICK_OPS_H_
+#define _BRICK_OPS_H_
+
+#include "Point.h"
+#include "Sketch.h"
+#include "BlobData.h"
+
+namespace DualCoding {
+
+  /* A collection of functions used in extracting corners from blobs 
+   * and extracting bricks and pyramids from the image. 
+   */
+  
+  
+  Point findEdgePoint(Point start, Point end, Sketch<bool>& rendering);
+  
+  int findRadialDistancesFromPoint(Point center, float radius, 
+				   Sketch<bool>& rendering,
+				   float distances[], Point points[]);
+  
+  void takeDerivative(float x[], float dx[], int len) ;
+  
+  void drawHist(float distances[], unsigned int len, Sketch<bool>& parent) ;
+  
+  void applyGaussian(float x[], float gx[], int len);
+
+  float getBoundingQuadrilateralScore(BlobData &blob, vector<Point>& corners, Sketch<bool> edgeImage, 
+				      int& borderCount, ShapeSpace &space);
+
+  float getBoundingQuadrilateralInteriorPointRatio(BlobData &blob, 
+						   vector<Point>& corners, 
+						   ShapeSpace &space);
+
+  float getQuadrilateralArea(vector<Point>& corners);
+
+  int countBorderPixelFit(BlobData &blob, const vector<Point> &corners, 
+			  Sketch<bool> edges, ShapeSpace &space);
+     
+  int pickMove(vector<float> scores, float weight);
+}
+
+#endif /* _BRICK_OPS_H_ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/DualCoding.h ./DualCoding/DualCoding.h
--- ../Tekkotsu_2.4.1/DualCoding/DualCoding.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/DualCoding.h	2006-07-21 13:57:47.000000000 -0400
@@ -0,0 +1,75 @@
+//-*-c++-*-
+// Master include file list to be used by user behaviors.
+
+#ifndef LOADED_DualCoding_h_
+#define LOADED_DualCoding_h_
+
+//! Dual coding vision representations (Sketches and Shapes)
+namespace DualCoding {}
+
+#include "Measures.h"
+#include "ShapeTypes.h"
+#include "SketchTypes.h"
+
+#include "SketchSpace.h"
+#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 "ViewerConnection.h"
+#include "VisualRoutinesStateNode.h"
+#include "VisualRoutinesBehavior.h" // this must preceed mapbuilders, pilot and lookout
+#include "VRmixin.h"
+
+#include "LookoutRequests.h"
+#include "Lookout.h"
+#include "MapBuilderRequests.h"
+#include "MapBuilder.h"
+#include "Pilot.h"
+
+#include "Particle.h"
+#include "ParticleShapes.h"
+#include "ParticleFilter.h"
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/EllipseData.cc ./DualCoding/EllipseData.cc
--- ../Tekkotsu_2.4.1/DualCoding/EllipseData.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/EllipseData.cc	2006-08-02 17:27:13.000000000 -0400
@@ -0,0 +1,217 @@
+//-*-c++-*-
+#include <iostream>
+#include <vector>
+#include <list>
+#include <math.h>
+
+#include "BaseData.h"    // superclass
+#include "Point.h"       // Point data member
+#include "Measures.h"    // coordinate_t; AngPi data member
+#include "ShapeTypes.h"  // ellipseDataType
+
+#include "SketchSpace.h"
+#include "Sketch.h"
+#include "Region.h"
+#include "visops.h"
+
+#include "ShapeSpace.h"  // required by DATASTUFF_CC
+#include "ShapeRoot.h"   // required by DATASTUFF_CC
+
+#include "EllipseData.h"
+#include "ShapeEllipse.h"
+
+namespace DualCoding {
+
+inline int round(float x) { return (int) ceil((double)x-0.5f); }
+
+EllipseData::EllipseData(ShapeSpace& _space, const Point &c) 
+  : BaseData(_space, getStaticType()),
+    center_pt(c), semimajor(0), semiminor(0), orientation(0)
+{ center_pt.setRefFrameType(getRefFrameType());
+  mobile = ELLIPSE_DATA_MOBILE; }
+  
+DATASTUFF_CC(EllipseData);
+
+BoundingBox EllipseData::getBoundingBox() const {
+  float o_sin = sin(orientation);
+  float o_cos = cos(orientation);
+  Point major_tip(semimajor*o_cos, semimajor*o_sin);
+  Point minor_tip(-semiminor*o_sin, semiminor*o_cos);
+  return BoundingBox(BoundingBox(BoundingBox(center_pt+major_tip),
+				 BoundingBox(center_pt-major_tip)),
+		     BoundingBox(BoundingBox(center_pt+minor_tip),
+				 BoundingBox(center_pt-minor_tip)));
+}
+
+bool EllipseData::isMatchFor(const ShapeRoot& other) const {
+  if (!(isSameTypeAs(other) && isSameColorAs(other)))
+    return false;
+  const Shape<EllipseData>& other_ellipse = ShapeRootTypeConst(other,EllipseData);
+  float dist = center_pt.distanceFrom(other_ellipse->centerPt());
+  return dist < 2*max(semimajor,other_ellipse->semimajor); // *** DST hack
+}
+
+bool EllipseData::updateParams(const ShapeRoot& other, bool) {
+  const Shape<EllipseData>& other_ellipse = ShapeRootTypeConst(other,EllipseData);
+  if (other_ellipse->confidence <= 0)
+    return false;
+  const int other_conf = other_ellipse->confidence;
+  center_pt = (center_pt*confidence + other_ellipse->centerPt()*other_conf) / (confidence+other_conf);
+  semimajor = (semimajor*confidence + other_ellipse->getSemimajor()*other_conf) / (confidence+other_conf);
+  semiminor = (semiminor*confidence + other_ellipse->getSemiminor()*other_conf) / (confidence+other_conf);
+  orientation = orientation*((orientation_t)confidence/(confidence+other_conf))
+    + other_ellipse->getOrientation()*((orientation_t)confidence/(confidence+other_conf));
+  return true;
+}
+
+//! 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;
+}
+
+pair<Point,Point> EllipseData::findFeaturePoints() const {
+  AngPi theta = getOrientation();
+  NEWMAT::ColumnVector from_center(4);
+
+  float dl = getSemimajor();
+  from_center << dl*cos(theta) << dl*sin(theta) << 0 << 0;
+  Point majorPt(from_center);
+  majorPt += center_pt;
+
+  dl = getSemiminor();
+  theta = theta + (AngPi) (M_PI/2);
+  from_center << dl*sin(theta) << dl*cos(theta) << 0 << 0;
+  Point minorPt(from_center);
+  minorPt += center_pt;
+  return pair<Point,Point>(majorPt,minorPt);
+}
+
+//! Transformations. (Virtual in BaseData.)
+void EllipseData::applyTransform(const NEWMAT::Matrix& Tmat) {
+  pair<Point,Point> featurePts = findFeaturePoints();
+  center_pt.applyTransform(Tmat);
+  //  orientation = orientation - (AngTwoPi)atan2(Tmat(1,2),Tmat(1,1));
+  featurePts.first.applyTransform(Tmat);
+  featurePts.second.applyTransform(Tmat);
+  updateProperties(featurePts.first, featurePts.second);
+}
+
+void EllipseData::updateProperties(const Point& majorPt, const Point& minorPt) {
+  setSemiminor(minorPt.xyDistanceFrom(center_pt));
+  setSemimajor(majorPt.xyDistanceFrom(center_pt));
+  setOrientation(atan2(majorPt.coords(2)-center_pt.coords(2),majorPt.coords(1)-center_pt.coords(1)));
+}
+
+void EllipseData::projectToGround(const NEWMAT::Matrix& camToBase,
+				  const NEWMAT::ColumnVector& groundplane) {
+  pair<Point,Point> featurePts = findFeaturePoints();
+  center_pt.projectToGround(camToBase,groundplane);
+  featurePts.first.projectToGround(camToBase,groundplane);  
+  featurePts.second.projectToGround(camToBase,groundplane);
+  updateProperties(featurePts.first, featurePts.second);
+}
+
+//! Functions to set properties.
+//{
+void EllipseData::setOrientation(const AngPi _orientation) {
+  orientation = AngPi(_orientation);
+  deleteRendering();
+}
+
+void EllipseData::setSemimajor(float _semimajor) {
+  semimajor = _semimajor;
+  deleteRendering();
+}
+
+void EllipseData::setSemiminor(float _semiminor) {
+  semiminor = _semiminor;
+  deleteRendering();
+}
+//}
+
+
+// ==================================================
+// BEGIN SKETCH MANIPULATION AND LINE EXTRACTION CODE
+// ==================================================
+
+
+//! Ellipse extraction.
+
+std::vector<Shape<EllipseData> > EllipseData::extractEllipses(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));
+  list<Region> regionlist = Region::extractRegions(labels,REGION_THRESH);
+  std::vector<Shape<EllipseData> > ellipses;
+  
+  if(regionlist.empty())
+    return ellipses;
+  
+  typedef list<Region>::iterator R_IT;
+  for (R_IT it = regionlist.begin(); it != regionlist.end(); ++it) {
+    float ratio = it->findSemiMajorAxisLength()/(float)(it->findSemiMinorAxisLength());
+    if((ratio < 2.0) && (ratio > 1.0/(float)2.0)
+       && (it->findArea() > M_PI*2.0*(it->findSemiMajorAxisLength())
+	   *2.0*(it->findSemiMinorAxisLength())*AREA_TOLERANCE/4.0)) {
+      Shape<EllipseData> temp_ellipse(*it);
+      temp_ellipse->setParentId(sketch->getViewableId());
+      temp_ellipse->setColor(sketch->getColor());
+      ellipses.push_back(Shape<EllipseData>(temp_ellipse));
+    };
+  }
+  return ellipses;
+}
+
+
+//! Render into a sketch space and return reference. (Private.)
+Sketch<bool>* EllipseData::render() const {
+  SketchSpace &SkS = space->getDualSpace();
+  NEWMAT::ColumnVector ctr(centerPt().getCoords());
+  SkS.applyTmat(ctr);
+  const float &cx = ctr(1);
+  const float &cy = ctr(2);
+  const NEWMAT::Matrix &Tmat = SkS.getTmat();
+  NEWMAT::ColumnVector ori(2);
+  ori << cos(orientation) << sin(orientation);
+  NEWMAT::Matrix rot(2,2);
+  rot(1,1) = Tmat(1,1);
+  rot(1,2) = Tmat(1,2);
+  rot(2,1) = Tmat(2,1);
+  rot(2,2) = Tmat(2,2);
+  ori = rot * ori;
+  const float &cosT = ori(1);
+  const float &sinT = ori(2);
+  const float xRange = semimajor / Tmat(4,4);
+  const float majorSq = xRange*xRange;
+  const float mnrDevMjr = semiminor/semimajor;
+  Sketch<bool> result(SkS, "render("+getName()+")");
+  result = 0;
+  for (float xDist = -xRange; xDist <= xRange; xDist+=0.2) {
+    const float yRange = sqrt(max((float)0, majorSq - xDist*xDist)) * mnrDevMjr;
+    for (float yDist = -yRange; yDist <= yRange; yDist+=0.2) {
+      int const px = round(cx+xDist*cosT-yDist*sinT);
+      int const py = round(cy+yDist*cosT+xDist*sinT);
+      if ( px >= 0 && px < result.width &&
+	   py >= 0 && py < result.height )
+	result(px,py) = true;
+    }
+  }
+  return new Sketch<bool>(result);
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/EllipseData.h ./DualCoding/EllipseData.h
--- ../Tekkotsu_2.4.1/DualCoding/EllipseData.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/EllipseData.h	2006-05-09 18:37:55.000000000 -0400
@@ -0,0 +1,105 @@
+//-*-c++-*-
+#ifndef _ELLIPSEDATA_H_
+#define _ELLIPSEDATA_H_
+
+#include <vector>
+#include <iostream>
+
+#include "Shared/newmat/newmat.h"
+
+#include "BaseData.h"    // superclass
+#include "Point.h"       // Point data member
+#include "Measures.h"    // coordinate_t; AngPi data member
+
+namespace DualCoding {
+
+class ShapeRoot;
+class SketchSpace;
+template<typename T> class Sketch;
+
+#define ELLIPSE_DATA_MOBILE false
+
+class EllipseData : public BaseData {
+private:
+  Point center_pt;
+  float semimajor;
+  float semiminor;
+  AngPi orientation;
+
+public:
+
+  //! Constructor
+  EllipseData(ShapeSpace& _space, const Point &c);
+
+  static ShapeType_t getStaticType() { return ellipseDataType; }
+
+  DATASTUFF_H(EllipseData);
+  
+  //! Centroid. (Virtual in BaseData.)
+  Point getCentroid() const { return center_pt; } 
+  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;
+
+  //! updates major/minor axis and orientation from feature points
+  void updateProperties(const Point& minorPt, const Point& majorPt);
+
+  BoundingBox getBoundingBox() const;
+
+  //! Match ellipses based on their parameters.  (Virtual in BaseData.)
+  virtual bool isMatchFor(const ShapeRoot& other) const;
+
+  virtual bool isAdmissible() const {
+    return (semimajor >= 9.0 );  // **DST Hack** minimum size for an ellipse to be added to local map
+  }
+
+  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);
+  
+  //! Project to ground
+  virtual void projectToGround(const NEWMAT::Matrix& camToBase,
+			       const NEWMAT::ColumnVector& groundplane);
+
+  //! Center point access function.
+  const Point& centerPt() const { return center_pt; }
+  
+  virtual unsigned short getDimension() const { return 2; }
+  
+  //! Properties functions.
+  //@{
+  AngPi getOrientation() const { return orientation; }
+  float getSemimajor() const { return semimajor; }
+  float getSemiminor() const { return semiminor; }
+  //@}
+  
+  
+  //! Set properties.
+  //@{
+  void setOrientation(const AngPi _orientation);
+  void setSemimajor(float _semimajor);
+  void setSemiminor(float _semiminor);
+  //@}
+
+  //! Extraction.
+  static std::vector<Shape<EllipseData> > extractEllipses(const Sketch<bool>& sketch);
+  
+  
+private:
+  //! Render into a sketch space and return reference. (Private.)
+  virtual Sketch<bool>* render() const;
+  //@}
+
+  EllipseData& operator=(const EllipseData&); //!< don't call
+
+};
+
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/EndPoint.cc ./DualCoding/EndPoint.cc
--- ../Tekkotsu_2.4.1/DualCoding/EndPoint.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/EndPoint.cc	2006-02-12 00:32:01.000000000 -0500
@@ -0,0 +1,28 @@
+#include "EndPoint.h"
+
+namespace DualCoding {
+
+void EndPoint::checkValidity(int width, int height, int edge_thresh) {
+  const bool v = ( coordX() > edge_thresh &&
+		   coordX() < (width-1-edge_thresh) &&
+		   coordY() > edge_thresh &&
+		   coordY() < (height-1-edge_thresh) );
+  setValid(v);
+}
+
+void EndPoint::updateParams(const EndPoint& other){
+  ++nsamples;
+  //  cout << "conf (this,other): " << nsamples << " " << other.nsamples << endl;
+  //  cout << "old coords: " << coordX() << " " << coordY() << endl;
+  //  cout << "other coords: " << other.coordX() << " " << other.coordY() << endl;
+  coords = (coords*nsamples + other.coords*other.nsamples)/(nsamples+other.nsamples);
+  rendering_valid = false;
+  //  cout << "new coords: " << coordX() << " " << coordY() << endl;
+}
+
+void EndPoint::updateParams(const EndPoint& other, unsigned int num_updates){
+  nsamples += num_updates-1;
+  updateParams(other);
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/EndPoint.h ./DualCoding/EndPoint.h
--- ../Tekkotsu_2.4.1/DualCoding/EndPoint.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/EndPoint.h	2006-02-12 00:32:01.000000000 -0500
@@ -0,0 +1,72 @@
+//-*-c++-*-
+#ifndef _ENDPOINT_H_
+#define _ENDPOINT_H_
+
+#include "Measures.h"
+#include "Point.h"
+
+namespace DualCoding {
+
+class EndPoint : public Point {
+private: 
+  //! @a valid indicates whether or not this is known to be the final end-point of the line.
+  /*! If false, this was the point at which the line went off-camera, not the true end point. */
+  bool valid;
+
+  //! @a active indicates whether or not the line is to terminate at this point.  
+  /*! If false, the line will continue infinitely as a ray beyond this point. */
+  bool active;
+
+  //! @a rendering_valid is set when the line is rendered and cleared if an endpoint is modified
+  bool rendering_valid;
+
+  //! How many measurements have gone into the estimate of this point.
+  int nsamples;
+	
+public:
+  friend class LineData;
+  friend class BoundaryDetector;
+  friend class PolygonData;
+	
+  EndPoint()
+    : Point(), valid(true), active(true), rendering_valid(false), nsamples(1) {};
+
+  EndPoint(coordinate_t const &xp, coordinate_t const &yp) 
+    : Point(xp,yp), valid(true), active(true), rendering_valid(false), nsamples(1) {};
+
+  EndPoint(const Point& otherPt)
+    : Point(otherPt), valid(true), active(true), rendering_valid(false), nsamples(1) {};
+
+  bool isValid() const { return valid; }
+  void setValid(bool _valid) { valid = _valid; }
+
+  bool isActive() const { return active; }
+  void setActive(bool _active) { 
+    if ( active != _active ) rendering_valid = false;
+    active = _active;
+  }
+
+  bool isMatchFor(const EndPoint& other, float dist_thresh) const {return distanceFrom(other) <= dist_thresh; }
+  bool operator==(const EndPoint& other) const { return isMatchFor(other,5); }
+
+
+  //! Checks if endpoint comes to close to edge of camera frame and if so,
+  //! marks it as invalid.
+  void checkValidity(int width, int height, int edge_thresh);
+
+  void updateParams(const EndPoint& other);
+  void updateParams(const EndPoint& other, unsigned int num_updates);
+
+private:
+  void clearNumUpdates(void) { nsamples=0; };
+  void setNumUpdates(long _nsamples) { nsamples = _nsamples; };
+
+public:
+  void incrementNumUpdates(void) { nsamples++; };
+  void decrementNumUpdates(void) { nsamples--; };
+  int numUpdates(void) const { return nsamples; };
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/LineData.cc ./DualCoding/LineData.cc
--- ../Tekkotsu_2.4.1/DualCoding/LineData.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/LineData.cc	2006-10-03 19:24:05.000000000 -0400
@@ -0,0 +1,1494 @@
+//-*-c++-*-
+#include <iostream>
+#include <math.h>
+#include <vector>
+#include <list>
+
+#include "Macrodefs.h"
+
+#include "SketchSpace.h"
+#include "Sketch.h"
+#include "Region.h"
+#include "visops.h"
+
+#include "ShapeSpace.h"
+#include "ShapeRoot.h"
+
+#include "PointData.h"
+#include "LineData.h"
+#include "ShapeLine.h"
+
+namespace DualCoding {
+
+DATASTUFF_CC(LineData);
+
+const Point LineData::origin_pt = Point(0,0);
+
+LineData::LineData(ShapeSpace& _space, const Point &p1, orientation_t orient)
+  : BaseData(_space,getStaticType()), end1_pt(p1), end2_pt(), 
+    rho_norm(0), theta_norm(0), orientation(0), length(0) {
+  int const width = space->getDualSpace().getWidth();
+  int const height = space->getDualSpace().getHeight();
+  // Use a large offset from p1 to p2 because SketchGUI must calculate
+  // the line slope from p1/p2 coords transmitted as strings; we don't
+  // transmit the orientation.  But don't use an offset so large that the line
+  // goes off-screen.
+  float p2x=0, p2y=0;
+  if ( fabs(orient-M_PI/2) < 0.001 ) {
+    p2x = p1.coordX();
+    p2y = p1.coordY() > height/2 ? 0 : height-1;
+  } else {
+    float slope = tan(orient);
+    float intcpt = p1.coordY() - p1.coordX()*slope;
+    p2x = p1.coordX() >= width/2 ? 0.0 : width-1;
+    p2y = p2x * slope + intcpt;
+    if ( p2y > height-1 ) {
+      p2x = (height - intcpt) / slope;
+      p2y = height;
+    } else if ( p2y < 0 ) {
+      p2x = -intcpt / slope;
+      p2y = 0;
+    }
+  }
+  end2_pt = Point(p2x,p2y);
+  end1_pt.setValid(false);
+  end1_pt.setActive(false);
+  end2_pt.setValid(false);
+  end2_pt.setActive(false);
+  update_derived_properties();
+}
+
+Point LineData::getCentroid() const { return (end1Pt()+end2Pt())*0.5; }
+
+void LineData::setInfinite(bool value) {
+  end1_pt.setActive(!value);
+  end2_pt.setActive(!value);
+}
+
+#define NORMPOINT_MATCH_DISTSQ 3500
+#define LINE_MATCH_OVERLAP -10
+#define LINE_ORIENTATION_MATCH M_PI/6
+
+bool LineData::isMatchFor(const ShapeRoot& other) const {
+  if (!(isSameTypeAs(other) && isSameColorAs(other)))
+    return false;
+  else {
+    const Shape<LineData>& other_ln = ShapeRootTypeConst(other,LineData);
+    return isMatchFor(other_ln.getData());
+  }
+}
+
+bool LineData::isMatchFor(const LineData& other_line) const {
+  float const px = rho_norm*cos(theta_norm), 
+    py = rho_norm*sin(theta_norm);
+  float const qx = other_line.rho_norm*cos(other_line.theta_norm),
+    qy = other_line.rho_norm*sin(other_line.theta_norm);
+  AngPi theta_diff = float(theta_norm) - float(other_line.theta_norm);
+  if ( theta_diff > M_PI/2 )
+    theta_diff = M_PI - theta_diff;
+  float normpointdistsq = (px-qx)*(px-qx) + (py-qy)*(py-qy);
+  // cout << "px=" << px << "  py=" << py << "  qx=" << qx << "  qy=" << qy << "  normpointdistsq=" << normpointdistsq 
+  //  << "  theta_diff=" << theta_diff
+  //   << "  perpdist=" << perpendicularDistanceFrom(other_line.getCentroid())
+  //   << "  isoverlapped=" << isOverlappedWith(other_line,LINE_MATCH_OVERLAP) << endl;
+  return normpointdistsq < NORMPOINT_MATCH_DISTSQ  // *** DST hack
+    && theta_diff < LINE_ORIENTATION_MATCH
+    && perpendicularDistanceFrom(other_line.getCentroid()) < 100
+    && isOverlappedWith(other_line,LINE_MATCH_OVERLAP);
+}
+
+  bool LineData::isOverlappedWith(const LineData& otherline, int amount) const {
+  if ( firstPtCoord() <= otherline.firstPtCoord() )
+    return secondPtCoord()-amount >= otherline.firstPtCoord();
+  else
+    return firstPtCoord()+amount <= otherline.secondPtCoord();
+}
+
+
+void LineData::mergeWith(const ShapeRoot& other) {
+  const Shape<LineData>& other_line = ShapeRootTypeConst(other,LineData);
+  if (other_line->confidence <= 0)
+    return;
+  const int other_conf = other_line->confidence;
+  confidence += other_conf;
+  end1_pt = (end1_pt*confidence + other_line->end1Pt()*other_conf) / (confidence+other_conf);
+  end2_pt = (end2_pt*confidence + other_line->end2Pt()*other_conf) / (confidence+other_conf);
+  update_derived_properties();
+}
+
+
+bool LineData::isValidUpdate(coordinate_t c1_cur, coordinate_t c2_cur, coordinate_t c1_new, coordinate_t c2_new) {
+  const float c1_noise = 10.0 + fabs(c1_cur+c1_new) / 20.0; // allow larger error for shapes far from the robot
+  const float c2_noise = 10.0 + fabs(c2_cur+c2_new) / 20.0;
+  return (c1_new-c1_noise < c1_cur && c2_cur < c2_new+c2_noise);
+}
+
+
+//! Update a line in the local map with info from a matching line in the ground space.
+bool LineData::updateParams(const ShapeRoot& ground_root, bool force) {
+  const Shape<LineData>& ground_line = ShapeRootTypeConst(ground_root,LineData);
+  //  cout << "updating local Line " << getId() << " with data from ground line " << ground_line->getId() << ":" << endl;
+  //  ground_line->printEnds();
+  //  cout << "Update from " << endl;
+  //  printEnds();
+  
+  const coordinate_t c1_cur = firstPtCoord();
+  const coordinate_t c2_cur = secondPtCoord();
+
+  Point _end1_pt = firstPt();
+  Point _end2_pt = secondPt();
+  
+  updateLinePt(firstPt(), firstPtCoord(), firstPt(ground_line), firstPtCoord(ground_line), -1);
+  updateLinePt(secondPt(), secondPtCoord(), secondPt(ground_line), secondPtCoord(ground_line), +1);
+  //  cout << "to" << endl;
+  //  printEnds();
+  
+  const coordinate_t c1_new = firstPtCoord();
+  const coordinate_t c2_new = secondPtCoord();
+  
+  if (isValidUpdate(c1_cur, c2_cur, c1_new, c2_new) || force){
+    //    cout << "was accepted, line updated" << endl;
+    //    ++nsamples;
+    update_derived_properties();
+    return true;
+  }
+  
+  //  cout << "was denied, line not updated" << endl;
+  setEndPts(_end1_pt, _end2_pt);
+  return false;
+}
+
+void LineData::updateLinePt(EndPoint& localPt, coordinate_t local_coord,
+			    const EndPoint& groundPt, coordinate_t ground_coord,
+			    int sign) {
+  if ( groundPt.isValid() ) {
+    if ( localPt.isValid() )
+      localPt.updateParams(groundPt);
+    else
+      localPt = groundPt;
+  }
+  else if ( (ground_coord - local_coord)*sign > 0 )
+    localPt = groundPt;
+}
+
+bool LineData::isAdmissible() const {
+  if (end1Pt().isValid() && end2Pt().isValid())
+    return length >= 70.0;  // *** DST hack: lines should be at least 70 mm long
+  else
+    return length >= 40.0;
+}
+
+//! 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 << "end2{" << end2Pt().coordX() << ", " << end2Pt().coordY() <<  "}";
+  cout << " active=" << end2Pt().isActive();
+  cout << " valid=" << end2Pt().isValid() << std::endl;
+  
+  cout << "rho_norm=" << rho_norm  << "  theta_norm=" << theta_norm;
+  cout << "  orientation=" << getOrientation() 
+       << "  length=" << getLength() << endl;
+  
+  printf("color = %d %d %d\n",getColor().red,getColor().green,getColor().blue);
+  
+  cout << "  mobile=" << isMobile() << endl;
+  cout << "  viewable=" << isViewable() << endl;
+  
+  vector<float> abc = lineEquation_abc();
+  printf("equ = %f %f %f\n",abc[0],abc[1],abc[2]);
+}
+
+void LineData::printEnds() const {
+  cout << "  end1{" << end1Pt().coordX() << ", " << end1Pt().coordY()  << "}";
+  cout << "  active=" << end1Pt().isActive() << ", valid=" << end1Pt().isValid() << endl;
+  cout << "  end2{" << end2Pt().coordX() << ", " << end2Pt().coordY() <<  "}";
+  cout << "  active=" << end2Pt().isActive() << ", valid=" << end2Pt().isValid() << endl;
+  // cout << endl;
+}
+
+
+
+//! Transformations.
+//@{
+//! Apply a transformation to this shape.
+void LineData::applyTransform(const NEWMAT::Matrix& Tmat) {
+  end1Pt().applyTransform(Tmat);
+  end2Pt().applyTransform(Tmat);
+  update_derived_properties();
+}
+
+void LineData::projectToGround(const NEWMAT::Matrix& camToBase,
+			       const NEWMAT::ColumnVector& groundplane) {
+  end1Pt().projectToGround(camToBase,groundplane);
+  end2Pt().projectToGround(camToBase,groundplane);
+  update_derived_properties();
+}
+
+//! Logical endpoints
+//@{
+
+EndPoint& LineData::leftPt() { return end1Pt().isLeftOf(end2Pt()) ? end1_pt : end2_pt; }
+EndPoint& LineData::rightPt() { return end1Pt().isLeftOf(end2Pt()) ? end2_pt : end1_pt; }
+EndPoint& LineData::topPt() { return end1Pt().isAbove(end2Pt()) ? end1_pt : end2_pt; }
+EndPoint& LineData::bottomPt() { return end1Pt().isAbove(end2Pt()) ? end2_pt : end1_pt; }
+
+Shape<PointData> LineData::leftPtShape() {
+  Shape<PointData> result(new PointData(*space, leftPt()));
+  result->setName("leftPt");
+  result->inheritFrom(*this);
+  result->setViewable(false);
+  return result;
+}
+
+Shape<PointData> LineData::rightPtShape() {
+  Shape<PointData> result(new PointData(*space, leftPt()));
+  result->setName("rightPt");
+  result->inheritFrom(*this);
+  result->setViewable(false);
+  return result;
+}
+
+Shape<PointData> LineData::topPtShape() {
+  Shape<PointData> result(new PointData(*space, leftPt()));
+  result->setName("topPt");
+  result->inheritFrom(*this);
+  result->setViewable(false);
+  return result;
+}
+
+Shape<PointData> LineData::bottomPtShape() {
+  Shape<PointData> result(new PointData(*space, leftPt()));
+  result->setName("bottomPt");
+  result->inheritFrom(*this);
+  result->setViewable(false);
+  return result;
+}
+
+EndPoint& LineData::firstPt() {
+  if ( isNotVertical() )
+    if ( end1Pt().coordX() < end2Pt().coordX() )
+      return end1Pt();
+    else return end2Pt();
+  else
+    if ( end1Pt().coordY() < end2Pt().coordY() )
+      return end1Pt();
+    else return end2Pt();
+}
+    
+EndPoint& LineData::firstPt(const Shape<LineData> &otherline) const {
+  if ( isNotVertical() )
+    if ( otherline->end1Pt().coordX() < otherline->end2Pt().coordX() )
+      return otherline->end1Pt();
+    else return otherline->end2Pt();
+  else
+    if ( otherline->end1Pt().coordY() < otherline->end2Pt().coordY() )
+      return otherline->end1Pt();
+    else return otherline->end2Pt();
+}
+    
+EndPoint& LineData::secondPt() {
+  if ( isNotVertical() )
+    if ( end1Pt().coordX() > end2Pt().coordX() )
+      return end1Pt();
+    else return end2Pt();
+  else
+    if ( end1Pt().coordY() > end2Pt().coordY() )
+      return end1Pt();
+    else return end2Pt();
+}
+    
+EndPoint& LineData::secondPt(const Shape<LineData> &otherline) const {
+  if ( isNotVertical() )
+    if ( otherline->end1Pt().coordX() > otherline->end2Pt().coordX() )
+      return otherline->end1Pt();
+    else return otherline->end2Pt();
+  else
+    if ( otherline->end1Pt().coordY() > otherline->end2Pt().coordY() )
+      return otherline->end1Pt();
+    else return otherline->end2Pt();
+}
+    
+coordinate_t LineData::firstPtCoord() const {
+  return  isNotVertical() ?
+    const_cast<LineData*>(this)->firstPt().coordX() :
+    const_cast<LineData*>(this)->firstPt().coordY();
+}
+
+coordinate_t LineData::firstPtCoord(const Shape<LineData> &otherline) const {
+  return  isNotVertical() ?
+    firstPt(otherline).coordX() :
+    firstPt(otherline).coordY();
+}
+
+coordinate_t LineData::secondPtCoord() const {
+  return  isNotVertical() ?
+    const_cast<LineData*>(this)->secondPt().coordX() :
+    const_cast<LineData*>(this)->secondPt().coordY();
+}
+
+coordinate_t LineData::secondPtCoord(const Shape<LineData> &otherline) const {
+  return  isNotVertical() ?
+    secondPt(otherline).coordX() :
+    secondPt(otherline).coordY();
+}
+
+//@}
+
+//! Functions to set endpoints.
+
+void LineData::setEndPts(const EndPoint& _end1_pt, const EndPoint& _end2_pt) {
+  end1_pt.setCoords(_end1_pt);
+  end1_pt.setActive(_end1_pt.isActive());
+  end1_pt.setValid(_end1_pt.isValid());
+  end1_pt.setNumUpdates(_end1_pt.numUpdates());
+
+  end2_pt.setCoords(_end2_pt);
+  end2_pt.setActive(_end2_pt.isActive());
+  end2_pt.setValid(_end2_pt.isValid());
+  end2_pt.setNumUpdates(_end2_pt.numUpdates());
+
+  update_derived_properties();
+}
+
+
+//! Properties functions.
+//@{
+
+std::pair<float,float> LineData::lineEquation_mb() const {
+  float m;
+  if ((fabs(end2Pt().coordX() - end1Pt().coordX()) * BIG_SLOPE)
+      <= fabs(end2Pt().coordY() - end2Pt().coordY()))
+    m = BIG_SLOPE;
+  else 
+    m = (end2Pt().coordY() - end1Pt().coordY())/(end2Pt().coordX() - end1Pt().coordX());
+  float b = end1Pt().coordY() - m * end1Pt().coordX();
+  return pair<float,float>(m,b);
+}
+
+
+//! Determine parameters a, b, c, d satisfying the equation ax + bz = c.
+std::vector<float> LineData::lineEquation_abc_xz() const {
+  float dx = end2Pt().coordX() - end1Pt().coordX();
+  float dz = end2Pt().coordZ() - end1Pt().coordZ();
+
+  std::vector<float> abc;
+  abc.resize(3, 1.0);
+  float& a = abc[0];
+  float& b = abc[1];
+  float& c = abc[2];
+
+  // If vertical...b = 0
+  if((dx == 0.0)
+     || (dz/dx > BIG_SLOPE)) {
+    a = 1.0;
+    b = 0.0;
+    c = end1Pt().coordX();
+  }
+  
+  // If horizontal...a = 0
+  else if((dz == 0.0)
+	  || (dx/dz > BIG_SLOPE)) {
+    a = 0.0;
+    b = 1.0;
+    c = end1Pt().coordZ();
+  }
+  
+  // If not horizontal or vertical...a = 1.0
+  else {
+    a = 1.0;
+    b = (end1Pt().coordX() - end2Pt().coordX()) 
+      / (end2Pt().coordZ() - end1Pt().coordZ());
+    c = end1Pt().coordX() + b*end1Pt().coordZ();
+  }
+  
+  return(abc);
+
+}
+//@}
+
+  //! 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();
+  
+  std::vector<float> abc;
+  abc.resize(3, 1.0);
+  float& a = abc[0];
+  float& b = abc[1];
+  float& c = abc[2];
+
+  // If vertical...b = 0
+  if( fabs(dx) < 1.0e-6 || dy/dx > BIG_SLOPE) {
+    a = 1.0;
+    b = 0.0;
+    c = end1Pt().coordX();
+  }
+  
+  // If horizontal...a = 0
+ else if ( fabs(dy) < 1.0e-6 || dx/dy > BIG_SLOPE ) {
+    a = 0.0;
+    b = 1.0;
+    c = end1Pt().coordY();
+  }
+  
+  // If not horizontal or vertical...a = 1.0
+  else {
+    a = 1.0;
+    //    b = (end1Pt().coordX() - end2Pt().coordX()) 
+    // / (end2Pt().coordY() - end1Pt().coordY());
+    b = -dx / dy;
+    c = end1Pt().coordX() + b*end1Pt().coordY();
+  }
+  
+  return(abc);
+}
+//@}
+
+
+//! Functions to set values dealing with orientation.
+//@{
+void LineData::update_derived_properties() {
+  rho_norm = perpendicularDistanceFrom(origin_pt);
+  const vector<float> abc = lineEquation_abc();
+  const float& a1 = abc[0];
+  const float& b1 = abc[1];
+  const float& c1 = abc[2];
+  const float c1sign = (c1 >= 0) ? 1.0 : -1.0;
+  theta_norm = atan2(b1*c1sign, a1*c1sign);
+  orientation = theta_norm + AngPi(M_PI/2);
+  length = end1Pt().distanceFrom(end2Pt());
+  const ReferenceFrameType_t ref = getRefFrameType();
+  end1_pt.setRefFrameType(ref);
+  end2_pt.setRefFrameType(ref);
+  deleteRendering();
+}
+
+bool LineData::isNotVertical() const {
+  const AngPi threshold = M_PI / 3;
+  const AngPi orient = getOrientation();
+  return (orient <= threshold) || (orient >= M_PI - threshold);
+}
+
+/*
+bool LineData::isRoughlyPerpendicularTo(Shape<LineData>& other) {
+  AngPi threshold = M_PI_4;
+  AngPi orientation_diff = getOrientation() - other->getOrientation();
+  if((orientation_diff >= threshold) && (orientation_diff < (M_PI-threshold)))
+    return true;
+  else
+    return false;
+}
+
+bool LineData::isExactlyPerpendicularTo(Shape<LineData>& other) {
+  AngPi orientation_diff = getOrientation() - other->getOrientation();
+  return (orientation_diff == M_PI_2);
+}
+
+*/
+
+
+//! These functions are true based on line length.
+//@{
+bool LineData::isLongerThan(const Shape<LineData>& other) const {
+  return length > other->length; }
+
+bool LineData::isLongerThan(float ref_length) const {
+  return length > ref_length; }
+
+bool LineData::isShorterThan(const Shape<LineData>& other) const {
+  return length < other->length; }
+
+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
+    float dl = perpendicularDistanceFrom(other.end1Pt()); // distance between the lines
+    return (perpendicularDistanceFrom(p) <= dl && other.perpendicularDistanceFrom(p) <= dl);
+  }
+  else {
+    bool b;
+    const LineData p_line (*space,  p,  // line from intersection of this and other to p
+			   intersectionWithLine(other, b, b));
+    const AngPi theta_pline = p_line.getOrientation();
+    const AngPi theta_greater = 
+      (getOrientation() > other.getOrientation()) ? getOrientation() : other.getOrientation();
+    const AngPi theta_smaller = 
+      (getOrientation() < other.getOrientation()) ? getOrientation() : other.getOrientation();
+    if (theta_greater - theta_smaller > M_PI/2)
+      return (theta_pline >= theta_greater || theta_pline <= theta_smaller);
+    else
+      return (theta_pline <= theta_greater && theta_pline >= theta_smaller);
+  }
+}
+
+//! Check intersection.
+//{
+bool
+LineData::intersectsLine(const Shape<LineData>& other) const {
+  return intersectsLine(other.getData());
+}
+
+bool
+LineData::intersectsLine(const LineData& other) const {
+  // Calculate F(x,y) = 0 for this line (x1,y1) to (x2,y2).
+  pair<float,float> F = lineEquation_mb();
+  
+  // Calculate G(x,y) = 0 for L (x3,y3) to (x4,y4).
+  pair<float,float> G = other.lineEquation_mb();
+  
+  // NOTE: These tests are assumed to be taking place in the space of
+  // "this" line.  Therefore, the limits of line extent (for lines
+  // with inactive endpoints) are calculated in the space of "this"
+  // line.
+  
+  // JJW *** YOU NEED TO TAKE ACCOUNT OF END POINTS BEING TURNED OFF.
+  
+  // 	float end1x, end1y, end2x, end2y, other_end1x, other_end1y, other_end2x, other_end2y;
+  // 	if(end1Pt().isActive()) {
+  // 		end1x = end1Pt().coordX();
+  // 		end1y = end1Pt().coordY();
+  // 	} else {
+  // 		end1x = 
+  
+  
+  // TEST 1
+  
+  // Calculate r3 = F(x3,y3)
+  float r3 = F.first * other.end1Pt().coordX() + F.second - other.end1Pt().coordY();
+  
+  // Calculate r4 = F(x4,y4)
+  float r4 = F.first * other.end2Pt().coordX() + F.second - other.end2Pt().coordY();
+  
+  // If r3 != 0...
+  // ...AND r4 != 0...
+  // ...AND SGN(r3) == SGN(r4)...
+  // ...THEN the lines do not intersect.
+  
+  if((r3 != 0)
+     && (r4 != 0)
+     && (SGN(r3) == SGN(r4))
+     )
+    return false;
+  
+  
+  // TEST 2
+  
+  // Calculate r1 = G(x1,y1)
+  float r1 = G.first * end1Pt().coordX() + G.second - end1Pt().coordY();
+  
+  // Calculate r2 = G(x2,y2)
+  float r2 = G.first * end2Pt().coordX() + G.second - end2Pt().coordY(); 
+  
+  // If r1 != 0...
+  // ...AND r2 != 0...
+  // ...AND SGN(r1) == SGN(r2)...
+  // ...THEN the lines do not intersect.
+  
+  if((r1 != 0)
+     && (r2 != 0)
+     && (SGN(r1) == SGN(r2))
+     )
+    return false;
+  
+  // Otherwise, the lines DO intersect.
+  return true;
+}
+
+
+Point LineData::intersectionWithLine(const Shape<LineData>& other,
+				     bool& intersection_on_this,
+				     bool& intersection_on_other) const { 
+  return intersectionWithLine(other.getData(), intersection_on_this,intersection_on_other); 
+}
+
+Point
+LineData::intersectionWithLine(const LineData& other, 
+			       bool& intersection_on_this, bool& intersection_on_other) const {
+
+  // Based upon algorithm written by Paul Bourke, April 1989.
+  // http://astronomy.swin.edu/~pbourke/geometry/lineline2d/  
+  // Accessed July 20th 2004
+  
+  // Points 1 and 2 are on "this" line. Points 3 and 4 define the "other" line.
+  //  float x1, x2, x3, x4, y1, y2, y3, y4;
+  float x1, x2, x3, x4, y1, y2, y3, y4;
+  x1 = end1Pt().coordX();
+  x2 = end2Pt().coordX();
+  x3 = other.end1Pt().coordX();
+  x4 = other.end2Pt().coordX();
+  // x3 = other->end1Pt().coordX();
+  // x4 = other->end2Pt().coordX();
+  y1 = end1Pt().coordY();
+  y2 = end2Pt().coordY();
+  y3 = other.end1Pt().coordY();
+  y4 = other.end2Pt().coordY();
+  // y3 = other->end1Pt().coordY();
+  // y4 = other->end2Pt().coordY();
+  
+  // x1 + u_a(x2-x1) = x3 + u_b(x4-x3)
+  // y1 + u_a(y2-y1) = y3 + u_b(y4-y3)
+  
+  // u_a = (x4-x3)(y1-y3) - (y4-y3)(x1-x3)
+  //       -------------------------------
+  //       (y4-y3)(x2-x1) - (x4-x3)(y2-y1)
+  
+  // u_b = (x2-x1)(y1-y3) - (y2-y1)(x1-x3)
+  //       -------------------------------
+  //       (y4-y3)(x2-x1) - (x4-x3)(y2-y1)
+  
+  float denom = ((y4-y3)*(x2-x1) - (x4-x3)*(y2-y1));
+  float u_a_numerator = ((x4-x3)*(y1-y3) - (y4-y3)*(x1-x3));
+  float u_b_numerator = ((x2-x1)*(y1-y3) - (y2-y1)*(x1-x3));
+  
+  // If denominators of u_a and u_b are zero, then lines are parallel.
+  if(denom == 0.0) {
+    if (u_a_numerator == 0.0 && u_b_numerator == 0.0) {
+      PRINTF("intersectionWithLine: lines are coincident!\n");
+      return(end1Pt());
+    }
+    else {
+      cout << x1 << " " << x2 << " " << x3 << " " << x4 << " "
+	   << y1 << " " << y2 << " " << y3 << " " << y4 << endl;
+      cout << "this theta; " << getOrientation() << ", other theta: " << other.getOrientation() << endl;
+      PRINTF("ERROR in intersectionWithLine: lines are parallel!\n");
+      return(Point(-9999.0,-99999.0));
+    }
+  }
+  
+  else {
+    float u_a = u_a_numerator / denom;
+    float u_b = u_b_numerator / denom;
+    
+    // If 0 <= u_a <=1  then intersection point is on segment a.
+    if(0.0 <= u_a <=1.0)
+      intersection_on_this = true;
+    else
+      intersection_on_this = false;
+    
+    // If 0 <= u_b <=1  then intersection point is on segment b.
+    if(0.0 <= u_b <=1.0)
+      intersection_on_other = true;
+    else
+      intersection_on_other = false;
+    
+    return(Point((x1+u_a*(x2-x1)),
+		 (y1+u_a*(y2-y1))));
+  }
+}
+
+//! Distance.
+//{
+
+float LineData::perpendicularDistanceFrom(const Point& otherPt) const {
+  // NOTE that this formula is rather slow, as it involves the
+  // calculation of the line equation in addition to a square root here.
+  
+  // Using the formula from http://www.tpub.com/math2/8.htm
+  vector<float> abc = lineEquation_abc();
+  float& a = abc[0];
+  float& b = abc[1];
+  float& c = abc[2];
+  
+  // Distance...
+  //    (x*A + y*B - C  )
+  // abs(-------------  )
+  //    (sqrt(a^2 + b^2)) 
+  float d = fabs((a * otherPt.coordX() + b * otherPt.coordY() - c)/sqrt(a*a + b*b));
+  //  cout << "abcd: " << a << ", " << b << ", " << c << ", " << d << endl;
+  return(d);
+}
+
+//}
+
+
+// ==================================================
+// BEGIN LINE EXTRACTION CODE
+// ==================================================
+
+//!@name Line Extraction.
+//@{
+
+
+#define BEG_DIST_THRESH 2
+#define END_DIST_THRESH 2
+
+Shape<LineData> LineData::extractLine(Sketch<bool>& sketch) {
+  NEW_SKETCH_N(fatmask,bool,visops::fillin(sketch,1,2,8));
+  NEW_SKETCH_N(skel,bool,visops::skel(fatmask));
+  return extractLine(skel, sketch);
+}
+
+Shape<LineData> LineData::extractLine(Sketch<bool>& skeleton, 
+				      const Sketch<bool>& occlusions) {
+  const int width = skeleton->getWidth(), height = skeleton->getHeight();
+  SketchSpace &SkS = skeleton->getSpace();
+  ShapeSpace &ShS = SkS.getDualSpace();
+
+  // approximate largest skel region with line
+  NEW_SKETCH_N(labels,usint,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
+    return ShapeRootType(invalid,LineData);
+  }
+  Region skelchunk = regions.front();  // regions not empty, so use the largest....
+  AngPi orientation(skelchunk.findPrincipalAxisOrientation());
+  Point centroid(skelchunk.findCentroid());
+  // cout << " orientation=" << orientation << "  centroid=" << centroid.getCoords() << endl;
+  if (! skelchunk.isContained(centroid, 3) ) {   //  region does not look like a straight line
+    Shape<LineData> result(splitLine(ShS, skelchunk, skeleton, occlusions));
+    if ( result.isValid() )
+      return result;
+  }
+  
+  // Create a symbolic line object.
+  Shape<LineData> extracted_line(ShS, centroid, orientation);
+  extracted_line->setColor(skeleton->getColor());
+  extracted_line->setParentId(skeleton->getViewableId());
+
+  // rho and theta describe the normal line.
+  // normpoint is where the normal line intersects with this line.
+  // normpoint may actually be off-image.
+  float x_normpoint = extracted_line->rho_norm*cos(extracted_line->theta_norm);
+  float y_normpoint = extracted_line->rho_norm*sin(extracted_line->theta_norm);
+  
+  // m is slope of this line (not the normal line)
+  // float m = (y_normpoint != 0) ? -(x_normpoint/y_normpoint) : BIG_SLOPE;
+  float m = max(min(tan(extracted_line->theta_norm+AngPi(M_PI/2)), (float)BIG_SLOPE), (float)(-BIG_SLOPE));
+  float b = y_normpoint - m*x_normpoint;
+  // cout << "  x_normpoint=" << x_normpoint << "  y_normpoint=" << y_normpoint
+  // << "  m=" << m << "  b=" << b <<std::endl;
+  
+  NEW_SKETCH_N(skelDist,usint,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
+    extracted_line->scanVertForEndPts(skelDist,occlusions,m,b);
+
+  // Check to see if any endpoints are near any edge of the screen.
+  // If they are, invalidate them, assuming that line continues beyond screen.
+  extracted_line->end1_pt.checkValidity(width,height,BEG_DIST_THRESH);
+  extracted_line->end2_pt.checkValidity(width,height,BEG_DIST_THRESH);
+
+  // Transform from SketchSpace coordinates to ShapeSpace coordinates
+  SkS.applyTmatinv(extracted_line->end1_pt.getCoords());
+  SkS.applyTmatinv(extracted_line->end2_pt.getCoords());
+  extracted_line->update_derived_properties();
+  return extracted_line;
+}
+
+
+  // hack to split a non-straight region by kei
+Shape<LineData> LineData::splitLine(ShapeSpace &ShS, Region &skelchunk, 
+			  Sketch<bool> &skeleton, const Sketch<bool> &occlusions) {
+  //  cout << "this region is not straight, needs be split into two regions" << endl;
+  Point bounds[4] = {skelchunk.findTopBoundPoint(), skelchunk.findLeftBoundPoint(),
+		     skelchunk.findRightBoundPoint(), skelchunk.findBotBoundPoint()};
+  //  cout << "top(0): " << bounds[0] << endl;
+  //  cout << "left(1): " << bounds[1] << endl;
+  //  cout << "right(2): " << bounds[2] << endl;
+  //  cout << "bottom(3): " << bounds[3] << endl;
+  for (int i = 0; i < 4; i++) {
+    for (int j = i+1; j < 4; j++) {
+      if (bounds[i].distanceFrom(bounds[j]) > 20 && ! skelchunk.isContained((bounds[i]+bounds[j])/2.0, 3)) {
+	//	cout << "[" << i << "," << j << "] form a line from which most distant point is where the region should split " << endl;
+	LineData ln(ShS,bounds[i],bounds[j]);
+	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;
+	NEW_SKETCH_N(not_too_close, bool, visops::edist(point_rendering) >= clear_dist);
+	skeleton &= not_too_close;
+	return extractLine(skeleton, occlusions);
+      }
+    }
+  }
+  ShapeRoot invalid; // need to define a named variable to avoid warning on next line
+  return ShapeRootType(invalid,LineData);
+}
+
+void LineData::scanHorizForEndPts(const Sketch<usint>& skelDist, 
+				  const Sketch<bool>& occlusions, 
+				  float m, float b) {
+  // Scan along the infinite line, looking for segments in the image.
+  bool on_line = false;			   // true if tracing a line skeleton
+  int beg_dist_thresh = BEG_DIST_THRESH;   // skel has to be <= this close to start segment
+  int end_dist_thresh = END_DIST_THRESH;   // how far line should extend from skel
+  int curxstart = -1;    // start of current segment we're examining
+  int possxstop = -1;    // end of current segment unless we bridge a gap
+  int bestxstart = -1;   // start of best (longest) segment seen so far
+  int bestxstop = -1;    // end of best segment seen so far
+  int bestlength = -1;   // length of best segment seen so far
+  for (int x = 0, y, dist=0; x < skelDist.width; x++) {
+    y = int(m*x+b);
+    
+    // If y is on-screen...
+    if (y >= 0 && y < skelDist.height) {
+      dist = skelDist(x,y);
+
+      if (on_line == false) {   // not currently on a line segment
+	if (dist <= beg_dist_thresh) {
+	  // start a new segment
+	  on_line = true;
+	  curxstart = x - dist;
+	  // if new segment begins at an occluder, back up over the occluder
+	  int curystart;
+	  bool backupflag = false;
+	  while ( curxstart >= 0 && (curystart=int(m*curxstart+b)) >= 0 && curystart < skelDist.height )
+	    if ( occlusions(curxstart,curystart) || skelDist(curxstart,curystart) == 0 ) {
+	      --curxstart;
+	      backupflag = true;
+	    } else { // if we backed up past the occluder, go one step forward
+	      curxstart += backupflag;
+	      break;
+	    }
+	  if ( curxstart < 0) // occluder extended to left edge of image
+	    curxstart = 0;
+	}
+      }
+      else {   // on_line == true:  currently on a line segment
+	const bool occ = occlusions(x,y);
+	// cout << "x=" << x << "  dist=" << dist <<"  occ=" << occ;
+	if ( dist <= end_dist_thresh || occ ) {
+	  if ( occ )
+	    possxstop = x;
+	  else
+	    possxstop = x - dist;
+	  // cout << "  possxstop=" << possxstop;
+	  if ( possxstop-curxstart > bestlength ) {
+	    bestxstart = curxstart;
+	    bestxstop = possxstop;
+	    bestlength = bestxstop-bestxstart;
+	    // cout << "  bestxstop=" << bestxstop << "  bestlength=" << bestlength;
+	  }
+	}
+	else if ( dist > extractorGapTolerance ) {
+	  // we're traversing a gap, and it just got too long
+	  on_line = false;
+	  // cout << "  on_line=" << on_line << "  dist=" << dist;
+	};	
+	// cout << endl;
+      }
+    }
+  }
+
+  // cout << "xstart:" << bestxstart << "xstop:" << bestxstop << endl;
+  float y1 = m*bestxstart + b;
+  float y2 = m*bestxstop + b;
+  setEndPts(Point(bestxstart,y1), Point(bestxstop,y2));
+  // cout << "m = " << m << "   b = " << b << endl;
+  balanceEndPointHoriz(end1_pt,occlusions,m,b);
+  balanceEndPointHoriz(end2_pt,occlusions,m,b);
+}
+
+void LineData::scanVertForEndPts(const Sketch<usint>& skelDist, 
+				  const Sketch<bool>& occlusions, 
+				  float m, float b) {
+  // Scan along the infinite line, looking for segments in the image.
+  bool on_line = false;			   // true if tracing a line skeleton
+  int beg_dist_thresh = BEG_DIST_THRESH;   // skel has to be <= this close to start segment
+  int end_dist_thresh = END_DIST_THRESH;   // how far line should extend from skel
+  int curystart = -1;    // start of current segment we're examining
+  int possystop = -1;    // end of current segment unless we bridge a gap
+  int bestystart = -1;   // start of best (longest) segment seen so far
+  int bestystop = -1;    // end of best segment seen so far
+  int bestlength = -1;   // length of best segment seen so far
+  for (int x, y = 0, dist=0; y < skelDist.height; y++) {
+    x = int((y-b)/m);
+    
+    // If x is on-screen...
+    if (x >= 0 && x < skelDist.width) {
+      dist = int(skelDist(x,y));
+
+      if (on_line == false) {   // not currently on a line segment
+	if (dist <= beg_dist_thresh) {
+	  // start a new segment
+	  on_line = true;
+	  curystart = y - dist;
+	  // if new segment begins at an occluder, back up over the occluder
+	  int curxstart;
+	  bool backupflag = false;
+	  while ( curystart >= 0 && (curxstart=int((curystart-b)/m)) >= 0 && curxstart < skelDist.width )
+	    if ( occlusions(curxstart,curystart) || skelDist(curxstart,curystart) == 0 ){
+	      --curystart;
+	      backupflag = true;
+	    } else { // if we backed up past the occluder, go one step forward
+	      curystart += backupflag;
+	      break;
+	    }
+	  if ( curystart < 0) // occluder extended to top edge of image
+	    curystart = 0;
+	}
+      }
+      else {   // on_line == true:  currently on a line segment
+	const bool occ = occlusions(x,y);
+	// cout << "y=" << y << "  dist=" << dist <<"  occ=" << occ;
+	if ( dist <= end_dist_thresh || occ ) {
+	  if ( occ )
+	    possystop = y;
+	  else
+	    possystop = y - dist;
+	  // cout << "  possystop=" << possystop;
+	  if ( possystop-curystart > bestlength ) {
+	    bestystart = curystart;
+	    bestystop = possystop;
+	    bestlength = bestystop-bestystart;
+	    // cout << "  bestystop=" << bestystop << "  bestlength=" << bestlength;
+	  }
+	}
+	else if ( dist > extractorGapTolerance ) {
+	  // we're traversing a gap, and it just got too long
+	  on_line = false;
+	  // cout << "  on_line=" << on_line;
+	};	
+	// cout << endl;
+      }
+    }
+  }
+
+  float x1 = (bestystart-b)/m;
+  float x2 = (bestystop-b)/m;
+  // cout << "x1=" << x1 << ", ystart=" << bestystart << "   x2=" << x2 << ", ystop=" << bestystop << endl;
+  setEndPts(Point(x1,bestystart), Point(x2,bestystop));
+  // cout << "m = " << m << "   b = " << b << endl;
+  balanceEndPointVert(end1_pt,occlusions,m,b);
+  balanceEndPointVert(end2_pt,occlusions,m,b);
+}
+
+void LineData::balanceEndPointHoriz(EndPoint &, Sketch<bool> const &, float, float) {
+  /*
+  int xstep = ( pt.coordX() < max(end1_pt.coordX(),end2_pt.coordX()) ? +1 : -1 );
+  int toppix = 0, bottompix = 0;
+  int const balance_rows = 5;    // check this many rows from the line endpoint inward
+  int const row_samples = 10; // for each row, check this many pixels each side of the line
+  */
+  return;
+}
+
+void LineData::balanceEndPointVert(EndPoint &pt, Sketch<bool> const &occluders, float m, float b) {
+  int ystep = ( pt.coordY() < max(end1_pt.coordY(),end2_pt.coordY()) ? +1 : -1 );
+  int leftpix = 0, rightpix = 0;
+  int const balance_rows = 8;    // check this many rows from the line endpoint inward
+  int const row_samples = 10; // for each row, check this many pixels each side of the line
+  // cout << endl << " ystep=" << ystep << " coords= ( " << pt.coordX() << " , " << pt.coordY() << ")"  << endl;
+  for ( int y = (int)pt.coordY(), ycnt=balance_rows ;
+	y>= 0 && y<occluders.height && ycnt-- > 0 ; y+=ystep ) {
+    int const xstart = (int) ((y-b)/m);
+    for ( int x = xstart-row_samples; x < xstart; x++ )
+      if ( x >= 0 )
+	leftpix += occluders(x,y);
+    for ( int x = xstart+row_samples; x > xstart; x-- )
+      if ( x < occluders.width )
+	rightpix += occluders(x,y);
+    // cout << "   " << xstart << "/" << y << "  =  " << leftpix << " " << rightpix << endl;;
+  }
+   float const new_x = pt.coordX() + (rightpix-leftpix)/(2*balance_rows);
+   // cout << "    leftpix=" << leftpix <<"  rightpix=" << rightpix << endl;
+   pt.setCoords(new_x, pt.coordY());
+}
+
+vector<Shape<LineData> > LineData::extractLines(Sketch<bool> const& sketch,
+						const int num_lines) {
+  NEW_SKETCH_N(fatmask,bool,visops::fillin(sketch,1,2,8));
+  NEW_SKETCH_N(skel,bool,visops::skel(fatmask));
+  return extractLines(skel, sketch, num_lines);
+}
+
+vector<Shape<LineData> > LineData::extractLines(Sketch<bool> const& skel,
+						Sketch<bool> const& occluders,
+						const int num_lines) {
+  vector<Shape<LineData> > lines_vec;
+  NEW_SKETCH_N(temp,bool,visops::copy(skel))
+  for (int gloop = 0; gloop<num_lines; gloop++) {  // <---- HACK TO LIMIT NUMBER OF LINES RETURNED
+    Shape<LineData> newline(extractLine(temp,occluders));
+    if ( !newline.isValid() ) break;
+    newline->clearLine(temp);
+    if (newline->isLongerThan(DEFAULT_MIN_LENGTH)) {
+      lines_vec.push_back(newline);
+    }
+  }
+  // std::cout << "extractLines returning " << lines_vec.size() << " lines." << std::endl;
+  
+  return lines_vec;
+}
+
+//! 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;
+  Sketch<bool> not_too_close = (visops::edist(line_rendering) >= clear_dist);
+  sketch &= not_too_close;
+} 
+
+//@}
+  
+
+// ==================================================
+// BEGIN LINE RENDERING CODE
+// ==================================================
+
+Sketch<bool>& LineData::getRendering() {
+  if ( ! end1Pt().rendering_valid || ! end2Pt().rendering_valid )
+    deleteRendering();
+  if ( rendering_sketch == NULL )
+    rendering_sketch = render();
+  return *rendering_sketch;
+}
+
+//! Render line to SketchSpace and return reference.
+//! This function does not link the Sketch<bool>* in the shape to the sketch returned.
+Sketch<bool>* LineData::render() const {
+  SketchSpace &renderspace = space->getDualSpace();
+  int const width = renderspace.getWidth();
+  int const height = renderspace.getHeight();
+  float x1,y1,x2,y2;
+  setDrawCoords(x1, y1, x2, y2, width, height);
+  Sketch<bool>* draw_result = 
+    new Sketch<bool>(renderspace, "render("+getName()+")");
+  (*draw_result)->setParentId(getViewableId());
+  (*draw_result)->setColor(getColor());
+  *draw_result = 0;
+  drawline2d(*draw_result, (int)x1, (int)y1, (int)x2, (int)y2);
+  const_cast<LineData*>(this)->end1Pt().rendering_valid = true;
+  const_cast<LineData*>(this)->end2Pt().rendering_valid = true;
+  return draw_result;
+}  
+ 
+  
+// This function will be called by both LineData and PolygonData renderers
+void LineData::setDrawCoords(float& x1,float& y1, float& x2, float& y2,
+			     const int width, const int height) const {
+  EndPoint e1(end1Pt());
+  EndPoint e2(end2Pt());
+  space->getDualSpace().applyTmat(e1.getCoords());
+  space->getDualSpace().applyTmat(e2.getCoords());
+  const EndPoint &left_point = e1.coordX() <= e2.coordX() ? e1 : e2;
+  const EndPoint &right_point = e1.coordX() <= e2.coordX() ? e2 : e1;
+
+  // Check if horizontal
+  if((int)left_point.coordY() == (int)right_point.coordY()) { 
+    if (!left_point.isActive())
+      x1 = 0;
+    else x1 = max(0,(int)left_point.coordX());
+    
+    if (!right_point.isActive())
+      x2 = width-1;
+    else x2 = min(width-1, (int)right_point.coordX());
+    
+    y1 = (int)left_point.coordY();
+    y2 = y1;
+  } 
+  else // Check if vertical...
+    if ((int)left_point.coordX() == (int)right_point.coordX()) { 
+    
+    x1 = (int)left_point.coordX();
+    x2 = x1;
+    
+    const EndPoint &top_point = end1Pt().coordY() <= end2Pt().coordY() ? end1Pt() : end2Pt();
+    const EndPoint &bottom_point = end1Pt().coordY() <= end2Pt().coordY() ? end2Pt() : end1Pt();
+
+    if(!top_point.isActive())
+      y1 = 0;
+    else y1 = max(0,(int)top_point.coordY());
+    
+    if (!bottom_point.isActive())
+      y2 = height-1;
+    else y2 = min(height-1,(int)bottom_point.coordY());
+  } 
+
+  else {   // Neither horizontal nor vertical...
+    float m = (right_point.coordY()-left_point.coordY())/(right_point.coordX()-left_point.coordX());
+    float b = left_point.coordY() - m*left_point.coordX();
+    
+    // find image edge intersections
+    int i0x = (int)((0-b)/m);
+    int ihx = (int)(((height-1)-b)/m);
+    int i0y = (int)(m*0+b);
+    int iwy = (int)(m*(width-1)+b);
+    
+    // If left point is active, set starting x and y accordingly.
+    if(left_point.isActive()) {
+      x1 = (int)left_point.coordX();
+      y1 = (int)left_point.coordY();
+    } 
+    
+    // If endpoint 1 extends past image edge...
+    else { 
+      
+      // intersects left edge
+      if(i0y >= 0 && i0y < height) { 
+	x1 = 0;
+	y1 = i0y;
+      } 
+      
+      // intersects top or bottom edge
+      else { 
+	
+	// intersects top first
+	if (i0x < ihx) { 
+	  x1 = i0x;
+	  y1 = 0;
+	} 
+	
+	// intersects bottom first
+	else { 
+	  x1 = ihx;
+	  y1 = height-1;
+	}
+      }
+    }
+    
+    // If right point is active, set starting x and y accordingly.
+    if(right_point.isActive()) {
+      x2 = (int)right_point.coordX();
+      y2 = (int)right_point.coordY();
+    } 
+    else { // endpoint extends to image edge
+      if(iwy >= 0 && iwy < height) { // intersects right edge
+	x2 = width-1;
+	y2 = iwy;
+      } 
+      else { // intersects top or bottom edge
+	if (i0x > ihx) { // intersects top last 
+	  x2 = i0x;
+	  y2 = 0;
+	} 
+	else { // intersects bottom last
+	  x2 = ihx;
+	  y2 = height-1;
+	}
+      }
+    }
+  }
+}
+
+void LineData::drawline2d(Sketch<bool>& canvas, int x0, int y0, int x1, int y1) {
+  int width = canvas->getWidth();
+  int height = canvas->getHeight();
+  
+  // code below from free Graphics Gems repository, graphicsgems.org
+  int d, x, y, ax, ay, sx, sy, dx, dy;
+  dx = x1-x0;  ax = abs(dx)<<1;  sx = SGN(dx);
+  dy = y1-y0;  ay = abs(dy)<<1;  sy = SGN(dy);
+  
+  x = x0;
+  y = y0;
+  if ( ax > ay ) {		/* x dominant */
+    d = ay-(ax>>1);
+    for (;;) {
+      if (x >= 0 && y >= 0 && x < width && y < height)
+	canvas(x,y) = true;
+      
+      if (x==x1)
+	return;
+      
+      if ( d >= 0 ) {
+	y += sy;
+	d -= ax;
+      }
+      
+      x += sx;
+      d += ay;
+    }
+  }
+  else {			/* y dominant */
+    d = ax-(ay>>1);
+    for (;;) {
+      if (x >= 0 && y >= 0 && x < width && y < height)
+	canvas(x,y) = true;
+      
+      if ( y == y1 )
+	return;
+      
+      if ( d >= 0 ) {
+	x += sx;
+	d -= ay;
+      }
+      
+      y += sy;
+      d += ax;
+    }
+  }
+}
+//}
+
+
+std::vector<Shape<LineData> > LineData::houghTransform(const Sketch<bool>& fat, 
+						const Sketch<bool>& skinny,
+						const Sketch<bool>& occlusions,
+						const size_t num_lines, int minLength)
+{
+  std::vector<Shape<LineData> > result;
+  ShapeSpace& ShS = fat->getSpace().getDualSpace();
+
+  const int width = fat->getWidth(), height = fat->getHeight();
+  const int numR = 120, numTheta = 120;
+  const int numRf = 40, numThetaf = 40;
+  int hsize = numR*numTheta, hsizef = numRf * numThetaf;
+  int htab[hsize], hfine[hsizef]; // Hough accumulator table
+  float minTheta = 0.0, maxTheta = 2*M_PI; //0.9999*M_PI;
+  float minR = 0.000, maxR = sqrt((float)width*width+(float)height*height); //240.0;
+  float thetaSpread = maxTheta - minTheta;
+  float rSpread = maxR - minR;
+  //float bestR = 0, bestTheta = 0;
+
+  for (int i = 0; i < hsize; i++)
+    htab[i] = 0; // zero accumulator table
+
+  // build accumulator table
+  float theta, r;
+  int ridx;
+  for (int x = 0; x < width; x++) {
+    for (int y = 0; y < height; y++) {
+      if (fat(x,y) == true) {
+	for (int tidx = 0; tidx < numTheta ; tidx++) {
+	  theta = minTheta + tidx*thetaSpread/numTheta;
+	  r = (float)x*cos(theta)+(float)y*sin(theta);
+	  ridx = (int)((r-minR)*(float)numR/rSpread); // Is this right calc?
+	  if (ridx >= 0 && ridx < numR) // check ridx bounds
+	    htab[ridx+tidx*numR]++;	
+	}
+      }
+    }
+  }
+
+
+  /*float lineLen = 500;
+  for (int i = 0; i < numR*numTheta; i++) {
+    if (htab[i] >= minCount)
+      {
+	const float curR = (i%numR)*rSpread/numR + minR;
+	const float curTheta = (i/numR)*thetaSpread/numTheta + minTheta;
+	const float x1 = curR*cos(curTheta), y1 = curR*sin(curTheta);
+	const float x2 = x1+lineLen*cos(curTheta+M_PI/2), y2 = y1+lineLen*sin(curTheta+M_PI/2);
+	const float x3 = x1-lineLen*cos(curTheta+M_PI/2), y3 = y1-lineLen*sin(curTheta+M_PI/2);
+
+	Point e1(x3,y3), e2(x2,y2);
+	Shape<LineData> line(ShS,e1,e2);
+	line->end1Pt().setValid(false);
+	line->end2Pt().setValid(false);
+	result.push_back(line);
+      }
+      }*/
+
+  // Finely explore the first n best lines in the rough table
+  int max_val = -1, max_i = 0;
+  while(result.size() < num_lines) {
+
+    // find maximum value in accumulator table
+    max_val = -1;
+    max_i = 0;
+    for (int i = 0; i < numR*numTheta; i++) {
+      if (max_val < htab[i]) {
+	max_val = htab[i];
+	max_i = i;
+      }
+    }
+
+    // Give up if the lines start getting too small
+    if (max_val < minLength)
+      break;
+    
+
+    float bestR = (max_i%numR)*rSpread/numR + minR;
+    float bestTheta = (max_i/numR)*thetaSpread/numTheta + minTheta;
+
+    // determine parameters for the fine hough iteration
+    const float fthetaSpread = M_PI/40.0; 
+    const float frSpread = maxR/40.0;
+    float fminTheta = bestTheta-fthetaSpread/2.0;
+    float fminR = bestR-frSpread/2.0;
+
+    for (int i = 0; i < hsizef; i++)
+      hfine[i] = 0; // zero fine table
+    
+    // build fine table
+    float thetaf, rf;
+    int ridxf;
+    for (int x = 0; x < width; x++) {
+      for (int y = 0; y < height; y++) {
+	if (skinny(x,y) == true) {
+	  for (int tidx = 0; tidx < numThetaf ; tidx++) {
+	    thetaf = fminTheta + tidx*fthetaSpread/numThetaf;
+	    rf = (float)x*cos(thetaf)+(float)y*sin(thetaf);
+	    ridxf = (int)((rf-fminR)*(float)numRf/frSpread); // Is this right calc?
+	    if (ridxf >= 0 && ridxf < numRf) // check ridx bounds
+	      hfine[ridxf+tidx*numRf]++;	
+	  }
+	}
+      }
+    }
+
+    
+    // Pull the best line out of the fine table
+    int max_val_f = -1, max_i_f = 0;
+    for (int i = 0; i < numRf*numThetaf; i++) {
+      if (max_val_f < hfine[i]) {
+	max_val_f = hfine[i];
+	max_i_f = i;
+      }
+    }
+    float bestRf = (max_i_f%numRf)*frSpread/numRf + fminR;
+    float bestThetaf = (max_i_f/numRf)*fthetaSpread/numThetaf + fminTheta;
+
+    // Add viable segments to the vector
+    // Step along the line, looking for segments. 
+    float lineLen = 500;
+    // Can be simpler
+    const float x1 = bestRf*cos(bestThetaf), y1 = bestRf*sin(bestThetaf);
+    const float x2 = x1+lineLen*cos(bestThetaf+M_PI/2), y2 = y1+lineLen*sin(bestThetaf+M_PI/2);
+    const float x3 = x1-lineLen*cos(bestThetaf+M_PI/2), y3 = y1-lineLen*sin(bestThetaf+M_PI/2);
+    
+    Point e1(x3,y3), e2(x2,y2);
+    Shape<LineData> line(ShS,e1,e2);
+
+
+    line->setColor(skinny->getColor());
+    line->setParentId(skinny->getViewableId());
+
+    // m is slope of this line (not the normal line)
+    float m = (y1 != 0) ? -(x1/y1) : BIG_SLOPE;
+    float b = y1 - m*x1;
+    
+    NEW_SKETCH_N(skelDist,usint,visops::edist(skinny));
+    if ( abs(m) <= 1 )  // when |slope| <= 1, scan along x, else scan along y
+      line->scanHorizForEndPts(skelDist,occlusions,m,b);
+    else
+      line->scanVertForEndPts(skelDist,occlusions,m,b);
+    
+    //! Check to see if any endpoints are near any edge of the screen.
+    //! If they are, invalidate them, assuming that line continues beyond screen.
+    line->end1_pt.checkValidity(width,height,BEG_DIST_THRESH);
+    line->end2_pt.checkValidity(width,height,BEG_DIST_THRESH);
+
+
+    // Experimental: check how much of the line actually lies along edge pixels
+    // only include lines that are at least 50% above edge pixels. 
+    
+    float len = line->getLength();
+    EndPoint start = line->end1_pt;
+    EndPoint dx = (line->end2_pt - start)/len;
+    float onCount = 0;
+    for (float i=0; i<len; i++) {
+      EndPoint cur = start+dx*i;
+      if (skinny((int)(cur.coordX()), (int)(cur.coordY()))) {
+	onCount++;
+      }
+    }
+
+
+    std::cout<<"Line with "<<onCount<<" / "<<len<<" pixels";
+    if (line->isLongerThan(minLength) && (onCount / len) > .5 )
+      {
+	std::cout<<" accepted";
+	result.push_back(line);
+      }
+    std::cout<<std::endl;
+
+
+    // Empty the corresponding bins in the rough hough table
+    //std::cout<<max_i%numR<<","<<max_i/numR<<std::endl;
+    for(int row = -5; row <= 5; row++)
+      {
+	for (int col = -(5-abs(row)); col <=5-abs(row); col++)
+	  {
+	    //int index = (max_i - (max_i%numR) + ((max_i+col)%numR)+row*numR + numR*numTheta)%(numR*numTheta);
+	    //std::cout<<index%numR<<","<<index/numR<<" ";
+	    htab[(max_i - (max_i%numR) + ((max_i+col)%numR)+row*numR + numR*numTheta)%(numR*numTheta)] = 0;
+	  }
+	//std::cout<<std::endl;
+      }
+    //std::cout<<std::endl;
+  }
+	
+  return result;
+}
+
+bool LineData::linesParallel(Shape<LineData> l1, Shape<LineData>l2)
+{
+  const float maxDTheta = .15, minDThetaR = 10.0;
+  float dTheta = l1->getOrientation() - l2->getOrientation(); 
+  if (dTheta > M_PI_2)
+    dTheta = dTheta - M_PI;
+  if (abs(dTheta) < maxDTheta)
+    {
+      if (abs (100*dTheta + (l1->rho_norm - l2->rho_norm)) > minDThetaR)
+	return true;
+    }
+  return false;
+}
+
+LineData& LineData::operator=(const LineData& other) {
+  if (&other == this)
+    return *this;
+  BaseData::operator=(other);
+  end1_pt = other.end1_pt;
+  end2_pt = other.end2_pt;
+  rho_norm = other.rho_norm;
+  theta_norm = other.theta_norm;
+  orientation = other.orientation;
+  length = other.length;
+  return *this;
+}
+
+
+// Compute if two points are on the same side of the line
+bool LineData::pointsOnSameSide(const Point& p1, const Point& p2)
+{
+  float dx = end2_pt.coordX() - end1_pt.coordX();
+  float dy = end2_pt.coordY() - end1_pt.coordY();
+  
+  float p1val = (p1.coordY() - end1_pt.coordY())*dx - (p1.coordX() - end1_pt.coordX())*dy;
+  float p2val = (p2.coordY() - end1_pt.coordY())*dx - (p2.coordX() - end1_pt.coordX())*dy;
+
+  return (p1val>0) == (p2val>0);
+}
+
+// Checks if the distance from the line to the point is less than 1 pixel,
+// and checks that the point is within the end points of the line.
+bool LineData::pointOnLine(const Point& p)
+{
+  const float BOUNDS_EXTEND = 1.0;
+  float dx = end2_pt.coordX() - end1_pt.coordX();
+  float dy = end2_pt.coordY() - end1_pt.coordY();
+  float val = (p.coordY() - end1_pt.coordY())*dx - (p.coordX() - end1_pt.coordX())*dy;
+  val /= length;
+  bool inBounds = (p.coordX() >= (leftPt().coordX() - BOUNDS_EXTEND)) &&
+    (p.coordX() <= (rightPt().coordX() + BOUNDS_EXTEND)) &&
+    (p.coordY() >= (topPt().coordY() - BOUNDS_EXTEND)) &&
+    (p.coordY() <= (bottomPt().coordY() + BOUNDS_EXTEND));
+  return (val > -1) && (val < 1) && inBounds;
+}
+
+
+// Comparison predicates
+
+bool LineData::LengthLessThan::operator() (const Shape<LineData> &line1, const Shape<LineData> &line2) const {
+      return line1->getLength() < line2->getLength();
+}
+
+bool LineData::ParallelTest::operator() (const Shape<LineData> &line1, const Shape<LineData> &line2) const {
+  return angdist(line1->getOrientation(),line2->getOrientation()) <= tolerance;
+}
+
+bool LineData::PerpendicularTest::operator() (const Shape<LineData> &line1, const Shape<LineData> &line2) const {
+  return angdist(angdist(line1->getOrientation(),line2->getOrientation()), M_PI/2) <= tolerance;
+}
+
+bool LineData::ColinearTest::operator() (const Shape<LineData> &line1, const Shape<LineData> &line2) const {
+  return ParallelTest(ang_tol)(line1,line2) && 
+    abs( line1->getRhoNorm() - line2->getRhoNorm() ) <= dist_tol;
+}
+
+bool LineData::IsHorizontal::operator() (const Shape<LineData> &line) {
+      const AngPi orient = line->getOrientation();
+      return  (orient <= threshold) || (orient >= M_PI - threshold);
+    }
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/LineData.h ./DualCoding/LineData.h
--- ../Tekkotsu_2.4.1/DualCoding/LineData.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/LineData.h	2006-09-23 23:45:20.000000000 -0400
@@ -0,0 +1,316 @@
+//-*-c++-*-
+#ifndef _LINEDATA_H_
+#define _LINEDATA_H_
+
+#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 "Shared/mathutils.h"   // deg2rad
+
+namespace DualCoding {
+
+class Region;
+
+#define EXTRACT_LINE_MIN_AREA 20
+#define DEFAULT_MIN_LENGTH 4.0
+
+class LineData : public BaseData {
+private:
+  EndPoint end1_pt;
+  EndPoint end2_pt;
+  float rho_norm;
+  AngTwoPi theta_norm;
+  AngPi orientation;
+  float length;
+
+  static const Point origin_pt;
+
+  friend class Shape<LineData>;   // grant access to line endpoints
+  friend class PolygonData;
+  friend class BlobData;
+
+public:
+  
+  //! Constructor
+  LineData(ShapeSpace& _space, const Point &p1, const Point &p2) 
+    : BaseData(_space,getStaticType()), 
+      end1_pt(p1), end2_pt(p2), rho_norm(0), theta_norm(0), orientation(0), length(0)
+  { update_derived_properties(); }
+  
+  //! Constructor
+  LineData(ShapeSpace& _space, const Point &pt, orientation_t orient);
+
+  //! Copy constructor
+  LineData(const LineData& other)
+    : BaseData(other),
+      end1_pt(other.end1_pt), end2_pt(other.end2_pt),
+      rho_norm(other.rho_norm), theta_norm(other.theta_norm),
+      orientation(other.orientation), length(other.length) {}
+
+  static ShapeType_t getStaticType() { return lineDataType; }
+  
+  DATASTUFF_H(LineData);
+  
+  //! Updates norm parameters (rho and theta)
+  void update_derived_properties();
+  
+  //! Centroid. (Virtual in BaseData.)
+  virtual Point getCentroid() const;	
+  
+  //! Makes endpoints inactive if value = true
+  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()));
+  }
+
+  //! Match lines based on their parameters.  (Virtual in BaseData.)
+  virtual bool isMatchFor(const ShapeRoot& other) const;
+  bool isMatchFor(const LineData& other) const;
+
+  //! Lines are admissible to the local map if they're long enough to not be noise.
+  virtual bool isAdmissible() const ;
+
+  virtual bool updateParams(const ShapeRoot& other, bool force=false);
+  static void updateLinePt(EndPoint& localPt, coordinate_t local_coord,
+			   const EndPoint& groundPt, coordinate_t ground_coord,
+			   int sign);
+  virtual void mergeWith(const ShapeRoot& other);
+
+  LineData& operator=(const LineData&);
+
+  //checks if update of endpoints from (p1,p2) to (p3,p4) is acceptable
+  bool isValidUpdate(coordinate_t p1, coordinate_t p2, coordinate_t p3, coordinate_t p4);
+
+  //! Print information about this shape. (Virtual in BaseData.)
+  virtual void printParams() const;
+  
+  //! Transformations. (Virtual in BaseData.)
+  virtual void applyTransform(const NEWMAT::Matrix& Tmat);
+  
+  //! Project to ground
+  virtual void projectToGround(const NEWMAT::Matrix& camToBase,
+			       const NEWMAT::ColumnVector& groundplane);
+
+  virtual unsigned short getDimension() const { return 1; }
+
+  //! Point Access functions.
+  //@{
+  EndPoint& end1Pt() { return end1_pt; }
+  EndPoint& end2Pt() { return end2_pt; }
+  const EndPoint& end1Pt() const { return end1_pt; }
+  const EndPoint& end2Pt() const { return end2_pt; }
+
+  EndPoint& leftPt();
+  EndPoint& rightPt();
+  EndPoint& topPt();
+  EndPoint& bottomPt();
+
+  Shape<PointData> leftPtShape();
+  Shape<PointData> rightPtShape();
+  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;
+
+  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.
+  //@{
+  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;
+  //@}
+  
+public:
+  
+  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);
+  //  bool isExactlyPerpendicularTo(Shape<LineData> &other);
+  //@}
+  
+  
+  //! Predicates based on line length.
+  //@{
+  bool isLongerThan(const Shape<LineData>& other) const;
+  bool isLongerThan(float ref_length) const;
+  bool isShorterThan(const Shape<LineData>& other) const;
+  bool isShorterThan(float ref_length) const;
+  //@}
+  
+  //! Check if point falls between the two lines
+  bool isBetween(const Point &p, const LineData &other) const;
+
+  //! Check intersection.
+  //@{
+  bool intersectsLine(const Shape<LineData>& other) const;
+  bool intersectsLine(const LineData& other) const;
+
+  Point intersectionWithLine(const Shape<LineData>& other) const
+  { bool b; return intersectionWithLine(other,b,b); };
+  Point intersectionWithLine(const Shape<LineData>& other,
+			     bool& intersection_on_this,
+			     bool& intersection_on_other) const;
+  Point intersectionWithLine(const LineData& other) const 
+  { bool b; return intersectionWithLine(other, b,b); };
+  Point intersectionWithLine(const LineData& other,
+			     bool& intersection_on_this,
+			     bool& intersection_on_other) const;
+  
+  //@}
+
+  bool pointsOnSameSide(const Point& p1, const Point& p2);
+  bool pointOnLine(const Point& p);
+  
+  //! Distance.
+  //@{
+  float perpendicularDistanceFrom(const Point& other) const;
+  //@}
+  
+  
+  // ==================================================
+  // BEGIN SKETCH MANIPULATION AND LINE EXTRACTION CODE
+  // ==================================================
+  
+  //! Extraction.
+  //@{
+
+  //! Extracts most prominent line from a skeletonized image.
+  static Shape<LineData> extractLine(Sketch<bool>& sketch);
+
+  //! Extracts most prominent line from a skeletonized image.
+  //! 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().
+  //@{
+  static Shape<LineData> splitLine(ShapeSpace &ShS, Region &skelchunk,
+				   Sketch<bool> &skeleton, const Sketch<bool> &occlusions);
+
+  //! Clears a line from a sketch.
+  void clearLine(Sketch<bool>& sketch);
+  
+  void scanHorizForEndPts(const Sketch<usint>& skelDist, const Sketch<bool>& occlusions,
+			  float m, float b);
+  void scanVertForEndPts(const Sketch<usint>& 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 vector<Shape<LineData> > extractLines(Sketch<bool> const& skel,
+					       Sketch<bool> const& occluders,
+					       int const num_lines=10);
+  
+  static std::vector<Shape<LineData> > houghTransform(const Sketch<bool>& fat, 
+					       const Sketch<bool>& skinny, 
+					       const Sketch<bool>& occlusions,
+					       const size_t num_lines,
+					       int minLength=DEFAULT_MIN_LENGTH); 
+
+  static bool linesParallel(Shape<LineData> l1, Shape<LineData>l2);
+
+  //@}
+  
+  //! Comparison predicates used by shape functions
+  //@{
+
+  class LengthLessThan : public BinaryShapePred<LineData> {
+  public:
+    bool operator() (const Shape<LineData> &ln1, const Shape<LineData> &ln2) const;
+  };
+
+  class ParallelTest : public BinaryShapePred<LineData> {
+  public:
+    AngPi tolerance;
+    ParallelTest(AngPi _tol=mathutils::deg2rad(20.0)) : tolerance(_tol) {}
+    bool operator() (const Shape<LineData> &line1, const Shape<LineData> &line2) const;
+  };
+
+
+  class PerpendicularTest : public BinaryShapePred<LineData> {
+  public:
+    AngPi tolerance;
+    PerpendicularTest(AngPi _tol=mathutils::deg2rad(20.0)) : tolerance(_tol) {}
+    bool operator() (const Shape<LineData> &line1, const Shape<LineData> &line2) const;
+  };
+
+
+  class ColinearTest : public BinaryShapePred<LineData> {
+  public:
+    AngPi ang_tol;
+    coordinate_t dist_tol;
+    ColinearTest(AngPi _ang_tol=mathutils::deg2rad(20.0), coordinate_t _dist_tol=10) : 
+      ang_tol(_ang_tol), dist_tol(_dist_tol) {}
+    bool operator() (const Shape<LineData> &line1, const Shape<LineData> &ln2) const;
+  };
+
+  class IsHorizontal : public UnaryShapePred<LineData> {
+  public:
+    IsHorizontal(AngPi thresh=M_PI/6) : UnaryShapePred<LineData>(), threshold(thresh) {}
+    bool operator() (const Shape<LineData> &line);
+  private:
+    AngPi threshold;
+  };
+      
+
+  //@}
+
+
+  virtual Sketch<bool>& getRendering();
+
+private:
+  static const int extractorGapTolerance = 8;
+
+  //! Rendering.
+  //@{
+  
+  //! Render into a sketch space and return reference.
+  Sketch<bool>* render() const;
+  
+  //! returns a Sketch which is true where the specified line is
+  //! end0_stop and end1_stop specify whether rendering should stop at endpoints
+  //  Sketch<bool>& drawline2d(SketchSpace &renderspace, 
+  //			   int x0, int y0, int x1, int y1) const;
+  void setDrawCoords(float& x1,float& y1, float& x2, float& y2, const int width, const int height) const;
+  static void drawline2d(Sketch<bool>& canvas, int x0, int y0, int x1, int y1);
+  //@}
+};
+
+} // namespace
+
+#endif
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/Lookout.cc ./DualCoding/Lookout.cc
--- ../Tekkotsu_2.4.1/DualCoding/Lookout.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Lookout.cc	2006-10-02 14:49:16.000000000 -0400
@@ -0,0 +1,609 @@
+//-*-c++-*-
+
+#include "Events/EventRouter.h"
+#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/WorldState.h"
+#include "Vision/RegionGenerator.h"
+
+#include "VRmixin.h"
+#include "LookoutRequests.h"
+#include "Lookout.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
+}
+
+
+Lookout::Lookout()
+  : BehaviorBase("Lookout"),
+    pointer_id(MotionManager::invalid_MC_ID), 
+    sequence_id(MotionManager::invalid_MC_ID), 
+    requests(), curReq(NULL), landmarkInView(true),
+    idCounter(0)
+{}
+
+void Lookout::DoStart() {
+  BehaviorBase::DoStart();
+}
+
+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(sequence_id);
+  sequence_id = MotionManager::invalid_MC_ID;
+  BehaviorBase::DoStop();
+}
+  /*
+
+vector<Point> Lookout::getVisionObjectData() {
+
+}
+
+vector<Point> Lookout::getIRData() {
+
+}
+  */
+
+void Lookout::processScan(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);
+  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);
+      }
+    }
+    else if (event.getSourceID() == sequence_id) {
+      sequence_id = MotionManager::invalid_MC_ID;
+      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);
+	storeVisionRegionDataTo(vrt->data,vrt->index,vrt->minArea);
+      }
+      else if (task->getTaskType() == ScanRequest::Task::visObj) {
+	erouter->addListener(this, EventBase::visSegmentEGID,
+			     ProjectInterface::visSegmentSID,EventBase::statusETID);
+	listeningObjEGID = true;
+      }
+      else if (task->getTaskType() == ScanRequest::Task::ir) 
+	storeIRDataTo(task->data);
+    }
+    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();
+	   it != curScanReq->tasks.end(); it++)
+	if ((*it)->getTaskType() == ScanRequest::Task::visObj) {
+	  ScanRequest::VisionTask& vTask = *dynamic_cast<ScanRequest::VisionTask*>(*it);
+	  if (vTask.index.find(event.getSourceID()) != vTask.index.end()) {
+	    vTask.data.push_back(findLocationFor(&voe));
+	    cout << "VisionObject at " << vTask.data.back() << endl;
+	    break;
+	  }
+	}
+    }
+    break;
+  default:
+    cout << "Lookout::processScan: unknown event " << event.getName() << endl;
+    break;
+  };
+}
+
+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::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;
+}
+
+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;
+	}
+      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;
+  }
+}
+  
+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);
+    }
+    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;
+      };
+      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();
+  }
+    break;
+  default:
+    cout << "Lookout::processPointAt: unknown event " << event.getName() << endl;
+    break;
+  };
+}
+  /*
+void Lookout::processTrackVision(float normX, float normY, bool isCurrentlyVisible) {
+  if (!isCurrentlyVisible && landmarkInView) { // landmark just lost
+    cout << "landmark just lost" << endl;
+    erouter->addTimer(this,start_pan,500,false); // wait 0.5 sec before starting to look for landmark
+    erouter->removeTimer(this,reset_pan);
+  }
+  else if (!landmarkInView && isCurrentlyVisible) { // landmark just found
+    cout << "found landmark" << endl;
+    erouter->removeTimer(this,start_pan);
+    erouter->addTimer(this,reset_pan,1000,false);
+  }
+  else if (isCurrentlyVisible) { // continue tracking landmark
+    trackObjectAt(normX,normY);
+  }
+  landmarkInView = isCurrentlyVisible;
+  lm_location = findLocationFor(normX,normY);
+  erouter->postEvent(EventBase::lookoutEGID, curReq->getRequestID(), EventBase::statusETID,0);
+}
+
+void Lookout::processTrack(const EventBase& event) {
+  switch (event.getGeneratorID()) {
+  case EventBase::visObjEGID:
+    if (event.getTypeID()==EventBase::statusETID) {
+      const VisionObjectEvent *voe = (static_cast<const VisionObjectEvent*>(&event));
+      const float area = voe->getBoundaryArea();
+      processTrackVision(voe->getCenterX(), voe->getCenterY(), area > 0.03);
+    }
+    break;
+  case EventBase::visSegmentEGID:
+    if (event.getTypeID() == EventBase::statusETID) {
+      vector<Point> pts = getRegionData();
+      if (pts.empty()) processTrackVision(0,0,false);
+      else processTrackVision(pts.front().coordX(),pts.front().coordY(),true);
+    }
+    break;
+  case EventBase::timerEGID:
+    switch (event.getSourceID()) {
+    case start_pan: //! enough time passed after landmark lost
+      cout << "landmark not seen for 0.5 sec\n";
+      if (curReq->isSticky())
+	lookForLandmark();
+      else
+	requestComplete();
+      break;
+    case reset_pan:
+      cout << "reset pan motion" << endl;
+      { MMAccessor<SmallMotionSequenceMC> (sequence_id)->setTime(0); }
+      break;
+    default:
+      cout << "unknown source timer evenet" << endl;
+      break;
+    }
+  case EventBase::motmanEGID:
+    if (event.getSourceID() == sequence_id && curReq->isSticky()) { // lookForLandmark() failed
+      cout << "Lookout::processTrack: track failed\n";
+      requestComplete();
+    }
+    break;
+  default:
+    cout << "Lookout::processTrack: unknown event" << endl;
+    break;
+  };
+}
+  */
+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);
+//  findLandmarkLocation(voe);
+//  erouter->postEvent(EventBase::lookoutEGID, curReq->getRequestID(), EventBase::statusETID,0);
+  double tilt=state->outputs[HeadOffset+TiltOffset]-vert*M_PI/7.5;
+  double pan=state->outputs[HeadOffset+PanOffset]-horiz*M_PI/6;
+  if(tilt<mathutils::deg2rad(-20.0))
+    tilt=mathutils::deg2rad(-20.0);
+  if(tilt>mathutils::deg2rad(40.0))
+    tilt=mathutils::deg2rad(40.0);
+  if(pan>mathutils::deg2rad(80.0))
+    pan=mathutils::deg2rad(80.0);
+  if(pan<mathutils::deg2rad(-80.0))
+    pan=mathutils::deg2rad(-80.0);
+
+#ifdef TGT_ERS7
+  //  cout << "tilt: " << state->outputs[HeadOffset+TiltOffset] << ", nod: " << state->outputs[HeadOffset+NodOffset] << endl;
+  if (tilt < -0.5)
+    MMAccessor<HeadPointerMC> (pointer_id)->setJoints(tilt,pan,outputRanges[HeadOffset+NodOffset][MinRange]);
+  else {
+    const float act_tilt = state->outputs[HeadOffset+TiltOffset];
+    const float nod_fact = act_tilt*act_tilt*4.0;
+    MMAccessor<HeadPointerMC> (pointer_id)->setJoints(tilt,pan,outputRanges[HeadOffset+NodOffset][MinRange]*nod_fact);
+  }
+#else
+  MMAccessor<HeadPointerMC> (pointer_id)->setJoints(tilt,pan,0);
+#endif
+}
+  */
+
+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);
+}
+
+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);
+  }
+}
+
+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::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);
+
+  // 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
+
+  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);
+
+  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;
+
+  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);
+  }
+  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);
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/Lookout.h ./DualCoding/Lookout.h
--- ../Tekkotsu_2.4.1/DualCoding/Lookout.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Lookout.h	2006-08-10 23:13:15.000000000 -0400
@@ -0,0 +1,116 @@
+//-*-c++-*-
+#ifndef INCLUDED_Lookout_h_
+#define INCLUDED_Lookout_h_
+
+#include <queue>
+#include "Behaviors/BehaviorBase.h"
+#include "Motion/MotionManager.h"
+#include "Motion/MotionSequenceMC.h"
+#include "Events/VisionObjectEvent.h"
+#include "LookoutRequests.h"
+
+namespace DualCoding {
+
+class LookoutRequest;
+class StoreModeImageRequest;
+class ModeImageRequest;
+
+/*!
+ 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.
+
+*/
+
+class Lookout : public BehaviorBase {
+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"; }
+  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 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;
+  
+protected:
+  virtual void executeRequest();
+  virtual void requestComplete();
+  template<class T>
+  void pushRequest(const LookoutRequest& req) {
+    requests.push(new T(*dynamic_cast<const T*>(&req)));
+  }
+    
+
+  //! PointAtReqeust
+  void processPointAt(const EventBase& event);
+  bool findPixelModes(StoreModeImageRequest& modeRequest);
+  void getData();
+  /*
+  //! 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);
+  }
+
+  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;
+  unsigned int idCounter;
+
+  enum LookoutTimerSourceId_t {
+    start_pan,
+    pan_complete,
+    reset_pan,
+    no_event,
+    dur_timer,
+    scan_timer, //scan_timer has to be at the end of enum list
+  };
+};
+
+} //namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/LookoutRequests.cc ./DualCoding/LookoutRequests.cc
--- ../Tekkotsu_2.4.1/DualCoding/LookoutRequests.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/LookoutRequests.cc	2006-08-11 18:21:33.000000000 -0400
@@ -0,0 +1,5 @@
+#include "LookoutRequests.h"
+
+namespace DualCoding {
+const float ScanRequest::defSpd = 0.0015;
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/LookoutRequests.h ./DualCoding/LookoutRequests.h
--- ../Tekkotsu_2.4.1/DualCoding/LookoutRequests.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/LookoutRequests.h	2006-08-11 18:21:33.000000000 -0400
@@ -0,0 +1,317 @@
+//-*-c++-*-
+#ifndef INCLUDED_LookoutRequests_h_
+#define INCLUDED_LookoutRequests_h_
+
+#include "Shared/newmat/newmat.h"
+#include "Shared/ProjectInterface.h"
+#include "Shared/WorldState.h"
+#include "DualCoding.h"
+#include "VRmixin.h"
+
+namespace DualCoding {
+  
+class LookoutRequest {
+public:
+  enum HeadMotionType_t { 
+    none,
+    pointAt,
+    scan,
+    track
+  };
+  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) {}
+
+  virtual PointAtRequestType_t getPointAtType() const { return none; }
+  virtual HeadMotionType_t getHeadMotionType() const { return pointAt; }
+  Point gazePt; //!< point to look at in base frame coordinates
+};
+
+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) {}
+
+  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&);
+};
+
+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) {}
+
+  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) {};
+
+  //! 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
+};
+
+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) {}
+
+  virtual PointAtRequestType_t getPointAtType() const { return storeImage; }
+  virtual HeadMotionType_t getHeadMotionType() const { return pointAt; }
+private:
+  StoreModeImageAtRequest& operator=(const StoreModeImageAtRequest&);
+};
+
+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;
+};
+
+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; }
+};
+
+//--------------------------------------------
+
+// ------------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;
+  }
+
+  // ------------Tasks may be implemented during scan -------------------
+  class Task {
+  public:
+    enum taskType_t { none, visObj, visReg, ir };
+    virtual taskType_t getTaskType() const = 0;// { return none; }
+    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:
+    Task& operator=(const Task&);
+  };
+
+  class IRTask : public Task {
+  public:
+    IRTask(AngPi _interval) : Task(_interval) {}
+    IRTask(const IRTask& t) : Task(t) {}
+    virtual taskType_t getTaskType() const { return ir; }
+    //  virtual ~IRTask() { cout << "deleting IRTask " << this << endl; }
+  };
+
+  //base class for vision tasks, should not be instantiated
+  class VisionTask : public Task {
+  public:
+    virtual taskType_t getTaskType() const { return none; }
+    set<int> 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); }
+  };
+
+  //! 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 VisionObjectTask& vot) : VisionTask(vot) {}
+    virtual taskType_t getTaskType() const { return visObj; }
+  };
+
+  //! Uses built-in colored region detectors via Region event stream
+  class VisionRegionTask : public VisionTask {
+  public:
+    VisionRegionTask(const set<int>& colorIndex, AngPi _interval,
+		     unsigned int _minArea=200)
+      : VisionTask(colorIndex,_interval), minArea(_minArea) {}
+    VisionRegionTask(int colorIndex, AngPi _interval,
+		     unsigned int _minArea=200)
+      : VisionTask(colorIndex,_interval), minArea(_minArea) {}
+    VisionRegionTask(const VisionRegionTask& vrt)
+      : VisionTask(vrt), minArea(vrt.minArea) {}
+    virtual taskType_t getTaskType() const { return visReg; }
+    unsigned int minArea;
+  };
+
+};
+
+class ScanAlongLineRequest : public ScanRequest {
+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;
+};
+
+class ScanAreaRequest : public ScanRequest {
+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;
+};
+//--------------------------------------------
+
+
+// ------------TRACK requests-------------------
+class TrackRequest : 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;
+};
+//--------------------------------------------
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/Macrodefs.h ./DualCoding/Macrodefs.h
--- ../Tekkotsu_2.4.1/DualCoding/Macrodefs.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Macrodefs.h	2006-01-08 06:08:34.000000000 -0500
@@ -0,0 +1,16 @@
+//-*-c++-*-
+#ifndef _MACRODEFS_H_
+#define _MACRODEFS_H_
+
+#define DEBUG_INFORMATION_VERBOSE 1  // <--- change this to control debug info
+
+#if DEBUG_INFORMATION_VERBOSE == 1
+# include "Wireless/Wireless.h"
+# define PRINTF(args, ...) serr->printf(args, ## __VA_ARGS__)
+#else
+# define PRINTF(args, ...)
+#endif
+
+#define SGN(a)		(((a)<0) ? -1 : 1)
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/MapBuilder.cc ./DualCoding/MapBuilder.cc
--- ../Tekkotsu_2.4.1/DualCoding/MapBuilder.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/MapBuilder.cc	2006-10-03 19:26:06.000000000 -0400
@@ -0,0 +1,1019 @@
+//-*-c++-*-
+#include "Events/EventRouter.h"
+#include "Events/LookoutEvents.h"
+#include "Events/TextMsgEvent.h"
+#include "Motion/HeadPointerMC.h"
+#include "Shared/mathutils.h"
+#include "Shared/newmat/newmat.h"
+
+#include "Measures.h"
+#include "EllipseData.h"    // for extractEllipses
+#include "SphereData.h"     // for extractSpheres
+#include "BlobData.h"       // for extractSpheres
+#include "PolygonData.h"   // for extractPolygons
+#include "ShapeRoot.h"
+#include "ShapeLine.h"
+#include "ShapeEllipse.h"
+#include "ShapeBlob.h"
+#include "ShapePolygon.h"
+#include "Sketch.h"    // for NEW_SKETCH
+#include "visops.h"
+#include "VRmixin.h"
+
+#include "MapBuilder.h"
+#include "Lookout.h"
+
+namespace DualCoding {
+
+typedef map<ShapeType_t,set<int> > colorMap;
+
+inline float distSq(const NEWMAT::ColumnVector& vec) {
+  return vec(1)*vec(1) + vec(2)*vec(2) + vec(3)*vec(3);
+}
+
+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),
+  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),
+  nextGazePoint() {}
+
+void MapBuilder::DoStart() {
+  cout << "MapBuilder::DoStart()\n";
+  BehaviorBase::DoStart();
+  erouter->addListener(this,EventBase::textmsgEGID);
+}
+
+/*
+  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
+*/
+void MapBuilder::DoStop() {
+  cout << "MapBuilder::DoStop()\n";
+  while(!requests.empty()) {
+    delete requests.front();
+    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;
+}
+
+void MapBuilder::executeRequest() {
+  if ( requests.empty() || curReq != NULL ) 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();
+  }
+}
+  
+void MapBuilder::processEvent(const EventBase &e) {
+  cout << "MapBuilder::processEvent got " << e.getDescription() << endl;
+  switch ( e.getGeneratorID() ) {
+  case EventBase::textmsgEGID: {
+    const TextMsgEvent &txtev = dynamic_cast<const TextMsgEvent&>(e);
+    if ( strcmp(txtev.getText().c_str(),"MoveHead") == 0 )
+      moveToNextGazePoint(true);
+    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) {
+      const vector<Point>& pts = dynamic_cast<const LookoutScanEvent*>(&e)->getTasks().front()->data;
+      cur->gazePts.insert(cur->gazePts.end(),pts.begin(), pts.end());
+    }
+    else
+      cout << "MapBuilder::processEvent(): unknown event " << e.getDescription()
+	   << "   pointAtID=" << pointAtID << endl;
+    
+    if ( requestExitTest() || !determineNextGazePoint() )
+      requestComplete();
+    else
+      moveToNextGazePoint();
+    break;
+  default:
+    cout << "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);
+  getCameraShapes(camFrame);
+  projectToGround(camToBase);
+  filterGroundShapes(baseToCam);
+}
+
+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
+    return b;
+  }
+  else
+    return determineNextGazePoint(cur->ShS.allShapes()) || determineNextGazePoint(cur->gazePts);
+}
+  
+bool MapBuilder::determineNextGazePoint(const vector<ShapeRoot>& shapes) {
+  const LocalMapRequest *locReq = dynamic_cast<const LocalMapRequest*>(curReq);
+  if ( locReq == NULL || ! locReq->pursueShapes )
+    return false;
+  HeadPointerMC headpointer_mc;
+  for (vector<ShapeRoot>::const_iterator it = shapes.begin();
+       it != shapes.end(); it++) {
+    // look for invalid endpoints of lines / polygons
+    if ((*it)->isType(lineDataType) || (*it)->isType(polygonDataType)) {
+      const Shape<LineData>& ld = ShapeRootTypeConst(*it,LineData);
+      const Shape<PolygonData>& pd = ShapeRootTypeConst(*it,PolygonData);
+      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]) 
+	    && badGazePoints.end() == find(badGazePoints.begin(), badGazePoints.end(), (Point) p[i])) {
+	  cout << "take snap 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()))
+	    badGazePoints.push_back((Point)p[i]);
+	  nextGazePoint = p[i];
+	  return true;
+	}
+      }
+    }
+    // look for shapes w/ <2 confidence
+    if ((!(*it)->isType(agentDataType)) &&
+	(*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()	 
+	   << " (confidence level: " << (*it)->getConfidence() << ")" << endl;      
+      cout << " at " << pt << endl;  
+      if (! headpointer_mc.lookAtPoint(pt.coordX(),pt.coordY(),pt.coordZ()))
+	badGazePoints.push_back(pt);
+      nextGazePoint = pt;
+      return true;
+    }
+    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;
+  }
+  /*
+  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;
+}
+
+void MapBuilder::moveToNextGazePoint(const bool manualOverride) {
+  if ( curReq == NULL ) {
+    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 ) {
+    cout << "To proceed to this gaze point:  !msg MoveHead" << endl;
+    return;
+  }
+  storeImageAt(nextGazePoint);
+}
+
+
+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);
+}
+
+void MapBuilder::storeImageAt(const Point& pt) { 
+  pointAtID = VRmixin::lookout.executeRequest(StoreImageAtRequest(pt));
+  cout << "MapBuilder sent new storeImageAt request; pointAtID=" << pointAtID << endl;
+}
+
+void MapBuilder::storeImage() { 
+  pointAtID = VRmixin::lookout.executeRequest(StoreImageRequest());
+  cout << "MapBuilder sent new storeImage request; pointAtID=" << pointAtID << endl;
+}
+
+void MapBuilder::scan(ScanRequest& req) {
+  set<int> colors;
+  for (colorMap::const_iterator it1 = curReq->objectColors.begin();
+       it1 != curReq->objectColors.end(); it1++)
+    for (set<int>::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);
+}
+
+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);
+}
+
+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);
+}
+
+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
+    return false;
+}
+
+void MapBuilder::requestComplete() {
+  const unsigned int reqID = curReq->requestID;
+  cout << "MapBuilderRequest " << reqID << " complete\n";
+  delete curReq;
+  curReq = NULL;
+  requests.pop();
+  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
+}
+
+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};
+  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};
+  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) {
+  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);
+}
+
+void MapBuilder::importLocalToWorld() {
+  if (!agentAtOrigin) {
+    world.ShS.applyTransform(worldToLocalTranslateMatrix);
+    world.ShS.applyTransform(worldToLocalRotateMatrix);
+  }
+  matchSrcToDst(local.ShS, world.ShS);
+  if (!agentAtOrigin)
+    world.ShS.applyTransform(localToWorldMatrix);
+}
+
+
+void MapBuilder::importWorldToLocal(const ShapeRoot &worldShape) {
+  ShapeRoot localShape(local.ShS.importShape(worldShape));
+  localShape->applyTransform(worldToLocalTranslateMatrix);
+  localShape->applyTransform(worldToLocalRotateMatrix);
+}
+
+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;
+  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
+}
+
+bool MapBuilder::isLineVisible(const LineData& ln, const NEWMAT::Matrix& baseToCam) {
+  float normX1,normX2,normY1,normY2;
+  NEWMAT::ColumnVector camCoords(4);
+  camCoords = baseToCam*ln.end1Pt().coords;
+  config->vision.computePixel(camCoords(1),camCoords(2),camCoords(3),normX1,normY1);
+  camCoords = baseToCam*ln.end2Pt().coords;
+  config->vision.computePixel(camCoords(1),camCoords(2),camCoords(3),normX2,normY2);
+  const bool end1Pt_visible = fabs(normX1) < 0.9 && fabs(normY1) < 0.9;
+  const bool end2Pt_visible = fabs(normX2) < 0.9 && fabs(normY2) < 0.9;
+  if (end1Pt_visible && end2Pt_visible)
+    return true;
+  LineData lnCam(VRmixin::groundShS, Point(normX1,normY1), Point(normX2,normY2));
+  // define bounding box of camera frame in terms of normalized coordinates with 10% offset
+  LineData camBounds[] = {LineData(VRmixin::groundShS, Point(0.9,0.9),Point(0.9,-0.9)),
+			  LineData(VRmixin::groundShS, Point(0.9,-0.9),Point(-0.9,-0.9)),
+			  LineData(VRmixin::groundShS, Point(-0.9,-0.9),Point(-0.9,0.9)),
+			  LineData(VRmixin::groundShS, Point(-0.9,0.9),Point(0.9,0.9))};
+  unsigned int ptCount = 0;
+  Point p[2];
+  // find if a portion of the line shows up in cam
+  if (end1Pt_visible) p[ptCount++].setCoords(normX1,normY1,0); // end1Pt in frame
+  else if (end2Pt_visible) p[ptCount++].setCoords(normX2,normY2,0); // end2Pt in frame
+  for (int i = 0; i < 4; i++)
+    if (camBounds[i].intersectsLine(lnCam)) {
+      p[ptCount++].setCoords(lnCam.intersectionWithLine(camBounds[i]));
+      // Let's say portion of line seen in cam should be longer than .1 normalized
+      if (ptCount > 1)
+	return p[0].distanceFrom(p[1]) > 0.1; 
+    }
+  return false;
+}
+
+bool MapBuilder::isShapeVisible(const ShapeRoot &ground_shape, const NEWMAT::Matrix& baseToCam,
+				   float maxDistanceSq) {
+  if (ground_shape->isType(lineDataType))
+    return isLineVisible(ShapeRootTypeConst(ground_shape,LineData).getData(), baseToCam);
+  else if (ground_shape->isType(polygonDataType)) {
+    const Shape<PolygonData>& polygon = ShapeRootTypeConst(ground_shape,PolygonData);
+    for (vector<LineData>::const_iterator edge_it = polygon->getEdges().begin();
+	 edge_it != polygon->getEdges().end(); edge_it++)
+      if (isLineVisible(*edge_it,baseToCam))
+	return true;
+    return false;
+  }
+  else 
+    return isPointVisible(ground_shape->getCentroid(), baseToCam, maxDistanceSq);
+}
+
+
+// filter "bad" ground shapes before importing to dst shape space.
+// 1. ignore shapes too far from dog or projected to the other side of cam plane
+// 2. chop off line at max distance if it is extending beyond the distance and leave the endpoint invalid
+void MapBuilder::filterGroundShapes(const NEWMAT::Matrix& baseToCam) {
+  //  cout << "MapBuilder::filterGroundShapes()" << endl;
+  vector<ShapeRoot> ground_shapes = groundShS.allShapes();
+
+  for (vector<ShapeRoot>::iterator ground_it = ground_shapes.begin();
+       ground_it != ground_shapes.end(); ground_it++ ) {
+    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";
+      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";
+      ground_it->deleteShape();
+    }
+    // if a line is extending to maxDistance, chop it off at maxdistance and mark the endpoint invalid
+    else if ((*ground_it)->isType(lineDataType)) {
+      const Shape<LineData>& line = ShapeRootTypeConst(*ground_it,LineData);
+      const coordinate_t e1x = line->end1Pt().coordX();
+      const coordinate_t e1y = line->end1Pt().coordY();
+      const coordinate_t e2x = line->end2Pt().coordX();
+      const coordinate_t e2y = line->end2Pt().coordY();
+      if (e1x*e1x + e1y*e1y > maxDistSq && e2x*e2x + e2y*e2y > maxDistSq)
+	ground_it->deleteShape();
+      else if (e1x*e1x + e1y*e1y > maxDistSq || e2x*e2x + e2y*e2y > maxDistSq) {
+	//	cout << (*ground_it)->getId() << "(lastMatch " << (*ground_it)->getLastMatchId() 
+	//	     << ")  extends beyond maximum distance we want. Chop off the line" << endl;
+	vector<float> line_abc = line->lineEquation_abc();
+	Point pt;
+	const EndPoint* far_ept = (e1x*e1x + e1y*e1y > maxDistSq) ? &line->end1Pt() : &line->end2Pt(); 
+      	if (line_abc[1] == 0.0) {
+	  const coordinate_t y_abs = sqrt(maxDistSq - line_abc[2]*line_abc[2]);
+	  if (fabs(far_ept->coordY()-y_abs) < fabs(far_ept->coordY()+y_abs))
+	    pt.setCoords(e1x, y_abs, far_ept->coordZ());
+	  else
+	    pt.setCoords(e1x, -y_abs, far_ept->coordZ());
+	}
+	else {
+	  const float a = - line_abc[0]/line_abc[1];
+	  const float b = line_abc[2]/line_abc[1];
+	  const coordinate_t x1 = (sqrt((a*a+1.0)*maxDistSq-b*b)-a*b)/(a*a+1.0);
+	  const coordinate_t x2 = (-sqrt((a*a+1.0)*maxDistSq-b*b)-a*b)/(a*a+1.0);
+	  if (fabs(far_ept->coordX()-x1) < fabs(far_ept->coordX()-x2))
+	    pt.setCoords(x1, a*x1+b, far_ept->coordZ());
+	  else
+	    pt.setCoords(x2, a*x2+b, far_ept->coordZ());
+	}
+	EndPoint temp_endPt(pt);
+	temp_endPt.setValid(false);
+	//	cout << " (" << far_ept->coordX() << "," << far_ept->coordY() << ") => ("
+	//	     << pt.coordX() << "," << pt.coordY() << ")" << endl;
+	if (e1x*e1x + e1y*e1y > maxDistSq)
+	  line->setEndPts(temp_endPt, line->end2Pt());
+	else
+	  line->setEndPts(line->end1Pt(), temp_endPt);
+	badGazePoints.push_back(pt);
+      }
+    }
+  }
+}
+
+void MapBuilder::calculateGroundPlane(const MapBuilderRequest::GroundPlaneAssumption_t& gpa) {
+  switch(gpa) {
+  case MapBuilderRequest::onLegs:
+    ground_plane << kine->calculateGroundPlane(); 
+    cout << "Neck pan = " << state->outputs[HeadOffset+PanOffset] << endl;
+    cout << "Calculated ground plane: " << NEWMAT::printmat(ground_plane) << endl;
+    break;
+  case MapBuilderRequest::onStand:
+#ifdef TGT_ERS210
+    ground_plane << 0 << 0 << (float)(-1/200.0) << 1;
+#else
+    ground_plane << 0 << 0 << (float)(-1/170.0) << 1; //for the order-made stands for ERS7 in the lab
+#endif
+    // cout << "Hard-coded ground plane: " << NEWMAT::printmat(ground_plane) << endl;
+    break;
+  };
+}
+
+void MapBuilder::projectToGround(const NEWMAT::Matrix& camToBase) {
+  VRmixin::projectToGround(camToBase, ground_plane);
+}
+    
+
+void MapBuilder::matchSrcToDst(ShapeSpace &srcShS, ShapeSpace &dstShS,
+				  set<int> polCols, bool mergeSrc, bool mergeDst) {
+  vector<ShapeRoot> src_shapes = srcShS.allShapes();
+  vector<ShapeRoot> dst_shapes = dstShS.allShapes();
+  vector<LineData> polygon_edges;
+  
+  // clean up src_shapes before messing with dst space
+  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;
+      (*src_it)->printParams();
+      src_shapes.erase(src_it--);
+    }
+    else if ((*src_it)->isType(polygonDataType)) { 
+      const vector<LineData>& lines = ShapeRootTypeConst(*src_it, PolygonData)->getEdges();
+      polygon_edges.insert(polygon_edges.end(), lines.begin(), lines.end());
+      src_shapes.erase(src_it--);
+    }
+    else if ((*src_it)->isType(lineDataType)) {
+      const int 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--);
+      }
+    }
+  }
+
+  // merge shapes inside srcShS
+  if (mergeSrc)
+    for ( vector<ShapeRoot>::iterator it = src_shapes.begin();
+	  it != src_shapes.end(); it++ )
+      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;
+	  src_shapes.erase(it2--);
+	}
+
+  vector<Shape<PolygonData> > existingPolygons;
+  // update dst shapes from src shapes
+  for (vector<ShapeRoot>::iterator dst_it = dst_shapes.begin();
+       dst_it != dst_shapes.end(); dst_it++ )
+    if ((*dst_it)->isType(polygonDataType))
+      existingPolygons.push_back(ShapeRootType(*dst_it,PolygonData));
+    else {
+      for (vector<ShapeRoot>::iterator src_it = src_shapes.begin();
+	   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;
+	  src_shapes.erase(src_it--);
+	}
+    }
+  
+  // form polygons from lines and import unmatched src shapes into dstShS
+  vector<ShapeRoot> deletedPolygons;
+  //  cout << existingPolygons.size() << " polygons\n";
+  vector<ShapeRoot> newPolygons = PolygonData::formPolygons(polygon_edges,existingPolygons,deletedPolygons);
+  //  cout << existingPolygons.size()+deletedPolygons.size() << " polygons\n";
+  for (vector<ShapeRoot>::iterator delete_it = deletedPolygons.begin();
+       delete_it != deletedPolygons.end(); delete_it++)
+    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";
+  
+  // match shapes inside dstShS
+  if (mergeDst) {
+    dst_shapes = dstShS.allShapes();
+    for ( vector<ShapeRoot>::iterator it = dst_shapes.begin();
+	  it < dst_shapes.end(); it++ )
+      for ( vector<ShapeRoot>::iterator it2 = it+1;
+	    it2 < dst_shapes.end(); it2++)
+	if ((*it2)->isMatchFor(*it) && (*it)->updateParams(*it2,true)) {
+	  // cout << "Matched src shape " << (*it)->getId() << " (lastMatch " 
+	  //  << (*it)->getLastMatchId()<< ") is a match for " 
+	  //   << (*it2)->getId() << " (lastMatch " 
+	  //   << (*it2)->getLastMatchId() << "), delete\n";
+	  it2->deleteShape();
+	  dst_shapes.erase(it2--);
+	}
+  }
+}
+
+// decrease confidence of those shapes 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();
+  for (vector<ShapeRoot>::iterator it = shapes.begin();
+       it != shapes.end(); it++ ) {
+    // was not looking for this object in the last snap, 
+    // and it's not fair to decrease this guy's confidence
+    if (curReq->objectColors[(*it)->getType()].find(ProjectInterface::getColorIndex((*it)->getColor())) ==
+	curReq->objectColors[(*it)->getType()].end())
+      continue; 
+    if ((*it)->isType(polygonDataType)) {
+      Shape<PolygonData>& polygon = ShapeRootType(*it,PolygonData);
+      vector<LineData>& edges = polygon->getEdgesRW();
+      unsigned int edge_index = 0;
+      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;
+	  edge_it->decreaseConfidence();
+	}
+      }
+      vector<ShapeRoot> brokenPolygons = polygon->updateState();
+      ShS.importShapes(brokenPolygons);
+      if (!polygon->isAdmissible()) {
+	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();
+      }
+    }
+  }
+}
+
+//================ 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;
+    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));
+
+  // 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));
+
+  // 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;
+
+  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));
+}
+
+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--);
+    }
+  }
+  // cout << num_points_seen << " pre-defined gaze points seen in last snap, "
+  //      << gazePts.size() << " left\n";
+}
+
+
+//================================================================
+
+//Prints shapespace in the format to be used for particle filter on simulator
+void MapBuilder::printShS(ShapeSpace &ShS) const {
+  cout << "MapBuilder::printShS()" << endl;
+  unsigned int line_count = 0;
+  vector<ShapeRoot> shapes = ShS.allShapes();
+  for (vector<ShapeRoot>::const_iterator it = shapes.begin();
+       it != shapes.end(); it++) {
+    if ((*it)->isType(lineDataType)) {
+      const Shape<LineData>& ld = ShapeRootTypeConst(*it,LineData);
+      cout << (*it)->getId() << " " << lineDataType << " " 
+	   << ProjectInterface::getColorIndex((*it)->getColor()) 
+	   << " " << ld->end1Pt().coordX()  << " " << ld->end1Pt().coordY()
+	   << " " << ++line_count << " " << ld->getLength() << " " << ld->end1Pt().isValid() << endl; 
+      cout << (*it)->getId() << " " << lineDataType << " " 
+	   << ProjectInterface::getColorIndex((*it)->getColor()) 
+	   << " " << ld->end2Pt().coordX()  << " " << ld->end2Pt().coordY()
+	   << " " << line_count << " " << ld->getLength() << " " << ld->end2Pt().isValid() << endl;
+    }
+    else {
+      cout << (*it)->getId() << " " << (*it)->getType() << " " 
+	   << ProjectInterface::getColorIndex((*it)->getColor()) 
+	   << " " << (*it)->getCentroid().coordX()  << " " << (*it)->getCentroid().coordY() << endl;
+    }
+  }
+}
+
+
+//================ Shape extraction ================
+
+
+void MapBuilder::getCameraShapes(const Sketch<uchar>& camFrame) { 
+  camShS.clear();
+  getCamLines(camFrame, curReq->objectColors[lineDataType], curReq->occluderColors[lineDataType]);
+  getCamEllipses(camFrame, curReq->objectColors[ellipseDataType], curReq->occluderColors[ellipseDataType]);
+  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]);
+}
+
+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;
+  NEW_SKETCH_N(occluders,bool,visops::zeros(camFrame));
+  for ( set<int>::const_iterator it = occluderColors.begin();
+	it != occluderColors.end(); it++ )
+    occluders |= visops::minArea(visops::colormask(camFrame,*it));
+
+  for (set<int>::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;
+  }
+  return lines;
+}
+
+vector<Shape<EllipseData> > 
+MapBuilder::getCamEllipses(const Sketch<uchar> &camFrame,
+			      const set<int>& objectColors, const set<int>& ) const {
+  vector<Shape<EllipseData> > ellipses;
+  if (objectColors.empty())
+    return ellipses;
+  cout << "*** Find the ellipses ***" << endl;
+  for (set<int>::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;
+  }
+  return ellipses;
+}
+
+vector<Shape<PolygonData> > 
+MapBuilder::getCamPolygons(const Sketch<uchar> &camFrame,
+			      const set<int>& objectColors, const set<int>& occluderColors) const {
+  vector<Shape<PolygonData> > polygons;
+  if ( objectColors.empty() ) 
+    return polygons;
+  cout << "*** Find the polygons ***" << endl;
+  NEW_SKETCH_N(occluders,bool,visops::zeros(camFrame));
+  for ( set<int>::const_iterator it = occluderColors.begin();
+	it !=occluderColors.end(); it++ )
+    occluders |= visops::colormask(camFrame,*it);
+  
+  for (set<int>::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));
+    NEW_SKETCH_N(skel,bool,visops::skel(fatmask));
+    NEW_SKETCH_N(fatskel,bool,visops::fillin(skel,1,2,8));
+    
+    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;
+  }
+  return polygons;
+}
+
+vector<Shape<SphereData> > 
+MapBuilder::getCamSpheres(const Sketch<uchar> &camFrame,
+			     const set<int>& objectColors, const set<int>& ) const {
+  vector<Shape<SphereData> > spheres;
+  if ( objectColors.empty() )
+    return spheres;
+  cout << "*** Find the spheres ***" << endl;
+  for (set<int>::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);
+    spheres.insert(spheres.end(), spheres.begin(), spheres.end());
+    cout << "Found " << sphere_shapes.size() << " spheres." << endl;
+  }
+  return spheres;
+}
+
+vector<Shape<LineData> > 
+MapBuilder::getCamWalls(const Sketch<uchar> &camFrame, unsigned int floorColor) const {
+  if (floorColor == 0)
+    return vector<Shape<LineData> >();
+  cout << "*** Find the walls ***" << endl;
+  const int camFrame_offset = 8;
+
+  NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,floorColor));
+  NEW_SKETCH_N(fillinmask ,bool,visops::fillin(colormask, 1, 6, 8)); //remove pixels w/ connectivity<6 (noise)
+  NEW_SKETCH_N(fillinmask2 ,bool,visops::fillin(fillinmask, 2, 3, 8)); //remove pixels w/ connectivity<3 and fill in the others
+  NEW_SKETCH_N(edgemask ,bool,visops::fillin(fillinmask2, 1, 5, 7)); //remove pixels w/ connectivity=8 (non-edge pixels)
+  NEW_SKETCH_N(edgemask2 ,bool,visops::non_bounds(edgemask, camFrame_offset)); //remove pixels close to cam_bound
+
+  NEW_SKETCH_N(occluders_floor, bool, camFrame != uchar(0) & camFrame != uchar(floorColor));
+  NEW_SKETCH_N(occ_mask ,bool,visops::fillin(occluders_floor, 1, 8, 8)); //remove pixels w/ connectivity<7 (noises)
+  usint const clear_dist = 15;
+  Sketch<bool> not_too_close = (visops::edist(occ_mask) >= clear_dist); 
+  edgemask2 &= not_too_close; //remove pixels around occuluders
+  
+  NEW_SKETCH_N(fatmask ,bool,visops::fillin(edgemask2,2,2,8)); //make the remaining pixels fat
+  NEW_SKETCH_N(skel,bool,visops::skel(fatmask));
+  NEW_SKETCH_N(fatskel,bool,visops::fillin(skel,1,2,8));
+  
+  vector<Shape<LineData> > wall_bounds = PolygonData::extractPolygonEdges(fatskel,fatmask|occluders_floor);
+
+  // larger offset from the cam frame should be applied to these lines
+  // since all pixels near cam frame bounds are removed before extracting these lines.
+  for (vector<Shape<LineData> >::iterator it = wall_bounds.begin();
+       it != wall_bounds.end(); it++) {
+    if (((*it)->end1Pt().coordX() < camFrame_offset*2.0 || (*it)->end1Pt().coordX() > xres - camFrame_offset*2.0
+	 || (*it)->end1Pt().coordY() < camFrame_offset*2.0 || (*it)->end1Pt().coordY() > yres - camFrame_offset*2.0)
+	&& (*it)->end1Pt().isValid())
+      (*it)->end1Pt().setValid(false);
+    if (((*it)->end2Pt().coordX() < camFrame_offset*2.0 || (*it)->end2Pt().coordX() > xres - camFrame_offset*2.0
+	 || (*it)->end2Pt().coordY() < camFrame_offset*2.0 || (*it)->end2Pt().coordY() > yres - camFrame_offset*2.0)
+	&& (*it)->end2Pt().isValid())
+      (*it)->end2Pt().setValid(false);
+  }
+  
+  cout << "Found " << wall_bounds.size() << " wall boundary lines" << endl;
+  return wall_bounds;
+}
+
+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();
+       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()) ? 
+      0 : curReq->minBlobAreas[*it];
+    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;
+  }
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/MapBuilder.h ./DualCoding/MapBuilder.h
--- ../Tekkotsu_2.4.1/DualCoding/MapBuilder.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/MapBuilder.h	2006-10-02 18:50:38.000000000 -0400
@@ -0,0 +1,299 @@
+//-*-c++-*-
+#ifndef _MapBuilder_h_
+#define _MapBuilder_h_
+
+#include <queue>
+
+#include "Behaviors/BehaviorBase.h"
+#include "Shared/newmat/newmat.h"
+
+#include "BlobData.h"
+#include "LineData.h"
+#include "Point.h"
+#include "VRmixin.h"
+#include "LookoutRequests.h"
+#include "MapBuilderRequests.h"
+#include "SketchTypes.h"
+#include "ShapeSpace.h"
+
+namespace DualCoding {
+
+class SketchSpace;
+class ScanRequest;
+
+class MapBuilder : public BehaviorBase {
+protected:
+  SketchSpace &camSkS;
+  ShapeSpace &camShS, &groundShS;
+
+  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
+
+protected:
+  Shape<AgentData> &theAgent; //!< agent in the world frame
+   //! trasformation 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.
+
+  queue<MapBuilderRequest*> requests;
+  MapBuilderRequest *curReq;
+  unsigned int idCounter;
+  
+  unsigned int maxDistSq; //!< sqrt 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
+  void executeRequest();
+  //! calls exitTest of current request if there is one and returns the result
+  bool requestExitTest();
+
+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);
+
+  void processImage(const Sketch<uchar>&, const NEWMAT::Matrix& camToBase, const NEWMAT::Matrix& baseToCam);
+
+  // returns 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
+  const Shape<AgentData>& getAgent() const { return theAgent; }
+
+  // sets the agent location and heading
+  void setAgent(const Point &location, const AngTwoPi heading);
+  
+  // 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();
+    if (&ShS == &camShS || &ShS == &groundShS || minConf <= 0) 
+      return allShapes;
+    vector<ShapeRoot> nonNoiseShapes;
+    for (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; }
+  //}@
+
+  //!@ 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);
+  }
+  //}@
+
+  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()));
+  }
+
+  void importLocalToWorld();
+  void importWorldToLocal(const ShapeRoot &shape);
+  // matching shapes between two spaces.
+  static void matchSrcToDst(ShapeSpace &src, ShapeSpace &dst, set<int> polygonEdgeColors=set<int>(),
+			    bool mergeSrc=true, bool mergeDst=true);
+
+protected:
+  //! functions to make requests to lookout
+  void scan(ScanRequest& req);
+  void storeImageAt(const Point& pt);
+  void storeImage();
+
+  //! 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 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);
+  
+  //! 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);
+  //! Starts robot moving to the next gaze point
+  void moveToNextGazePoint(const bool manualOverride=false);
+
+  // 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);
+
+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.
+
+*/
+
+} // namespace
+
+#endif
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/MapBuilderRequests.h ./DualCoding/MapBuilderRequests.h
--- ../Tekkotsu_2.4.1/DualCoding/MapBuilderRequests.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/MapBuilderRequests.h	2006-09-23 23:44:30.000000000 -0400
@@ -0,0 +1,202 @@
+//-*-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_2.4.1/DualCoding/Measures.cc ./DualCoding/Measures.cc
--- ../Tekkotsu_2.4.1/DualCoding/Measures.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Measures.cc	2006-03-21 16:03:48.000000000 -0500
@@ -0,0 +1,72 @@
+#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_2.4.1/DualCoding/Measures.h ./DualCoding/Measures.h
--- ../Tekkotsu_2.4.1/DualCoding/Measures.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Measures.h	2006-09-21 18:58:57.000000000 -0400
@@ -0,0 +1,83 @@
+#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_2.4.1/DualCoding/Particle.cc ./DualCoding/Particle.cc
--- ../Tekkotsu_2.4.1/DualCoding/Particle.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Particle.cc	2006-05-10 19:21:57.000000000 -0400
@@ -0,0 +1,26 @@
+//-*-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_2.4.1/DualCoding/Particle.h ./DualCoding/Particle.h
--- ../Tekkotsu_2.4.1/DualCoding/Particle.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Particle.h	2006-05-10 19:21:57.000000000 -0400
@@ -0,0 +1,36 @@
+//-*-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_2.4.1/DualCoding/ParticleFilter.cc ./DualCoding/ParticleFilter.cc
--- ../Tekkotsu_2.4.1/DualCoding/ParticleFilter.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ParticleFilter.cc	2006-10-02 17:54:56.000000000 -0400
@@ -0,0 +1,406 @@
+//-*-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_2.4.1/DualCoding/ParticleFilter.h ./DualCoding/ParticleFilter.h
--- ../Tekkotsu_2.4.1/DualCoding/ParticleFilter.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ParticleFilter.h	2006-10-02 17:56:29.000000000 -0400
@@ -0,0 +1,159 @@
+//-*-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_2.4.1/DualCoding/ParticleShapes.cc ./DualCoding/ParticleShapes.cc
--- ../Tekkotsu_2.4.1/DualCoding/ParticleShapes.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ParticleShapes.cc	2006-10-02 17:54:56.000000000 -0400
@@ -0,0 +1,150 @@
+//-*-c++-*-
+
+#include <iostream>
+#include <vector>
+#include <fstream>
+
+#include "ShapeRoot.h"
+#include "ShapeLine.h"
+#include "ShapeEllipse.h"
+#include "ShapeBlob.h"
+#include "ShapePoint.h"
+
+#include "ParticleShapes.h"
+
+using namespace std;
+
+namespace DualCoding {
+
+vector<PfRoot*>* PfRoot::loadLms(const vector<ShapeRoot> &lms, bool isWorld){
+  int id;
+  int type;
+  rgb color;
+  vector<PfRoot*> *landmarks = new vector<PfRoot*>(2*lms.size(),(PfRoot*)NULL);
+  landmarks->clear();
+  for (unsigned int i = 0; i<lms.size(); i++){
+    type = lms[i]->getType();
+    color = lms[i]->getColor();
+    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(), 
+				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);
+      if ( isWorld ) {
+	PfLine *land2 = new PfLine(id, color, 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);
+      }
+    }
+    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());
+      land->link = &lms[i];
+      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());
+      land->link = &lms[i];
+      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());
+      land->link = &lms[i];
+      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::findBounds(const vector<PfRoot*> &landmarks, 
+			 coordinate_t &xmin, coordinate_t &ymin,
+			 coordinate_t &xmax, coordinate_t &ymax) {
+  if ( landmarks.size() == 0 ) {  // should never get here
+    cout << "Error in PFRoot::findBounds -- empty landmark vector" << endl;
+    return;
+  }
+  xmin = xmax = landmarks[0]->x;
+  ymin = ymax = landmarks[0]->y;
+  for ( size_t i = 1; i<landmarks.size(); i++ ) {
+    if ( (*landmarks[i]).x < xmin )
+      xmin = landmarks[i]->x;
+    else if  ( landmarks[i]->x > xmax )
+      xmax = landmarks[i]->x;
+    if ( landmarks[i]->y < ymin )
+      ymin = landmarks[i]->y;
+    else if  ( landmarks[i]->y > ymax )
+      ymax = landmarks[i]->y;
+  }
+}
+
+void PfRoot::printLms(const vector<PfRoot*> &landmarks) {
+  for (unsigned int i = 0; i<landmarks.size(); i++)
+    cout << *landmarks[i] << endl;
+}
+
+void PfRoot::printRootInfo(ostream &os) const {
+    os << "id=" << id
+       << ", x=" << x
+       << ", y=" << y;
+  }
+
+ostream& operator<<(ostream &os, const PfRoot &obj) {
+  obj.print(os);
+  return os;
+}
+
+void PfLine::print(ostream &os) const {
+  os << "PfLine(";
+  printRootInfo(os);
+  os << ", x2=" << x2
+     << ", y2=" << y2
+     << ", length=" << length
+     << ")";
+}
+
+void PfEllipse::print(ostream &os) const {
+  os << "PfEllipse(";
+  printRootInfo(os);
+  os << ")";
+}
+
+void PfPoint::print(ostream &os) const {
+  os << "PfPoint(";
+  printRootInfo(os);
+  os << ")";
+}
+
+void PfBlob::print(ostream &os) const {
+  os << "PfBlob(";
+  printRootInfo(os);
+  os << ")";
+}
+
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ParticleShapes.h ./DualCoding/ParticleShapes.h
--- ../Tekkotsu_2.4.1/DualCoding/ParticleShapes.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ParticleShapes.h	2006-05-10 19:21:57.000000000 -0400
@@ -0,0 +1,95 @@
+//-*-c++-*-
+#ifndef LOADED_ParticleShapes_h
+#define LOADED_ParticleShapes_h
+
+#include <vector>
+#include <string>
+
+#include "Vision/colors.h"
+
+#include "Measures.h"     // coordinate_t
+#include "ShapeRoot.h"
+
+namespace DualCoding {
+
+//! Root class for the particle filter landmark classes.
+class PfRoot {
+ public:
+  int type;
+  int id;
+  rgb color;
+  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) {}
+    
+  virtual ~PfRoot() {} //!< destructor, doesn't delete #link
+
+  virtual void print(ostream &os) const = 0;
+
+  void printRootInfo(ostream &os) const;
+
+  static vector<PfRoot*>* loadLms(const vector<ShapeRoot> &lms, bool isWorld);
+
+  static void deleteLms(vector<PfRoot*> *vec);
+
+  static void findBounds(const vector<PfRoot*> &map, 
+			 coordinate_t &xmin, coordinate_t &ymin,
+			 coordinate_t &xmax, coordinate_t &ymax);
+  
+  static void printLms(const vector<PfRoot*> &lmvec);
+
+private:
+  PfRoot(const PfRoot&); //!< don't call this
+  PfRoot& operator=(const PfRoot&); //!< don't call this
+};
+
+//! A line landmark; world lines will have two of these, with the endpoints switched
+class PfLine : public PfRoot {
+public:
+  coordinate_t x2, y2;
+  bool valid1, valid2;
+  AngPi orientation;
+  float length;
+
+  PfLine(int _id, rgb _color, coordinate_t _x, coordinate_t _y, 
+	 coordinate_t _x2, coordinate_t _y2, bool _v1, bool _v2) :
+    PfRoot(lineDataType, _id, _color, _x, _y),
+    x2(_x2), y2(_y2), valid1(_v1), valid2(_v2), orientation(0), length(0) {}
+
+  virtual void print(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) {}
+
+  virtual void print(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) {}
+
+  virtual void print(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) {}
+
+  virtual void print(ostream &os) const;
+};
+
+ostream& operator<<(ostream &os, const PfRoot &x);
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/PathPlanner.cc ./DualCoding/PathPlanner.cc
--- ../Tekkotsu_2.4.1/DualCoding/PathPlanner.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/PathPlanner.cc	2006-05-19 14:01:11.000000000 -0400
@@ -0,0 +1,356 @@
+//-*-c++-*-
+#include "PathPlanner.h"
+#include "Shared/ProjectInterface.h"
+#include <iostream>
+#include <ctime>
+#include <vector>
+#include <queue>
+#include <map>
+#include <math.h>
+
+using namespace std;
+
+namespace DualCoding {
+
+using ProjectInterface::defSegmentedColorGenerator;
+
+PathPlanner::PathPlanner(coordinate_t xMax, coordinate_t xMin, coordinate_t yMax, coordinate_t yMin)
+  : allStates(), unreached(NULL), reached(), 
+    numX((unsigned int) ((xMax-xMin)/size)+1), numY((unsigned int) ((yMax-yMin)/size)+1), 
+    minX(xMin), minY(yMin), dX((xMax-xMin)/numX), dY((yMax-yMin)/numY), 
+    start(), goal(), maxDistance(800), costs(), 
+    startPt(), goalPt(),startOrientation(), goalOrientation(),
+    costMap(NULL), landmarks(), lmCosts(), obstacles()
+{
+  unreached = new vector<state*>[numX*numY*4];
+  costMap = new unsigned int [numX*numY];
+  // default costs; these can be modefied anytime before calling findPath()
+  costs[transF] = 1;
+  costs[transB] = 2;
+  costs[transY] = 4;
+  costs[rotate] = 3;
+  costs[noLM] = 20;
+  costs[oneLM] = 10;
+}
+
+void PathPlanner::findPath() {
+  initialize();
+  while (!reached.empty()) {
+    edge top = reached.top();
+    if (top.from != NULL && top.from->dst == NULL) { // best action not determined yet for this state
+      top.from->cost = top.cost;
+      top.from->dst = top.to;
+      vector<state*>& lms = unreached[top.from->loc.pos*4 + top.from->loc.dir];
+      for (vector<state*>::iterator it = lms.begin();
+	   it != lms.end(); it++)
+	if ((*it)->lms == top.from->lms) {
+	  lms.erase(it);
+	  break;
+	}
+      if (top.from->loc==start) {
+	cout << "best path:\n";
+	state* s = top.from;
+	while(s) {
+	  cout << toString(*s)  << endl;
+	  s = s->dst;
+	}
+	cout << endl;
+	break;
+      }
+      else
+	findLinks(*top.from);
+    }
+    reached.pop();
+  }
+  cout << "done: " << reached.empty() << endl;
+}
+
+void PathPlanner::findLinks(state& s) {
+  unsigned int newCostMotion = s.cost+lmCosts[s.lms.first]+lmCosts[s.lms.second]+1;
+  if (s.lms.first < 0)
+    if (s.lms.second < 0)
+      newCostMotion += costs[noLM];
+    else
+      newCostMotion += costs[oneLM];
+  { //translate
+    if (s.loc.pos%numY+1 < numY) // go west
+      if (state* it = thereIs(s.loc.pos+1,s.loc.dir,s.lms))
+	if (s.loc.dir==direction::E)
+	  reached.push(edge(*it,s,newCostMotion+costMap[s.loc.pos]+costs[transB]));
+	else if (s.loc.dir == direction::W)
+	  reached.push(edge(*it,s,newCostMotion+costMap[s.loc.pos]+costs[transF]));
+	else
+	  reached.push(edge(*it,s,newCostMotion+costMap[s.loc.pos]+costs[transY]));
+    if (s.loc.pos%numY > 0) // go east
+      if (state* it = thereIs(s.loc.pos-1,s.loc.dir,s.lms))
+	if (s.loc.dir==direction::E)
+	  reached.push(edge(*it,s,newCostMotion+costMap[s.loc.pos]+costs[transF]));
+	else if (s.loc.dir == direction::W)
+	  reached.push(edge(*it,s,newCostMotion+costMap[s.loc.pos]+costs[transB]));
+	else
+	  reached.push(edge(*it,s,newCostMotion+costMap[s.loc.pos]+costs[transY]));
+    if (s.loc.pos < numY*(numX-1)) // go north
+      if (state* it = thereIs(s.loc.pos+numY,s.loc.dir,s.lms))
+	if (s.loc.dir==direction::N)
+	  reached.push(edge(*it,s,newCostMotion+costMap[s.loc.pos]+costs[transF]));
+	else if (s.loc.dir == direction::S)
+	  reached.push(edge(*it,s,newCostMotion+costMap[s.loc.pos]+costs[transB]));
+	else
+	  reached.push(edge(*it,s,newCostMotion+costMap[s.loc.pos]+costs[transY]));
+    if (s.loc.pos >= numY) // go south
+      if (state* it = thereIs(s.loc.pos-numY,s.loc.dir,s.lms))
+	if (s.loc.dir==direction::N)
+	  reached.push(edge(*it,s,newCostMotion+costMap[s.loc.pos]+costs[transB]));
+	else if (s.loc.dir == direction::S)
+	  reached.push(edge(*it,s,newCostMotion+costMap[s.loc.pos]+costs[transF]));
+	else
+	  reached.push(edge(*it,s,newCostMotion+costMap[s.loc.pos]+costs[transY]));
+  }
+  { //rotate
+    const int newRotateCost = newCostMotion+costs[rotate];
+    if (state* it = thereIs(s.loc.pos,s.loc.dir.cw(),s.lms))
+      reached.push(edge(*it,s,newRotateCost+costMap[s.loc.pos]));
+    if (state* it = thereIs(s.loc.pos,s.loc.dir.ccw(),s.lms))
+      reached.push(edge(*it,s,newRotateCost+costMap[s.loc.pos]));
+  }
+  { //switch landmarks
+    vector<pair<int,int> > lms = findLMs(s.loc);
+    for (vector<pair<int,int> >::const_iterator it = lms.begin();
+	 it != lms.end(); it++)
+      if (*it != s.lms)
+	reached.push(edge(*(thereIs(s.loc.pos,s.loc.dir,*it)),s,s.cost+1));
+  }
+}
+
+
+Point PathPlanner::findWorldCoords(unsigned int pos) {
+  return Point (minX+dX*(pos/numY),minY+dY*(pos%numY),0);
+}
+
+
+void PathPlanner::computeLandmarkCosts() {
+  map<unsigned int, float> distSum; // maps id of landmark against sum of distance with other landmarks of same color
+  map<unsigned int, vector<unsigned int> > lmsSortedByColor; // maps color index against vector of idlandmarks' id having the color
+  for (map<unsigned int, PointData>::const_iterator it1 = landmarks.begin();
+       it1 != landmarks.end(); it1++) {
+    map<unsigned int, PointData>::const_iterator it2 = it1; // cannot write it2 = it1+1?
+    it2++;
+    for (; it2 != landmarks.end(); it2++)
+      if (it1->second.getColor() == it2->second.getColor()) {
+	float dist = it1->second.getCentroid().xyDistanceFrom(it2->second);
+	float cost = 10000/(dist*dist);
+	distSum[it1->first] += cost;
+	distSum[it2->first] += cost;
+      }
+    lmsSortedByColor[defSegmentedColorGenerator->getColorIndex(it1->second.getColor())].push_back(it1->first);
+  }
+  for (map<unsigned int, vector<unsigned int> >::const_iterator col_it = lmsSortedByColor.begin();
+       col_it != lmsSortedByColor.end(); col_it++)
+    for (vector<unsigned int>::const_iterator lm_it = col_it->second.begin();
+	 lm_it != col_it->second.end(); lm_it++)
+      lmCosts[*lm_it] = (unsigned int) distSum[*lm_it];
+}
+
+void PathPlanner::initialize() {
+  // set start and goal
+  float minStartDist = findWorldCoords(0).distanceFrom(startPt);
+  float minGoalDist = findWorldCoords(0).distanceFrom(goalPt);
+  unsigned int startIdx=0, goalIdx=0;
+  for (unsigned int pos = 1; pos < numX*numY; pos++) {
+    float startDist = findWorldCoords(pos).distanceFrom(startPt);
+    float goalDist = findWorldCoords(pos).distanceFrom(goalPt);
+    if (startDist < minStartDist) {
+      minStartDist = startDist;
+      startIdx = pos;
+    }
+    if (goalDist < minGoalDist) {
+      minGoalDist = goalDist;
+      goalIdx = pos;
+    }
+  }
+  start.pos = startIdx;
+  goal.pos = goalIdx;
+  
+  if (startOrientation > M_PI/4) {
+    if (startOrientation < M_PI*3/4)
+      start.dir = direction::W;
+    else if (startOrientation < M_PI*5/4)
+      start.dir = direction::S;
+    else if (startOrientation < M_PI*7/4)
+      start.dir = direction::E;
+  }
+  else
+    start.dir = direction::N;
+
+  if (goalOrientation > M_PI/4) {
+    if (goalOrientation < M_PI*3/4)
+      goal.dir = direction::W;
+    else if (goalOrientation < M_PI*5/4)
+      goal.dir = direction::S;
+    else if (goalOrientation < M_PI*7/4)
+      goal.dir = direction::E;
+  }
+  else
+    goal.dir = direction::N;
+
+
+  // initialize cost map
+  for (unsigned int pos = 0; pos < numX*numY; pos++) {
+    costMap[pos] = 0;
+    for (vector<pair<Point, unsigned int> >::const_iterator it = obstacles.begin();
+	 it != obstacles.end(); it++) {
+      Point vec = findWorldCoords(pos)-it->first;
+      float distSq = (vec.coordX()*vec.coordX() + vec.coordY()*vec.coordY())/10000; // cm^2
+      costMap[pos] += (unsigned int) ((distSq > 0) ? it->second/distSq : -1U);
+    }
+  }
+  computeLandmarkCosts();
+  cout << "costs:\n";
+  cout << " costs[transF]: " << costs[transF] << endl;
+  cout << " costs[transB]: " << costs[transB] << endl;
+  cout << " costs[transY]: " << costs[transY] << endl;
+  cout << " costs[rotate]: " << costs[rotate] << endl;
+  cout << " costs[noLM]: " << costs[noLM] << endl;
+  cout << " costs[oneLM]: " << costs[oneLM] << endl;
+  
+  cout << "landmarks:\n"; 
+  for (map<unsigned int, PointData>::const_iterator it = landmarks.begin();
+       it != landmarks.end(); it++)
+    cout<< "lm id " << it->first << " at " << it->second
+      //	<< ", color index=" << defSegmentedColorGenerator->getColorIndex(it->second.getColor())
+	<< ", cost=" << lmCosts[it->first] << endl;
+  
+  cout << "obstacles:\n";
+  for (vector<pair<Point, unsigned int> >::const_iterator it = obstacles.begin();
+       it != obstacles.end(); it++)
+    cout << " " << it->first << ": " << it->second << endl;
+
+  // print map
+  cout << "costMap:\n";
+  for (int j = numX-1; j >= 0; j--) {
+    for (int i = numY-1; i >= 0; i--)
+      if (i+j*numY == start.pos)
+	cout << " S";
+      else if (i+j*numY == goal.pos)
+	cout << " G";
+      else
+	cout << " " << costMap[i+j*numY];
+    cout << endl;
+  }
+
+  while (!reached.empty()) 
+    reached.pop();
+  for (unsigned int i = 0; i < numX*numY*4; i++)
+    unreached[i].clear();
+  while (!allStates.empty())
+    allStates.pop();
+
+  // find all possible vertices (states)
+  vector<state*> goals;
+  fillState(0,goal.pos);
+  for (unsigned int i = 0; i < 4; i++) {
+    location loc (goal.pos,i);
+    vector<pair<int,int> > lms = findLMs(loc);
+    for (vector<pair<int,int> >::const_iterator it = lms.begin();
+	 it < lms.end(); it++) {
+      allStates.push(state(loc,*it));
+      if (i == goal.dir)
+	goals.push_back(&allStates.back());
+      else
+	unreached[loc.pos*4 + loc.dir].push_back(&(allStates.back()));
+    }
+  }
+  fillState(goal.pos+1,numX*numY);
+
+  cout << "start state:\n";
+  cout << " " << findWorldCoords(start.pos) << endl;
+  //  for (vector<
+  //	 cout << " is lm 1 visible ? " << isLMVisible(start,pt) << endl;
+
+  cout << "goal state(s):\n";
+  for (vector<state*>::iterator it = goals.begin();
+       it != goals.end(); it++) {
+    (*it)->cost = 0;
+    findLinks(**it);
+    cout << " " << toString(**it) <<  " => " << findWorldCoords((*it)->loc.pos) << endl;
+  }
+}
+
+void PathPlanner::fillState(unsigned int low, unsigned int high) {
+  for (unsigned int pos = low; pos < high; pos++) {
+    for (unsigned int i = 0; i < 4; i++) {
+      location loc(pos,i);
+      vector<pair<int,int> > lms = findLMs(loc);
+      for (vector<pair<int,int> >::const_iterator it = lms.begin();
+	   it < lms.end(); it++) {
+	allStates.push(state(loc,*it));
+	unreached[loc.pos*4 + loc.dir].push_back(&(allStates.back()));
+      }
+    }
+  }
+}
+  
+PathPlanner::state* PathPlanner::thereIs(unsigned int pos, direction dir, 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();
+       it < states.end(); it++)
+    if ((*it)->lms == lms)
+      return *it;
+  return NULL;
+}
+
+
+vector<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();
+       it != landmarks.end(); it++)
+    if (isLMVisible(loc,it->second)) lms.push_back(it->first);
+  vector<pair<int,int> > lmPairs;
+  lmPairs.push_back(pair<int,int>(-1,-1));
+  for(vector<int>::const_iterator it1 = lms.begin();
+      it1 != lms.end(); it1++)
+    for(vector<int>::const_iterator it2 = it1+1;
+	it2 != lms.end(); it2++)
+      lmPairs.push_back(pair<int,int>(*it1,*it2));
+  return lmPairs;
+}
+
+bool PathPlanner::isLMVisible(location l, const Point& lm) {
+  Point agent = findWorldCoords(l.pos);
+  float dx = lm.coordX()-agent.coordX();
+  float dy = lm.coordY()-agent.coordY();
+  float distance = sqrt(dx*dx + dy*dy);
+  //  cout << "distance: " << distance << endl;
+  if (distance > maxDistance || distance < 200) return false; // too far or too close
+  AngTwoPi angle = atan2(dy,dx);
+  //  cout << "angle: " << angle << endl;
+  switch (l.dir) {
+  case direction::N: return (angle < M_PI/3 || angle > M_PI*5/3);
+  case direction::W: return (angle > M_PI/6 && angle < M_PI*5/6);
+  case direction::S: return (angle > M_PI*2/3 && angle < M_PI*4/3);
+  case direction::E: return (angle > M_PI*7/6 && angle < M_PI*11/6);
+  };
+  return false;
+}
+
+std::string PathPlanner::toString(const PathPlanner::state &s) {
+  stringstream ss;
+  ss << "[(" << (s.loc.pos/numY) << ',' << (s.loc.pos%numY) << ','
+     << s.loc.dir << "), (" << s.lms.first << ',' << s.lms.second << "), " << s.cost << ']';
+  return ss.str();
+}
+
+std::ostream& operator<<(std::ostream& out, const PathPlanner::direction& d) {
+  switch (d) {
+  case PathPlanner::direction::N: out << "N"; break;
+  case PathPlanner::direction::W: out << "W"; break;
+  case PathPlanner::direction::S: out << "S"; break;
+  default: out << "E"; break;
+  };
+  return out;
+}
+
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/PathPlanner.h ./DualCoding/PathPlanner.h
--- ../Tekkotsu_2.4.1/DualCoding/PathPlanner.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/PathPlanner.h	2006-05-19 14:01:12.000000000 -0400
@@ -0,0 +1,125 @@
+//-*-c++-*-
+#ifndef INCLUDED_PathPlanner_h_
+#define INCLUDED_PathPlanner_h_
+
+#include <map>
+#include <iostream>
+#include <queue>
+#include <map>
+#include <bitset>
+#include "DualCoding.h"
+
+namespace DualCoding {
+
+// plans path given start and goal locations, landmarks, obstacles and area allowed to be in.
+// path is a set of waypoints which consist of position, heading and landmark(s).
+// path is actually computed from goal to start, which I guess could have been other way around
+class PathPlanner {
+public:
+  PathPlanner(coordinate_t xMax, coordinate_t xMin, coordinate_t yMax, coordinate_t yMin);
+  virtual ~PathPlanner() { 
+    delete [] unreached; 
+    delete [] costMap; 
+  }
+
+  //{ data structures used to represent the map and path
+  struct direction {
+    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;
+    direction cw() const { direction cwd(bitVal.to_ulong()+1); return cwd; }
+    direction ccw() const { direction ccwd(bitVal.to_ulong()-1); return ccwd; }
+  };
+  struct location {
+    unsigned int pos;
+    direction dir;
+    location()
+      : pos(0), dir(direction::N) {}
+    location(unsigned int _pos, direction _dir)
+      : pos(_pos), dir(_dir) {}
+    location(const location& l)
+      : pos(l.pos), dir(l.dir) {}
+    bool operator==(const location& l) const { return pos==l.pos && dir==l.dir; }
+  };
+  struct state { // structure representing each node 
+    location loc;
+    unsigned int cost;
+    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)
+      : 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) {}
+    state& operator=(const state& s) 
+    { if (this!=&s) { loc = s.loc; cost = s.cost; lms = s.lms; dst = s.dst; } return *this; }
+  };
+  struct edge { // structure representing transition b/w two states
+    state *from, *to;
+    unsigned int cost; // cost of transition
+    edge(state& _from, state& _to, unsigned int _cost) : from(&_from), to(&_to), cost(_cost) {}
+    edge(const edge& l) : from(&(*l.from)), to(&(*l.to)), cost(l.cost) {}
+    edge& operator=(const edge& l) 
+    { if (this!=&l) { from = &(*l.from); to = &(*l.to); cost = l.cost; } return *this; }
+  };
+  //}
+
+protected:
+  queue<state> allStates; // all possible states
+  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;
+  static const int size=300; // length of dog
+  unsigned int numX, numY;
+  float minX, minY, dX, dY;
+  location start, goal;
+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
+  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; 
+  // 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
+
+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>
+		     (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));
+  }
+
+protected:
+  bool isLMVisible(location loc, const Point& lm); // finds if landmark is visible from the location
+  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);
+  void computeLandmarkCosts();
+  Point findWorldCoords(unsigned int pos);
+  std::string toString(const PathPlanner::state &s);
+
+private:
+  PathPlanner& operator=(const PathPlanner&);
+  PathPlanner(const PathPlanner&);
+
+};
+  std::ostream& operator<<(std::ostream& out, const PathPlanner::direction& d);
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/Pilot.h ./DualCoding/Pilot.h
--- ../Tekkotsu_2.4.1/DualCoding/Pilot.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Pilot.h	2006-08-02 17:34:04.000000000 -0400
@@ -0,0 +1,155 @@
+//-*-c++-*-
+#ifndef INCLUDED_Pilot_h_
+#define INCLUDED_Pilot_h_
+
+#include "Behaviors/BehaviorBase.h"
+#include "Motion/MotionManager.h"
+
+class EventBase;
+
+namespace DualCoding {
+
+class ShapeRoot;
+
+class PilotRequest {
+public:
+
+  enum requestType_t {
+    reactiveWalk,
+    waypointWalk,
+    gotoShapeWalk,
+  } requestType;
+
+  typedef struct Motion {
+    enum PilotMotionType_t {
+      transX=0,
+      transY,
+      rotate,
+    } type;
+
+    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;
+    }
+
+    Motion(const Motion& m) : type(m.type), val(m.val) {}
+    Motion(PilotMotionType_t t, float s) : type(t), val(s) {}
+  };
+
+  typedef struct Constraint {
+    enum PilotConstraintType_t {
+      coordX,
+      coordY,
+      angle,
+      distance,
+    } type;
+
+    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)) {}
+  };
+
+  unsigned int request_id;
+  vector<Motion> motions;
+  vector<Constraint> constraints;
+
+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); }
+    
+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); }
+
+  // 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)); }
+
+  // gotoShape walk
+  static PilotRequest GotoShape(unsigned int _req_id)
+  { return PilotRequest(gotoShapeWalk,_req_id,vector<Motion>(),vector<Constraint>()); }
+
+  
+  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 Pilot : public BehaviorBase {
+private:
+  vector<PilotRequest> requests;
+  //  vector<unsigned int> colors;
+
+  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,
+  };
+  */
+public:
+  //! Constructor
+  Pilot() : BehaviorBase("Pilot"), requests() {} //;
+
+  //  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){}//;
+
+  //  MotionManager::MC_ID walker_id;
+  //  MotionManager::MC_ID waypoint_id;
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/Point.cc ./DualCoding/Point.cc
--- ../Tekkotsu_2.4.1/DualCoding/Point.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Point.cc	2006-08-02 17:27:59.000000000 -0400
@@ -0,0 +1,214 @@
+//-*-c++-*-
+
+#include <math.h>
+
+#include "Shared/Config.h"
+#include "Motion/Kinematics.h"
+
+#include "Measures.h"
+#include "Point.h"
+#include "LineData.h"
+#include "ShapeTypes.h"  // for ReferenceFrameType_t
+#include "VRmixin.h"
+
+namespace DualCoding {
+
+  Point::Point(void) : coords(4), refFrameType(unspecified) {
+  coords << 0 << 0 << 0 << 1;
+  }
+
+Point::Point(coordinate_t const &xp, coordinate_t const &yp, coordinate_t zp, 
+	     ReferenceFrameType_t ref) : coords(4), refFrameType(ref) {
+  coords << xp << yp << zp << 1;
+};
+
+Point::Point(const NEWMAT::ColumnVector& c, ReferenceFrameType_t ref) : 
+  coords(4), refFrameType(ref) { coords = c; }
+
+//!Set Position
+//{
+void Point::setCoords(const Point& otherPt) {
+  coords = otherPt.coords;
+}
+
+void Point::setCoords(coordinate_t x, coordinate_t y, coordinate_t z) {
+  coords << x << y << z << 1;
+}
+//}
+
+float Point::distanceFrom(const Point& otherPt) const {
+  return (coords - otherPt.coords).NormFrobenius();
+}
+
+float Point::xyDistanceFrom(const Point& other) const {
+  float dx = coords(1)-other.coords(1);
+  float dy = coords(2)-other.coords(2);
+  return sqrt(dx*dx+dy*dy);
+}
+
+bool Point::isLeftOf(const Point& other, float distance) const {
+  switch ( refFrameType ) {
+  case camcentric:
+    return coordX()+distance < other.coordX();
+  case egocentric:  
+    return coordY()-distance > other.coordY();
+  case allocentric:
+  default:
+    cout << "Allocentric Point::isLeftOf fudged for now" << endl;
+    return coordY()-distance > other.coordY();
+    // Should really calculate bearings to both points from current
+    // agent location and check sign of the difference
+  }
+}
+
+bool Point::isRightOf(const Point& other, float distance) const {
+  return other.isLeftOf(*this,distance); }
+
+bool Point::isAbove(const Point& other,float distance) const {
+  switch ( refFrameType ) {
+  case camcentric:
+    return coordY()+distance < other.coordY();
+  case egocentric:  
+    return coordX()-distance > other.coordX();
+  case allocentric:
+  default:
+    cout << "Allocentric Point::isLeftOf fudged for now" << endl;
+    return coordX()-distance > other.coordX();
+    // Should really calculate bearings to both points from current
+    // agent location and check sign of the difference
+  }
+}
+
+bool Point::isBelow(const Point& other, float distance) const {
+  return other.isAbove(*this,distance); }
+
+
+//! Apply a transformation matrix to translate and/or rotate  the point.
+void Point::applyTransform(const NEWMAT::Matrix& Tmat) { coords = Tmat*coords; }
+
+void Point::projectToGround(const NEWMAT::Matrix& camToBase,
+			    const NEWMAT::ColumnVector& groundPlane) {
+  NEWMAT::Matrix T2 = camToBase.i();
+  T2.SubMatrix(4,4,1,3)=T2.SubMatrix(1,3,4,4).t()*T2.SubMatrix(1,3,1,3);
+  T2.SubMatrix(1,3,4,4)=0;
+  //cout << "Transform plane b->j:\n"<<T2;
+
+  const float normX = 2*(coordX()/VRmixin::camSkS.getWidth()) - 1;
+  const float normY = 2*(coordY()/VRmixin::camSkS.getHeight()) - 1;
+  NEWMAT::ColumnVector camera_point(4), camPlane(4);
+  config->vision.computeRay(normX, normY,
+			    camera_point(1),camera_point(2),camera_point(3));
+  camera_point(4) = 1;
+  camPlane = T2*groundPlane;
+  
+  float denom=0;
+  for(unsigned int i=1; i<=3; i++)
+    denom+=camera_point(i)*camPlane(i);
+  NEWMAT::ColumnVector intersect=camera_point;
+  if(denom==0)
+    intersect(4)=0;
+  else {
+    float s=camPlane(4)/denom;
+    for(unsigned int i=1; i<=3; i++)
+      intersect(i)*=s;
+    intersect(4)=1;
+  }
+  coords = camToBase*intersect;
+}
+
+void Point::projectToGround(int xres, int yres,
+			    const NEWMAT::ColumnVector& ground_plane) {
+  // Normalize coordinate system to [-1,+1]
+  const float normX = 2*(coordX()/xres) - 1;
+  const float normY = 2*(coordY()/yres) - 1;
+  NEWMAT::ColumnVector camera_point(4), ground_point(4);
+  config->vision.computeRay(normX, normY,
+			    camera_point(1),camera_point(2),camera_point(3));
+  camera_point(4) = 1;
+  ground_point = 
+    kine->projectToPlane(CameraFrameOffset, camera_point,
+			 BaseFrameOffset, ground_plane, BaseFrameOffset);
+  //  std::cout << "Ground plane: " << NEWMAT::printmat(ground_plane) << 
+  //    "  camera_point: " << NEWMAT::printmat(camera_point) << 
+  //    "  ground_point: " << NEWMAT::printmat(ground_point) << std::endl;
+  coords(1) = ground_point(1) / ground_point(4);
+  coords(2) = ground_point(2) / ground_point(4);
+  coords(3) = ground_point(3) / ground_point(4);
+}
+  
+
+// Calling point and groundPoint must both have been projectToGround'ed already
+float Point::getHeightAbovePoint(const Point& groundPoint, const NEWMAT::ColumnVector& groundplane) {
+  float camX, camY, camZ;
+  NEWMAT::Matrix baseToCam = kine->jointToBase(CameraFrameOffset);
+  NEWMAT::ColumnVector camOffset = baseToCam.Column(4);
+  //std::cout<<std::endl;
+  //std::cout<<"cam offset = "<<NEWMAT::printmat(camOffset)<<std::endl;
+  //std::cout<<"groundPlane = "<<NEWMAT::printmat(groundplane)<<std::endl;
+  camOffset = camOffset - groundplane;
+  camOffset(4) = 1;
+  
+  Kinematics::unpack(camOffset, camX, camY, camZ);
+  //std::cout<<"top pt coords = "<<NEWMAT::printmat(coords)<<std::endl;
+  float dx = camX - coords(1);
+  float dy = camY - coords(2);
+  float dz = camZ - coords(3);
+  //std::cout<<"Cam to point = "<<dx<<" "<<dy<<" "<<dz<<std::endl;
+  float dHorizCam = sqrt(dx*dx + dy*dy);
+
+  Point dP = groundPoint - *this;
+  float dHorizPoint = sqrt(dP.coordX()*dP.coordX() + dP.coordY()*dP.coordY());
+  
+  return dz*dHorizPoint/dHorizCam;
+}
+
+
+  Point Point::operator+ (const Point& b) const { return Point(coords+b.coords,refFrameType); }
+
+Point& Point::operator+= (const Point& b) {
+  coords += b.coords;
+  return *this;
+}
+
+
+Point Point::operator- (const Point& b) const { return Point(coords-b.coords,refFrameType); }
+
+Point& Point::operator-= (const Point& b) {
+  coords -= b.coords;
+  return *this;
+}
+
+
+Point Point::operator* (float const b) const { return Point(coords*b,refFrameType); }
+
+Point& Point::operator *= (float const b) {
+  coords *= b;
+  return *this;
+}
+
+
+Point Point::operator/ (float const b) const { return Point(coords/b,refFrameType); }
+
+Point& Point::operator /= (float const b) {
+  coords /= b;
+  return *this;
+}
+
+bool Point::operator ==(const Point& b) const {
+  return (coordX() == b.coordX() 
+	  && coordY() == b.coordY() 
+	  && coordZ() == b.coordZ());
+}
+
+std::ostream& operator<< (std::ostream& out, const Point &p) {
+  out << "(" << p.coordX() << ", " << p.coordY() 
+      << ", " << p.coordZ() << ")";
+  return out;
+}
+
+void Point::printData()
+{
+  cout<<"{"<<coordX()<<","<<coordY()<<","<<coordZ()<<"}";
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/Point.h ./DualCoding/Point.h
--- ../Tekkotsu_2.4.1/DualCoding/Point.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Point.h	2006-08-02 17:27:59.000000000 -0400
@@ -0,0 +1,127 @@
+//-*-c++-*-
+#ifndef _POINT_H_
+#define _POINT_H_
+
+#include <iostream>
+#include <vector>
+
+#include "Shared/newmat/newmat.h"
+#include "Shared/newmat/newmatio.h"
+
+#include "Measures.h"   // coordinate_t, AngPi
+#include "ShapeTypes.h" // ReferenceFrameType_t
+
+namespace DualCoding {
+
+class LineData;
+template<typename T> class Shape;
+
+/*! We define Point as a separate lightweight class because it is used
+ * as a component of all the xxxData classes, and we don't want to nest
+ * these structures.
+ */
+
+class Point {
+
+public:
+  NEWMAT::ColumnVector coords;
+  ReferenceFrameType_t refFrameType;
+
+  //! Constructors
+  //@{
+  Point(void);
+  Point(coordinate_t const &xp, coordinate_t const &yp, coordinate_t zp=0, ReferenceFrameType_t ref=unspecified);
+  Point(const NEWMAT::ColumnVector& c, ReferenceFrameType_t ref=unspecified);
+  //@}
+
+  //! Copy constructor
+  Point(const Point& otherPt) : coords(otherPt.coords), refFrameType(otherPt.refFrameType) {}
+
+  //! Destructor
+  virtual ~Point() { }
+
+  NEWMAT::ColumnVector& getCoords() const { return const_cast<Point*>(this)->coords; }
+  coordinate_t coordX() const { return coords(1); }
+  coordinate_t coordY() const { return coords(2); }
+  coordinate_t coordZ() const { return coords(3); }
+
+  //! Set position.
+  //@{
+  void setCoords(const Point& otherPt);
+  void setCoords(coordinate_t _x, coordinate_t _y, coordinate_t z=0);
+  //@}
+
+  //! Set reference frame type
+  void setRefFrameType(const ReferenceFrameType_t ref) { refFrameType = ref; }
+
+  //! Euclidean distance from another point to this one
+  float distanceFrom(const Point& other) const;
+  float xyDistanceFrom(const Point& other) const;
+
+
+  //! These functions need a ShapeSpace argument because left/right depends on reference frame type.
+  //@{
+  bool isLeftOf(const Point& other, float distance=0) const;
+  bool isRightOf(const Point& other, float distance=0) const;
+  bool isAbove(const Point& other, float distance=0) const;
+  bool isBelow(const Point& other, float distance=0) const;
+//@}
+
+  //! These functions return true based on relative positions, assuming points line in a 2D plane (z coordinate is ignored).
+  //@{
+  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;
+//@}
+
+  void applyTransform(const NEWMAT::Matrix& T);
+  
+  float getHeightAbovePoint(const Point& groundPoint, const NEWMAT::ColumnVector& groundplane);
+  
+
+  //! projects this to ground plane according to camToBase matrix
+  void projectToGround(const NEWMAT::Matrix& camToBase,
+		       const NEWMAT::ColumnVector& groundPlane);
+
+  void projectToGround(int xres, int yres,
+		       const NEWMAT::ColumnVector& ground_plane);
+
+  Point operator+(const Point& b) const;
+  Point& operator+=(const Point& b);
+
+  Point operator-(const Point& b) const;
+  Point& operator-=(const Point& b);
+
+  Point operator*(float b) const;
+  Point& operator*=(float b);
+
+  Point operator/(float b) const;
+  Point& operator/=(float b);
+
+  bool operator==(const Point& b) const;
+  bool operator!=(const Point& b) const { return !operator==(b); }
+
+  Point& operator=(const Point& b) {
+    if (&b==this) return *this;
+    setCoords(b);
+    refFrameType = b.refFrameType;
+    return *this;
+  }
+
+  void printData();
+
+  friend class EndPoint;
+
+};
+
+inline Point& leftMost(Point &pt1, Point &pt2) { return pt1.isLeftOf(pt2) ? pt1 : pt2; }
+inline Point& rightMost(Point &pt1, Point &pt2) { return pt1.isLeftOf(pt2) ? pt2 : pt1; }
+inline Point& topMost(Point &pt1, Point &pt2) { return pt1.isAbove(pt2) ? pt1 : pt2; }
+inline Point& bottomMost(Point &pt1, Point &pt2) { return pt1.isAbove(pt2) ? pt2 : pt1; }
+
+std::ostream& operator<<(std::ostream &os, const Point &p);
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/PointData.cc ./DualCoding/PointData.cc
--- ../Tekkotsu_2.4.1/DualCoding/PointData.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/PointData.cc	2006-08-02 17:34:58.000000000 -0400
@@ -0,0 +1,128 @@
+//-*-c++-*-
+
+#include <iostream>
+#include <vector>
+
+#include "BaseData.h"    // superclass
+#include "Point.h"       // Point data member
+#include "ShapeTypes.h"  // pointDataType
+
+#include "SketchSpace.h"
+#include "Sketch.h"
+#include "visops.h"
+
+#include "ShapeSpace.h"  // required by DATASTUFF_CC
+#include "ShapeRoot.h"   // required by DATASTUFF_CC
+
+#include "PointData.h"
+#include "ShapePoint.h"
+
+namespace DualCoding {
+
+PointData::PointData(ShapeSpace& _space, const Point &c) 
+  : BaseData(_space,getStaticType()), the_point(c) {
+  the_point.refFrameType = space->getRefFrameType();
+}
+  
+DATASTUFF_CC(PointData);
+
+bool PointData::isMatchFor(const ShapeRoot& other) const {
+  if (!(isSameTypeAs(other) && isSameColorAs(other)))
+    return false;
+  const Shape<PointData>& other_point = ShapeRootTypeConst(other,PointData);
+  float dist = the_point.distanceFrom(other_point->getCentroid());
+  return dist < 20; // *** DST hack
+}
+
+void PointData::mergeWith(const ShapeRoot& other) {
+  const Shape<PointData>& other_point = ShapeRootTypeConst(other,PointData);
+  if (other_point->confidence <= 0)
+    return;
+  const int other_conf = other_point->confidence;
+  confidence += other_conf;
+  the_point = (the_point*confidence + other_point->getCentroid()*other_conf) / (confidence+other_conf);
+}
+
+bool PointData::updateParams(const ShapeRoot& other, bool) {
+  const Shape<PointData>& other_point = *static_cast<const Shape<PointData>*>(&other);
+  ++confidence;
+  the_point = (the_point*(confidence-1) + other_point->getCentroid())/confidence;
+  deleteRendering();
+  return true;
+}
+
+//! Print information about this shape. (Virtual in BaseData.)
+void
+PointData::printParams() const {
+  cout << "Type = " << getTypeName();
+  cout << "Shape ID = " << getId() << endl;
+  cout << "Parent ID = " << getParentId() << endl;
+  
+  // Print critical points.
+  cout << endl;
+  cout << "center{" << getCentroid().coordX() << ", " << getCentroid().coordY() << "}" << endl;
+  printf("color = %d %d %d\n",getColor().red,getColor().green,getColor().blue);
+  cout << "viewable = " << isViewable() << endl;
+}
+
+
+//! Transformations. (Virtual in BaseData.)
+void PointData::applyTransform(const NEWMAT::Matrix& Tmat) {
+  the_point.applyTransform(Tmat);
+}
+
+void PointData::projectToGround(const NEWMAT::Matrix& camToBase,
+				const NEWMAT::ColumnVector& groundplane) {
+  the_point.projectToGround(camToBase,groundplane);
+}
+
+// ==================================================
+// BEGIN SKETCH MANIPULATION AND POINT EXTRACTION CODE
+// ==================================================
+
+
+//! Point extraction.
+
+std::vector<ShapeRoot> PointData::extractPoints(const Sketch<bool>& sketch)
+{
+  SketchSpace &SkS = sketch->getSpace();
+  ShapeSpace &ShS = SkS.getDualSpace();
+  std::vector<ShapeRoot> result;
+  size_t num_pixels = sketch.width * sketch.height;
+  for ( size_t i=0; i < num_pixels; i++ )
+    if ( sketch[i] ) {
+      int const y = int(i/sketch.width);
+      int const x = i - y*sketch.width;
+      Point pt(x,y,0);
+      SkS.applyTmat(pt.getCoords());
+      Shape<PointData> new_point_shape(new PointData(ShS,pt));
+      new_point_shape->inheritFrom(sketch.rootGetData());
+      result.push_back(new_point_shape);
+    }
+  return result;
+}
+
+
+//! Render into a sketch space and return a pointer. (Private.)
+Sketch<bool>* PointData::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;
+}
+
+PointData& PointData::operator=(const PointData& other) {
+  if (&other == this)
+    return *this;
+  BaseData::operator=(other);
+  the_point = other.the_point;
+  return *this;
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/PointData.h ./DualCoding/PointData.h
--- ../Tekkotsu_2.4.1/DualCoding/PointData.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/PointData.h	2006-08-02 17:34:58.000000000 -0400
@@ -0,0 +1,76 @@
+//-*-c++-*-
+#ifndef _POINTDATA_H_
+#define _POINTDATA_H_
+
+#include <vector>
+#include <iostream>
+#include <string>
+
+#include "Shared/newmat/newmat.h"
+
+#include "BaseData.h"    // superclass
+#include "Point.h"       // Point data member
+#include "ShapeTypes.h"  // pointDataType
+
+namespace DualCoding {
+
+class ShapeRoot;
+class SketchSpace;
+template<typename T> class Sketch;
+
+class PointData : public BaseData {
+public:
+  Point the_point;
+
+  //! Constructor
+  PointData(ShapeSpace& _space, const Point &c);
+
+  static ShapeType_t getStaticType() { return pointDataType; }
+
+  DATASTUFF_H(PointData);
+  
+  //! Centroid. (Virtual in BaseData.)
+  Point getCentroid() const { return the_point; }  
+  
+  BoundingBox getBoundingBox() const {
+    return BoundingBox(the_point.coordX(),the_point.coordY(),the_point.coordX(),the_point.coordY());
+  }
+
+  //! Match points based on their parameters.  (Virtual in BaseData.)
+  virtual bool isMatchFor(const ShapeRoot& other) const;
+
+  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);
+  
+  //! Project to ground
+  virtual void projectToGround(const NEWMAT::Matrix& camToBase,
+			       const NEWMAT::ColumnVector& groundplane);
+
+  //! Extraction.
+  static std::vector<ShapeRoot> extractPoints(const Sketch<bool>& sketch);
+
+  virtual unsigned short getDimension() const { return 0; }
+
+  PointData& operator=(const PointData&);
+  operator Point&() { return the_point; };
+  operator const Point&() const { return the_point; };
+  
+private:
+  //! Render into a sketch space and return reference. (Private.)
+  Sketch<bool>* render() const;
+  //@}
+
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/PolygonData.cc ./DualCoding/PolygonData.cc
--- ../Tekkotsu_2.4.1/DualCoding/PolygonData.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/PolygonData.cc	2006-08-02 17:27:14.000000000 -0400
@@ -0,0 +1,608 @@
+//-*-c++-*-
+#include "ShapeLine.h"
+#include "ShapeRoot.h"
+#include "ShapeSpace.h"
+#include "Sketch.h"
+#include "SketchSpace.h"
+#include "visops.h"
+
+#include "PolygonData.h"
+#include "ShapePolygon.h"
+
+namespace DualCoding {
+
+DATASTUFF_CC(PolygonData);
+
+PolygonData::PolygonData(const LineData& side) 
+  : BaseData(*side.space,polygonDataType), edges(), vertices()
+{ 
+  edges.push_back(side);
+  updateVertices();
+  mobile = POLYGON_DATA_MOBILE;
+}
+
+PolygonData::PolygonData(ShapeSpace& _space, const vector<Point>& pts, 
+			 bool closed, bool end1Valid, bool end2Valid)
+  : BaseData(_space, polygonDataType), edges(), vertices(pts.size()>1 ? pts : vector<Point>())
+{
+  mobile = POLYGON_DATA_MOBILE;
+  if (pts.empty()) return;
+  for(vector<Point>::const_iterator vtx_it = pts.begin();
+      vtx_it < pts.end()-1; vtx_it++)
+    edges.push_back(LineData(_space, *vtx_it, *(vtx_it+1)));
+  edges.front().end1Pt().setValid(end1Valid);
+  edges.back().end2Pt().setValid(end2Valid);
+  if (closed) // close polygon
+    tryClosePolygon();
+}
+
+
+vector<Shape<LineData> > PolygonData::extractPolygonEdges(Sketch<bool> const& sketch,
+							  Sketch<bool> const& occluder) {
+  vector<Shape<LineData> > lines(LineData::extractLines(sketch, occluder,4));
+  return lines;
+}
+
+void PolygonData::updateVertices() {
+  vertices.clear();
+  if (edges.empty()) return;
+
+  if (isClosed())
+    vertices.push_back(end1Ln().intersectionWithLine(end2Ln()));
+  else
+    vertices.push_back(end1Pt());
+  if (edges.size() > 1)
+    for (vector<LineData>::const_iterator it = edges.begin();
+	 it != edges.end()-1; it++)
+      vertices.push_back(it->intersectionWithLine(*(it+1)));
+  if (isClosed())
+    vertices.push_back(vertices.front());
+  else
+    vertices.push_back(end2Pt());
+}
+
+vector<ShapeRoot> PolygonData::formPolygons(const vector<LineData>& lines) {
+  if (lines.empty()) return vector<ShapeRoot>();
+  // sort lines from longest to shortest
+  vector<LineData> allEdges = lines;
+  sort(allEdges.begin(),allEdges.end(), ptr_fun(isFirstLineLonger));
+  
+  vector<ShapeRoot> newPolygons;
+  for (vector<LineData>::iterator line_it = allEdges.begin();
+      line_it != allEdges.end(); line_it++) {
+    Shape<PolygonData> temp_polygon(*line_it);
+    for (vector<LineData>::iterator line_it2 = line_it+1;
+	 line_it2 < allEdges.end(); line_it2++) {
+      if (line_it2->getColor() == line_it->getColor()
+	  && (temp_polygon->tryUpdateEdge(Shape<LineData>(*line_it2))
+	      || temp_polygon->tryImportNewEndline(*line_it2))) {
+	allEdges.erase(line_it2);
+	line_it2 = line_it;
+      }
+    }
+    temp_polygon->setColor(line_it->getColor());
+    temp_polygon->updateVertices();
+    temp_polygon->printParams();
+    newPolygons.push_back(temp_polygon);
+  }
+  return newPolygons;
+}
+
+vector<ShapeRoot> PolygonData::formPolygons(const vector<LineData>& lines, 
+					    vector<Shape<PolygonData> >& existingPolygons, 
+					    vector<ShapeRoot>& deletedPolygons) {
+  if (lines.empty()) return vector<ShapeRoot>();
+
+  vector<LineData> allEdges = lines;
+  for (vector<Shape<PolygonData> >::const_iterator pol_it = existingPolygons.begin();
+       pol_it < existingPolygons.end(); pol_it++) {
+    vector<LineData> existingEdges = (*pol_it)->getEdges();
+    const int existingParentID = (*pol_it)->getId();
+    for (vector<LineData>::iterator edge_it = existingEdges.begin();
+	 edge_it != existingEdges.end(); edge_it++)
+      edge_it->setParentId(existingParentID); // set parent id of all edges to its owner
+    allEdges.insert(allEdges.end(), existingEdges.begin(),existingEdges.end());
+  }
+
+  vector<ShapeRoot> newPolygons = formPolygons(allEdges);
+
+  for (vector<Shape<PolygonData> >::iterator existing_it = existingPolygons.begin();
+       existing_it < existingPolygons.end(); existing_it++) {
+    vector<ShapeRoot>::iterator new_it = newPolygons.begin();
+    for (; new_it < newPolygons.end(); new_it++) {
+      const Shape<PolygonData>& newPolygon = ShapeRootTypeConst(*new_it,PolygonData);
+      if ((*existing_it)->getEdges().size() == newPolygon->getEdges().size()) {
+	vector<LineData>::const_iterator edge_it = newPolygon->getEdges().begin();
+	const int parentPolygonID = (*existing_it)->getId();
+	for (;edge_it != newPolygon->getEdges().end(); edge_it++)
+	  if (parentPolygonID != edge_it->getParentId())
+	    break;
+	if (edge_it == newPolygon->getEdges().end()) {// this new_it has the exactly same set of edges as existing_it
+	  (*existing_it)->edges = newPolygon->edges;
+	  (*existing_it)->vertices = newPolygon->vertices;
+	  new_it->deleteShape();
+	  newPolygons.erase(new_it--);
+	  cout << " => match for existing polygon " << parentPolygonID << endl;
+	  break;
+	}
+      }
+    }
+    if (new_it == newPolygons.end()) {
+      deletedPolygons.push_back(*existing_it);
+      existingPolygons.erase(existing_it--);
+    }
+  }
+  return newPolygons;
+}
+
+
+BoundingBox PolygonData::getBoundingBox() const {
+  BoundingBox result(vertices[0].coordX(), vertices[0].coordX(),
+		     vertices[0].coordY(), vertices[0].coordY());
+  for (vector<Point>::const_iterator it = vertices.begin();
+       it != vertices.end();
+       it++) {
+    if ( (*it).coordX() < result.xmin )
+      result.xmin = (*it).coordX();
+    else if ( (*it).coordX() > result.xmax )
+      result.xmax = (*it).coordX();
+    if ( (*it).coordY() < result.ymin )
+      result.ymin = (*it).coordY();
+    else if ( (*it).coordY() > result.ymax )
+      result.ymax = (*it).coordY();
+  }
+  return result;
+}
+
+bool PolygonData::formsNewEndline(const LineData& ln, bool useEnd1Pt, bool useEnd2Pt) const {
+  if (edges.empty()) return true;
+
+  useEnd1Pt &= ln.end1Pt().isValid(); // don't use invalid endpoint
+  useEnd2Pt &= ln.end2Pt().isValid(); // don't use invalid endpoint
+
+  if (!(useEnd1Pt || useEnd2Pt))
+    return false;
+
+  if (end1Pt().isValid()) //forms vertex with end1Ln?
+    if((useEnd1Pt && end1Pt().distanceFrom(ln.end1Pt()) < THRESH_DIST_VERTEX)
+       || (useEnd2Pt && end1Pt().distanceFrom(ln.end2Pt()) < THRESH_DIST_VERTEX))
+      return true;
+  if (end2Pt().isValid()) //forms vertex with end2Ln?
+    if((useEnd1Pt && end2Pt().distanceFrom(ln.end1Pt()) < THRESH_DIST_VERTEX)
+       || (useEnd2Pt && end2Pt().distanceFrom(ln.end2Pt()) < THRESH_DIST_VERTEX))
+      return true;
+
+  return false;
+}
+
+bool PolygonData::tryImportNewEndline(const LineData& ln, bool useEnd1Pt, bool useEnd2Pt) {
+  if (edges.empty()) {
+    edges.push_back(ln);
+    return true;
+  }
+      
+  useEnd1Pt &= ln.end1Pt().isValid(); // don't use invalid endpoint
+  useEnd2Pt &= ln.end2Pt().isValid(); // don't use invalid endpoint
+  if (!(useEnd1Pt || useEnd2Pt))
+    return false;
+  
+  if (end1Pt().isValid()) {
+    if (useEnd1Pt && 
+	end1Pt().distanceFrom(ln.end1Pt()) < THRESH_DIST_VERTEX) {
+      LineData end1ln = ln;
+      end1ln.setEndPts(ln.end2Pt(),ln.end1Pt());
+      edges.insert(edges.begin(), end1ln);
+      return true;
+    }
+    else if (useEnd2Pt && 
+	     end1Pt().distanceFrom(ln.end2Pt()) < THRESH_DIST_VERTEX) {
+      edges.insert(edges.begin(), ln);
+      return true;
+    }
+  }
+  
+  if (end2Pt().isValid()) {
+    if (useEnd1Pt && 
+	end2Pt().distanceFrom(ln.end1Pt()) < THRESH_DIST_VERTEX) {
+      edges.push_back(ln);
+      return true;
+    }
+    else if (useEnd2Pt &&
+	     end2Pt().distanceFrom(ln.end2Pt()) < THRESH_DIST_VERTEX) {
+      LineData end2ln = ln;
+      end2ln.setEndPts(ln.end2Pt(),ln.end1Pt());
+      edges.push_back(end2ln);
+      return true;
+    }
+  }
+  return false;
+}
+
+bool PolygonData::tryClosePolygon() {
+  if (vertices.size()<3 || 
+      !end1Pt().isValid() || !end2Pt().isValid())
+    return false;
+  if (end1Ln().isMatchFor(end2Ln())) {
+    cout << "end1 match for end2\n";
+    end1Ln().printParams();
+    end2Ln().printParams();
+    edges.erase(edges.end());
+  }
+  edges.push_back(LineData(*space,end2Pt(),end1Pt()));
+  edges.front().end1Pt().setValid(true);
+  updateVertices();
+  return true;
+}
+
+bool PolygonData::isClosed() const {
+  return (edges.size() > 2 &&
+	  (end1Ln().isMatchFor(end2Ln()) || 
+	   ((end1Pt().distanceFrom(end2Pt()) < THRESH_DIST_VERTEX)
+	    && end1Pt().isValid() && end2Pt().isValid())));
+}
+
+
+bool PolygonData::isMatchForEdge(const LineData& other) const {
+  for(vector<LineData>::const_iterator this_it = edges.begin();
+      this_it != edges.end(); this_it++)
+    if (this_it->isMatchFor(other))
+      return true;
+  return false;
+}
+
+// remove edges whose confidence < 0
+// break polygon into pieces if inner edge removed
+vector<ShapeRoot> PolygonData::updateState() {
+  bool breakPolygon = false;
+  for (vector<LineData>::iterator it = edges.begin();
+       it != edges.end(); it++) {
+    if (it->getConfidence() < 0) {
+      if (! (it == edges.begin() || it == edges.end()-1)) //inner edge deleted
+	breakPolygon = true;
+      edges.erase(it--);
+    }
+  }
+  if (breakPolygon && !edges.empty()) { //form new polygons from the remaining edges of this polygon
+    vector<LineData> lines(edges);
+    edges.clear(); 
+    return formPolygons(lines);
+  }
+  else
+    return vector<ShapeRoot>();
+}
+
+
+bool PolygonData::tryUpdateEdge(const ShapeRoot& ln) {
+  for(vector<LineData>::iterator it = edges.begin();
+      it != edges.end(); it++)
+    if (it->isMatchFor(ln) && it->updateParams(ln)) {
+      it->increaseConfidence(ln);
+      if (it->getParentId() == 0 && ln->getParentId() != 0)
+	it->setParentId(ln->getParentId());
+      return true;
+    }
+  return false;
+}
+
+  /*
+  for(vector<Point>::iterator it = polygon.getVertices.begin();
+      it != polygon.getVertices.end(); it++)
+    .....
+  */
+
+bool PolygonData::isMatchFor(const ShapeRoot& other) const {
+  if (other->isType(lineDataType) && isSameColorAs(other)) {
+    const LineData& other_ln = ShapeRootTypeConst(other,LineData).getData();
+    return (isMatchForEdge(other_ln));
+  }
+  if (other->isType(polygonDataType) && isSameColorAs(other)) {
+    const PolygonData& other_polygon = ShapeRootTypeConst(other,PolygonData).getData();
+    if (other_polygon.getEdges().size() == edges.size()) {
+      vector<LineData>::const_iterator other_it = other_polygon.getEdges().begin();
+      vector<LineData>::const_iterator this_it = getEdges().begin();
+      for (; other_it != other_polygon.getEdges().end(); other_it++, this_it++)
+	if (!this_it->isMatchFor(*other_it)) break;
+      if (this_it == edges.end())
+	return true;
+      vector<LineData>::const_reverse_iterator other_rit = other_polygon.getEdges().rbegin();
+      this_it = edges.begin();
+      for (; other_rit != other_polygon.getEdges().rend(); other_it++, this_it++)
+	if (!this_it->isMatchFor(*other_rit)) break;
+      return (this_it == edges.end());
+    }
+  }
+  return false;
+}
+
+int PolygonData::getConfidence() const {
+  switch (edges.size()) {
+  case 0:
+    return -1;
+  case 1:
+    return edges.front().getConfidence();
+  default:
+    vector<LineData>::const_iterator it = edges.begin();
+    int conf = (it++)->getConfidence();
+    for (; it != edges.end(); it++)
+      if (conf > it->getConfidence())
+	conf = it->getConfidence();
+    return conf;
+  };
+}
+
+bool PolygonData::updateParams(const ShapeRoot& other, bool) {
+  if (other->isType(lineDataType) && tryUpdateEdge(other)) {
+    updateVertices();
+    return true;
+  }
+  return false;
+}
+
+/*    
+bool PolygonData::doUpdateParams(const ShapeRoot& other, bool) {
+if (other->isType(lineDataType))
+return (tryUpdateEdge(other)); ||
+tryImportNewEndline(ShapeRootTypeConst(other,LineData).getData()));
+else if (other->isType(polygonDataType)) {
+const PolygonData& other_polygon = ShapeRootTypeConst(other, PolygonData).getData();
+return tryImportNewEndline(other_polygon.end1Ln(),true,false)
+|| tryImportNewEndline(other_polygon.end2Ln(),false,true);
+}
+return false;
+}
+*/
+
+bool PolygonData::isAdmissible() const {
+  for (vector<LineData>::const_iterator it = edges.begin();
+       it != edges.end(); it++) {
+    if (it->isAdmissible())
+      return true;
+  }
+  return false;
+}
+
+// define a line from pt to most distant vertex from this point.
+// count number of intersections with edges (except the ones 
+bool PolygonData::isInside(const Point& pt) const {
+  if (!isClosed()) return false;
+  float mostDist = -1;
+  unsigned int mostDistIndex = -1U;
+  const unsigned int numVertices = vertices.size()-1; // number of unique vertices (first and last are same) 
+  for (unsigned int i = 0; i < numVertices; i++) {
+    float dist = pt.distanceFrom(vertices[i]);
+    if (dist > mostDist) {
+      mostDist = dist;
+      mostDistIndex = i;
+    }
+  }
+  //  cout << "Most distant vertex: " << vertices[mostDistIndex] << endl;
+  LineData ln(this->getSpace(),pt,(vertices[mostDistIndex]));
+  unsigned int intersectionCount = 0;
+  // this is a check if this point falls between the two edges surrounding the most distant vertex from this point
+  // if not, odd number of intersection indicates the point is inside, so increment the count by 1
+  {
+    float theta0 = (mostDistIndex == 0) ? 
+      ((vertices.front() == vertices.back()) ? 
+       atan2(vertices[vertices.size()-2].coordY()-vertices[mostDistIndex].coordY(),
+	     vertices[vertices.size()-2].coordX()-vertices[mostDistIndex].coordX()) :
+       atan2(vertices[vertices.size()-1].coordY()-vertices[mostDistIndex].coordY(),
+	     vertices[vertices.size()-1].coordX()-vertices[mostDistIndex].coordX())) :
+      atan2(vertices[mostDistIndex-1].coordY()-vertices[mostDistIndex].coordY(),
+	    vertices[mostDistIndex-1].coordX()-vertices[mostDistIndex].coordX());
+    float theta1 = atan2(pt.coordY()-vertices[mostDistIndex].coordY(),pt.coordX()-vertices[mostDistIndex].coordX());
+    float theta2 = (mostDistIndex == vertices.size()-1) ?
+      ((vertices.front() == vertices.back()) ? 
+       atan2(vertices[1].coordY()-vertices[mostDistIndex].coordY(),
+	     vertices[1].coordX()-vertices[mostDistIndex].coordX()) :
+       atan2(vertices[0].coordY()-vertices[mostDistIndex].coordY(),
+	     vertices[0].coordX()-vertices[mostDistIndex].coordX())) :
+      atan2(vertices[mostDistIndex+1].coordY()-vertices[mostDistIndex].coordY(),
+	    vertices[mostDistIndex+1].coordX()-vertices[mostDistIndex].coordX());
+    if ((theta2>theta0 && !((theta2-theta0<M_PI && theta2>theta1 && theta1>theta0) ||
+			   (2*M_PI-theta2+theta0<M_PI && (theta1>theta2 || theta0>theta1)))) 
+	|| (theta0>theta2 && !((theta0-theta2<M_PI && theta0>theta1 && theta1>theta2) ||
+			       (2*M_PI-theta0+theta2<M_PI && (theta1>theta0 || theta2>theta1))))) {
+      //      cout << "orientataion not b/w edges\n";
+      intersectionCount++;
+    }
+  }
+    //  cout << "  " << ln.end1Pt() << " <-> " << ln.end2Pt() << endl;
+  for (unsigned int i = mostDistIndex+1; i < numVertices+mostDistIndex-1; i++) {
+    LineData cleanEdge(*space,vertices[i%numVertices],vertices[(i+1)%numVertices]);
+    //    cout << "  " << i << ": " << cleanEdge.end1Pt() << " <-> " << cleanEdge.end2Pt();
+    if (ln.getOrientation() != cleanEdge.getOrientation()
+	&& ln.intersectsLine(cleanEdge)) {
+      //      cout << " true\n";
+      intersectionCount++;
+    }
+  }
+  return (intersectionCount%2) == 0;
+}
+
+
+void PolygonData::printParams() const {
+  cout << edges.size() << " edge(s)\n";
+  for (vector<LineData>::const_iterator it = edges.begin();
+       it != edges.end(); it++)
+    cout << it->end1Pt() << " -> " << it->end2Pt() << endl;
+
+  cout << vertices.size () << " vertice(s):\n";
+  for (vector<Point>::const_iterator it = vertices.begin();
+       it != vertices.end(); it++)
+    cout << (*it) << endl;
+}
+
+void PolygonData::applyTransform(const NEWMAT::Matrix& Tmat) {
+  for (vector<LineData>::iterator it = edges.begin();
+       it != edges.end(); it++)
+    it->applyTransform(Tmat);
+  for (vector<Point>::iterator it = vertices.begin();
+       it != vertices.end(); it++)
+    it->applyTransform(Tmat);
+}
+
+void PolygonData::projectToGround(const NEWMAT::Matrix& camToBase,
+				  const NEWMAT::ColumnVector& groundplane) {
+  for (vector<LineData>::iterator it = edges.begin();
+       it != edges.end(); it++)
+    it->projectToGround(camToBase,groundplane);
+}
+
+Point PolygonData::getCentroid() const {
+  if (edges.empty())
+    return Point(0,0,0,getRefFrameType());
+  vector<LineData>::const_iterator it = edges.begin();
+  Point centroid = (it++)->getCentroid();
+  for (; it != edges.end(); it++)
+    centroid += it->getCentroid();
+  return centroid/edges.size();
+}
+
+
+void PolygonData::setColor(rgb new_color) {
+  color_rgb = new_color;
+  for (vector<LineData>::iterator it = edges.begin();
+       it != edges.end(); it++)
+    it->setColor(color_rgb);
+  deleteRendering();
+}
+
+// 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;
+  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);
+  }
+  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);
+}
+
+//================ Convex Hull ================
+
+class convexHullPoint {
+public:
+  int x, y;
+  float angle;
+
+  convexHullPoint() : x(0), y(0), angle(0) {}
+
+  convexHullPoint(int _x, int _y, float _a) : x(_x), y(_y), angle(_a) {}
+
+  static int crossProduct(const convexHullPoint &p1, const convexHullPoint &p2, const convexHullPoint &p3) {
+    return (p2.x - p1.x)*(p3.y - p1.y) - (p3.x - p1.x)*(p2.y - p1.y);
+  }
+
+  class pointCompare : public binary_function<convexHullPoint, convexHullPoint, bool> {
+  private:
+    const convexHullPoint &pivot;
+  public:
+    pointCompare(const convexHullPoint &_pivot) : pivot(_pivot) {}
+    bool operator() (const convexHullPoint &p1, const convexHullPoint &p2) {
+      if ( p1.angle < p2.angle )
+	return true;
+      else if ( p1.angle > p2.angle )
+	return false;
+      else {
+	int const d1x = pivot.x - p1.x;
+	int const d1y = pivot.y - p1.y;
+	int const d2x = pivot.x - p2.x;
+	int const d2y = pivot.y - p2.y;
+	return (d1x*d1x+d1y*d1y) < (d2x*d2x+d2y*d2y);
+      }
+    }
+  }
+;
+};
+
+Shape<PolygonData> PolygonData::convexHull(const Sketch<bool> &sketch) {
+  int const spts = sketch->sum();
+  int const width = sketch.width;
+  int const npix = sketch->getNumPixels();
+  
+  //  cout << "septs,width,npix= " << spts << ", " << width << ", " << npix << endl;
+
+  // construct a vector of points and find the pivot point
+  NEW_SKETCH_N(neighbs, uchar, visops::neighborSum(sketch));
+  std::vector<convexHullPoint> points(spts);
+  points.clear();
+  int pivot_x = -1, pivot_y = width+1;
+  for (int i=0; i<npix; i++) {
+    //    cout << sketch[i] << " : " << neighbs[i] << endl;
+    if ( sketch[i] && neighbs[i] < 8 ) {
+      int const x = i % width;
+      int const y = i / width;
+      points.push_back(convexHullPoint(x,y,0));
+      if ( y < pivot_y || (y == pivot_y && x > pivot_x) ) {
+	pivot_x = x;
+	pivot_y = y;
+      };
+    }
+  }
+  int const npts = points.size();
+
+
+  // sort points by angle from the pivot, and if colinear, take closer point first
+  for (int i=0; i<npts; i++)
+    points[i].angle  = (float) -atan2((float) (pivot_y - points[i].y), (float) (pivot_x - points[i].x));
+  std::sort(points.begin(),points.end(),convexHullPoint::pointCompare(convexHullPoint(pivot_x,pivot_y,0)));
+
+  // push points onto a stack to form the convex hull
+  vector<convexHullPoint> hull(npts);
+  hull.clear();
+  hull.push_back(points[0]);
+  hull.push_back(points[1]);
+  for ( int i=2; i<npts; i++ ) {
+    int last = hull.size() - 1;
+    int o = convexHullPoint::crossProduct(hull[last-1],hull[last],points[i]);
+    if ( o == 0 )
+      hull[last] = points[i];
+    else if ( o < 0 )
+      hull.push_back(points[i]);
+    else {
+      while ( o >= 0 && hull.size() > 2 ) {
+	hull.pop_back();
+	last--;
+	o = convexHullPoint::crossProduct(hull[last-1],hull[last],points[i]);
+      }
+      hull.push_back(points[i]);
+    }
+  }
+  int const nhull = hull.size();
+  // build a polygon to represent the hull
+  ShapeSpace &ShS = sketch->getDualSpace();
+  vector<Point> vertices;
+  for (int i=0; i<nhull; i++)
+    vertices.push_back(Point(hull[i].x, hull[i].y));
+  vertices.push_back(Point(hull[0].x, hull[0].y));  // force closed polygon: don't trust tryClose()
+  return Shape<PolygonData>(new PolygonData(ShS,vertices,true));
+}
+
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/PolygonData.h ./DualCoding/PolygonData.h
--- ../Tekkotsu_2.4.1/DualCoding/PolygonData.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/PolygonData.h	2006-05-14 12:19:32.000000000 -0400
@@ -0,0 +1,117 @@
+//-*-c++-*-
+#ifndef _POLYGONDATA_H_
+#define _POLYGONDATA_H_
+
+#include <vector>
+#include <iostream>
+#include <string>
+
+#include "BaseData.h"    // superclass
+#include "LineData.h"    // LineData data member
+#include "Measures.h"    // coordinate_t; AngPi data member
+
+namespace DualCoding {
+
+class EndPoint;
+class NEWMAT::ColumnVector;
+class NEWMAT::Matrix;
+class ShapeRoot;
+class ShapeSpace;
+template<> class Shape<LineData>;
+
+#define POLYGON_DATA_MOBILE false
+#define THRESH_DIST_VERTEX 50
+
+//vertices unique
+//num vertices >= 1
+//for wall bounds, vertices are in clockwise order
+//order of vertices isn't ambiguous
+//average of vertices is the centroid
+
+class PolygonData : public BaseData {
+protected:
+  vector<LineData> edges; // edges which consist this polygon
+private:
+  vector<Point> vertices; // cache of vertices
+
+public:
+  static ShapeType_t getStaticType() { return polygonDataType; }
+
+  DATASTUFF_H(PolygonData);
+  friend class Shape<PolygonData>;
+
+  //! Constructors
+  PolygonData(const LineData&);
+  PolygonData(ShapeSpace& space, const vector<Point>& pts, bool closed, 
+	      bool end1Valid=true, bool end2Valid=true);
+  PolygonData(const 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
+  //! 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
+  
+  //! Edge/Vertex Access Functions
+  //@{
+  const LineData& end1Ln() const { return edges.front(); } //!< returns first edge of this polygon
+  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
+  //@}
+  
+  BoundingBox getBoundingBox() const;
+
+  vector<ShapeRoot> updateState();
+
+  bool isClosed() const ; //<! returns if this polygon is closed
+  
+  //! Convex hull using Graham's scan.
+  static Shape<PolygonData> convexHull(const Sketch<bool> &sketch);
+
+  PolygonData& operator=(const PolygonData& other) {
+    if (&other == this)
+      return *this;
+    BaseData::operator=(other);
+    edges = other.edges;
+    vertices = other.vertices;
+    return *this;
+  }
+
+private:
+  bool tryClosePolygon();
+  bool tryImportNewEndline(const LineData& line, bool useEnd1Pt=true, bool useEnd2Pt=true);
+  bool tryUpdateEdge(const ShapeRoot&);
+  bool isMatchForEdge(const LineData& other) const;
+  bool formsNewEndline(const LineData& ln, bool useEnd1Pt=true, bool useEnd2Pt=true) const;
+  void updateVertices(); //!< called everytime polygon is changed. updates vertices by finding intersections of adjascent edges
+  static bool isFirstLineLonger(const Shape<LineData>& ln1,const Shape<LineData>& ln2);
+
+public:   
+  //{@! functions virtual in BaseData
+  virtual Point getCentroid() const;
+  virtual bool isMatchFor(const ShapeRoot& other) const;
+  virtual bool isAdmissible() const;
+  virtual bool updateParams(const ShapeRoot& other, bool forceUpdate=false); //!< updates existing edges, but does not importing new edges
+  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 projectToGround(const NEWMAT::Matrix& camToBase,
+			       const NEWMAT::ColumnVector& groundplane);
+  virtual void setColor(rgb new_color);
+  virtual Sketch<bool>* render() const;
+  virtual unsigned short getDimension() const { return 2; }
+  //}
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/PyramidData.cc ./DualCoding/PyramidData.cc
--- ../Tekkotsu_2.4.1/DualCoding/PyramidData.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/PyramidData.cc	2006-07-21 14:30:57.000000000 -0400
@@ -0,0 +1,373 @@
+//-*-c++-*-
+
+#include <iostream>
+#include <vector>
+
+#include "BaseData.h"    // superclass
+#include "Point.h"       // Point data member
+#include "ShapeTypes.h"  // pyramidDataType
+
+#include "SketchSpace.h"
+#include "Sketch.h"
+#include "visops.h"
+
+#include "ShapeSpace.h"  // required by DATASTUFF_CC
+#include "ShapeRoot.h"   // required by DATASTUFF_CC
+
+#include "PyramidData.h"
+#include "ShapePyramid.h"
+#include "ShapePoint.h"
+#include "Region.h"
+
+
+namespace DualCoding {
+
+  PyramidData::PyramidData(ShapeSpace& _space,
+			   const EndPoint &_FL, const EndPoint &_FR, 
+			   const EndPoint &_BL, const EndPoint &_BR, 
+			   const EndPoint &_Top)
+    : BaseData(_space,pyramidDataType), 
+      FL(_FL), FR(_FR), BL(_BL), BR(_BR), Top(_Top),
+      centroid((FL + FR + BL + BR + Top) / 5)
+  {
+  }
+
+  
+  DATASTUFF_CC(PyramidData);
+
+  bool PyramidData::isMatchFor(const ShapeRoot& other) const {
+    if (!(isSameTypeAs(other) && isSameColorAs(other)))
+      return false;
+
+    // needs implementation
+    float dist = 0;
+    return dist < 20; 
+  }
+  
+  void PyramidData::mergeWith(const ShapeRoot& other) {
+    const Shape<PyramidData>& other_pyramid = ShapeRootTypeConst(other,PyramidData);
+    if (other_pyramid->confidence <= 0)
+      return;
+  }
+
+  bool PyramidData::updateParams(const ShapeRoot& other, bool) {
+    const Shape<PyramidData>& other_pyramid = *static_cast<const Shape<PyramidData>*>(&other);
+    //  ++confidence;
+    FL = (FL*(confidence-1) + other_pyramid->getFL())/confidence;
+    FR = (FR*(confidence-1) + other_pyramid->getFR())/confidence;
+    BL = (BL*(confidence-1) + other_pyramid->getBL())/confidence;
+    BR = (BR*(confidence-1) + other_pyramid->getBR())/confidence;
+    Top = (Top*(confidence-1) + other_pyramid->getTop())/confidence;
+    deleteRendering();
+    return true;
+  }
+
+  //! Print information about this shape. (Virtual in BaseData.)
+  void PyramidData::printParams() const {
+    cout << "Type = " << getTypeName();
+    cout << "Shape ID = " << getId() << endl;
+    cout << "Parent ID = " << getParentId() << endl;
+  
+    printf("color = %d %d %d\n",getColor().red,getColor().green,getColor().blue);
+    cout << "viewable = " << isViewable() << endl;
+  }
+
+
+  //! 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::projectToGround(const NEWMAT::ColumnVector& groundplane) {
+    FL.projectToGround(groundplane);
+    FR.projectToGround(groundplane);
+    BL.projectToGround(groundplane);
+    BR.projectToGround(groundplane);
+
+    Point bottomCenter = (FL + FR + BL + BR) / 4.0;
+    float height;
+    Top.projectToGround(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";
+    }*/
+
+  void PyramidData::projectToGround(const NEWMAT::Matrix & camToBase, 
+				    const NEWMAT::ColumnVector& groundplane) {
+    FL.projectToGround(camToBase, groundplane);
+    FR.projectToGround(camToBase, groundplane);
+    BL.projectToGround(camToBase, groundplane);
+    BR.projectToGround(camToBase, groundplane);
+
+    Point bottomCenter = (FL + FR + BL + BR) / 4.0;
+    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";
+  }
+
+  // =====================================================
+  // BEGIN SKETCH MANIPULATION AND PYRAMID EXTRACTION CODE
+  // =====================================================
+
+
+  //! Pyramid extraction.
+
+
+  //! Render into a sketch space and return reference. (Private.)
+  Sketch<bool>* PyramidData::render() const {
+    SketchSpace &renderspace = space->getDualSpace();
+    //int const width = renderspace.getWidth();
+    //int const height = renderspace.getHeight();
+    //float x1,y1,x2,y2;
+    Sketch<bool>* draw_result = 
+      new Sketch<bool>(renderspace, "render("+getName()+")");
+    (*draw_result)->setParentId(getViewableId());
+    (*draw_result)->setColor(getColor());
+    *draw_result = 0;
+    LineData F(*space, FL, FR);
+    *draw_result = *draw_result & F.getRendering();
+    LineData L(*space, FL, BL);
+    *draw_result = *draw_result & L.getRendering();
+    LineData B(*space, BL, BR);
+    *draw_result = *draw_result & B.getRendering();
+    LineData R(*space, BR, FR);
+    *draw_result = *draw_result & R.getRendering();
+    LineData FT(*space, FL, Top);
+    *draw_result = *draw_result & FT.getRendering();
+    LineData LT(*space, FR, Top);
+    *draw_result = *draw_result & LT.getRendering();
+    LineData BT(*space, BL, Top);
+    *draw_result = *draw_result & BT.getRendering();
+    LineData RT(*space, BR, Top);
+    *draw_result = *draw_result & RT.getRendering();
+  
+    return draw_result;
+  }
+
+
+
+
+  /* Same idea as extractBrick, but simpler
+   */
+  Shape<PyramidData> PyramidData::extractPyramid(ShapeSpace& space, vector<Shape<BlobData> > &blobs)
+  {
+    unsigned int nblobs = blobs.size();
+    std::vector<Point> centroids;
+
+    ShapeRoot invalid;
+    if (nblobs != 2) {
+      return ShapeRootType(invalid,PyramidData);
+    }
+
+    for (unsigned int i=0; i<nblobs; i++) {
+      centroids.push_back(blobs[i]->getCentroid());
+    }
+  
+    // Check inter-blob distance
+    if (centroids[0].distanceFrom(centroids[1]) >= 
+	blobs[0]->topLeft.distanceFrom(centroids[0]) + 
+	blobs[1]->topLeft.distanceFrom(centroids[1])){
+      return ShapeRootType(invalid,PyramidData);	
+    }
+
+    int left=-1, right=-1;
+  
+    if (centroids[0].isLeftOf(centroids[1], camcentric)) {
+      left = 0;
+      right = 1;
+    }
+    else {
+      left = 1;
+      right = 0;
+    }
+
+    const int INTERSECT_DIST = 5, MIN_REQUIRED_DIST = 2;
+    NEW_SKETCH_N(leftEdist, uchar, visops::edist(blobs[left]->getRendering()));
+    NEW_SKETCH_N(rightEdist, uchar, visops::edist(blobs[right]->getRendering()));
+    NEW_SKETCH(small, bool, leftEdist<MIN_REQUIRED_DIST & rightEdist<MIN_REQUIRED_DIST);
+    if (!small->max()){
+      return ShapeRootType(invalid,PyramidData);	
+    }
+    NEW_SKETCH(boundary, bool, leftEdist<INTERSECT_DIST & rightEdist<INTERSECT_DIST);
+    rgb green_rgb(0, 255, 0);
+    boundary->setColor(green_rgb);
+
+    // Extract candidate points
+    std::vector<std::vector<Point> > points(5);
+
+    /*
+     *          0
+     *         /|\ 
+     *        / | \  
+     *       /  |  \ 
+     *      / L | R \ 
+     *     /    |    \ <--- 4
+     *    1-----2-----3
+     */
+
+
+    NEW_SHAPE(boundaryline, LineData, LineData::extractLine(boundary));
+
+    if (boundaryline.isValid()) {
+      points[0].push_back(boundaryline->topPt());
+      points[2].push_back(boundaryline->bottomPt());
+    }
+
+
+    // Find the corners for each face individually
+    // blobData::findCorners takes the number of corners you expect, so this 
+    // uses the same method as extractBrick
+
+    std::vector<Point> candidates; 
+
+    candidates = findBoundingTriangle(space, blobs[left], 
+				      centroids[left], boundaryline);
+
+    float cornerValue;
+
+    std::vector<Point> lcorners = blobs[left]->findCorners(3, candidates, cornerValue);
+
+    if (lcorners.size() == 3) {
+
+      unsigned int leftCorner = 0;
+      for (unsigned int i=1; i<3; i++){
+	if (lcorners[i].isLeftOf(lcorners[leftCorner], camcentric)) {
+	  leftCorner = i;
+	}
+      }
+
+      points[1].push_back(lcorners[leftCorner]);
+      points[2].push_back(lcorners[(leftCorner+1)%3]);
+      points[0].push_back(lcorners[(leftCorner+2)%3]);
+    
+    }
+    else {
+      return ShapeRootType(invalid,PyramidData);
+    }
+
+
+    // find the corners of the right face.
+
+    candidates.clear();
+    candidates = findBoundingTriangle(space, blobs[right], 
+				      centroids[right], boundaryline);
+
+    std::vector<Point> rcorners = blobs[right]->findCorners(3, candidates, cornerValue);
+
+    if (rcorners.size() == 3) {
+
+      unsigned int rightCorner = 0;
+      for (unsigned int i=1; i<3; i++){
+	if (rcorners[i].isRightOf(rcorners[rightCorner], camcentric)) {
+	  rightCorner = i;
+	}
+      }
+
+      points[3].push_back(rcorners[rightCorner]);
+      points[0].push_back(rcorners[(rightCorner+1)%3]);
+      points[2].push_back(rcorners[(rightCorner+2)%3]);
+    
+    }
+    else {
+      return ShapeRootType(invalid,PyramidData);
+    }
+
+    // debug output
+    for (unsigned int i=0; i<5; i++){
+      for (unsigned int j=0; j<points[i].size(); j++) {
+	NEW_SHAPE(corner, PointData, PointData(space, points[i][j]));
+	char name[10];
+	sprintf(name, "corner%d%d",i,j);
+	corner->setName(name);
+      }
+    }
+
+
+    vector<Point> finalCorners(5);
+
+    Point empty(0,0);
+
+    for (unsigned int i=0; i<5; i++) {
+      finalCorners[i] = empty;
+      for (unsigned int j=0; j<points[i].size(); j++) {
+	finalCorners[i]+=points[i][j];
+      }
+      if (points[i].size() > 0) {
+	finalCorners[i]/=points[i].size();
+      }
+    }
+
+
+
+
+    finalCorners[4] = finalCorners[1] + finalCorners[3] - finalCorners[2];
+
+
+    NEW_SHAPE(returnPyramid, PyramidData, new PyramidData(space,
+							  finalCorners[1],
+							  finalCorners[2],
+							  finalCorners[4],
+							  finalCorners[3],
+							  finalCorners[0]));
+  
+    return returnPyramid;
+  }
+
+
+
+  // A bounding triangle with room around it
+  // contracted in quadrilateral (polygon) fitting
+  vector<Point> PyramidData::findBoundingTriangle(ShapeSpace& space, Shape<BlobData> blob, 
+						  Point /*centroid*/, Shape<LineData> parallel)
+  {
+
+    const float PARALLEL_EXTEND_FACTOR = .4, ORTHO_EXTEND_FACTOR = .4;
+    
+    vector<Point> candidates;
+    
+    Point thirdPoint = (Region::extractRegion(blob->getRendering())).mostDistantPtFrom(parallel.getData());
+    
+    LineData perpendicular(space, thirdPoint, parallel->getThetaNorm());
+
+    Point isect(perpendicular.intersectionWithLine(parallel));
+    
+    Point orthoExtend((thirdPoint - isect)*ORTHO_EXTEND_FACTOR);
+    Point parallelExtend((parallel->end2Pt() - parallel->end1Pt())*PARALLEL_EXTEND_FACTOR);
+
+    Point pt1(parallel->end1Pt() - parallelExtend - orthoExtend);
+    Point pt2(parallel->end2Pt() + parallelExtend - orthoExtend);
+
+    if (pt1.isAbove(pt2, camcentric) && thirdPoint.isLeftOf(pt1, camcentric) || 
+	!pt1.isAbove(pt2, camcentric) && !thirdPoint.isLeftOf(pt1, camcentric)){
+      candidates.push_back(pt2);
+      candidates.push_back(pt1);
+    }
+    else {
+      candidates.push_back(pt1);
+      candidates.push_back(pt2);
+    }
+    candidates.push_back(thirdPoint + orthoExtend);
+
+    // debug output
+    NEW_SHAPE(candidate31, PointData, PointData(space, candidates[0]));
+    NEW_SHAPE(candidate32, PointData, PointData(space, candidates[1]));
+    NEW_SHAPE(candidate33, PointData, PointData(space, candidates[2]));
+    candidate31->setParentId(blob->getViewableId());
+    candidate32->setParentId(blob->getViewableId());
+    candidate33->setParentId(blob->getViewableId());
+
+    return candidates;
+  }
+
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/PyramidData.h ./DualCoding/PyramidData.h
--- ../Tekkotsu_2.4.1/DualCoding/PyramidData.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/PyramidData.h	2006-07-21 13:57:52.000000000 -0400
@@ -0,0 +1,99 @@
+//-*-c++-*-
+#ifndef _PYRAMIDDATA_H_
+#define _PYRAMIDDATA_H_
+
+#include <vector>
+#include <iostream>
+#include <string>
+
+#include "Shared/newmat/newmat.h"
+
+#include "BaseData.h"    // superclass
+#include "Point.h"       // Point data members
+#include "ShapeTypes.h"  // brickDataType
+
+#include "LineData.h"
+#include "ShapeLine.h"
+#include "ShapeBlob.h"
+
+namespace DualCoding {
+
+class ShapeRoot;
+class SketchSpace;
+template<typename T> class Sketch;
+
+class PyramidData : public BaseData {  
+ private:
+  EndPoint FL;
+  EndPoint FR;
+  EndPoint BL;
+  EndPoint BR;
+  EndPoint Top;
+
+  Point centroid;
+
+ public:
+
+  //! Constructor
+  PyramidData(ShapeSpace& _space,
+	    const EndPoint &FL, const EndPoint &FR, const EndPoint &BL, const EndPoint &BR, 
+	    const EndPoint &Top);
+
+
+  //! Copy constructor
+  //PyramidData(PyramidData& otherPyramid);
+
+  static ShapeType_t getStaticType() { return pyramidDataType; }
+  DATASTUFF_H(PyramidData);
+  
+  //! Centroid. (Virtual in BaseData.)
+  Point getCentroid() const { return centroid; } 
+  
+  EndPoint getFL() {return FL;}
+  EndPoint getFR() {return FR;}
+  EndPoint getBL() {return BL;}
+  EndPoint getBR() {return BR;}
+  EndPoint getTop() {return Top;}
+  
+  //! Match pyramids based on their parameters.  (Virtual in BaseData.)
+  virtual bool isMatchFor(const ShapeRoot& other) const;
+
+  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);
+  
+  //! Project to ground
+  //void projectToGround(const NEWMAT::ColumnVector& groundplane);
+
+  void projectToGround(const NEWMAT::Matrix & camToBase, 
+		       const NEWMAT::ColumnVector& groundplane);
+    
+  virtual unsigned short getDimension() const { return 3; }
+
+  //! Extraction.
+
+  static Shape<PyramidData> extractPyramid(ShapeSpace& space, vector<Shape<BlobData> > &blobs);
+    
+  static vector<Point> findBoundingTriangle(ShapeSpace& space, Shape<BlobData> blob, 
+					    Point centroid, Shape<LineData> parallel);
+private:
+  //! Render into a sketch space and return reference. (Private.)
+  Sketch<bool>* render() const;
+
+
+  //@}
+
+  PyramidData& operator=(const PyramidData&); //!< don't call
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/Region.cc ./DualCoding/Region.cc
--- ../Tekkotsu_2.4.1/DualCoding/Region.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Region.cc	2006-07-21 13:57:52.000000000 -0400
@@ -0,0 +1,373 @@
+//-*-c++-*-
+#include <cmath>
+#include <vector>
+#include <list>
+
+#include "Measures.h"
+#include "SketchSpace.h"
+#include "SketchIndices.h"
+#include "Sketch.h"
+
+#include "Region.h"
+
+namespace DualCoding {
+
+// be careful about changing this value, b/c memset writes bytes
+#define NOTCOMPUTED 0
+
+Region::Region(const SketchSpace& _space) : 
+  SketchIndices(), space(_space),
+  topBound(NOTCOMPUTED), botBound(NOTCOMPUTED), 
+  leftBound(NOTCOMPUTED), rightBound(NOTCOMPUTED),
+  area(NOTCOMPUTED)
+{ 
+  memset(&moments, NOTCOMPUTED, sizeof(float)*(MAX_MOMENT+1)*(MAX_MOMENT+1));
+  memset(&cmoments, NOTCOMPUTED, sizeof(float)*(MAX_MOMENT+1)*(MAX_MOMENT+1));
+}
+
+void Region::recomputeProperties() {
+  topBound = NOTCOMPUTED;
+  botBound = NOTCOMPUTED; 
+  leftBound = NOTCOMPUTED;
+  rightBound = NOTCOMPUTED;
+  area = NOTCOMPUTED;
+  memset(&moments, NOTCOMPUTED, sizeof(float)*(MAX_MOMENT+1)*(MAX_MOMENT+1));
+  memset(&cmoments, NOTCOMPUTED, sizeof(float)*(MAX_MOMENT+1)*(MAX_MOMENT+1));
+}
+
+std::list<Region> Region::extractRegions(const Sketch<usint>& labels, int 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
+  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++) {
+    if (areas[r] >= area_thresh) {
+      // construct Region and add to list
+      Region cur_reg(labels->getSpace());
+      for (size_t i = 0; i < length; i++)
+	if (labels[i] == r)
+	  cur_reg.table.insert(i);
+      cur_reg.area = areas[r]; // go ahead and pre-set area
+      regionlist.push_back(cur_reg); // actually calls copy constructor
+    }
+  }
+  
+  regionlist.sort();
+  return regionlist;
+}
+
+
+Region Region::extractRegion(const Sketch<bool>& sketch)
+{
+  size_t length = sketch->getNumPixels();
+
+  Region cur_reg(sketch->getSpace());
+
+  int area = 0;
+
+  for (size_t i = 0; i< length; i++) {
+    if (sketch[i]) {
+      area++;
+      cur_reg.table.insert(i);
+    }
+  }
+
+  cur_reg.area = area;
+
+  return cur_reg;
+}
+
+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 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;
+    topBound = top;
+    return top;
+  }
+}
+
+int Region::findBotBound() {
+  if (botBound != NOTCOMPUTED)  // problem if NOTCOMPUTED == 0
+    return botBound;	
+  else {
+    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;
+    botBound = bot;
+    return bot;
+  }
+}
+
+int Region::findLeftBound() {
+  if (leftBound != NOTCOMPUTED)  // problem if NOTCOMPUTED == 0
+    return leftBound;	
+  else {
+    SketchIndices::CI it;
+    int left = 9999;
+    int width = space.getWidth();
+    for (it = table.begin(); it != table.end(); it++)
+      if ((*it)%width < left)
+	left = (*it)%width;
+    leftBound = left;
+    return left;
+  }
+}
+
+int Region::findRightBound() {
+  if (rightBound != NOTCOMPUTED)  // problem if NOTCOMPUTED == 0
+    return rightBound;	
+  else {
+    SketchIndices::CI it;
+    int right = -1;
+    int width = space.getWidth();
+    for (it = table.begin(); it != table.end(); it++)
+      if ((*it)%width > right)
+	right = (*it)%width;
+    rightBound = right;
+    return right;
+  }
+}
+
+// returns x coordinate of first match Point for given y_coord
+int Region::findXcoordFor(const coordinate_t y_coord) {
+  const int width = space.getWidth();
+  //  const int width = space.getWidth()+1;
+  for (SketchIndices::CI it = table.begin(); 
+       it != table.end(); it++) 
+    if ((*it)/width == y_coord) 
+      return (*it)%width;
+  //return (*it)%(width-1);
+  return -1;
+}
+
+// returns y coordinate of first match Point for given x_coord
+int Region::findYcoordFor(const coordinate_t x_coord) {
+  const int width = space.getWidth();
+  for (SketchIndices::CI it = table.begin(); 
+       it != table.end(); it++)
+    if ((*it)%width == x_coord)
+      return (*it)/width;
+  return -1;
+}
+
+Point Region::findTopBoundPoint() {
+  const coordinate_t y_coord = findTopBound();
+  return Point(findXcoordFor(y_coord),y_coord);
+}
+Point Region::findBotBoundPoint() {
+  const coordinate_t y_coord = findBotBound();
+  return Point(findXcoordFor(y_coord),y_coord);
+}
+Point Region::findLeftBoundPoint() {
+  const coordinate_t x_coord = findLeftBound();
+  return Point(x_coord, findYcoordFor(x_coord));
+}
+Point Region::findRightBoundPoint() {
+  const coordinate_t x_coord = findRightBound();
+  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();
+  //  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))
+      return true;
+  return false;
+}
+
+Point Region::mostDistantPtFrom(const LineData& ln) {
+  float max_dist = 0;
+  Point most_dist_pt;
+  const int width = space.getWidth();
+  //  cout << pt << endl;
+  for (SketchIndices::CI it = table.begin(); 
+       it != table.end(); it++) {
+    if (ln.perpendicularDistanceFrom(Point((*it)%width, (*it)/width)) > max_dist) {
+      max_dist = ln.perpendicularDistanceFrom(Point((*it)%width, (*it)/width));
+      most_dist_pt.setCoords((*it)%width, (*it)/width);
+    }
+  }
+  return most_dist_pt;
+}
+
+
+
+
+// All moment-based equations taken from Prokop & Reeves 1992, "A survey of moment-based techniques for unoccluded object representation and recognition"
+float Region::findMoment(size_t p, size_t q) 
+{
+  // should add in more efficient routines for some low-moments like area
+  
+  if(moments[p][q] != NOTCOMPUTED) {
+    return moments[p][q];
+  } else {
+    // should pre-calculate powers for rows and columns, as in Flusser (1998)
+    int xmin = findLeftBound(), xmax = findRightBound();
+    float powp[xmax-xmin+1];
+    for (int x = xmin; x <= xmax; x++) {
+      if (x == 0) // if don't check for this, risk floating-point exception
+	powp[x-xmin] = 1;
+      else powp[x-xmin] = pow((float)(x), (float)p); 
+    }
+    int ymin = findTopBound(), ymax = findBotBound();
+    float powq[ymax-ymin+1];
+    for (int y = ymin; y <= ymax; y++) {
+      if (y == 0)
+	powq[y-ymin] = 1;
+      else powq[y-ymin] = pow((float)(y), (float)q); 
+    }
+    
+    float m = 0;
+    int xval, yval;
+    for (SketchIndices::CI it = table.begin(); it != table.end(); ++it) {
+      xval = (*it) % space.getWidth();
+      yval = (*it) / space.getWidth();
+      m += powp[xval-xmin] * powq[yval-ymin];
+    }
+    moments[p][q] = m;
+    return m;
+  }
+}
+
+float Region::findCentralMoment(size_t p, size_t q) {
+  // should add in more efficient routines for some low-moments like area
+  
+  if(cmoments[p][q] != NOTCOMPUTED) {
+    return cmoments[p][q];
+  } else {
+    Point centroid = findCentroid(); //cen.first;
+    const float cx = centroid.coordX();
+    const float cy = centroid.coordY();
+    
+    // should pre-calculate powers for rows and columns, as in Flusser (1998)
+    int xmin = findLeftBound(), xmax = findRightBound();
+    float powp[xmax-xmin+1];
+    for (int x = xmin; x <= xmax; x++) {
+      if ((x-cx)==0) // if don't check for this, risk floating-point exception
+	powp[x-xmin] = 1;
+      else powp[x-xmin] = pow((float)(x-cx), (float)p); 
+    }
+    int ymin = findTopBound(), ymax = findBotBound();
+    float powq[ymax-ymin+1];
+    for (int y = ymin; y <= ymax; y++) {
+      if ((y-cy)==0)
+	powq[y-ymin] = 1;
+      else powq[y-ymin] = pow((float)(y-cy), (float)q); 
+    }
+    
+    float m = 0;
+    int xval, yval;
+    for (SketchIndices::CI it = table.begin(); it != table.end(); ++it) {
+      xval = (*it) % space.getWidth();
+      yval = (*it) / space.getWidth();
+      //m += pow(xval,(float)p) * pow(yval,(float)q);
+      m += powp[xval-xmin] * powq[yval-ymin];
+    }
+    
+    cmoments[p][q] = m;
+    return m;
+  }
+}
+
+float Region::findNormCentralMoment(size_t p, size_t q) {
+  // normalize
+  // from Gonzalez & Woods (1992)
+  float gamma = (p+q)/2 + 1;
+  return(findCentralMoment(p,q) / pow(findArea(), gamma));
+}
+
+int Region::findArea() {
+  if (area != NOTCOMPUTED)
+    return area;
+  else {
+    area = table.size();
+    return area;
+  }
+}
+
+Point Region::findCentroid() {
+  findArea();
+  return Point(findMoment(1,0)/area, findMoment(0,1)/area);
+  //	centroid.first = findMoment(1,0)/findMoment(0,0);
+  //	centroid.second = findMoment(0,1)/findMoment(0,0);
+  //	return centroid;
+  
+  /*	if (centroid.first != NOTCOMPUTED) {
+	return centroid;
+	} else {
+	int xsum = 0, ysum = 0;
+	typedef SketchIndices::const_iterator CI;
+	for (CI i = begin(); i != end(); ++i) {
+	xsum += (*i) % space.getWidth();
+	ysum += (*i) / space.getWidth();
+	}
+	centroid.first = xsum/findArea();
+	centroid.second = ysum/findArea();
+	return centroid;
+	}*/
+}
+
+AngPi Region::findPrincipalAxisOrientation() {
+  return AngPi((0.5)*atan2(2*findCentralMoment(1,1), 
+			   findCentralMoment(2,0)-findCentralMoment(0,2)));
+}
+
+float Region::findSemiMajorAxisLength() {
+  float u20 = findCentralMoment(2,0);
+  float u02 = findCentralMoment(0,2);
+  float u11 = findCentralMoment(1,1);
+  //  float u00 = findCentralMoment(0,0);
+  float u00 = findArea();
+  return sqrt((2.0*(u20+u02+sqrt((u20-u02)*(u20-u02)+4*u11*u11)))/u00);
+}
+
+float Region::findSemiMinorAxisLength() {
+  float u20 = findCentralMoment(2,0);
+  float u02 = findCentralMoment(0,2);
+  float u11 = findCentralMoment(1,1);
+  // float u00 = findCentralMoment(0,0);
+  float u00 = findArea();
+  return sqrt((2.0*(u20+u02-sqrt((u20-u02)*(u20-u02)+4*u11*u11)))/u00);
+}
+
+/* FIX THIS
+float Region::findRadius() {
+  float u20 = findCentralMoment(2,0);
+  float u02 = findCentralMoment(0,2);
+  float u00 = findArea();
+  return sqrt((2.0*(u20+u02))/u00);
+}
+*/
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/Region.h ./DualCoding/Region.h
--- ../Tekkotsu_2.4.1/DualCoding/Region.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Region.h	2006-07-21 13:57:53.000000000 -0400
@@ -0,0 +1,97 @@
+//-*-c++-*-
+#ifndef INCLUDED_Region_h
+#define INCLUDED_Region_h
+
+#include <list>
+
+#include "Measures.h"
+#include "SketchIndices.h"
+#include "Point.h"
+#include "LineData.h"
+
+namespace DualCoding {
+
+class SketchSpace;
+
+#define MAX_MOMENT 5
+
+class Region : public SketchIndices {
+public:
+  Region(const SketchSpace& _space); //!< initializes all properties to be NOTCOMPUTED
+  ~Region() {};
+  
+  //! 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);
+
+  //! Return a single region from a sketch<bool>
+  static Region extractRegion(const Sketch<bool>& sketch);
+  
+  //! Compares areas of two Regions; really only used to sort Regions
+  //! assumes area already calculated
+  //! Notes that it actually returns greater-than instead of less-than, so
+  //! that lists are sorted with biggest areas first
+  bool operator< (const Region& other) const;
+  
+
+  //! sets all properties to be NOTCOMPUTED
+  //! called after making changes (either addition/deletion) to table
+  void recomputeProperties();
+
+  int findTopBound();
+  int findBotBound();
+  int findLeftBound();
+  int findRightBound();
+
+  Point findTopBoundPoint();
+  Point findBotBoundPoint();
+  Point findLeftBoundPoint();
+  Point findRightBoundPoint();
+  bool isContained(const Point&, const int max_dist=0);
+
+  Point mostDistantPtFrom(const LineData&);
+  
+  //! Calculates the two-dimensional Cartesian moment Mpq 
+  float findMoment(size_t p, size_t q);
+  float findCentralMoment(size_t p, size_t q);
+  //! Finds the area-normalized central moment
+  float findNormCentralMoment(size_t p, size_t q);
+  
+  int findArea();
+  Point findCentroid(); //!< returns coords of center of mass
+  
+  //! Returns the angle of the orientation of the principal axis in radians
+  AngPi findPrincipalAxisOrientation();
+  
+  //! Returns the length of the semi-major (x) axis of the image ellipse
+  float findSemiMajorAxisLength();
+  
+  //! Returns the length of the semi-minor (y) axis of the image ellipse
+  float findSemiMinorAxisLength();
+  
+  float findRadius() { return findSemiMajorAxisLength(); } //FIX THIS
+
+private:
+  const SketchSpace& space;
+  
+  int topBound;
+  int botBound;
+  int leftBound;
+  int rightBound;
+  
+  float moments[MAX_MOMENT+1][MAX_MOMENT+1];
+  float cmoments[MAX_MOMENT+1][MAX_MOMENT+1];
+  
+  int area;
+  
+  int findXcoordFor(const coordinate_t y_coord);
+  int findYcoordFor(const coordinate_t x_coord);
+  
+public:
+  const SketchSpace& getSpace() const { return space; };
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeAgent.cc ./DualCoding/ShapeAgent.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapeAgent.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeAgent.cc	2006-01-08 06:08:35.000000000 -0500
@@ -0,0 +1,16 @@
+//-*-c++-*-
+
+#include "SketchSpace.h"
+#include "ShapeSpace.h"
+
+#include "Point.h"
+#include "BaseData.h"
+#include "AgentData.h"
+
+#include "ShapeAgent.h"
+
+namespace DualCoding {
+
+SHAPESTUFF_CC(AgentData);
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeAgent.h ./DualCoding/ShapeAgent.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapeAgent.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeAgent.h	2006-09-23 23:45:20.000000000 -0400
@@ -0,0 +1,24 @@
+//-*-c++-*-
+#ifndef _SHAPEAGENT_H_
+#define _SHAPEAGENT_H_
+
+#include "Point.h"
+#include "ShapeRoot.h"
+#include "AgentData.h"
+
+namespace DualCoding {
+
+class ShapeSpace;
+
+template<>
+class Shape<AgentData> : public ShapeRoot {
+public:
+  SHAPESTUFF_H(AgentData);
+
+  Shape<AgentData>(ShapeSpace &s, Point centerval=Point(0,0,0)) :
+    ShapeRoot(addShape(new AgentData(s,centerval))) { };
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeBlob.cc ./DualCoding/ShapeBlob.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapeBlob.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeBlob.cc	2006-01-08 06:08:35.000000000 -0500
@@ -0,0 +1,11 @@
+//-*-c++-*-
+
+#include "ShapeSpace.h"
+
+#include "ShapeBlob.h"
+
+namespace DualCoding {
+
+SHAPESTUFF_CC(BlobData);    // defined in ShapeRoot.h
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeBlob.h ./DualCoding/ShapeBlob.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapeBlob.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeBlob.h	2006-04-19 17:11:10.000000000 -0400
@@ -0,0 +1,20 @@
+//-*-c++-*-
+#ifndef _SHAPEBLOB_H_
+#define _SHAPEBLOB_H_
+
+#include "ShapeRoot.h"
+#include "BlobData.h"
+
+namespace DualCoding {
+
+class ShapeSpace;
+
+template<>
+class Shape<BlobData> : public ShapeRoot {
+public:
+  SHAPESTUFF_H(BlobData);   // defined in ShapeRoot.h
+};
+
+} // namespace
+
+#endif // _SHAPEBLOB_H_
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeBrick.cc ./DualCoding/ShapeBrick.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapeBrick.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeBrick.cc	2006-01-08 06:08:35.000000000 -0500
@@ -0,0 +1,12 @@
+//-*-c++-*-
+#include <iostream>
+
+#include "SketchSpace.h"
+
+#include "ShapeBrick.h"
+
+namespace DualCoding {
+
+SHAPESTUFF_CC(BrickData);
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeBrick.h ./DualCoding/ShapeBrick.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapeBrick.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeBrick.h	2006-09-23 23:45:20.000000000 -0400
@@ -0,0 +1,26 @@
+//-*-c++-*-
+#ifndef _SHAPEBRICK_H_
+#define _SHAPEBRICK_H_
+
+#include "ShapeRoot.h"
+#include "BrickData.h"
+
+namespace DualCoding {
+
+class ShapeSpace;
+class Point;
+
+template<>
+class Shape<BrickData> : public ShapeRoot {
+public:
+  SHAPESTUFF_H(BrickData);   // defined in ShapeRoot.h
+
+  Shape<BrickData>(ShapeSpace &s, Point &GFL, Point &GFR, Point &GBL, Point &GBR, 
+		   Point &TFL, Point &TFR, Point &TBL, Point &TBR) 
+    : ShapeRoot(addShape(new BrickData(s, GFL, GFR, GBL, GBR, TFL, TFR, TBL, TBR))) {};
+	
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeEllipse.cc ./DualCoding/ShapeEllipse.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapeEllipse.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeEllipse.cc	2006-09-23 23:45:20.000000000 -0400
@@ -0,0 +1,25 @@
+//-*-c++-*-
+#include <iostream>
+
+using namespace std;
+
+#include "SketchSpace.h"
+#include "Region.h"
+
+#include "ShapeEllipse.h"
+
+namespace DualCoding {
+
+SHAPESTUFF_CC(EllipseData);
+	
+Shape<EllipseData>::Shape(Region& region)
+  : ShapeRoot(addShape(new EllipseData(region.getSpace().getDualSpace(),
+				       region.findCentroid())))
+{ 
+	(*this)->setSemimajor(region.findSemiMajorAxisLength());
+	(*this)->setSemiminor(region.findSemiMinorAxisLength());
+	(*this)->setOrientation(region.findPrincipalAxisOrientation());
+};
+
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeEllipse.h ./DualCoding/ShapeEllipse.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapeEllipse.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeEllipse.h	2006-09-23 23:45:20.000000000 -0400
@@ -0,0 +1,28 @@
+//-*-c++-*-
+#ifndef _SHAPEELLIPSE_H_
+#define _SHAPEELLIPSE_H_
+
+#include "ShapeRoot.h"
+#include "EllipseData.h"
+
+namespace DualCoding {
+
+class ShapeSpace;
+class Point;
+class Region;
+
+template<>
+class Shape<EllipseData> : public ShapeRoot {
+public:
+  SHAPESTUFF_H(EllipseData);   // defined in ShapeRoot.h
+
+  Shape<EllipseData>(ShapeSpace &s, Point &centerval)
+    : ShapeRoot(addShape(new EllipseData(s,centerval))) {};
+	
+  Shape<EllipseData>(Region& region);
+
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeFuns.cc ./DualCoding/ShapeFuns.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapeFuns.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeFuns.cc	2006-08-02 17:32:52.000000000 -0400
@@ -0,0 +1,25 @@
+//-*-c++-*-
+
+#include "ShapeRoot.h"
+#include "ShapeLine.h"
+#include "ShapeBlob.h"
+
+#include "ShapeFuns.h"
+
+namespace DualCoding {
+
+// ================
+
+bool IsLeftOf::operator() (const ShapeRoot &s1, const ShapeRoot &s2) const {
+  const Point c1 = s1->getCentroid();
+  const Point c2 = s2->getCentroid();
+  return c1.isLeftOf(c2,dist);
+}
+
+bool IsAbove::operator() (const ShapeRoot &s1, const ShapeRoot &s2) const {
+  const Point c1 = s1->getCentroid();
+  const Point c2 = s2->getCentroid();
+  return c1.isAbove(c2,dist);
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeFuns.h ./DualCoding/ShapeFuns.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapeFuns.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeFuns.h	2006-08-02 17:33:36.000000000 -0400
@@ -0,0 +1,314 @@
+//-*-c++-*-
+#ifndef INCLUDED_ShapeFuns_h_
+#define INCLUDED_ShapeFuns_h_
+
+#include <vector>
+
+#include "Shared/ProjectInterface.h"
+
+#include "ShapeTypes.h"
+#include "ShapeRoot.h"
+
+namespace DualCoding {
+
+// Note: the double parens in _name((_value)) are needed to keep the
+// compiler from confusing a copy constructor call with a function
+// description in certain cases, such as this one:
+//
+//    NEW_SHAPE(foo, LineData, Shape<LineData>(newline))
+
+//! Create a new shape and make it visible in the SketchGUI
+#define NEW_SHAPE(_name, _type, _value) \
+  Shape<_type> _name((_value)); \
+  if ( _name.isValid() ) _name->V(#_name);
+
+//! Create a new shape but hide it from the SketchGUI
+#define NEW_SHAPE_N(_name, _type, _value) \
+  NEW_SHAPE(_name, _type, _value); \
+  if ( _name.isValid() ) _name->N(#_name);
+
+//! Retrieve a shape based on its name
+#define GET_SHAPE(_name, _type, _shapevec) \
+  Shape<_type> _name(find_shape<_type>(_shapevec,#_name));
+
+//! Create a new vector of shapes of the specified type
+#define NEW_SHAPEVEC(_name, _type, _value) \
+  vector<Shape<_type> > _name((_value));
+
+//! Create a new vector of shapes of mixed type
+#define NEW_SHAPEROOTVEC(_name, _value) \
+  vector<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(); \
+        _var##_it != _shapesvec.end(); _var##_it++ ) { \
+    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); \
+        _var2##_it != _shapesvec.end(); _var2##_it++ ) { \
+    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(); \
+        _var##_it != _shapesvec.end(); _var##_it++ ) { \
+    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(); \
+        _var##_it != _shapesvec.end(); _var##_it++ ) { \
+    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); \
+        _var2##_it != _shapesvec.end(); _var2##_it++ ) { \
+    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(); \
+        _var##_it != _shapesvec.end(); _var##_it++ ) { \
+    ShapeRoot &_var = *_var##_it; \
+    _body }
+
+// ================================================================
+
+//! Unary predicates over ShapeRoot objects
+class UnaryShapeRootPred : public 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> {
+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> {
+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> {
+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.
+//@{
+template<typename PredType1, typename PredType2>
+class shortcircuit_and : public 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) {}
+  bool operator() (const typename PredType1::argument_type &shape) const {
+    if ( p1(shape) )
+      return p2(shape);
+    else return false;
+  }
+};
+
+template<typename PredType1, typename PredType2>
+class shortcircuit_or : public 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) {}
+  bool operator() (const typename PredType1::argument_type &shape) const {
+    if ( p1(shape) )
+      return true;
+    else return p2(shape);
+  }
+};
+
+/*! 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
+  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. */
+
+//@{
+
+//! 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) {
+  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) {
+  return shortcircuit_or<PredType1,PredType2>(p1,p2);
+}
+
+//@}
+
+// ================ Unary ShapeRoot predicates
+
+class isType : public UnaryShapeRootPred {
+ public:
+  ShapeType_t type;
+  explicit isType(ShapeType_t _type) : UnaryShapeRootPred(), type(_type) {}
+   bool operator()(const ShapeRoot &shape) const {
+    return shape->getType() == type; }
+};
+
+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)) {}
+   bool operator()(const ShapeRoot &shape) const {
+    return shape->getColor() == color; }
+};
+
+class isName : public UnaryShapeRootPred {
+ public:
+  std::string 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; }
+};
+
+// ================ find_if, find_shape, subset, max_element, stable_sort, etc.
+
+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);
+  if ( result != vec.end() )
+    return *result;
+  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();
+	it != vec.end(); it++ )
+    if ( (*it)->getType() == T::getStaticType() && (*it)->getName() == name )
+      return ShapeRootTypeConst(*it,T);
+  return Shape<T>();
+}
+
+//! Select the Shape<T> elements from a vector of ShapeRoots
+template<class T>
+std::vector<Shape<T> > select_type(std::vector<ShapeRoot> &vec) {
+  std::vector<Shape<T> > result(vec.size());
+  result.clear();
+  isType tpred(T::getStaticType());
+  DO_SHAPEROOTVEC(vec, element, {
+    if ( tpred(element) ) result.push_back(reinterpret_cast<const Shape<T>&>(element));
+  });
+  return result;
+}
+
+template<class T, typename PredType>
+std::vector<Shape<T> > subset(const std::vector<Shape<T> > &vec, PredType pred) {
+  std::vector<Shape<T> > result;
+  remove_copy_if(vec.begin(), vec.end(),
+		 std::back_insert_iterator<std::vector<Shape<T> > >(result),
+		 not1(pred));
+  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);
+  if ( result != vec.end() )
+    return *result;
+  else
+    return Shape<T>();
+}
+
+template<class T, typename ComparisonType>
+Shape<T> min_element(const vector<Shape<T> > &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);
+  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).
+
+#define DIRECTION_PAIR(dir, oppdir)                                             \
+class Is##dir : public BinaryShapeRootPred {                                    \
+ public:                                                                        \
+  Is##dir(float distance=0) : dist(distance) {}                                 \
+  bool operator() (const ShapeRoot&, const ShapeRoot&) const;                   \
+ private:                                                                       \
+  float dist;                                                                   \
+};                                                                              \
+                                                                                \
+class Is##dir##This : public UnaryShapeRootPred {                               \
+ public:                                                                        \
+  Is##dir##This(const ShapeRoot &_s2, float distance=0) :                       \
+     UnaryShapeRootPred(), s2(_s2), dist(distance) {}                           \
+  bool operator() (const ShapeRoot &s1) const {                                 \
+    return Is##dir(dist)(s1,s2); }                                             \
+ private:                                                                       \
+  ShapeRoot s2;                                                                 \
+  float dist;                                                                   \
+};                                                                              \
+                                                                                \
+class Is##oppdir : public BinaryShapeRootPred {                                 \
+ public:                                                                        \
+  Is##oppdir(float distance=0) : dist(distance) {}                              \
+  bool operator() (const ShapeRoot &s1, const ShapeRoot &s2) const {            \
+    return Is##dir(dist) (s2, s1); }                                            \
+ private:                                                                       \
+  float dist;                                                                   \
+};                                                                              \
+                                                                                \
+class Is##oppdir##This : public UnaryShapeRootPred {                            \
+ public:                                                                        \
+  Is##oppdir##This(const ShapeRoot &_s2, float distance=0) :                    \
+    UnaryShapeRootPred(), s2(_s2), dist(distance) {}                            \
+  bool operator() (const ShapeRoot &s1) const {                                 \
+    return Is##dir(dist) (s2,s1); }                                             \
+ private:                                                                       \
+  ShapeRoot s2;                                                                 \
+  float dist;                                                                   \
+};
+
+
+DIRECTION_PAIR(LeftOf, RightOf)
+DIRECTION_PAIR(Above, Below)
+
+#undef DIRECTION_PAIR
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeLine.cc ./DualCoding/ShapeLine.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapeLine.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeLine.cc	2006-09-23 23:45:20.000000000 -0400
@@ -0,0 +1,37 @@
+//-*-c++-*-
+#include <math.h>
+#include <vector>
+
+#include "ShapeLine.h"
+
+namespace DualCoding {
+
+SHAPESTUFF_CC(LineData);   // defined in ShapeRoot.h
+
+Shape<LineData>::Shape(ShapeSpace &s, const Point &colinear_pt, AngPi orientation)
+  : ShapeRoot(addShape(new LineData(s, colinear_pt,
+				    Point(colinear_pt.coordX() + 10.0 * cos(orientation),
+					  colinear_pt.coordY() + 10.0 * sin(orientation)))))
+{
+	(*this)->end1_pt.setActive(false);
+	(*this)->end1_pt.setValid(false);
+
+	(*this)->end2_pt.setActive(false);
+	(*this)->end2_pt.setValid(false);
+}
+
+
+Shape<LineData>::Shape(ShapeSpace &s, const Point &colinear_pt, Slope slope) 
+  : ShapeRoot(addShape(new LineData(s, colinear_pt,
+				    Point(colinear_pt.coordX()+10.0,
+					  slope * (colinear_pt.coordX()+10.0) +
+					  (colinear_pt.coordY()-slope*colinear_pt.coordX())))))
+{
+	(*this)->end1_pt.setActive(false);
+	(*this)->end1_pt.setValid(false);
+
+	(*this)->end2_pt.setActive(false);
+	(*this)->end2_pt.setValid(false);
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeLine.h ./DualCoding/ShapeLine.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapeLine.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeLine.h	2006-09-23 23:45:20.000000000 -0400
@@ -0,0 +1,36 @@
+//-*-c++-*-
+#ifndef _SHAPELINE_H_
+#define _SHAPELINE_H_
+
+#include "Measures.h"
+#include "ShapeRoot.h"
+#include "LineData.h"
+
+namespace DualCoding {
+
+class ShapeSpace;
+class Point;
+
+template<> class Shape<LineData> : public ShapeRoot {
+public:
+
+  SHAPESTUFF_H(LineData);  // defined in ShapeRoot.h
+
+  //! Make a line from two points.
+  Shape<LineData>(ShapeSpace &s, const Point &end1pt, const Point &end2pt)
+    : ShapeRoot(addShape(new LineData(s, end1pt, end2pt))) { };
+	
+  //! Make a line from a point and an orientation.
+  Shape<LineData>(ShapeSpace &s, const Point &colinear_pt, AngPi orientation);
+
+  //! Make a line from a point and a slope.
+  Shape<LineData>(ShapeSpace &s, const Point &colinear_pt, Slope slope);
+
+  //! Copy constructor.
+  Shape<LineData>(const LineData& newData) : ShapeRoot(addShape(new LineData(newData))) {};
+
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapePoint.cc ./DualCoding/ShapePoint.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapePoint.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapePoint.cc	2006-01-08 06:08:35.000000000 -0500
@@ -0,0 +1,12 @@
+//-*-c++-*-
+#include <iostream>
+
+#include "SketchSpace.h"
+
+#include "ShapePoint.h"
+
+namespace DualCoding {
+
+SHAPESTUFF_CC(PointData);
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapePoint.h ./DualCoding/ShapePoint.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapePoint.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapePoint.h	2006-09-23 23:45:20.000000000 -0400
@@ -0,0 +1,28 @@
+//-*-c++-*-
+#ifndef _SHAPEPOINT_H_
+#define _SHAPEPOINT_H_
+
+#include "ShapeRoot.h"
+#include "PointData.h"
+
+namespace DualCoding {
+
+class ShapeSpace;
+class Point;
+
+template<>
+class Shape<PointData> : public ShapeRoot {
+public:
+  SHAPESTUFF_H(PointData);   // defined in ShapeRoot.h
+
+  Shape<PointData>(ShapeSpace &s, const Point &pt)
+    : ShapeRoot(addShape(new PointData(s,pt))) {};
+
+  Shape<PointData>(const PointData& newData) : 
+    ShapeRoot(addShape(new PointData(newData))) {};
+
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapePolygon.cc ./DualCoding/ShapePolygon.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapePolygon.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapePolygon.cc	2006-01-08 06:08:35.000000000 -0500
@@ -0,0 +1,14 @@
+#include <iostream>
+
+#include "SketchSpace.h"
+#include "ShapeSpace.h"
+#include "ShapeLine.h"
+
+#include "PolygonData.h"
+#include "ShapePolygon.h"
+
+namespace DualCoding {
+
+SHAPESTUFF_CC(PolygonData);
+	
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapePolygon.h ./DualCoding/ShapePolygon.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapePolygon.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapePolygon.h	2006-09-23 23:45:21.000000000 -0400
@@ -0,0 +1,29 @@
+//-*-c++-*-
+#ifndef _SHAPEPOLYGON_H_
+#define _SHAPEPOLYGON_H_
+
+#include "ShapeRoot.h"
+#include "ShapeLine.h"
+#include "PolygonData.h"
+
+namespace DualCoding {
+
+class ShapeSpace;
+class Point;
+class Region;
+
+template<>
+class Shape<PolygonData> : public ShapeRoot {
+public:
+  SHAPESTUFF_H(PolygonData);   // defined in ShapeRoot.h
+
+  Shape<PolygonData>(const LineData& side) : ShapeRoot(addShape(new PolygonData(side))) {};
+
+  Shape<PolygonData>(const Shape<LineData>& side)
+    : ShapeRoot(addShape(new PolygonData(LineData(side.getSpace(), side->end1Pt(), side->end2Pt())))) {};
+  
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapePyramid.cc ./DualCoding/ShapePyramid.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapePyramid.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapePyramid.cc	2006-07-21 13:57:53.000000000 -0400
@@ -0,0 +1,12 @@
+//-*-c++-*-
+#include <iostream>
+
+#include "SketchSpace.h"
+
+#include "ShapePyramid.h"
+
+namespace DualCoding {
+
+SHAPESTUFF_CC(PyramidData);
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapePyramid.h ./DualCoding/ShapePyramid.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapePyramid.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapePyramid.h	2006-09-23 23:45:21.000000000 -0400
@@ -0,0 +1,25 @@
+//-*-c++-*-
+#ifndef _SHAPEPYRAMID_H_
+#define _SHAPEPYRAMID_H_
+
+#include "ShapeRoot.h"
+#include "PyramidData.h"
+
+namespace DualCoding {
+
+class ShapeSpace;
+class Point;
+
+template<>
+class Shape<PyramidData> : public ShapeRoot {
+public:
+  SHAPESTUFF_H(PyramidData);   // defined in ShapeRoot.h
+
+  Shape<PyramidData>(ShapeSpace &s, Point &FL, Point &FR, Point &BL, Point &BR, Point &Top)
+    : ShapeRoot(addShape(new PyramidData(s, FL, FR, BL, BR, Top))) {};
+	
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeRoot.cc ./DualCoding/ShapeRoot.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapeRoot.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeRoot.cc	2006-09-23 23:45:21.000000000 -0400
@@ -0,0 +1,94 @@
+#include "SketchSpace.h"
+#include "ShapeSpace.h"
+
+#include "Macrodefs.h"
+
+#include "ShapeTypes.h"
+#include "ShapeRoot.h"
+
+#include "BaseData.h"
+
+namespace DualCoding {
+
+ShapeRoot::ShapeRoot(BaseData *p) : id(p->getId()), data(p) {
+  ++data->refcount;
+}
+
+ShapeRoot::ShapeRoot(const ShapeRoot &other) 
+  : id(other.id), data(other.data) {
+  if ( data != NULL )
+    ++data->refcount;
+};
+
+ShapeRoot& ShapeRoot::operator=(const ShapeRoot& src) {
+  if ( data != NULL && --data->refcount == 0 && data != src.data )
+    delete data;
+  id = src.id;
+  data = src.data;
+  if ( data != NULL )
+    ++data->refcount;
+  return *this;
+}
+
+ShapeRoot::~ShapeRoot(void) { 
+  if ( data != NULL && --data->refcount == 0 )
+	 delete data;
+}
+
+void ShapeRoot::deleteShape(void) { 
+  if ( isValid() )
+	 data->space->deleteShape(*this); 
+}
+
+void ShapeRoot::sanity_check(void) const {
+  if ( !isValid() ) {
+    cerr << "ERROR: Reference to invalid shape at " << (const void*)this
+			<< "  id=" << id << "  data=" << (const void*)data;
+	 if ( data != NULL )
+		cout << "  data->id=" << data->id;
+	 cout << endl;
+  }
+}
+
+BaseData* ShapeRoot::operator-> (void) {
+	sanity_check();
+ 	return data;
+}
+
+BaseData* ShapeRoot::operator-> (void) const { 
+	sanity_check(); 
+	return data;
+}
+
+BaseData& ShapeRoot::getData() const {
+  sanity_check(); 
+  return *data;;
+}
+
+ShapeSpace& ShapeRoot::getSpace() const {
+  sanity_check(); 
+  return *(data->space);
+}
+
+bool ShapeRoot::operator==(const ShapeRoot& other) const {
+  if ( isValid() )
+    if ( other.isValid() )
+      return id == other.id;
+    else
+      return false;
+  else
+    return !other.isValid();
+}      
+
+std::ostream& operator<<(std::ostream &os, const ShapeRoot &r) {
+  if ( r.isValid() ) {
+    cout << r.data->getSpace().name << " " << "Shape<" << r->getTypeName() << ">(id="
+	 << r.id << ", data=" << r.data  << ")";
+  }
+  else {
+	 cout << "Shape(id=" << r.getId() << ",data=" << (unsigned int)r.data << ")[invalid]";
+  }
+  return os;
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeRoot.h ./DualCoding/ShapeRoot.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapeRoot.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeRoot.h	2006-09-23 23:45:21.000000000 -0400
@@ -0,0 +1,106 @@
+//-*-c++-*-
+#ifndef _SHAPEROOT_H_
+#define _SHAPEROOT_H_
+
+#include <vector>
+
+#include "ShapeSpace.h"
+#include "ShapeTypes.h"
+#include "BaseData.h"
+
+namespace DualCoding {
+
+//! Parent class for all Shape<T>
+
+/*! Shape<T> points to data objects of type T within a ShapeSpace, e.g.,
+    Shape<LineData> points to 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
+    a shape decrements it.  If refcount goes to zero we delete the
+    data object.  If the user calls deleteShape on a Shape, we remove the
+    shape from the ShapeSpace but don't actually delete it until the
+    reference count goes to zero.
+*/
+
+class ShapeRoot {
+protected:
+  int        id;
+  BaseData   *data;
+  
+  friend class ShapeSpace;
+  friend std::ostream& operator<<(std::ostream &os, const ShapeRoot &r);
+
+public:
+  //! Construct a dummy ShapeRoot, e.g., so we can assign into it, or return it
+  //! as an indicator of an invalid or failure result.
+  ShapeRoot(void): id(-1), data(NULL) {};  
+  
+  //! The usual constructor.
+  ShapeRoot(BaseData *p);
+  
+  //! Copy constructor: shallow copy
+  ShapeRoot(const ShapeRoot &other);
+
+  virtual ~ShapeRoot(void);
+
+  void deleteShape(void);
+
+  void sanity_check(void) const;
+  
+  inline bool isValid() const { 
+    return data != NULL && id > 0 && id == data->id;
+  }
+
+  void setInvalid() {
+    if ( id > 0 )
+      id = -id;
+  }
+
+  // Overload the -> operator, and other things...
+  virtual BaseData* operator-> (void);
+  virtual BaseData* operator-> (void) const;
+
+  int getId() const { return id; }
+  virtual BaseData& getData() const;
+  ShapeSpace& getSpace() const;
+
+  //! Shape comparison.  Invalid shapes are considered equal.
+  //@{
+  virtual bool operator==(const ShapeRoot& other) const;
+
+  virtual bool operator!=(const ShapeRoot& other) const {
+    return ! operator==(other);
+  }
+  //@}
+
+  ShapeRoot& operator=(const ShapeRoot&);
+
+protected:
+  ShapeRoot& addShape(BaseData *p) { return p->space->addShape(p); }
+
+};
+
+std::ostream& operator<<(std::ostream &os, const ShapeRoot &r);
+
+//****************
+
+
+#define ShapeRootTypeConst(_arg,_type) (*reinterpret_cast<const Shape<_type>*>(&_arg))
+#define ShapeRootType(_arg,_type) (*reinterpret_cast<Shape<_type>*>(&_arg))
+
+#define SHAPESTUFF_H(T) \
+  Shape<T>() : ShapeRoot() {} \
+  Shape<T>(T* newdata) : ShapeRoot(addShape(newdata)) {}	\
+  virtual T* operator->(); \
+  virtual T* operator->() const; \
+  virtual T& getData() const;
+
+#define SHAPESTUFF_CC(T) \
+  T* Shape<T>::operator->() { sanity_check(); return static_cast<T*>(data); };        \
+  T* Shape<T>::operator->() const { sanity_check(); return static_cast<T*>(data); };  \
+  T& Shape<T>::getData() const { return  *static_cast<T*>(data); };
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeSpace.cc ./DualCoding/ShapeSpace.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapeSpace.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeSpace.cc	2006-09-23 23:45:21.000000000 -0400
@@ -0,0 +1,279 @@
+#include <iostream>
+#include <vector>
+#include <sstream>
+#include <string>
+
+#include "Shared/newmat/newmat.h"
+#include "Shared/newmat/newmatio.h"
+
+#include "ShapeRoot.h"
+#include "ShapeAgent.h"
+#include "ShapeLine.h"
+#include "ShapeEllipse.h"
+#include "ShapePoint.h"
+#include "ShapeSphere.h"
+#include "ShapeBlob.h"
+#include "ShapePolygon.h"
+#include "ShapeBrick.h"
+#include "ShapePyramid.h"
+#include "BaseData.h"
+#include "SketchSpace.h"
+#include "ShapeSpace.h"
+#include "VRmixin.h"
+
+namespace DualCoding {
+
+ShapeSpace::ShapeSpace(SketchSpace* dualSkS, int init_id, 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.clear();
+}
+
+ShapeSpace::~ShapeSpace(void) {
+  //cout << "Deleting ShapeSpace " << name << " at " << this << endl;
+  // do not call clear() here; VRmixin::theAgent's reference count (in AgentData) may be wrong if the static Shape was already deleted
+};
+
+ShapeRoot& ShapeSpace::addShape(BaseData *p) {
+  p->id = ++id_counter;
+  shapeCache.push_back(ShapeRoot(p));
+  return shapeCache[shapeCache.size()-1];
+};
+
+void ShapeSpace::importShapes(vector<ShapeRoot>& foreign_shapes) {
+  for (vector<ShapeRoot>::const_iterator it = foreign_shapes.begin();
+       it != foreign_shapes.end();
+       ++it) importShape(*it);
+}
+
+BaseData* ShapeSpace::importShape(const ShapeRoot& foreign_shape) {
+  BaseData *own = foreign_shape->clone();
+  own->space = this;
+  own->parentId = 0;
+  own->lastMatchId = foreign_shape.id;
+  own->refcount = 0;
+  addShape(own);
+  return own;  // return value is used by MapBuilder::importLocalToWorld
+}
+
+void ShapeSpace::deleteShape(ShapeRoot &b) {
+  if ( b.isValid() )
+    for ( vector<ShapeRoot>::iterator it = shapeCache.begin();
+	  it != shapeCache.end(); ++it ) {
+      if ( it->id == b.id ) {
+	shapeCache.erase(it);
+	break;
+      }
+    }
+  else
+    std::cerr << "ERROR: Attempt to delete an invalid " << b << std::endl;
+}
+
+void ShapeSpace::deleteShapes(vector<ShapeRoot>& shapes_vec) {
+  for (size_t i=0; i < shapes_vec.size(); i++)
+    deleteShape(shapes_vec[i]);
+}
+
+void ShapeSpace::clear() {
+  shapeCache.clear();
+  if ( this == &VRmixin::worldShS && VRmixin::theAgent.isValid() )
+    shapeCache.push_back(VRmixin::theAgent);
+}
+
+void ShapeSpace::applyTransform(const NEWMAT::Matrix& Tmat) {
+  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);
+}
+
+Point ShapeSpace::getCentroid() {
+  vector<ShapeRoot> allShapes_vec = allShapes();
+  return(getCentroidOfSubset(allShapes_vec));
+}
+
+Point ShapeSpace::getCentroidOfSubset(const 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++)
+    subset_centroid_pt += subsetShapes_vec[cur_shape]->getCentroid();
+  return(subset_centroid_pt/(float)nshapes);	
+}
+
+std::vector<ShapeRoot> ShapeSpace::allShapes(ShapeType_t type) {
+  allShapes();  // make sure cache is valid;
+  std::vector<ShapeRoot> result;
+  for ( std::vector<ShapeRoot>::const_iterator it = shapeCache.begin();
+	it != shapeCache.end(); it++ )
+    if ( (*it)->getType() == type )
+      result.push_back(*it);
+  return result;
+}
+
+std::vector<ShapeRoot> ShapeSpace::allShapes(rgb color) {
+  std::vector<ShapeRoot> result(shapeCache.size());
+  result.clear();
+  for ( std::vector<ShapeRoot>::const_iterator it = shapeCache.begin();
+	it != shapeCache.end(); ++it )
+    if ( (*it)->getColor() == color )
+      result.push_back(*it);
+  return result;
+}
+
+string ShapeSpace::getShapeListForGUI(void) {
+  vector<ShapeRoot> &allShapes_vec = allShapes();
+  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() ) {
+      liststream << "shape" << endl;
+      liststream << "id: " << allShapes_vec[i]->getId() << endl;
+      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 << "cxyz: " << writept(allShapes_vec[i]->getCentroid()) << endl;
+		
+      if(allShapes_vec[i]->isType(lineDataType)) { // lineshape
+	const Shape<LineData>& current = ShapeRootTypeConst(allShapes_vec[i],LineData);
+	liststream << "e1xyz: " << writept(current->end1Pt()) << endl; 
+	liststream << "e2xyz: " << writept(current->end2Pt()) << endl; 
+	liststream << "r:" << current->getRhoNorm() << endl;
+	liststream << "theta: " << current->getThetaNorm() << endl;
+	liststream << "end1: " << (current->end1Pt().isValid()) << " " 
+		   << (current->end1Pt().isActive()) << endl;
+	liststream << "end2: " << (current->end2Pt().isValid()) << " "
+		   << (current->end2Pt().isActive()) << endl;
+      } 
+		
+      else if (allShapes_vec[i]->isType(ellipseDataType)) { // ellipseshape
+	const Shape<EllipseData>& current = ShapeRootTypeConst(allShapes_vec[i],EllipseData);
+	liststream << "axes: " << current->getSemimajor()
+		   << " " << current->getSemiminor() << endl;
+	liststream << "orientation: " << current->getOrientation() 
+		   << endl;
+      } 
+		
+      else if (allShapes_vec[i]->isType(pointDataType)) { // pointshape
+	;
+      }
+		
+      else if (allShapes_vec[i]->isType(agentDataType)) { // agentshape
+	const Shape<AgentData>& current = ShapeRootTypeConst(allShapes_vec[i],AgentData);
+	liststream << "orientation: " << current->getOrientation() << endl;
+      }
+		
+      else if (allShapes_vec[i]->isType(sphereDataType)) { // sphereshape
+	const Shape<SphereData>& current = ShapeRootTypeConst(allShapes_vec[i],SphereData);
+	liststream << "radius: " << current->getRadius() << endl;
+      }
+		
+      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();
+	     vtx_it != current->getVertices().end(); vtx_it++)
+	  liststream << "vertex: " << writept((*vtx_it)) << endl;
+	liststream << "end1_valid: " << (current->end1Ln().end1Pt().isValid()) << endl;
+	liststream << "end2_valid: " << (current->end2Ln().end2Pt().isValid()) << endl;
+      }
+		
+      else if (allShapes_vec[i]->isType(blobDataType)) { // blobshape
+	const Shape<BlobData>& current = ShapeRootTypeConst(allShapes_vec[i],BlobData);
+	liststream << "area: " << current->getArea() << endl;
+	liststream << "orient: " << current->orientation << endl;
+	liststream << "topLeft: " << writept(current->topLeft) << endl;
+	liststream << "topRight: " << writept(current->topRight) << endl;
+	liststream << "bottomLeft: " << writept(current->bottomLeft) << endl;
+	liststream << "bottomRight :" << writept(current->bottomRight) << endl;
+      }
+      else if (allShapes_vec[i]->isType(brickDataType)) { // brickshape
+	const Shape<BrickData>& current = ShapeRootTypeConst(allShapes_vec[i],BrickData);
+	liststream << "GFL: " << writept(current->getGFL()) << endl;
+	liststream << "GBL: " << writept(current->getGBL()) << endl;
+	liststream << "GFR: " << writept(current->getGFR()) << endl;
+	liststream << "GBR: " << writept(current->getGBR()) << endl;
+	liststream << "TFL: " << writept(current->getTFL()) << endl;
+	liststream << "TBL: " << writept(current->getTBL()) << endl;
+	liststream << "TFR: " << writept(current->getTFR()) << endl;
+	liststream << "TBR: " << writept(current->getTBR()) << endl;
+      }
+      else if (allShapes_vec[i]->isType(pyramidDataType)) { // pyramidshape
+	const Shape<PyramidData>& current = ShapeRootTypeConst(allShapes_vec[i],PyramidData);
+	liststream << "FL: " << writept(current->getFL()) << endl;
+	liststream << "BL: " << writept(current->getBL()) << endl;
+	liststream << "FR: " << writept(current->getFR()) << endl;
+	liststream << "BR: " << writept(current->getBR()) << endl;
+	liststream << "Top: " << writept(current->getTop()) << endl;
+      }
+    }	
+  }
+#undef writept
+  return liststream.str();	
+}
+
+void
+ShapeSpace::printParams()
+{
+  cout << endl;
+  cout << "SHAPE SPACE : PARAMETERS BEGIN" << endl;
+  int cur, num;
+  
+  vector<ShapeRoot> &allShapes_vec = allShapes();
+  num = (int)(allShapes_vec.size());
+  
+  for(cur = 0; cur < num; cur++) {
+    
+    cout << "SHAPE " <<  allShapes_vec[cur].getId() 
+	 << " (" << cur+1 << " of " << num << ")" 
+	 << endl;
+    
+    allShapes_vec[cur]->printParams();
+    
+    cout << "===========================================" << endl;
+    cout << endl;
+    
+  }
+  
+  cout << endl;
+  cout << "SHAPE SPACE : PARAMETERS END" << endl;
+}
+
+
+
+void
+ShapeSpace::printSummary()
+{
+  // JJW will this cause a memory leak?
+  vector<ShapeRoot> allShapes_vec = allShapes();
+  int cur;
+  int num = (int)(allShapes_vec.size());
+  cout << "SHAPE SPACE : SUMMARY BEGIN" << endl;
+  vector<int> shape_counts;
+  shape_counts.resize(numDataTypes,0);
+  
+  cout << endl << "Shape Listing:" << endl;
+  for(cur = 0; cur < num; cur++) {
+    cout << "Shape " << allShapes_vec[cur].getId() 
+	 << " (" << cur+1 << " of " << num << ")."
+	 << "\tType: " << allShapes_vec[cur]->getTypeName() 
+	 << endl;
+    shape_counts[allShapes_vec[cur]->getType()]++;
+  }
+  
+  cout << endl << "Shape Counts:" << endl;
+  num = numDataTypes;
+  for(cur = 0; cur < num; cur++) {
+    cout << "Shape Type " << cur << " " << data_name(cur) 
+	 << ":\t" << shape_counts[cur] << endl;
+  }
+  cout << endl;
+  
+  cout << "SHAPE SPACE : SUMMARY END" << endl;
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeSpace.h ./DualCoding/ShapeSpace.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapeSpace.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeSpace.h	2006-09-23 23:45:21.000000000 -0400
@@ -0,0 +1,100 @@
+//-*-c++-*-
+#ifndef _SHAPESPACE_H_
+#define _SHAPESPACE_H_
+
+#include <vector>
+#include <iostream>
+
+#include "Vision/colors.h"
+#include "Shared/newmat/newmat.h"
+
+#include "Measures.h"
+#include "ShapeTypes.h"
+
+namespace DualCoding {
+
+//****************
+//
+// ShapeSpace holds a collection of data objects, e.g., AgentData,
+// LineData, EllipseData
+
+class BaseData;
+class ShapeRoot;
+class Point;
+class SketchSpace;
+class LineData;
+template<typename T> class Shape;
+class Shape<LineData>;
+
+//! Holds a collection of diverse shapes such as LineData or EllipseData
+
+class ShapeSpace {
+private:
+  friend class SketchSpace;
+  friend class ShapeRoot;
+  friend class VisualRoutinesBehavior;
+  //  friend class WorldMapBuilder;
+  
+public:
+  string name;  //!< Name of the ShapeSpace
+
+private:
+  SketchSpace* dualSpace;
+  int id_counter;
+  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="", 
+	     ReferenceFrameType_t _refFrameType=camcentric);
+  
+  ~ShapeSpace(void);
+  
+  SketchSpace& getDualSpace(void) const { return *dualSpace; }
+  ReferenceFrameType_t getRefFrameType() const { return refFrameType; }
+  
+  void importShapes(std::vector<ShapeRoot>& foreign_shapes);
+  BaseData* importShape(const ShapeRoot& foreign_shape);
+  
+  void deleteShape(ShapeRoot &b);
+  void deleteShapes(std::vector<ShapeRoot>& shapes_vec); 
+  
+  void clear();
+  
+  std::vector<ShapeRoot>& allShapes(void) { return shapeCache; }
+  const std::vector<ShapeRoot>& allShapes(void) const { return shapeCache; }
+  std::vector<ShapeRoot> allShapes(ShapeType_t type);
+  std::vector<ShapeRoot> allShapes(rgb color);
+
+  // Coerce a ShapeSpace into a vector of ShapeRoots it contains
+  operator std::vector<ShapeRoot>&() { return shapeCache; }
+  std::vector<ShapeRoot>::iterator begin() { return shapeCache.begin(); }
+  std::vector<ShapeRoot>::iterator end() { return shapeCache.end(); }
+
+  std::string getShapeListForGUI(void);
+  
+  
+  void printParams(void);
+  void printSummary(void);
+  
+  //! Transformation and Location Utilities
+  //@{
+  void applyTransform(const NEWMAT::Matrix& Tmat);
+  
+  Point getCentroid(void);
+  
+  Point getCentroidOfSubset(const std::vector<ShapeRoot>& subset);
+  //@}
+
+private:
+  ShapeSpace(const ShapeSpace&);  //!< never call this
+  ShapeSpace& operator=(const ShapeSpace&); //!< never call this
+
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeSphere.cc ./DualCoding/ShapeSphere.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapeSphere.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeSphere.cc	2006-09-23 23:45:21.000000000 -0400
@@ -0,0 +1,21 @@
+#include <iostream>
+
+using namespace std;
+
+#include "SketchSpace.h"
+#include "Region.h"
+
+#include "ShapeSphere.h"
+
+namespace DualCoding {
+
+SHAPESTUFF_CC(SphereData);
+	
+Shape<SphereData>::Shape(Region& region)
+  : ShapeRoot(addShape(new SphereData(region.getSpace().getDualSpace(), 
+				      region.findCentroid())))
+{ 
+	(*this)->setRadius(region.findRadius());
+};
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeSphere.h ./DualCoding/ShapeSphere.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapeSphere.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeSphere.h	2006-09-23 23:45:21.000000000 -0400
@@ -0,0 +1,27 @@
+//-*-c++-*-
+#ifndef _SHAPESPHERE_H_
+#define _SHAPESPHERE_H_
+
+#include "ShapeRoot.h"
+#include "SphereData.h"
+
+namespace DualCoding {
+
+class ShapeSpace;
+class Point;
+class Region;
+
+template<>
+class Shape<SphereData> : public ShapeRoot {
+public:
+  SHAPESTUFF_H(SphereData);   // defined in ShapeRoot.h
+
+  Shape<SphereData>(ShapeSpace &s, Point centerval)
+    : ShapeRoot(addShape(new SphereData(s,centerval))) {};
+	
+  Shape<SphereData>(Region& region);
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeTypes.cc ./DualCoding/ShapeTypes.cc
--- ../Tekkotsu_2.4.1/DualCoding/ShapeTypes.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeTypes.cc	2006-07-21 13:57:56.000000000 -0400
@@ -0,0 +1,44 @@
+//-*-c++-*-
+
+#include "ShapeTypes.h"
+
+namespace DualCoding {
+
+const char* data_name(int data_type)
+{
+  switch(data_type) {
+  case lineDataType:
+    return("LineData");
+    break;
+  case ellipseDataType:
+    return("EllipseData");
+    break;
+  case pointDataType:
+    return("PointData");
+    break;
+  case agentDataType:
+    return("AgentData");
+    break;
+  case sphereDataType:
+    return("SphereData");
+    break;
+  case polygonDataType:
+    return("PolygonData");
+    break;
+  case blobDataType:
+    return("BlobData");
+    break;
+  case brickDataType:
+    return("BrickData");
+    break;
+  case pyramidDataType:
+    return("PyramidData");
+    break;
+  case unknownDataType:
+  default:
+    return("*Unknown*");
+    break;
+  }
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ShapeTypes.h ./DualCoding/ShapeTypes.h
--- ../Tekkotsu_2.4.1/DualCoding/ShapeTypes.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ShapeTypes.h	2006-08-02 17:36:43.000000000 -0400
@@ -0,0 +1,36 @@
+//-*-c++-*-
+#ifndef _ShapeTypes_H_
+#define _ShapeTypes_H_
+
+namespace DualCoding {
+
+enum ReferenceFrameType_t {
+  unspecified,
+  camcentric,
+  egocentric,
+  allocentric
+};
+
+//! NOTE: If any of these type numbers are changed, the corresponding type
+//! number must be changed in SketchGUI.java and possibly elsewhere!
+enum ShapeType_t {
+  unknownDataType = 0,
+  lineDataType,
+  ellipseDataType,
+  pointDataType,
+  agentDataType,
+  sphereDataType,
+  polygonDataType,
+  blobDataType,
+  brickDataType,
+  pyramidDataType,
+  
+  // this one must always come last
+  numDataTypes
+};
+
+const char* data_name(int data_type);
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/Sketch.cc ./DualCoding/Sketch.cc
--- ../Tekkotsu_2.4.1/DualCoding/Sketch.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Sketch.cc	2006-02-22 21:26:33.000000000 -0500
@@ -0,0 +1,136 @@
+//-*-c++-*-
+
+#include "Sketch.h"
+
+namespace DualCoding {
+
+// These functions must go here instead of in Sketch.h because
+// they are not templated.
+
+#define DEF_MATHOPS_CC(_T1, _T2, _Result) \
+  DEF_MATHOP_CC( +, _T1, _T2, _Result ) \
+  DEF_MATHOP_CC( -, _T1, _T2, _Result ) \
+  DEF_MATHOP_CC( *, _T1, _T2, _Result ) \
+  DEF_MATHOP_CC( /, _T1, _T2, _Result )
+
+#define DEF_MATHOP_CC(_Op, _T1, _T2, _Result) \
+Sketch<_Result> operator _Op (const Sketch<_T1> &lhs, const Sketch<_T2> &rhs) { \
+  Sketch<_Result> result(lhs->getName() + #_Op + rhs->getName(), lhs); \
+  _Result* dest = &(*result.pixels)[0]; \
+  const _T1* src1 = &(*lhs.pixels)[0]; \
+  const _T1* end1 = &(*lhs.pixels)[lhs->getNumPixels()]; \
+  const _T2* src2 = &(*rhs.pixels)[0]; \
+  while ( src1 != end1 ) \
+    *dest++ = *src1++ _Op *src2++; \
+  return result; \
+} \
+/* continued... */ \
+Sketch<_Result> operator _Op (const Sketch<_T1> &lhs, const _T2 value) { \
+  Sketch<_Result> result(lhs->getName() + #_Op + "scalar", lhs); \
+  _Result* dest = &(*result.pixels)[0]; \
+  const _T1* src1 = &(*lhs.pixels)[0]; \
+  const _T1* end1 = &(*lhs.pixels)[lhs->getNumPixels()]; \
+  while ( src1 != end1 ) \
+    *dest++ = *src1++ _Op (_Result)value; \
+  return result; \
+}
+
+// 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, float, float)
+
+DEF_MATHOPS_CC(uchar, bool, uchar)
+DEF_MATHOPS_CC(uchar, uchar, uchar)
+DEF_MATHOPS_CC(uchar, usint, usint)
+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(float, bool, float)
+DEF_MATHOPS_CC(float, uchar, float)
+DEF_MATHOPS_CC(float, usint, float)
+DEF_MATHOPS_CC(float, float, float)
+
+#undef DEF_MATHOPS_CC
+#undef DEF_MATHOP_CC
+
+#define DEF_MATHOPS_INT_CC(_T1) \
+  DEF_MATHOP_INT_CC( +, _T1) \
+  DEF_MATHOP_INT_CC( -, _T1) \
+  DEF_MATHOP_INT_CC( *, _T1) \
+  DEF_MATHOP_INT_CC( /, _T1)
+
+#define DEF_MATHOP_INT_CC(_Op, _T1) \
+Sketch<_T1> operator _Op (const Sketch<_T1>& lhs, const int value) { \
+  Sketch<_T1> result(lhs->getName() + #_Op + "scalar", lhs); \
+  *result.pixels = *lhs.pixels _Op (_T1)(value); \
+  return result; \
+}
+
+//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(float)
+
+#undef DEF_MATHOPS_INT_CC
+#undef DEF_MATHOP_INT_CC
+
+// Define a special version of int math ops on Sketch<bool> that converts to Sketch<uchar>
+
+#define DEF_MATHBOOL_INT_CC(_Op) \
+Sketch<uchar> operator _Op (const Sketch<bool>& lhs, const int value) { \
+  Sketch<uchar> result(lhs->getName() + #_Op + "scalar", lhs); \
+  uchar* dest = &(*result.pixels)[0]; \
+  const bool* src1 = &(*lhs.pixels)[0]; \
+  const bool* end1 = &(*lhs.pixels)[lhs->getNumPixels()]; \
+  while ( src1 != end1 ) \
+    *dest++ = *src1++ _Op (uchar)value; \
+  return result; \
+}
+
+DEF_MATHBOOL_INT_CC( + )
+DEF_MATHBOOL_INT_CC( - )
+DEF_MATHBOOL_INT_CC( * )
+DEF_MATHBOOL_INT_CC( / )
+
+#undef DEF_MATHBOOL_INT_CC
+
+template<>
+Sketch<bool>::operator Sketch<uchar>() const {
+  /*
+    std::cout << "Converting " << this << " '" << getName() << "'"
+    << " id=" << getId() << ",parent=" << getParentId() << ",refcount=" << data->refcount
+    << " to Sketch<uchar>\n";
+  */
+  Sketch<uchar> converted("uchar("+(*this)->getName()+")", *this);
+  copyPixels(converted, *this);
+  return converted;
+}
+
+template<>
+Sketch<uchar>::operator Sketch<bool>() const {
+  /*
+    std::cout << "Converting " << this << " '" << getName() << "'"
+    << " id=" << getId() << ",parent=" << getParentId() << ",refcount=" << data->refcount
+    << " to Sketch<bool>\n";
+  */
+  Sketch<bool> converted("bool(" + (*this)->getName() + ")", *this);
+  copyPixels(converted, *this);
+  return converted;
+}
+
+Sketch<bool>& operator&= (Sketch<bool>& arg1, Sketch<bool> const& arg2) {
+  *(arg1.pixels) &= *(arg2.pixels); 
+  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_2.4.1/DualCoding/Sketch.h ./DualCoding/Sketch.h
--- ../Tekkotsu_2.4.1/DualCoding/Sketch.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/Sketch.h	2006-08-10 23:16:57.000000000 -0400
@@ -0,0 +1,529 @@
+//-*-c++-*-
+
+#ifndef INCLUDED_Sketch_h
+#define INCLUDED_Sketch_h
+
+#include <valarray>
+#include <string>
+
+#include "SketchTypes.h"
+#include "SketchRoot.h"
+
+namespace DualCoding {
+
+class SketchSpace;
+class SketchIndices;
+template<typename T> class SketchData;
+
+//! Smart pointers for referencing @code SketchData<T> @endcode instances
+/*! This is the structure that provides safe user-level access to sketches.
+ *  It's a smart pointer that does reference counting, and
+ *  overloads operator-> so it can do validity checking.
+ *  If the validity check succeeds, operator-> dereferences to a
+ *  SketchData<T> object.  */
+
+template<typename T>
+class Sketch : public SketchRoot {
+public:
+  int width, height;
+
+  //! The SketchData object referenced by this Sketch.
+  SketchData<T> *data;
+
+  //! The image resource for the Sketch, owned by the SketchData object.
+  std::valarray<T> *pixels;
+
+  //! Constructor.  Allocates a new SketchData<T> to hold the data.
+  Sketch(SketchSpace &_space, const std::string& _name = "(no name)");
+
+  //! Constructor.  Inherits parent and color information from parent sketch.
+  Sketch(const std::string& _name, const SketchRoot& parent);
+
+  //! Dummy constructor, for use in vector construction.
+  Sketch();
+
+  /*! @brief Copy constructor, used in something like @code Sketch<bool> image = original; @endcode
+   *  This is a shallow copy: it does not copy the underlying pixels. */
+  Sketch(const Sketch &other);
+
+  //! Shallow copy constructor used by NEW_SKETCH and NEW_SKETCH_N
+  Sketch(const Sketch &other, const std::string &name, bool viewable);
+
+  //! Destructor.  Cleans up and decrements SketchData reference count.
+  virtual ~Sketch();
+
+  //! Retrieve an existing sketch by name.
+  Sketch(const std::string &name, SketchSpace &space);
+
+  //! True if this Sketch actually points to a SketchData
+  inline bool isValid() const { return data != NULL; }
+
+  //! Print error message if Sketch fails isValid() test
+  void checkValid() const;
+
+  SketchData<T>* operator->() { checkValid(); return data; }
+  const SketchData<T>* operator->() const { checkValid(); return data; }
+
+  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;
+
+  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]; };
+
+  Sketch& setIndices(const SketchIndices& indices, const T& value);
+
+  //! Make this sketch point to another sketch's SketchData.
+  void bind(const Sketch& other);
+
+  //! Assignment operator: copies the pixels.
+  Sketch& operator= (const Sketch& other);
+
+  //! Sets all pixels in the Sketch to the specified value.
+  Sketch& operator= (const T& value);
+
+  Sketch<bool> operator!() const;
+  
+  Sketch<T>& operator+= (const Sketch<T>& other);
+  Sketch<T>& operator-= (const Sketch<T>& other);
+  Sketch<T>& operator*= (const Sketch<T>& other);
+  Sketch<T>& operator/= (const Sketch<T>& other);
+
+  Sketch<T>& operator+= (const T value);
+  Sketch<T>& operator-= (const T value);
+  Sketch<T>& operator*= (const T value);
+  Sketch<T>& operator/= (const T value);
+
+  Sketch& operator+= (const int value);
+  Sketch& operator-= (const int value);
+  Sketch& operator*= (const int value);
+  Sketch& operator/= (const int value);
+
+  void printVals() const;
+
+  //! operator for implicitly or explicitly converting to Sketch<bool>
+  operator Sketch<bool>() const;
+
+  //! 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<float>
+  operator Sketch<float>() const;
+
+};
+
+// ****************************************************************
+
+
+} // namespace
+
+#include "SketchData.h"
+#include "SketchIndices.h"
+#include "SketchSpace.h"
+
+namespace visops {
+  template <class T> DualCoding::Sketch<T> copy(const DualCoding::Sketch<T>& other);
+}
+
+namespace DualCoding {
+
+// First constructor: requires a SketchSpace
+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()),
+    pixels(&data->pixels)
+{
+  data->name = _name;
+  data->id = getNewId();
+  data->parentId = 0;
+  data->viewable = false;
+  data->colormap = segMap;
+  ++data->refcount;
+  (*pixels)[_space.dummy] = 0;
+  /*
+  std::cout << "Creating new Sketch " << this << " '" << data->name << "'"
+	    << " [" << data << "]"
+	    << " id=" << getId() << ",parent=" << getParentId()
+	    << ",refcount=" << data->refcount << std::endl;
+  */
+}
+
+// Second constructor: requires a parent sketch
+template <class T>
+Sketch<T>::Sketch(const std::string& _name, const SketchRoot& _parent)
+  : SketchRoot(), width(), height(), data(NULL), pixels(NULL) {
+  SketchSpace& space = _parent.rootGetSpace();
+  width = space.getWidth();
+  height = space.getHeight();
+  data = space.get_pool(*this).get_free_element();
+  data->name = _name;
+  data->id = getNewId();
+  data->inheritFrom(_parent.rootGetData());
+  data->viewable = false;
+  ++data->refcount;
+  pixels = &data->pixels;
+  (*pixels)[space.dummy] = 0;
+  /*
+  std::cout << "Creating new Sketch " << this << " '" << data->name << "'"
+	    << " [" << data << "]"
+	    << " id=" << getId() << ",parent=" << getParentId()
+	    << ",refcount=" << data->refcount << std::endl;
+  */
+}
+
+// Dummy constructor
+template <typename T>
+Sketch<T>::Sketch()
+  : SketchRoot(), width(), height(), data(NULL), pixels(NULL) {}
+
+// Retrieve existing sketch
+template <typename T>
+Sketch<T>::Sketch(const std::string &name, SketchSpace &space)
+  : SketchRoot(), width(space.getWidth()), height(space.getHeight()), 
+	 data(space.get_pool(*this).findSketchData(name)), 
+	 pixels(data != NULL ? &data->pixels : NULL) {
+  if ( data != NULL )
+	 ++data->refcount;
+}
+
+#define NEW_SKETCH_N(name,T,value) Sketch<T> name(value,#name,false);
+#define NEW_SKETCH(name,T,value) Sketch<T> name(value,#name,true);
+#define GET_SKETCH(name,T,space) Sketch<T> name(#name,space);
+
+template <class T>
+Sketch<T>::Sketch(const Sketch<T> &other)
+  : SketchRoot(),
+    width(other.width), height(other.height),
+    data(other.data), pixels(other.pixels) 
+{
+  if ( isValid() ) {
+    ++data->refcount;
+  /*
+  std::cout << "Copying Sketch " << this << " '"
+	    << "'  <--  Sketch '" << other.data->name << "'"
+	    << " [" << data << "]"
+	    << " id=" << getId() << ",parent=" << getParentId()
+	    << ",refcount=" << data->refcount << std::endl;
+  */
+  }
+}
+
+// Shallow copy constructor: does not copy the underlying pixels.
+template <class T>
+Sketch<T>::Sketch(const Sketch<T> &other, const std::string &name, bool viewable)
+  : SketchRoot(),
+    width(other.width), height(other.height),
+    data(other.data), pixels(other.pixels) 
+{
+  if ( isValid() ) {
+    ++data->refcount;
+    data->setName(name);
+    data->setViewable(viewable);
+  }
+}
+
+
+// Destructor
+template <class T> Sketch<T>::~Sketch() {
+  if ( isValid() ) {
+  /*
+  std::cout << "Deleting Sketch " << this << " '" << getName() << "'"
+	    << " [" << 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;
+  */
+  }
+}
+
+template <class T>
+void Sketch<T>::checkValid() const {
+  if ( ! isValid() )
+    std::cerr << "ERROR!  Attempt to dereference an invalid Sketch." << std::endl;
+}
+
+// Parallel indexed access via operator[]
+
+template <class T>
+const Sketch<T> Sketch<T>::operator[] (const Sketch<usint>& indirection) const
+{
+  checkValid();
+  Sketch<T> result(*(data->space), "shift("+(*this)->getName()+","+indirection->getName()+")");
+  for (size_t i = 0; i < pixels->size(); i++) {
+    (*result.pixels)[i] = (*pixels)[indirection[i]];
+  }
+  return result;
+}
+
+template <class T>
+Sketch<T>& Sketch<T>::setIndices(const SketchIndices& indices, const T& value) {
+  checkValid();
+  for (SketchIndices::CI it = indices.table.begin(); it != indices.table.end(); ++it)
+    (*pixels)[*it] = value;
+  return *this;
+}
+
+template <class T>
+void Sketch<T>::bind(const Sketch<T>& other)
+{
+  if ( isValid() )
+    --data->refcount;
+  data = other.data;
+  ++data->refcount;
+  pixels = other.pixels;
+  width = other.width;
+  height = other.height;
+}
+
+template <class T>
+Sketch<T>& Sketch<T>::operator= (const Sketch<T>& other) {
+  if ( isValid() )
+    if ( other.isValid() )
+      *pixels = *other.pixels;
+    else {
+      if ( --data->refcount == 0 && data->refreshTag < data->space->getRefreshCounter() ) {
+	data->setViewable(false);
+	data->clearPending = false;
+      }
+      pixels = NULL;
+      data = NULL;
+    }
+  else
+    if ( other.isValid() )
+      bind(::visops::copy(other));
+  return *this;
+}
+
+template <class T>
+Sketch<T>& Sketch<T>::operator= (const T& value) { 
+  checkValid();
+  *pixels = value; 
+  return *this;
+}
+
+
+//================================================================
+
+//! non-member math operators
+//@{
+
+#define DEF_MATHOPS_H(_T1, _T2, _Result) \
+  DEF_MATHOP_H( +, _T1, _T2, _Result ) \
+  DEF_MATHOP_H( -, _T1, _T2, _Result ) \
+  DEF_MATHOP_H( *, _T1, _T2, _Result ) \
+  DEF_MATHOP_H( /, _T1, _T2, _Result )
+
+#define DEF_MATHOP_H(_Op, _T1, _T2, _Result) \
+Sketch<_Result> operator _Op (const Sketch<_T1> &lhs, const Sketch<_T2> &rhs); \
+Sketch<_Result> operator _Op (const Sketch<_T1> &lhs, const _T2 value);
+
+// 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, float, float)
+
+DEF_MATHOPS_H(uchar, bool, uchar)
+DEF_MATHOPS_H(uchar, uchar, uchar)
+DEF_MATHOPS_H(uchar, usint, usint)
+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(float, bool, float)
+DEF_MATHOPS_H(float, uchar, float)
+DEF_MATHOPS_H(float, usint, float)
+DEF_MATHOPS_H(float, float, float)
+
+#undef DEF_MATHOPS_H
+#undef DEF_MATHOP_H
+
+#define DEF_MATHOPS_INT_H(_T1) \
+  DEF_MATHOP_INT_H( +, _T1) \
+  DEF_MATHOP_INT_H( -, _T1) \
+  DEF_MATHOP_INT_H( *, _T1) \
+  DEF_MATHOP_INT_H( /, _T1)
+
+#define DEF_MATHOP_INT_H(_Op, _T1) \
+Sketch<_T1> operator _Op (const Sketch<_T1>& lhs, const int value);
+
+//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(float)
+
+#undef DEF_MATHOPS_INT_H
+#undef DEF_MATHOP_INT_H
+
+#define DEF_MATHBOOL_INT_H(_Op) \
+Sketch<uchar> operator _Op (const Sketch<bool>& lhs, const int value);
+
+DEF_MATHBOOL_INT_H( + )
+DEF_MATHBOOL_INT_H( - )
+DEF_MATHBOOL_INT_H( * )
+DEF_MATHBOOL_INT_H( / )
+
+#undef DEF_MATHBOOL_INT_H
+
+template <class T> Sketch<T>& Sketch<T>::operator+= (const Sketch<T>& other) { *pixels += *other.pixels; return *this; }
+template <class T> Sketch<T>& Sketch<T>::operator-= (const Sketch<T>& other) { *pixels -= *other.pixels; return *this; }
+template <class T> Sketch<T>& Sketch<T>::operator*= (const Sketch<T>& other) { *pixels *= *other.pixels; return *this; }
+template <class T> Sketch<T>& Sketch<T>::operator/= (const Sketch<T>& other) { *pixels /= *other.pixels; return *this; }
+
+template <class T> Sketch<T>& Sketch<T>::operator+= (const T value) {*pixels += (T)value; return *this; }
+template <class T> Sketch<T>& Sketch<T>::operator-= (const T value) {*pixels -= (T)value; return *this; }
+template <class T> Sketch<T>& Sketch<T>::operator*= (const T value) {*pixels *= (T)value; return *this; }
+template <class T> Sketch<T>& Sketch<T>::operator/= (const T value) {*pixels /= (T)value; return *this; }
+
+template <class T> Sketch<T>& Sketch<T>::operator+= (const int value) {*pixels += T(value); return *this; }
+template <class T> Sketch<T>& Sketch<T>::operator-= (const int value) {*pixels -= T(value); return *this; }
+template <class T> Sketch<T>& Sketch<T>::operator*= (const int value) {*pixels *= T(value); return *this; }
+template <class T> Sketch<T>& Sketch<T>::operator/= (const int value) {*pixels /= T(value); return *this; }
+
+  //@}
+
+
+  //! non-member logical operators
+  //@{
+#define DEFINE_LOGICAL_OPERATOR(_Op)					             \
+template <class T> 								     \
+Sketch<bool> operator _Op (const Sketch<T>& lhs, const Sketch<T>& rhs) {             \
+  Sketch<bool> result(lhs->getName() + #_Op + rhs->getName(), lhs);                  \
+    *(result.pixels) = *(lhs.pixels) _Op *(rhs.pixels); 		             \
+    return result;                                                                   \
+}										     \
+/* continued... */								     \
+template <class T>								     \
+Sketch<bool> operator _Op (const Sketch<T>& lhs, const T value) {		     \
+  Sketch<bool> result(lhs->getName() + #_Op "scalar", lhs);                          \
+    *(result.pixels) = *(lhs.pixels) _Op value; 				     \
+    return result;								     \
+}										     \
+/* continued... */								     \
+template <class T>								     \
+Sketch<bool> operator _Op (const Sketch<T>& lhs, const int value) {		     \
+  Sketch<bool> result(lhs->getName() + #_Op "scalar", lhs);                          \
+    *(result.pixels) = *(lhs.pixels) _Op T(value); 				     \
+    return result;								     \
+}
+
+  DEFINE_LOGICAL_OPERATOR( == )
+  DEFINE_LOGICAL_OPERATOR( != )
+  DEFINE_LOGICAL_OPERATOR( <  )
+  DEFINE_LOGICAL_OPERATOR( >  )
+  DEFINE_LOGICAL_OPERATOR( <= )
+  DEFINE_LOGICAL_OPERATOR( >= )
+  DEFINE_LOGICAL_OPERATOR( & )
+  DEFINE_LOGICAL_OPERATOR( | )
+#undef DEFINE_LOGICAL_OPERATOR
+//@}
+
+template <class T>
+Sketch<bool> Sketch<T>::operator! () const {
+  Sketch<bool> result("operator!",*this);
+  *(result.pixels) = !(*pixels);
+  return result;
+}
+
+//! Logical assignment operators.
+//@{
+Sketch<bool>& operator&= (Sketch<bool>& arg1, Sketch<bool> const& arg2);
+Sketch<bool>& operator|= (Sketch<bool>& arg1, Sketch<bool> const& arg2);
+//@}
+
+template <class T>
+void Sketch<T>::printVals() const {
+  std::cout << ((*this)->getName() +":") << std::endl;
+  for (size_t i = 0; i < pixels->size(); i++) {
+    if ((i % width) == 0)
+      std::cout << std::endl;
+    std::cout << (*pixels)[i] << ' ';
+  }
+  std::cout << std::endl;
+}
+
+// Type coercion
+
+template <class T>
+Sketch<T>::operator Sketch<bool>() const {
+  Sketch<bool> converted("bool(" + (*this)->getName() + ")", *this);
+  copyPixels(converted, *this);
+  return converted;
+}
+
+template <class T>
+Sketch<T>::operator Sketch<uchar>() const {
+  /*
+  std::cout << "Converting " << this << " '" << getName() << "'"
+	    << " id=" << getId() << ",parent=" << getParentId() << ",refcount=" << data->refcount
+	    << " to Sketch<uchar>\n";
+  */
+  Sketch<uchar> converted("uchar("+(*this)->getName()+")", *this);
+  copyPixels(converted, *this);
+  return converted;
+}
+
+template <>
+Sketch<bool>::operator Sketch<uchar>() const;
+
+template <>
+Sketch<uchar>::operator Sketch<bool>() const;
+
+template <class T>
+Sketch<T>::operator Sketch<usint>() const {
+  /*
+  std::cout << "Converting " << this << " '" << getName() << "'"
+	    << " id=" << getId() << ",parent=" << getParentId() << ",refcount=" << data->refcount
+	    << " to Sketch<usint>\n";
+  */
+  Sketch<usint> converted("usint("+(*this)->getName()+")", *this);
+  copyPixels(converted, *this);
+  return converted;
+}
+
+template <class T>
+Sketch<T>::operator Sketch<float>() const {
+  Sketch<float> converted("float("+(*this)->getName()+")", *this);
+  copyPixels(converted, *this);
+  return converted;
+}
+
+//! utility function used by type conversion operators
+template<class A, class B>
+void copyPixels(Sketch<A>& dest, const Sketch<B>& src)
+{
+  std::valarray<A> &destpix = *dest.pixels;
+  const std::valarray<B> &srcpix = *src.pixels;
+  size_t length = src->getSpace().getNumPixels();
+  for (size_t i = 0; i < length; i++) {
+    destpix[i] = (A)(srcpix[i]);
+  }
+}
+
+} // namespace
+
+/*! @file
+ * @brief Templated class for an image-like Sketch
+ * @author neilh (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchData.h ./DualCoding/SketchData.h
--- ../Tekkotsu_2.4.1/DualCoding/SketchData.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchData.h	2006-09-09 00:32:40.000000000 -0400
@@ -0,0 +1,354 @@
+//-*-c++-*-
+
+#ifndef INCLUDED_SketchData_h
+#define INCLUDED_SketchData_h
+
+#include <valarray>
+#include <iostream>
+#include <stdexcept>
+#include <limits> // needed for findMinPlus
+#include <map>
+
+#include "Shared/LoadSave.h"
+#include "Shared/Config.h"
+#include "Shared/debuget.h" // needed for ASSERT macros
+#include "Vision/SegmentedColorGenerator.h"
+#include "Shared/ProjectInterface.h" // needed for defSegmentedColorGenerator
+
+#include "SketchTypes.h"
+#include "SketchDataRoot.h"
+#include "ViewerConnection.h"
+
+namespace DualCoding {
+
+class SketchSpace;
+template<typename T> class SketchPool;
+template<typename T> class Sketch;
+
+//! Holds the pixels for an individual sketch.
+
+/*! SketchData<T> holds the pixels for an individual sketch of type T, using a valarray<T>.  A collection of
+    SketchData<T> objects is maintained in a SketchPool<T>.  Basic functions such as indexed access and empty test
+    that are not implemented as Sketch operators are implemented as SketchData<T> member functions.  Sketch<T>
+    overrides the -> operator to provide "smart pointer" access to these SketchData<T> functions.   */
+
+template<class T>
+class SketchData : public SketchDataRoot {
+  //! the valarray which actually stores the image
+  std::valarray<T> pixels;
+
+  friend class Sketch<T>;
+  friend class SketchPool<T>;
+
+public:
+  //! Constructor.  Don't call this.  SketchData objects should only be created and managed by their SketchSpace
+  SketchData(SketchSpace *_space);
+  ~SketchData();
+
+  //! The type of this sketch.
+  virtual SketchType_t getType() const;  // must go here, not in SketchDataRoot, due to templating
+
+  //! Address of the memory area containing the actual pixel data.
+  T* getRawPixels() { return &(pixels[0]); }
+
+  //! Address of the memory area containing the actual pixel data.
+  const T* getRawPixels() const { return &(pixels[0]); }
+
+  //! Serializes a sketch to a buffer, for transmission to the sketch viewer.
+  unsigned int saveBuffer(char buf[], unsigned int avail) const;
+
+  //@{
+  //! Indexed access, with bounds checking
+  T& at(size_t x);
+
+  //! Subscripted (x,y) access, with bounds checking
+  T& at(size_t x, size_t y);
+
+  //@}
+
+  //! Returns true if all pixels are zero.
+  bool empty() const;
+
+  //!@name Sum/Max/Min
+  //@{
+
+  //! Sum of pixels
+  T sum() const;
+
+  //! Max of pixel values
+  T max() const;
+
+  //! Index of first maximum-value pixel
+  int findMax() const;
+
+  //! Min of pixel values
+  T min() const;
+
+  //! Index of first minimum-value pixel
+  int findMin() const;
+
+  //! Min of non-zero pixel values
+  T minPlus() const;
+
+  //! Index of first minimum non-zero pixel, or -1 if none
+  int findMinPlus() const;
+
+  //! Mode (most common) pixel value
+  T mode() const;
+
+  //! Mode (most common) non-zero pixel value
+  T modePlus() const;
+
+  //@}
+
+protected:
+  unsigned int savePixels(char buf[], unsigned int avail) const; //!< handle copying pixels to buffer
+
+private:
+  SketchData (const SketchData& other); //!< never call this
+};
+
+} // namespace
+
+#include "SketchSpace.h"
+
+namespace DualCoding {
+
+template<class T>
+SketchData<T>::SketchData(SketchSpace *_space) :
+  SketchDataRoot(_space), pixels(_space->getNumPixels()+1) {
+  if  ( getType() == sketchUsint || getType() == sketchFloat )
+    colormap = jetMapScaled;
+  else
+    colormap = segMap;
+}
+
+template<class T> SketchData<T>::~SketchData() {}
+
+template <class T>
+SketchData<T>::SketchData (const SketchData<T> &other)
+  : SketchDataRoot(other.space), pixels(other.pixels) {}
+
+template<>
+inline SketchType_t SketchData<bool>:: getType() const { return sketchBool; }
+template<>
+inline SketchType_t SketchData<uchar>::getType() const { return sketchUchar; }
+template<>
+inline SketchType_t SketchData<usint>::getType() const { return sketchUsint; }
+template<>
+inline SketchType_t SketchData<float>::getType() const { return sketchFloat; }
+
+template<class T>
+T& SketchData<T>::at(size_t x) {
+  if ( x < (unsigned int)(space->getWidth()*space->getHeight()) )
+    return pixels[x];
+  else
+    throw std::out_of_range("Sketch subscript out of bounds");
+}
+
+template <class T>
+T& SketchData<T>::at(size_t x, size_t y) {
+  if ( x < (unsigned int)(space->getWidth()) && y < (unsigned int)(space->getHeight()) )
+    return pixels[y*space->getWidth()+x];
+  else
+    throw std::out_of_range("Sketch subscript out of bounds");
+}
+
+template <class T>
+bool SketchData<T>::empty() const {
+  for ( size_t i=0; i < pixels.size(); i++ )
+    if ( pixels[i] != 0 )
+      return false;
+  return true;
+}
+
+template <class T>
+T SketchData<T>::sum() const {
+  T result = pixels[0];
+  for (unsigned int i=1; i<getNumPixels(); i++)
+    result += pixels[i];
+  return result;
+}
+
+template <class T>
+T SketchData<T>::max() const {
+  T result = pixels[0];
+  for (unsigned int i=1; i<getNumPixels(); i++)
+    result = std::max(result,pixels[i]);
+  return result;
+}
+
+template <class T>
+int SketchData<T>::findMax() const {
+  T maxval = pixels[0];
+  int maxidx = -1;
+  for (unsigned int i = 1; i<getNumPixels(); i++)
+    if ( pixels[i] > maxval ) {
+      maxidx = i;
+      maxval = pixels[i];
+    }
+  return maxidx;
+}
+
+template <class T>
+T SketchData<T>::min() const {
+  T result = pixels[0];
+  for (unsigned int i=1; i<getNumPixels(); i++)
+    result = std::min(result,pixels[i]);
+  return result;
+}
+
+template <class T>
+int SketchData<T>::findMin() const {
+  T minval = pixels[0];
+  int minidx = -1;
+  for (unsigned int i = 1; i<getNumPixels(); i++)
+    if ( pixels[i] < minval ) {
+      minidx = i;
+      minval = pixels[i];
+    }
+  return minidx;
+}
+
+template <class T>
+T SketchData<T>::minPlus() const {
+  T result = 0;
+  unsigned int i = 0;
+  for (; i<getNumPixels(); i++)
+    if ( pixels[i] != 0 ) {
+      result = pixels[i];
+      break;
+    }
+  for (; i<getNumPixels(); i++)
+    if ( pixels[i] != 0 )
+      result = std::min(result,pixels[i]);
+  return result;
+}
+
+template <class T>
+int SketchData<T>::findMinPlus() const {
+  T minval=std::numeric_limits<T>::max();
+  int minidx = -1;
+  for (unsigned int i=getNumPixels()-1; i!=-1U; --i)
+    if ( pixels[i] != 0 && pixels[i] <= minval ) {
+      minidx = i;
+      minval = pixels[i];
+    }
+  return minidx;
+}
+
+template <class T>
+T SketchData<T>::mode() const {
+	std::map<T,size_t> hist;
+	for(unsigned int i=0; i<getNumPixels(); i++)
+		hist[pixels[i]]++;
+	T maxval=T();
+	size_t maxcnt=0;
+	for(typename std::map<T,size_t>::const_iterator it=hist.begin(); it!=hist.end(); ++it) {
+		if(maxcnt<=it->second) {
+			maxval=it->first;
+			maxcnt=it->second;
+		}
+	}
+	return maxval;
+}
+
+template <class T>
+T SketchData<T>::modePlus() const {
+	std::map<T,size_t> hist;
+	for(unsigned int i=0; i<getNumPixels(); i++)
+		if(pixels[i]!=0)
+			hist[pixels[i]]++;
+	T maxval=T();
+	size_t maxcnt=0;
+	for(typename std::map<T,size_t>::const_iterator it=hist.begin(); it!=hist.end(); ++it) {
+		if(maxcnt<=it->second) {
+			maxval=it->first;
+			maxcnt=it->second;
+		}
+	}
+	return maxval;
+}
+
+
+// ================================================================
+
+#define SKETCHDATA_ENCODE(a) \
+  if(!LoadSave::encodeInc(a,buf,avail,"SketchData encode ran out of space at %s:%u\n",__FILE__,__LINE__)) return 0;
+
+template <class T>
+unsigned int SketchData<T>::saveBuffer(char buf[], unsigned int avail) const
+{
+  char* packet = buf; // beginning of packet
+  static int frameNum = 0; // should this become a static member variable?
+  unsigned int used=0;
+
+  SKETCHDATA_ENCODE("TekkotsuImage");
+  SKETCHDATA_ENCODE(Config::vision_config::ENCODE_SINGLE_CHANNEL);
+  SKETCHDATA_ENCODE(Config::vision_config::COMPRESS_NONE);
+  SKETCHDATA_ENCODE(getWidth());
+  SKETCHDATA_ENCODE(getHeight());
+  SKETCHDATA_ENCODE(get_time()); // is this what should be used for time stamp?
+  SKETCHDATA_ENCODE(frameNum++);
+
+  // encode filterbank info
+  SKETCHDATA_ENCODE("FbkImage");
+  SKETCHDATA_ENCODE(getWidth());
+  SKETCHDATA_ENCODE(getHeight());
+  SKETCHDATA_ENCODE(CAM_LAYER);
+  SKETCHDATA_ENCODE(CAM_CHANNEL);
+
+  // encode actual image data
+  SKETCHDATA_ENCODE("SketchImage");
+  SKETCHDATA_ENCODE((unsigned char)getType());
+  const unsigned int imglength  = savePixels(buf,avail);
+  if(imglength==0)
+		return 0; // savePixels should have already reported the error
+  avail-=imglength;
+  buf+=imglength;
+
+  // encode color table(same as color table of segmentedcolorgenerator for now
+  used = (dynamic_cast<SegmentedColorGenerator*>
+	  (ProjectInterface::defSegmentedColorGenerator))->encodeColorsInc(buf,avail);
+  return buf-packet;
+}
+
+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;
+}
+
+#ifdef __POWERPC__
+//bool can be 4 bytes on PowerPC systems
+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;
+}
+#endif
+
+} // namespace
+
+/*! @file
+ * @brief A resource which holds the image date for a Sketch, managed collectively by a SketchSpace
+ * @author neilh (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchDataRoot.cc ./DualCoding/SketchDataRoot.cc
--- ../Tekkotsu_2.4.1/DualCoding/SketchDataRoot.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchDataRoot.cc	2006-03-03 06:13:07.000000000 -0500
@@ -0,0 +1,43 @@
+// These have to go in the .cc file because SketchSpace.h circularly depends
+// on SketchData.h, so we can't reference members of SketchSpace in the
+// SketchDataRoot.h file.
+
+#include "SketchDataRoot.h"
+#include "SketchSpace.h"  // can't include this in SketchDataRoot.h due to circularities
+
+namespace DualCoding {
+
+const size_t SketchDataRoot::getWidth() const { return space->getWidth(); }
+const size_t SketchDataRoot::getHeight() const { return space->getHeight(); }
+const size_t SketchDataRoot::getNumPixels() const { return space->getNumPixels(); }
+
+void SketchDataRoot::inheritFrom(const SketchDataRoot &parent) {
+  setParentId(parent.getViewableId());
+  setColor(parent.getColor());
+  if ( getType() == sketchBool )
+    setColorMap(segMap);
+  else
+    setColorMap(parent.getColorMap());
+}
+
+void SketchDataRoot::inheritFrom(const ShapeRoot &parent) {
+  setParentId(parent->getViewableId());
+  setColor(parent->getColor());
+}
+
+void SketchDataRoot::inheritFrom(const BaseData &parent) {
+  setParentId(parent.getViewableId());
+  setColor(parent.getColor());
+}
+
+void SketchDataRoot::V(std::string const &_name) {
+  setViewable(true);
+  if ( !_name.empty() ) setName(_name);
+}
+
+void SketchDataRoot::N(std::string const &_name) {
+  setViewable(false);
+  if ( !_name.empty() ) setName(_name);
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchDataRoot.h ./DualCoding/SketchDataRoot.h
--- ../Tekkotsu_2.4.1/DualCoding/SketchDataRoot.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchDataRoot.h	2006-07-19 17:54:12.000000000 -0400
@@ -0,0 +1,119 @@
+//-*-c++-*-
+
+#ifndef INCLUDED_SketchDataRoot_h
+#define INCLUDED_SketchDataRoot_h
+
+#include <string>
+
+#include "Shared/ProjectInterface.h"
+
+#include "SketchTypes.h"
+#include "SketchSpace.h"
+#include "ShapeRoot.h"
+
+namespace DualCoding {
+
+//! Parent class for SketchData<T>
+class SketchDataRoot {
+private:
+  //! The SketchSpace that owns the pool containing this SketchData object.
+  SketchSpace *space;
+  
+  //! Name of this sketch.
+  std::string name;
+
+  //! Sketch-specific integer ID, for unique identification
+  int id;
+
+  //! Integer ID of the "parent" Sketch, 0 if no parent; used in GUI
+  int parentId;
+
+  //! Reference count for the sketch. When SketchPool detects this as 0, it may reuse it.
+  int refcount;
+
+  //! True if the Sketch is currently viewable.
+  bool viewable;
+
+  //! Last time this sketch was included in a sketch list sent to the GUI
+  int refreshTag;
+
+  //! True if we've tried to clear this sketch but the SketchGUI was looking at it
+  bool clearPending;
+
+  //! Color to use for displaying this sketch.  Only meaningful for Sketch<bool>,
+  //! but info is preserved in case we coerce bool to int or float and then back to bool.
+  rgb color;
+
+  //! Which color map to use; default is to use the robot's own color table.
+  //! Other tables are used for displaying grayscale images, or scaled quantities like
+  //! distance or area using a continuous color scale from red to blue.
+  ColorMapType_t colormap;
+
+  template<typename T> friend class SketchPool;
+  template<typename T> friend class Sketch;
+  template<typename T> friend class SketchData;
+  friend class SketchRoot;
+
+public:
+  SketchDataRoot(SketchSpace *s) : 
+	  space(s), name(), id(0), parentId(0), 
+	  refcount(0), viewable(false), refreshTag(0), clearPending(false),
+	  color((ProjectInterface::getNumColors() != -1U) ? ProjectInterface::getColorRGB(1) : rgb(0,0,255)), // color 0 is invalid, so use color 1 as default, or blue if colors aren't loaded yet
+	  colormap(segMap) {}
+
+  virtual ~SketchDataRoot() {};
+
+  //! Returns the SketchSpace that owns the pool containing this SketchData object.
+  SketchSpace& getSpace() const { return *space; }
+
+  //! Returns the ShapeSpace associated with the SketchSpace for this Sketch
+  ShapeSpace& getDualSpace() const { return space->getDualSpace(); }
+
+  int getId() const { return id; }
+  int getParentId() const { return parentId; }
+  int getViewableId() const { return (isViewable() ? getId() : getParentId()); }
+  void setParentId(int const _id) { parentId = _id; }
+  bool isViewable() const { return viewable; }
+  void setViewable(bool const v) { viewable=v; }
+  rgb getColor() const { return color; }
+  void setColor(const rgb _color) { color = _color; }
+  ColorMapType_t getColorMap() const { return colormap; }
+  void setColorMap(const ColorMapType_t _map) { colormap = _map; }
+  const std::string& getName() const { return name; }
+  void setName(const std::string &_name) { name = _name; }
+
+  virtual SketchType_t getType() const=0;
+
+  void V(std::string const &_name="");
+  void N(std::string const &_name="");
+
+  void inheritFrom(const SketchDataRoot &parent);
+  void inheritFrom(const ShapeRoot &parent);
+  void inheritFrom(const BaseData &parent);
+
+  //@{
+  //! Width and height of sketches in this space.
+  const size_t getWidth() const;
+  const size_t getHeight() const;
+  const size_t getNumPixels() const;
+  //@}
+
+  //! X coordinate encoded by sketch index
+  int indexX(int index) { return index % getWidth(); }
+
+  //! Y coordinate encoded by sketch index
+  int indexY(int index) { return index / getWidth(); }
+
+  //! converts (x,y) into a sketch index
+  int indexOf(int x, int y) { return y*getWidth() + x; }
+
+  virtual unsigned int saveBuffer(char buf[], unsigned int avail) const=0;
+
+private:
+  SketchDataRoot(const SketchDataRoot&); //!< never call this
+  SketchDataRoot& operator=(const SketchDataRoot&); //!< never call this
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchIndices.cc ./DualCoding/SketchIndices.cc
--- ../Tekkotsu_2.4.1/DualCoding/SketchIndices.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchIndices.cc	2006-04-27 18:53:10.000000000 -0400
@@ -0,0 +1,58 @@
+#include <algorithm>
+#include <iostream>
+
+#include "SketchIndices.h"
+#include "Sketch.h"
+#include "SketchSpace.h"
+
+namespace DualCoding {
+
+const SketchIndices SketchIndices::operator[] (const Sketch<usint>& indirection) const {
+  SketchIndices redir;
+  for (CI it = table.begin(); it != table.end(); ++it)
+    redir.table.insert(indirection[*it]);
+  return redir;	
+}
+
+const SketchIndices 
+SketchIndices::operator+ (const SketchIndices& other) const {
+  SketchIndices result(*this);
+  for (CI it = other.table.begin(); it != other.table.end(); ++it)
+    result.table.insert(*it);
+  return result;
+}
+
+const SketchIndices SketchIndices::operator- (const SketchIndices& other) const {
+  SketchIndices result(*this);
+  for (CI o = other.table.begin(); o != other.table.end(); ++o)
+    result.table.erase(*o);
+  return result;
+}
+
+std::ostream& operator<< (std::ostream& out, const SketchIndices &s) {
+  typedef std::ostream_iterator<SketchIndices::SketchIndicesTable::value_type, char,
+    std::char_traits<char> > ositer;
+  std::copy(s.table.begin(), s.table.end(), ositer(std::cout," "));
+  return out;
+}
+
+void SketchIndices::addIndices(const Sketch<bool>& im)
+{
+  size_t length = im->getNumPixels();
+  for (size_t i = 0; i < length; i++)
+    if ( im[i] )
+      table.insert(i);
+}
+
+void SketchIndices::trimBounds(const SketchSpace &space) {
+  SketchIndices result;
+  for (SketchIndices::CI it = table.begin(); it != table.end(); ++it)
+    if ( *it < space.getNumPixels() )
+      result.table.insert(*it);
+  table = result.table;
+}
+
+
+
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchIndices.h ./DualCoding/SketchIndices.h
--- ../Tekkotsu_2.4.1/DualCoding/SketchIndices.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchIndices.h	2006-04-27 18:53:10.000000000 -0400
@@ -0,0 +1,59 @@
+//-*-c++-*-
+#ifndef INCLUDED_SketchIndices_h
+#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"
+
+namespace DualCoding {
+
+class SketchSpace;
+template<class T> class Sketch;
+
+//! 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 SketchIndicesTable::const_iterator CI;
+
+  SketchIndicesTable table;
+  
+  //! Constructor
+  SketchIndices() : table() {};
+
+  //! Destructor
+  virtual ~SketchIndices() {};
+  
+  //! 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;
+  
+  //! Returns the result of adding the elements of another SketchIndices
+  //! to the current SketchIndices
+  const SketchIndices operator+ (const SketchIndices& other) const;
+  
+  //! Returns the result of removing the elements of another SketchIndices
+  //! from the current SketchIndices.
+  //! This is much more computationally expensive than addition, so try
+  //! to minimize usage by distribution law: x-y-z=x-(y+z)
+  const SketchIndices operator- (const SketchIndices& other) const;
+
+  //! Adds indices of non-zero pixels.
+  void addIndices(const Sketch<bool>& im);
+
+  //! Removes any indices from SketchIndices which are outside the bounds of the SketchSpace
+  void trimBounds(const SketchSpace &space);
+  
+private:
+};
+
+//! prints out SketchIndices for debugging
+std::ostream& operator<< (std::ostream& out, const SketchIndices &s);
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchPool.h ./DualCoding/SketchPool.h
--- ../Tekkotsu_2.4.1/DualCoding/SketchPool.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchPool.h	2006-07-23 05:40:31.000000000 -0400
@@ -0,0 +1,167 @@
+//-*-c++-*-
+#ifndef INCLUDED_SketchPool_h
+#define INCLUDED_SketchPool_h
+
+#include <vector>
+#include <iostream>
+#include <sstream> // for ostringstream
+
+#include "Shared/ProjectInterface.h"
+
+#include "SketchPoolRoot.h"
+#include "Macrodefs.h"
+
+namespace DualCoding {
+
+class SketchSpace;
+class SketchDataRoot;
+template<class T> class SketchData;
+
+//! Manages a pool of SketchData<T> instances
+
+template<typename T>
+class SketchPool : public SketchPoolRoot {
+public:
+  //! this is made public so VisualRoutinesBehavior can access
+  std::vector<SketchData<T>*> elements;
+  
+  SketchPool<T>(SketchSpace *_space, int poolsize = 0); 
+  
+  ~SketchPool<T>();
+  
+  //! called by SketchPool to clear out non-static Viewable Sketch's
+  void clear();
+
+  SketchData<T>* get_free_element(void); 
+  
+  SketchData<T>* findSketchData(const std::string &name);
+
+  //! Returns a list of the valid SketchData's in this pool.
+  std::string getSketchListForGUI();
+  
+  //! Returns a copy of the sketch with specified ID, null if no such Sketch.
+  SketchDataRoot* retrieveSketch(int id);
+  
+  void dumpPool() const;
+
+ private:
+  // typename for iteration over elements
+  typedef typename std::vector<SketchData<T>*>::const_iterator CI;
+
+  SketchPool(const SketchPool&); //<! never call this
+  SketchPool& operator=(const SketchPool&); //!< never call this
+};
+
+// **************** Implementation ****************
+
+template <class T>
+SketchPool<T>::SketchPool(SketchSpace *_space, int poolsize) :
+	SketchPoolRoot(_space),
+	elements(std::vector<SketchData<T>*>(poolsize)) 
+{
+  for (int i=0; i<poolsize; i++) {
+    elements[i] = new SketchData<T>(space);
+  };
+}
+
+template <class T>
+SketchPool<T>::~SketchPool() {
+  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);
+    else
+      delete elements[i];
+  }
+}
+
+template <class T>
+void SketchPool<T>::clear() {
+  for (CI it = elements.begin(); it != elements.end(); it++ ) {
+    /*
+    cout << "clear " << (*it)->space->name << "  " << (*it)->id
+	 << " " << (*it)->name << " refcount=" << (*it)->refcount
+	 << " refreshTag=" << (*it)->refreshTag
+	 << " refCntr=" << getRefreshCounter()
+	 << " viewable=" << (*it)->viewable
+	 << " clrpend=" << (*it)->clearPending << endl;
+    */
+    if ( (*it)->refcount == 0  && (*it)->refreshTag < getRefreshCounter() ) {
+      (*it)->setViewable(false);
+      (*it)->clearPending = false;
+    }
+    else
+      (*it)->clearPending = true;
+  }
+}
+
+template <class T>
+SketchData<T>* SketchPool<T>::get_free_element(void) 
+{
+  for (CI it = elements.begin(); it != elements.end(); it++ ) {
+    if ( (*it)->refcount == 0 && (*it)->viewable == false )
+      return *it;
+    else if ( (*it)->refcount < 0 )
+      std::cerr << "PROBLEM: negative refcount" << std::endl;
+  };
+  SketchData<T>* res = new SketchData<T>(space);
+  elements.push_back(res);
+  return res;
+}
+
+template<class T>
+SketchData<T>* SketchPool<T>::findSketchData(const std::string &name) {
+  for (CI it = elements.begin(); it != elements.end(); it++ )
+	 if ( (*it)->name == name )
+		return *it;
+  return NULL;
+}
+	 
+
+template<class T>
+std::string SketchPool<T>::getSketchListForGUI()
+{
+	std::ostringstream liststream;
+	for ( unsigned int i = 0; i < elements.size(); i++ ) {
+		if ( elements[i]->clearPending ) {
+			elements[i]->setViewable(false);
+			elements[i]->clearPending = false;
+		}
+		else if ( elements[i]->isViewable() ) {
+			elements[i]->refreshTag = getRefreshCounter();
+			liststream << "sketch" << std::endl;
+			liststream << "id:" << (elements[i])->id << std::endl;
+			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 << "colormap:" << elements[i]->colormap << std::endl;
+		}
+	}
+	return liststream.str();
+}
+
+template <class T>  
+SketchDataRoot* SketchPool<T>::retrieveSketch(int id)
+{
+  for(unsigned int i = 0; i < elements.size(); i++)
+    if(elements[i]->id == id)
+      return elements[i];
+  return NULL;
+}
+
+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);
+    }
+  }
+}
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchPoolRoot.cc ./DualCoding/SketchPoolRoot.cc
--- ../Tekkotsu_2.4.1/DualCoding/SketchPoolRoot.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchPoolRoot.cc	2006-05-09 18:37:56.000000000 -0400
@@ -0,0 +1,14 @@
+//-*-c++-*-
+
+#include "SketchSpace.h"
+
+namespace DualCoding {
+
+SketchPoolRoot::~SketchPoolRoot() {}
+
+int SketchPoolRoot::getRefreshCounter() {
+	return space->getRefreshCounter();
+}
+
+} // namespace
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchPoolRoot.h ./DualCoding/SketchPoolRoot.h
--- ../Tekkotsu_2.4.1/DualCoding/SketchPoolRoot.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchPoolRoot.h	2006-05-09 13:07:53.000000000 -0400
@@ -0,0 +1,35 @@
+//-*-c++-*-
+#ifndef INCLUDED_SketchPoolRoot_h
+#define INCLUDED_SketchPoolRoot_h
+
+namespace DualCoding {
+
+class SketchSpace;
+
+//! 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
+	 dependencies, but we can safely include it from SketchPoolRoot.cc. */
+
+class SketchPoolRoot {
+protected:
+  SketchSpace *space;
+  
+  int getRefreshCounter();
+
+ public:
+
+  SketchPoolRoot(SketchSpace* _space) : space(_space) {}
+  
+  virtual ~SketchPoolRoot()=0; //!< used as a base class, but never directly instantiated, so has an virtual abstract destructor
+
+  SketchPoolRoot(const SketchPoolRoot&);  //!< never call
+
+  SketchPoolRoot& operator=(const SketchPoolRoot&); //!< never call
+
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchRoot.cc ./DualCoding/SketchRoot.cc
--- ../Tekkotsu_2.4.1/DualCoding/SketchRoot.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchRoot.cc	2006-08-10 23:11:04.000000000 -0400
@@ -0,0 +1,27 @@
+//-*-c++-*-
+
+#include "SketchRoot.h"
+#include "Sketch.h"
+
+namespace DualCoding {
+
+SketchSpace& SketchRoot::rootGetSpace() const {
+  const Sketch<bool>& faker = *reinterpret_cast<const Sketch<bool>*>(this);
+  return *(faker.data->space);
+}
+
+const SketchDataRoot& SketchRoot::rootGetData() const {
+  const Sketch<bool>& faker = *reinterpret_cast<const Sketch<bool>*>(this);
+  return *(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() << ")";
+  return os;
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchRoot.h ./DualCoding/SketchRoot.h
--- ../Tekkotsu_2.4.1/DualCoding/SketchRoot.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchRoot.h	2006-04-22 01:37:50.000000000 -0400
@@ -0,0 +1,41 @@
+//-*-c++-*-
+
+#ifndef INCLUDED_SketchRoot_h
+#define INCLUDED_SketchRoot_h
+
+#include "SketchSpace.h"
+#include "SketchDataRoot.h"
+
+namespace DualCoding {
+
+//! Parent class for all Sketch<T>
+class SketchRoot {
+ public:
+
+  SketchRoot() {}
+  virtual ~SketchRoot() {}
+
+  SketchSpace& rootGetSpace() const;
+  const SketchDataRoot& rootGetData() const;
+
+  int getNewId() { return ++idCounter; }
+
+private:
+  static int idCounter;
+
+  friend class SketchRootReset;
+  friend std::ostream& operator<<(std::ostream &os, const SketchRoot &r);
+};
+
+//! Dummy class used by SketchSpace to reset static SketchRoot::idCounter
+class SketchRootReset {
+public:
+  SketchRootReset() { SketchRoot::idCounter = 0; } //!< constructor, set idCounter to 0
+  virtual ~SketchRootReset() {} //!< virtual destructor to satisfy compiler warning
+};
+
+std::ostream& operator<<(std::ostream &os, const SketchRoot &r);
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchSpace.cc ./DualCoding/SketchSpace.cc
--- ../Tekkotsu_2.4.1/DualCoding/SketchSpace.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchSpace.cc	2006-09-12 17:39:45.000000000 -0400
@@ -0,0 +1,187 @@
+#include <iostream>
+#include <sstream> // for ostringstream
+
+#include "SketchSpace.h"
+#include "ShapeRoot.h"
+#include "ShapeSpace.h"
+#include "Sketch.h"
+#include "BaseData.h"
+#include "ViewerConnection.h"
+
+namespace DualCoding {
+
+SketchSpace::SketchSpace(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),
+  idxN(NULL), idxS(NULL), idxE(NULL), idxW(NULL), 
+  idxNE(NULL), idxNW(NULL), idxSE(NULL), idxSW(NULL),
+  viewer(new ViewerConnection)
+{
+}
+
+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);
+}
+
+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");
+    int i = 0;
+    for (size_t y = 0; y < height; y++) {
+      for (size_t x = 0; x < width; x++) {
+      setIdx(*idxN, x, y, i-width);
+      setIdx(*idxS, x, y, i+width);
+      setIdx(*idxW, x, y, i-1);
+      setIdx(*idxE, x, y, i+1);
+      i++;
+      }
+    }
+  }
+}
+
+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");
+    int i = 0;
+    for (size_t y = 0; y < height; y++) {
+      for (size_t x = 0; x < width; x++) {
+      setIdx(*idxNE, x, y, i-width+1);
+      setIdx(*idxNW, x, y, i-width-1);
+      setIdx(*idxSE, x, y, i+width+1);
+      setIdx(*idxSW, x, y, i+width-1);
+      i++;
+      }
+    }
+  }
+}
+
+void SketchSpace::freeIndexes() {
+  delete idx;
+  idx=NULL;
+  delete idxN; delete idxS; delete idxE; delete idxW; 
+  idxN=idxS=idxE=idxW=NULL;
+  delete idxNE; delete idxNW; delete idxSE; delete idxSW;
+  idxNE=idxNW=idxSE=idxSW=NULL;
+}
+
+
+SketchSpace::~SketchSpace() { 
+  delete dualSpace;
+  //printf("Destroying SketchSpace %s at 0x%p\n",name.c_str(),this);
+  freeIndexes();
+  delete viewer;
+}
+
+
+void SketchSpace::dumpSpace() const {
+  boolPool.dumpPool();
+  ucharPool.dumpPool();
+  usintPool.dumpPool();
+  floatPool.dumpPool();
+}
+
+void SketchSpace::clear() {
+  boolPool.clear();
+  ucharPool.clear();
+  usintPool.clear();
+  floatPool.clear();
+}
+
+void SketchSpace::setTmat(const NEWMAT::Matrix &mat) {
+  Tmat = mat;
+  Tmatinv = mat.i();
+}
+
+void SketchSpace::setTmat(float scale, float tx, float ty) {
+  NEWMAT::Matrix mat(4,4);
+  mat << 1 << 0 << 0 << tx
+      << 0 << 1 << 0 << ty
+      << 0 << 0 << 1 << 0
+      << 0 << 0 << 0 << 1/scale;
+  setTmat(mat);
+}
+
+void SketchSpace::setTmat(const BoundingBox &b) {
+  float const xscale = (b.xmax - b.xmin) / width;
+  float const yscale = (b.ymax - b.ymin) / height;
+  float const scale = min(xscale,yscale);
+  setTmat(scale, -b.xmin, -b.ymin);
+}    
+
+void SketchSpace::applyTmat(NEWMAT::ColumnVector &vec) {
+  vec = Tmat * vec;
+  if ( vec(4) != 0 )
+    vec = vec / vec(4);
+}
+
+void SketchSpace::applyTmatinv(NEWMAT::ColumnVector &vec) {
+  vec = Tmatinv * vec;
+  if ( vec(4) != 0 )
+    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;	
+}
+
+std::string SketchSpace::getTmatForGUI() {
+  std::ostringstream tmat_stream;
+  tmat_stream << "tmat" << endl;
+  for (int i=1; i<5; i++)
+    for (int j=1; j<5; j++)
+      tmat_stream << " " << Tmat(i,j);
+  tmat_stream << endl;
+  return tmat_stream.str();
+}
+
+std::string SketchSpace::getSketchListForGUI() {
+	bumpRefreshCounter();
+	std::string sketchlist;
+	sketchlist += boolPool.getSketchListForGUI();
+	sketchlist += ucharPool.getSketchListForGUI();
+	sketchlist += usintPool.getSketchListForGUI();
+	sketchlist += floatPool.getSketchListForGUI();
+	return sketchlist;	
+}
+
+SketchDataRoot* SketchSpace::retrieveSketch(int 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);
+  if(sketchp) return sketchp;
+  sketchp = floatPool.retrieveSketch(id);
+  return sketchp;
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchSpace.h ./DualCoding/SketchSpace.h
--- ../Tekkotsu_2.4.1/DualCoding/SketchSpace.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchSpace.h	2006-09-06 20:44:39.000000000 -0400
@@ -0,0 +1,161 @@
+//-*-c++-*-
+#ifndef INCLUDED_SketchSpace_h
+#define INCLUDED_SketchSpace_h
+
+#include "Shared/newmat/newmat.h"
+
+#include "Macrodefs.h"
+#include "SketchTypes.h"
+#include "ShapeTypes.h"
+#include "SketchPool.h"
+#include "SketchIndices.h"
+
+namespace DualCoding {
+
+class BoundingBox;
+class ShapeSpace;
+template<typename T> class Sketch;
+class ViewerConnection;
+
+//! Holds a collection of sketches of various types
+/*! All the sketches in a SketchSpace have the same dimensions (width and height).
+   They are organized into pools, managed by SketchPool<T> instances.
+   Each SketchSpace has a dual, called a ShapeSpace.  Several standard
+   SketchSpace/ShapeSpace pairs are built in to VisualRoutinesBehavior.
+   The most basic is @a camSkS, the camera sketch space.   */
+
+class SketchSpace {
+public:
+  std::string name;    //!< name of this SketchSpace
+
+private:
+  size_t width;	  //!< pixels along x axis
+  size_t height;  //!< pixels along y axis
+  size_t numPixels; //!< total pixels = width * height
+  NEWMAT::Matrix Tmat; //!< transformation matrix for rendering shapes
+  NEWMAT::Matrix Tmatinv; //!< inverse transformation matrix for extracting shapes
+    
+  int idCounter; //!< Incremented with each new Sketch, to guarantee a unique ID.
+  int refreshCounter; //!< Incremented each time SketchGUI refreshes the sketch/shape list
+  
+  ShapeSpace* dualSpace; //!< Pointer to the ShapeSpace associated with this SketchSpace
+  
+  //! Pool for one of the SketchData<T> classes
+  //@{
+  SketchPool<bool>  boolPool; 
+  SketchPool<uchar> ucharPool;
+  SketchPool<usint> usintPool;
+  SketchPool<float> floatPool; 
+  //@}
+  
+public:
+  //! The value assigned to out-of-bounds indices: @a numPixels, i.e., one beyond the last image pixel.
+  int dummy;
+
+  //!@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;
+  //@}
+  
+  SketchSpace(std::string const _name, ReferenceFrameType_t _refFrameType,
+	      int const init_id, size_t const _width, size_t const _height);
+  
+  ~SketchSpace();
+  
+  ShapeSpace& getDualSpace() const { return *dualSpace; }
+  
+  //! dumps contents of sketch space
+  void dumpSpace() const;
+  
+  //! 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
+  size_t getHeight() const { return height; }
+  //! returns the number of pixels of images in this space
+  size_t getNumPixels() const { return numPixels; }
+  
+  int getRefreshCounter() const { return refreshCounter; }
+  void bumpRefreshCounter() { ++refreshCounter; }
+
+  //! creates #idx if needed
+  void requireIdx();
+	
+  //! creates #idxN, #idxS, #idxE, and #idxW if needed
+  void requireIdx4way();
+
+  //! creates #idxNE, #idxNW, #idxSE, and #idxSW, plus NSEW cases via requireIdx4way(), if needed
+  void requireIdx8way();
+	
+  //! frees the idx members
+  void freeIndexes();
+
+  //! return the ShapeSpace-to-SketchSpace coordinate transformation matrix
+  NEWMAT::Matrix& getTmat() { return Tmat; }
+
+  //! return the SketchSpace-to-ShapeSpace coordinate transformation matrix
+  NEWMAT::Matrix& getTmatinv() { return Tmatinv; }
+
+  //! set the ShapeSpace-to-SketchSpace coordinate transformation matrix
+  void setTmat(const NEWMAT::Matrix &mat);
+
+  void setTmat(float scale=1, float tx=0, float ty=0);
+
+  void setTmat(const BoundingBox &b);
+
+  //! apply the ShapeSpace-to-SketchSpace coordinate transformation to a vector
+  void applyTmat(NEWMAT::ColumnVector &vec);
+
+  //! apply the SketchSpace-to-ShapeSpace coordinate transformation to a vector
+  void applyTmatinv(NEWMAT::ColumnVector &vec);
+
+  //! Returns the SketchPool of appropriate type for the calling Sketch
+  //@{
+  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<float>& get_pool(const Sketch<float>&) { return floatPool; }
+  
+  //@}
+  
+  //!@name SketchGUI interface
+  //@{
+  
+  //! Socket and port info for communication with a sketch viewer GUI.
+  ViewerConnection *viewer;
+
+  //! Returns a string describing the shape-to-sketch transformation matrix.
+  std::string getTmatForGUI();
+
+  //! Returns a string containing a list of all the sketches and their attributes
+  std::string getSketchListForGUI();
+
+  //! Returns a pointer to the sketch with specified ID number; null if not found
+  SketchDataRoot* retrieveSketch(int id);
+  //@}
+  
+protected:
+  //! helper function to ensure indices of idx Sketches are proper
+  void setIdx(Sketch<usint>& indices, int x, int y, int shift_i);
+  
+  // We don't want clients accidentally copying or assigning SketchSpace.
+  SketchSpace(const SketchSpace&); //!< never call this
+  SketchSpace& operator= (const SketchSpace&); //!< never call this
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SketchTypes.h ./DualCoding/SketchTypes.h
--- ../Tekkotsu_2.4.1/DualCoding/SketchTypes.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SketchTypes.h	2006-04-26 16:50:00.000000000 -0400
@@ -0,0 +1,31 @@
+//-*-c++-*-
+#ifndef INCLUDED_SketchTypes_h
+#define INCLUDED_SketchTypes_h
+
+#include <string>
+
+namespace DualCoding {
+
+typedef unsigned char uchar;
+typedef unsigned short int usint;
+
+enum SketchType_t {
+  sketchUnknown = 0,
+  sketchBool,
+  sketchUchar,
+  sketchUsint,
+  sketchFloat
+};
+
+const std::string SketchTypeNames[] = {"unknown","bool","uchar","usint","float"};
+
+enum ColorMapType_t {
+  segMap = 0,	// use the color segmentation table (default)
+  grayMap = 1,	// gray scale image
+  jetMap = 2,	// Matlab-style blue to red color map
+  jetMapScaled = 3  // blue to red map that  scales the spectrum to the image
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SphereData.cc ./DualCoding/SphereData.cc
--- ../Tekkotsu_2.4.1/DualCoding/SphereData.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SphereData.cc	2006-07-19 17:54:12.000000000 -0400
@@ -0,0 +1,267 @@
+#include <iostream>
+#include <vector>
+#include <list>
+#include <math.h>
+
+#include "Motion/Kinematics.h"  // for kine
+
+#include "SketchSpace.h"
+#include "Sketch.h"
+#include "ShapeRoot.h"
+#include "LineData.h"
+#include "Region.h"
+#include "visops.h"
+
+#include "SphereData.h"
+#include "ShapeSphere.h"
+
+namespace DualCoding {
+
+SphereData::SphereData(ShapeSpace& _space, const Point &c) 
+  : BaseData(_space,sphereDataType),
+    centroid(c), radius(0)
+  { mobile = SPHERE_DATA_MOBILE; }
+  
+SphereData::SphereData(const SphereData& otherData)
+  : BaseData(otherData),centroid(otherData.centroid),radius(otherData.radius) 
+  { mobile = otherData.mobile; }
+  
+DATASTUFF_CC(SphereData);
+
+bool SphereData::isMatchFor(const ShapeRoot& other) const {
+  if (!(isSameTypeAs(other) && isSameColorAs(other)))
+    return false;
+  const Shape<SphereData>& other_sphere = ShapeRootTypeConst(other,SphereData);
+  float dist = centroid.distanceFrom(other_sphere->centerPt());
+  return dist < 2*max(radius,other_sphere->radius); // *** DST hack
+}
+
+void SphereData::mergeWith(const ShapeRoot& other) {
+  const Shape<SphereData>& other_sphere = ShapeRootTypeConst(other,SphereData);
+  if (other_sphere->confidence <= 0)
+    return;
+  const int other_conf = other_sphere->confidence;
+  confidence += other_conf;
+  centroid = (centroid*confidence + other_sphere->centerPt()*other_conf) / (confidence+other_conf);
+  radius = (radius*confidence + other_sphere->getRadius()*other_conf) / (confidence+other_conf);
+}
+
+bool SphereData::updateParams(const ShapeRoot& other, bool) {
+  const Shape<SphereData>& other_sphere = *static_cast<const Shape<SphereData>*>(&other);
+  centroid = (centroid*(confidence-1) + other_sphere->getCentroid())/confidence;
+  radius = (radius*(confidence-1) + other_sphere->getRadius())/confidence;
+  return true;
+}
+
+//! Print information about this shape. (Virtual in BaseData.)
+void SphereData::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 << "radius = " << getRadius() << endl;
+  printf("color = %d %d %d\n",getColor().red,getColor().green,getColor().blue);
+  cout << "mobile = " << isMobile() << endl;
+  cout << "viewable = " << isViewable() << endl;
+}
+
+
+//! Transformations. (Virtual in BaseData.)
+void SphereData::applyTransform(const NEWMAT::Matrix& Tmat) {
+  centroid.applyTransform(Tmat);
+}
+
+bool SphereData::isInside(const Point& pt) const {
+  float dist = pt.distanceFrom(centerPt());
+  return radius>dist;
+}
+
+
+void SphereData::projectToGround(const NEWMAT::Matrix& camToBase,
+				 const NEWMAT::ColumnVector& groundplane) {
+  NEWMAT::ColumnVector cam_pos = (kine->jointToBase(CameraFrameOffset)).SubMatrix(1,4,4,4);
+  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.
+  Point cam_pt(cam_pos(1)/cam_pos(4), cam_pos(2)/cam_pos(4), cam_pos(3)/cam_pos(4)); // position of camera w.r.t. base
+  cout << "sphere in cam frame: centroid:" << "(" << centroid.coordX() 
+       << "," << centroid.coordY() << "," << centroid.coordZ() << ");  tangent_pt:" 
+       << "(" << tangent_pt.coordX() << "," << tangent_pt.coordY() << "," << tangent_pt.coordZ()
+       << ")" << endl;
+
+  centroid.projectToGround(camToBase,groundplane);
+  tangent_pt.projectToGround(camToBase,groundplane);
+  cout << "sphere projected to ground: centroid:" << "(" << centroid.coordX() 
+       << "," << centroid.coordY() << "," << centroid.coordZ() << ");  tangent_pt:" 
+       << "(" << tangent_pt.coordX() << "," << tangent_pt.coordY() << "," << tangent_pt.coordZ()
+       << ")" << endl;
+
+  LineData tangent_line(getSpace(), cam_pt, tangent_pt); // tangent line from camera to sphere
+  LineData cam_center(getSpace(), cam_pt, centroid); // line from camera passing through center point of sphere
+
+  // a line perpendicular to tangent_line should cross cam_center line at the center point of the sphere if it
+  // crosses tangent_line at the tangent point. Distance b/w tangent point and center point is the radius of sphere
+  // which should also equal the height of the sphere (coordZ = 1/groundplane(3) + radius)
+  // line from tangent_pt to centroid: z = ax + b (a known, b unkown)
+  // line from camera to centroid: z = cx + d (c,d known)
+  // tangent_line: z = ex + f (e,f known)
+  // tangent_pt: x = (f-b)/(a-e)
+  // centroid: x = (d-b)/(a-c), z = d + c(d-b)/(a-c) = 1/groundplane(3) + radius = (radius above groud level)
+  // solve for b and substitute it to get centroid and radius
+
+  vector<float> t_abc_xz = tangent_line.lineEquation_abc_xz();
+  vector<float> cc_abc_xz = cam_center.lineEquation_abc_xz();
+  vector<float> cc_abc_xy = cam_center.lineEquation_abc();
+
+  const float f = cc_abc_xz[2] / cc_abc_xz[1];
+  const float e = - cc_abc_xz[0] / cc_abc_xz[1];
+  const float d = t_abc_xz[2] / t_abc_xz[1];
+  const float c = - t_abc_xz[0] / t_abc_xz[1];
+  const float a = -1.0 / e; // perpendicular to e
+  const float ground = 1.0/groundplane(3);
+  const float DXtoR = 1/ cos(atan(a)) / cos(atan(-cc_abc_xy[0]/cc_abc_xy[1])); // radius = dx * DXtoR where dx is b/w center pt and tangent pt
+  const float b = (-DXtoR*f*a+DXtoR*f*c+DXtoR*d*a-DXtoR*d*e+ground*a*a-ground*a*c-ground*e*a+ground*e*c-d*a*a+d*e*a)/(-a*c+e*c+DXtoR*c-DXtoR*e);
+
+  cout << "ground level: " << ground << ", DXtoR: " << DXtoR << endl;
+  cout << "tangent line: z = " << e << " * x + " << f << endl;
+  cout << "perpendicular line: z = " << a << " * x + " << b << endl;
+  cout << "center line: z = " << c << " * x + " << d << endl;
+  cout << "dx b/w tangent pt and center pt: " << ((f-b)/(a-e)-(d-b)/(a-c)) << endl;
+
+  const float x = (d-b)/(a-c);
+  const float z = d + c*(d-b)/(a-c);
+  const float y = (cc_abc_xy[2]-cc_abc_xy[0]*x) / cc_abc_xy[1];
+
+  centroid.setCoords(x,y,z);
+  radius = z-ground;
+
+  cout << " => (" << x << "," << y << "," << z << ");  radius: " << radius << endl;
+}
+
+void SphereData::setRadius(float _radius) {
+  radius = _radius;
+  deleteRendering();
+}
+//}
+
+
+// ==================================================
+// BEGIN SKETCH MANIPULATION AND LINE EXTRACTION CODE
+// ==================================================
+
+
+//! Extraction.
+//{
+std::vector<ShapeRoot> 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));
+  list<Region> regionlist = Region::extractRegions(labels,REGION_THRESH);
+  std::vector<ShapeRoot> spheres;
+  
+  if(regionlist.empty())
+    return spheres;
+  
+  typedef list<Region>::iterator R_IT;
+  for (R_IT it = regionlist.begin(); it != regionlist.end(); ++it) {
+    float ratio = it->findSemiMajorAxisLength()/(float)(it->findSemiMinorAxisLength());
+    if((ratio < 2.0) && (ratio > 1.0/(float)2.0)
+       && (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());
+      spheres.push_back(Shape<SphereData>(temp_sphere));
+    };
+  }
+  return spheres;
+}
+
+std::vector<ShapeRoot> SphereData::get_spheres(const Sketch<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<bool>& Valid_Colors) {
+  std::vector<ShapeRoot> spheres_vec;
+  uchar cur_color;
+  uchar num_colors = (uchar)Valid_Colors.size();
+  char *pmask_name_chr = (char *)malloc(128*sizeof(char));
+  
+  // Loop through all valid colors.
+  for(cur_color = 0; cur_color < num_colors; cur_color++) {
+    
+    if(Valid_Colors[cur_color] == true) {
+      
+      // Segment color pixels.
+      NEW_SKETCH_N(pmask, bool, 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);
+      
+      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));
+	spheres_vec.push_back(spheresList[cur_sphere]); 
+      }
+      
+    };
+  }
+  return(spheres_vec);
+}
+
+
+//! Render into a sketch space and return reference. (Private.)
+Sketch<bool>* SphereData::render() const {
+  const int cx = int(centerPt().getCoords()(1));
+  const int cy = int(centerPt().getCoords()(2));
+  /*  
+  // Sure the sphere rendering is terribly inefficient, but it works
+  float a = getRadius();
+  float x_skip = atan(1/(0.5*a)); // minimum x-diff w/o gaps 
+  for( float x = (cx-a); x<(cx+a); x+=x_skip) {
+    float y_y0_sq = 1 - (x-cx)*(x-cx);
+    if(y_y0_sq > 0) {
+      int y_bot = cy + (int)(sqrt(y_y0_sq));
+      int y_top = cy - (int)(sqrt(y_y0_sq));
+      draw_result((int)x,y_bot) = true;
+      draw_result((int)x,y_top) = true;
+    }
+  }
+  draw_result(cx-(int)a,cy) = true; // fill in "holes" at ends
+  draw_result(cx+(int)a,cy) = true;
+  */  
+  // Fill the sphere.
+
+  Sketch<bool> result(space->getDualSpace(), "render("+getName()+")");
+  result = 0;
+  const int rad =(int) floor(getRadius()+0.5);
+  const int radSq = rad*rad + rad/10; // rad/10 added to make sphere look nicer
+  const int minX = (rad > cx) ? 0 : cx-rad;
+  const int maxX = ((unsigned int) (rad+cx) > getSpace().getDualSpace().getWidth()-1)
+    ? getSpace().getDualSpace().getWidth()-1 : cx+rad;
+  for (int x = minX; x <= maxX; x++) {
+    const int yRange = (int) sqrt((float) (radSq-(cx-x)*(cx-x))); 
+    const int minY = (yRange > cy) ? 0 : cy-yRange;
+    const int maxY = ((unsigned int) yRange+cy > getSpace().getDualSpace().getHeight()-1)
+      ? getSpace().getDualSpace().getHeight()-1 : cy+yRange;
+    for (int y = minY; y <= maxY; y++)
+      result(x,y) = true;
+  }
+  return new Sketch<bool>(result);
+}
+
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/SphereData.h ./DualCoding/SphereData.h
--- ../Tekkotsu_2.4.1/DualCoding/SphereData.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/SphereData.h	2006-05-09 18:37:56.000000000 -0400
@@ -0,0 +1,105 @@
+//-*-c++-*-
+#ifndef _SPHEREDATA_H_
+#define _SPHEREDATA_H_
+
+#include <vector>
+#include <iostream>
+
+#include "BaseData.h"    // superclass
+#include "Point.h"       // Point data member
+#include "ShapeTypes.h"  // sphereDataType
+
+namespace DualCoding {
+
+class ShapeRoot;
+class SketchSpace;
+template<typename T> class Sketch;
+
+#define SPHERE_DATA_MOBILE false
+
+class SphereData : public BaseData {
+private:
+  Point centroid;
+  float radius;
+
+public:
+
+  //! Constructor
+  SphereData(ShapeSpace& _space, const Point &c);
+
+  //! Copy constructor
+  SphereData(const SphereData& otherData);
+  
+  static ShapeType_t getStaticType() { return sphereDataType; }
+
+  DATASTUFF_H(SphereData);
+  
+  friend class Shape<SphereData>;
+  
+  //! Centroid. (Virtual in BaseData.)
+  Point getCentroid() const { return centroid; }  
+  
+  void setCentroidPt(const Point& pt) { centroid.setCoords(pt); }
+
+  //! Match spheres based on their parameters.  (Virtual in BaseData.)
+  virtual bool isMatchFor(const ShapeRoot& other) const;
+
+  virtual void mergeWith(const ShapeRoot& other);
+
+  virtual bool isAdmissible() const {
+    return (radius >= 9.0 );  // **DST Hack** minimum size for a sphere to be added to local map
+  }
+
+  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);
+  
+  //! Project to ground
+  virtual void projectToGround(const NEWMAT::Matrix& camToBase,
+			       const NEWMAT::ColumnVector& groundplane);
+
+  virtual bool isInside(const Point& pt) const;
+  //! Center point access function.
+  const Point& centerPt() const { return centroid; }
+  
+  virtual unsigned short getDimension() const { return 3; }
+
+  //! Properties functions.
+  //@{
+  float getRadius() const { return radius; }
+  //@}
+  
+  
+  //! Set properties.
+  //@{
+  void setRadius(float _radius);
+  //@}
+  
+  // ==================================================
+  // BEGIN SKETCH MANIPULATION AND SPHERE EXTRACTION CODE
+  // ==================================================
+  
+  
+  //! 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);
+  //@}
+  
+  
+private:
+  //! Render into a sketch space and return pointer. (Private.)
+  Sketch<bool>* render() const;
+
+  SphereData& operator=(const SphereData&); //!< don't call
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/VRmixin.cc ./DualCoding/VRmixin.cc
--- ../Tekkotsu_2.4.1/DualCoding/VRmixin.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/VRmixin.cc	2006-09-06 20:44:39.000000000 -0400
@@ -0,0 +1,352 @@
+#include <sstream>
+
+#include "Vision/RawCameraGenerator.h"
+#include "Vision/RLEGenerator.h"
+#include "Vision/RegionGenerator.h"
+#include "Vision/SegmentedColorGenerator.h"
+
+#include "SketchData.h"
+#include "ShapeBlob.h"
+#include "Sketch.h"
+
+#include "Lookout.h"
+#include "MapBuilder.h"
+#include "ParticleFilter.h"
+#include "Pilot.h"
+
+#include "ViewerConnection.h"  // for port numbers and buffer sizes
+#include "VRmixin.h"
+
+namespace DualCoding {
+
+//----------------------------------------------------------------
+
+VRmixin* VRmixin::theOne=NULL;
+
+//! static function allows us to specify intialization order because static within a function isn't created until the function is called
+template<ReferenceFrameType_t _refFrameType,int const init_id, size_t const _width, size_t const _height>
+static SketchSpace& createStaticSkS(const std::string& _name) {
+  static SketchSpace SkS(_name,_refFrameType,init_id,_width,_height);
+  //  cout << _name << " space is constructed\n";
+  return SkS;
+}
+
+SketchSpace& VRmixin::getCamSkS() {
+  return createStaticSkS<camcentric,10000,CameraResolutionX,CameraResolutionY>("cam");
+}
+SketchSpace& VRmixin::getLocalSkS() {
+  return createStaticSkS<egocentric,20000,WORLD_WIDTH,WORLD_HEIGHT>("local"); 
+}
+SketchSpace& VRmixin::getWorldSkS() {
+  return createStaticSkS<allocentric,30000,WORLD_WIDTH,WORLD_HEIGHT>("world");
+}
+ShapeSpace& VRmixin::getGroundShS() {
+  static ShapeSpace ShS(&VRmixin::getCamSkS(),90000,"ground",egocentric);
+  return ShS;
+}
+
+MapBuilder& VRmixin::getMapBuilder() {
+  static MapBuilder mapbuilder;
+  return mapbuilder;
+}
+
+SketchSpace& VRmixin::camSkS=VRmixin::getCamSkS();
+ShapeSpace& VRmixin::camShS=VRmixin::getCamSkS().getDualSpace();
+
+ShapeSpace& VRmixin::groundShS=VRmixin::getGroundShS();
+
+SketchSpace& VRmixin::localSkS=VRmixin::getLocalSkS();
+ShapeSpace& VRmixin::localShS=VRmixin::getLocalSkS().getDualSpace();
+
+SketchSpace& VRmixin::worldSkS=VRmixin::getWorldSkS();
+ShapeSpace& VRmixin::worldShS=VRmixin::getWorldSkS().getDualSpace();
+
+Shape<AgentData> VRmixin::theAgent;
+
+Socket *VRmixin::camDialogSock=NULL;
+Socket *VRmixin::camRleSock=NULL;
+Socket *VRmixin::localDialogSock=NULL;
+Socket *VRmixin::localRleSock=NULL;
+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());
+
+
+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;
+      return;
+    }
+    theOne=this;
+    camSkS.requireIdx();
+    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);
+		
+    wireless->setReceiver(camDialogSock->sock, &camDialogSockCallback);
+    wireless->setReceiver(worldDialogSock->sock, &worldDialogSockCallback);
+    wireless->setReceiver(localDialogSock->sock, &localDialogSockCallback);
+		
+    wireless->setDaemon(camDialogSock,   true);
+    wireless->setDaemon(camRleSock,      true);
+    wireless->setDaemon(worldDialogSock, true);
+    wireless->setDaemon(worldRleSock,    true);
+    wireless->setDaemon(localDialogSock, true);
+    wireless->setDaemon(localRleSock,    true);
+		
+    wireless->listen(camDialogSock,   CAM_DIALOG_PORT);
+    wireless->listen(camRleSock,      CAM_RLE_PORT);
+    wireless->listen(worldDialogSock, WORLD_DIALOG_PORT);
+    wireless->listen(worldRleSock,    WORLD_RLE_PORT);
+    wireless->listen(localDialogSock, LOCAL_DIALOG_PORT);
+    wireless->listen(localRleSock,    LOCAL_RLE_PORT);
+		
+    camSkS.viewer->setDialogSocket(camDialogSock,     CAM_DIALOG_PORT);
+    camSkS.viewer->setRleSocket(camRleSock,           CAM_RLE_PORT);
+    localSkS.viewer->setDialogSocket(localDialogSock, LOCAL_DIALOG_PORT);
+    localSkS.viewer->setRleSocket(localRleSock,       LOCAL_RLE_PORT);
+    worldSkS.viewer->setDialogSocket(worldDialogSock, WORLD_DIALOG_PORT);
+    worldSkS.viewer->setRleSocket(worldRleSock,       WORLD_RLE_PORT);
+
+    theAgent = Shape<AgentData>(worldShS,Point());
+
+    mapBuilder.SetAutoDelete(false);
+    pilot.SetAutoDelete(false);
+    lookout.SetAutoDelete(false);
+  }
+}
+
+VRmixin::~VRmixin() {
+  if(--instanceCount==0) {
+    // cout << "Destructing VRmixin statics" << endl;
+    if (theOne == NULL) {
+      cerr << "VRmixin statics already destructed!?!?!" << endl;
+      return;
+    }
+    
+    wireless->setDaemon(camDialogSock,  false);
+    wireless->setDaemon(camRleSock,     false);
+    wireless->setDaemon(localDialogSock,false);
+    wireless->setDaemon(localRleSock,   false);
+    wireless->setDaemon(worldDialogSock,false);
+    wireless->setDaemon(worldRleSock,   false);
+    
+    wireless->close(camRleSock->sock);
+    wireless->close(camDialogSock->sock);
+    wireless->close(localRleSock->sock);
+    wireless->close(localDialogSock->sock);
+    wireless->close(worldRleSock->sock);
+    wireless->close(worldDialogSock->sock);
+		
+    theOne=NULL;
+    
+    // clear ShapeSpace first because it may contain rendering links to SketchSpace
+    camShS.clear();
+    camSkS.bumpRefreshCounter(); // release visible sketches
+    camSkS.clear();
+    
+    localShS.clear();
+    localSkS.bumpRefreshCounter(); // release visible sketches
+    localSkS.clear();
+    
+    worldShS.clear();
+    worldSkS.bumpRefreshCounter(); // release visible sketches
+    worldSkS.clear();
+		
+    filter.reinitialize();
+    
+    camSkS.freeIndexes();
+    localSkS.freeIndexes();
+    worldSkS.freeIndexes();
+  }
+}
+
+void VRmixin::startCrew() {
+  if(crewCount++==0) {
+    //cout << "Starting crew" << endl;
+    mapBuilder.SetAutoDelete(false);
+    mapBuilder.DoStart();
+    lookout.SetAutoDelete(false);
+    lookout.DoStart();
+    pilot.SetAutoDelete(false);
+    pilot.DoStart();
+  }
+}
+
+void VRmixin::stopCrew() {
+  if(--crewCount==0) {
+    //cout << "Stopping crew" << endl;
+    pilot.DoStop();
+    lookout.DoStop();
+    mapBuilder.DoStop();
+  }
+}
+
+void VRmixin::projectToGround(const NEWMAT::Matrix& camToBase,
+			      const NEWMAT::ColumnVector& ground_plane) {
+  groundShS.clear();
+  groundShS.importShapes(camShS.allShapes());
+  const vector<ShapeRoot> &groundShapes_vec = groundShS.allShapes();
+  for(size_t i = 0; i < groundShapes_vec.size(); i++)
+    groundShapes_vec[i]->projectToGround(camToBase, ground_plane);
+}
+
+int VRmixin::camDialogSockCallback(char *buf, int bytes) {
+  static std::string incomplete;
+  dialogCallback(buf, bytes, incomplete, theOne->camSkS, theOne->camShS);
+  return 0;
+}
+
+int VRmixin::localDialogSockCallback(char *buf, int bytes) {
+  static std::string incomplete;
+  dialogCallback(buf, bytes, incomplete, theOne->localSkS, theOne->localShS);
+  return 0;
+}
+
+int VRmixin::worldDialogSockCallback(char *buf, int bytes) {
+  static std::string incomplete;
+  dialogCallback(buf, bytes, incomplete, theOne->worldSkS, theOne->worldShS);
+  return 0;
+}
+
+void VRmixin::dialogCallback(char* buf, int bytes, std::string& incomplete,
+			     SketchSpace& SkS, ShapeSpace& ShS) {
+  std::string s(buf,bytes);
+  while(s.size()>0) {
+    size_t endline=s.find('\n');
+    if(endline==std::string::npos) {
+      incomplete+=s;
+      return;
+    }
+    else {
+      incomplete+=s.substr(0,endline);
+      theOne->processSketchRequest(incomplete,SkS,ShS);
+      incomplete.erase();
+      s=s.substr(endline+1);
+    }
+  }
+  return;
+}
+
+bool VRmixin::rleEncodeSketch(const SketchDataRoot& image)
+{
+  unsigned int avail = RLE_BUFFER_SIZE-1;
+  Socket* rleSock = image.getSpace().viewer->getRleSocket();
+  char* buf=(char*)rleSock->getWriteBuffer(avail);
+  ASSERTRETVAL(buf!=NULL,"could not get buffer",false);
+  unsigned int used = image.saveBuffer(buf, avail);
+  rleSock->write(used);
+  return true;
+}
+
+//! Import a color-segmented image as a Sketch<uchar>
+Sketch<uchar> VRmixin::sketchFromSeg() {
+  Sketch<uchar> cam(camSkS, "camimage");
+  cam->setColorMap(segMap);
+  size_t const npixels = cam->getNumPixels();
+  cmap_t* seg_image = ProjectInterface::defSegmentedColorGenerator->getImage(CAM_LAYER,CAM_CHANNEL);
+  for(size_t i = 0; i < npixels; i++)
+    cam[i] = seg_image[i];
+  return cam;
+}
+
+//! 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> 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);
+  if(chan_ptr==NULL) {
+    for (unsigned int row = 0; row < cam->getHeight(); row++)
+      for (unsigned int col = 0; col < cam->getWidth(); col++)
+        *campixels++ = 0;
+  } else {
+    chan_ptr -= incr;  // back up by one pixel to prepare for loop
+    for (unsigned int row = 0; row < cam->getHeight(); row++) {
+      for (unsigned int col = 0; col < cam->getWidth(); col++)
+        *campixels++ = *(chan_ptr += incr);
+      chan_ptr += skip;
+    }
+  }
+  return cam;
+}
+
+Sketch<uchar> VRmixin::sketchFromRawY() {
+  return sketchFromChannel(RawCameraGenerator::CHAN_Y);
+}
+
+
+//! 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) {
+  vector<Shape<BlobData> > result;
+  const CMVision::run<uchar> *rle_buffer = reinterpret_cast<const CMVision::run<uchar>*>
+    (ProjectInterface::defRLEGenerator->getImage(CAM_LAYER,CAM_CHANNEL));
+  const CMVision::color_class_state* ccs = reinterpret_cast<const CMVision::color_class_state*>
+    (ProjectInterface::defRegionGenerator->getImage(CAM_LAYER,CAM_CHANNEL));
+  //  cout << "Color " << color << " name '" << ccs[color].name 
+  //   << "' has " << ccs[color].num << " regions." << endl;
+  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);
+    result.push_back(Shape<BlobData>(blobdat));
+  }
+  return result;
+}
+
+void VRmixin::processSketchRequest(const std::string &line,
+				   SketchSpace& SkS, 
+				   ShapeSpace& ShS)
+{
+  Socket* dialogSock = SkS.viewer->getDialogSocket();
+  if(line.compare(0,strlen("size"),"size")==0) {
+    dialogSock->printf("size begin\n");
+    dialogSock->printf("width %d\nheight %d\n",int(SkS.getWidth()),int(SkS.getHeight()));
+    dialogSock->printf("size end\n");
+  }
+  else if(line.compare(0,strlen("list"),"list")==0) {
+    dialogSock->printf("list begin\n");
+    SkS.viewer->writeBigString(SkS.getTmatForGUI());	
+    SkS.viewer->writeBigString(SkS.getSketchListForGUI());	
+    SkS.viewer->writeBigString(ShS.getShapeListForGUI());	
+    dialogSock->printf("list end\n");
+  } else if(line.compare(0,strlen("get"),"get")==0) {
+    dialogSock->printf("get begin\n");
+    std::string tempstring = line.substr(strlen("get"),
+					 line.length()-strlen("get"));
+    std::istringstream ist(tempstring);
+    int requested_id = -1;
+    ist >> requested_id;
+    dialogSock->printf("get read:%d\n",requested_id);
+    SketchDataRoot* sketchptr=(SkS.retrieveSketch(requested_id));
+    if(sketchptr != NULL)
+      rleEncodeSketch(*sketchptr);
+    dialogSock->printf("get end\n");
+  } else {
+    dialogSock->printf("Invalid command\n");
+  }
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/VRmixin.h ./DualCoding/VRmixin.h
--- ../Tekkotsu_2.4.1/DualCoding/VRmixin.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/VRmixin.h	2006-05-10 19:21:57.000000000 -0400
@@ -0,0 +1,133 @@
+//-*-c++-*-
+#ifndef _VRmixin_h_
+#define _VRmixin_h_
+
+#include <string>
+#include <iostream>
+
+#include "Behaviors/BehaviorBase.h"
+#include "Shared/debuget.h" // needed for ASSERT macros
+#include "Vision/RawCameraGenerator.h"
+#include "Vision/SegmentedColorGenerator.h"
+#include "Vision/cmv_types.h" // needed for 'run' type?
+#include "Wireless/Wireless.h"
+#include "Shared/Config.h"
+#include "Shared/get_time.h" // needed for time stamp, for serialization 
+
+#include "ShapeAgent.h"
+#include "BlobData.h"
+#include "SketchRoot.h"
+
+namespace DualCoding {
+
+class Lookout;
+class Pilot;
+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
+	
+public:
+  //! returns reference to the global space instances, call there from global constructors instead of accessing #camSkS, which might not be initialized yet
+  static SketchSpace& getCamSkS();
+  static SketchSpace& getLocalSkS();
+  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
+  
+  static ShapeSpace& groundShS;    //!< The ground shape space of MapBuilder (MapBuilder::groundShS)
+  
+  static SketchSpace& localSkS;    //!< The localmap sketch space (LocalMapBuilder::localSkS)
+  static ShapeSpace& localShS;     //!< The localmap shape space (LocalMapBuilder::localShS)
+  
+  static SketchSpace& worldSkS;    //!< The worldmap sketch space (WorldMapBuilder::localSkS)
+  static ShapeSpace& worldShS;     //!< The worldmap sketch space (WorldMapBuilder::localShS)
+  static Shape<AgentData> theAgent; //!< The robot (usually lives in worldShS)
+  
+  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
+  
+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
+  static Socket *localDialogSock;  //!< socket to talk with local-space sketch viewer
+  static Socket *localRleSock;     //!< socket for transmitting RLE images to local-space sketch viewer
+  static Socket *worldDialogSock;  //!< socket to talk with world-space sketch viewer
+  static Socket *worldRleSock;     //!< socket for transmitting RLE images to world-space sketch viewer
+  
+public:
+  //! Constructor
+  VRmixin();
+
+  //! Destructor
+  virtual ~VRmixin(void);
+  
+  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);
+  
+  //! Import the current color-segmented camera image as a Sketch<uchar>
+  static Sketch<uchar> sketchFromSeg();
+  
+  //! Import channel n image as a Sketch<uchar>
+  static Sketch<uchar> sketchFromChannel(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);
+  
+  //! processes a single line of input for a Sketch request
+  static void processSketchRequest(const std::string &line, 
+				   SketchSpace &sketches, 
+				   ShapeSpace &shapes);
+  
+  //! project shapes from cam space to ground space
+  static void projectToGround(const NEWMAT::Matrix& camToBase = kine->jointToBase(CameraFrameOffset),
+			      const NEWMAT::ColumnVector& ground_plane = kine->calculateGroundPlane());
+
+private:
+  //! used so static member functions can access non-static members
+  static VRmixin* theOne;
+  
+  // dummy functions to satisfy the compiler
+  VRmixin (const VRmixin&);	 //!< never call this
+  VRmixin& operator=(const VRmixin&); //!< never call this
+  
+  //! Called whenever data is received on camDialogSocket
+  static int camDialogSockCallback(char *buf, int bytes);
+  
+  //! Called whenever data is received on localDialogSocket
+  static int localDialogSockCallback(char *buf, int bytes);
+  
+  //! Called whenever data is received on worldDialogSocket
+  static int worldDialogSockCallback(char *buf, int bytes);
+  
+  static void dialogCallback(char* buf, int bytes, std::string& incomplete,
+			     SketchSpace &SkS, ShapeSpace &ShS);
+};
+  
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ViewerConnection.cc ./DualCoding/ViewerConnection.cc
--- ../Tekkotsu_2.4.1/DualCoding/ViewerConnection.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ViewerConnection.cc	2006-02-05 19:11:03.000000000 -0500
@@ -0,0 +1,24 @@
+//-*-c++-*-
+
+#include <iostream>
+#include <string>
+#include <math.h>  // for min
+
+using namespace std;
+
+#include "ViewerConnection.h"
+
+namespace DualCoding {
+
+void ViewerConnection::writeBigString(std::string const &msg) {
+  size_t const len = msg.size();
+  for (size_t startpos = 0; startpos<len; ) {
+    size_t const chunksize = min(len-startpos, (size_t)(DIALOG_BUFFER_SIZE-1));
+    string const chunk = msg.substr(startpos,chunksize);
+    dialogSock->printf(chunk.c_str());
+    startpos += chunksize;
+  }
+}
+
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/ViewerConnection.h ./DualCoding/ViewerConnection.h
--- ../Tekkotsu_2.4.1/DualCoding/ViewerConnection.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/ViewerConnection.h	2006-04-14 00:49:24.000000000 -0400
@@ -0,0 +1,56 @@
+//-*-c++-*-
+#ifndef INCLUDED_ViewerConnection_h_
+#define INCLUDED_ViewerConnection_h_
+
+#include <string>
+
+#include "Shared/ProjectInterface.h"
+#include "Wireless/Wireless.h"
+
+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 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 WORLD_WIDTH=225;
+static const unsigned int WORLD_HEIGHT=225;
+
+static const unsigned short CAM_DIALOG_PORT   = 5800;
+static const unsigned short CAM_RLE_PORT      = 5801;
+static const unsigned short LOCAL_DIALOG_PORT = 5802;
+static const unsigned short LOCAL_RLE_PORT    = 5803;
+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:
+  Socket *dialogSock, *rleSock;
+  int dialogPort, rlePort;
+
+ public:
+  ViewerConnection(void) : dialogSock(NULL), rleSock(NULL), dialogPort(0), rlePort(0) {}
+
+  Socket *getDialogSocket() const { return dialogSock; }
+  Socket *getRleSocket() const { return rleSock; }
+
+  void setDialogSocket(Socket* sock, int const port) { dialogSock = sock; dialogPort = port; }
+  void setRleSocket(Socket* sock, int const port) { rleSock = sock; rlePort = port; }
+
+  void writeBigString(std::string const &msg);
+
+ private:
+  ViewerConnection(const ViewerConnection&); //!< never call this
+  ViewerConnection& operator=(const ViewerConnection&); //!< never call this
+
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/VisualRoutinesBehavior.cc ./DualCoding/VisualRoutinesBehavior.cc
--- ../Tekkotsu_2.4.1/DualCoding/VisualRoutinesBehavior.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/VisualRoutinesBehavior.cc	2006-05-08 18:27:38.000000000 -0400
@@ -0,0 +1,17 @@
+#include "VisualRoutinesBehavior.h"
+
+namespace DualCoding {
+
+//----------------------------------------------------------------
+
+void VisualRoutinesBehavior::DoStart() {
+  BehaviorBase::DoStart();
+  startCrew();
+}
+
+void VisualRoutinesBehavior::DoStop() {
+  stopCrew();
+  BehaviorBase::DoStop();
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/VisualRoutinesBehavior.h ./DualCoding/VisualRoutinesBehavior.h
--- ../Tekkotsu_2.4.1/DualCoding/VisualRoutinesBehavior.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/VisualRoutinesBehavior.h	2006-05-08 18:27:38.000000000 -0400
@@ -0,0 +1,39 @@
+//-*-c++-*-
+#ifndef INCLUDED_VisualRoutinesBehavior_h_
+#define INCLUDED_VisualRoutinesBehavior_h_
+
+#include "Behaviors/BehaviorBase.h"
+#include "DualCoding/VRmixin.h"
+
+namespace DualCoding {
+
+/*! @brief Base class from which visual-routines based behaviors
+ *  (which all share a common SketchSpace) inherit */
+class VisualRoutinesBehavior : public BehaviorBase, public VRmixin {
+public:
+  virtual void DoStart();
+  virtual void DoStop();
+	
+protected:
+  //! constructor, @a name is used as both instance name and class name
+  explicit VisualRoutinesBehavior(const std::string &name)
+    : BehaviorBase(name), VRmixin()
+  {}
+	
+  //! constructor, allows different initial values for class name and instance name
+  VisualRoutinesBehavior(const std::string& classname, const std::string& instancename)
+    : BehaviorBase(classname,instancename), VRmixin()
+  {}
+	
+  //! destructor, does nothing
+  virtual ~VisualRoutinesBehavior(void) {}
+	
+private:
+  // dummy functions to satisfy the compiler
+  VisualRoutinesBehavior (const VisualRoutinesBehavior&);  //!< never call this
+  VisualRoutinesBehavior& operator=(const VisualRoutinesBehavior&); //!< never call this
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/VisualRoutinesStateNode.cc ./DualCoding/VisualRoutinesStateNode.cc
--- ../Tekkotsu_2.4.1/DualCoding/VisualRoutinesStateNode.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/VisualRoutinesStateNode.cc	2006-02-21 00:27:13.000000000 -0500
@@ -0,0 +1,17 @@
+#include "VisualRoutinesStateNode.h"
+
+namespace DualCoding {
+
+//----------------------------------------------------------------
+
+void VisualRoutinesStateNode::DoStart() {
+	StateNode::DoStart();
+	startCrew();
+}
+
+void VisualRoutinesStateNode::DoStop() {
+	stopCrew();
+	StateNode::DoStop();
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/VisualRoutinesStateNode.h ./DualCoding/VisualRoutinesStateNode.h
--- ../Tekkotsu_2.4.1/DualCoding/VisualRoutinesStateNode.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/VisualRoutinesStateNode.h	2006-02-21 00:27:13.000000000 -0500
@@ -0,0 +1,39 @@
+//-*-c++-*-
+#ifndef INCLUDED_VisualRoutinesStateNode_h_
+#define INCLUDED_VisualRoutinesStateNode_h_
+
+#include "Behaviors/StateNode.h"
+#include "DualCoding/VRmixin.h"
+
+namespace DualCoding {
+
+/*! @brief Base class from which visual-routines based state nodes
+ *  (which all share a common SketchSpace) inherit */
+class VisualRoutinesStateNode : public StateNode, public VRmixin {
+public:
+	virtual void DoStart();
+	virtual void DoStop();
+	
+protected:
+	//! constructor, @a name is used as both instance name and class name
+	explicit VisualRoutinesStateNode(const std::string &name)
+		: StateNode(name), VRmixin()
+	{}
+	
+	//! constructor, allows different initial values for class name and instance name
+	VisualRoutinesStateNode(const std::string& classname, const std::string& instancename)
+		: StateNode(classname,instancename), VRmixin()
+	{}
+	
+	//! destructor, does nothing
+	virtual ~VisualRoutinesStateNode(void) {}
+	
+private:
+	// dummy functions to satisfy the compiler
+	VisualRoutinesStateNode (const VisualRoutinesStateNode&);  //!< never call this
+	VisualRoutinesStateNode& operator=(const VisualRoutinesStateNode&); //!< never call this
+};
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/lookout-issues.txt ./DualCoding/lookout-issues.txt
--- ../Tekkotsu_2.4.1/DualCoding/lookout-issues.txt	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/lookout-issues.txt	2006-04-12 12:56:48.000000000 -0400
@@ -0,0 +1,40 @@
+
+Lookout design issues:
+
+Request format:
+
+- A request should include a scheduling policy:
+   * "time critical within n msec" (for obstacle avoidance; wall following)
+   * "as time permits" (for object search)
+
+Since the Pilot controls body motion, Lookout needs to be sensitive to
+what Pilot is doing.
+
+================================================================
+
+TRACK
+Current: look for largest region of specified color; project to ground; point head there
+
+Problems:
+  - do this in camera space so don't assume region is on ground (Ethan fixed this?)
+  - what if we want to track a region other than the biggest one?
+  - jitter when moving makes it hard to stay focused on an object, but Kei has done it
+  - need a policy to reacquire target when lost
+  - should track last position and area of target so we can glance away and come back
+
+================================================================
+
+FIND
+
+Current: continuous scan; look for region of specified color
+
+Problems:
+  - what if you want to find blobs of two different colors?  don't want two scans
+  - scan runs to completion; then has to come back to take snaps; better to snap as we go
+  - we might prefer to use a list of gaze points so we can do shape extraction
+  - offer predefined scan patterns, e.g., middle-foreground for lab10
+  - need policy on what can move (head, body rotation, or full roaming search)
+  - scan pattern should be more aggressive than a simple near-to-far
+
+================================================================
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/susan.cc ./DualCoding/susan.cc
--- ../Tekkotsu_2.4.1/DualCoding/susan.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/susan.cc	2006-02-07 18:00:21.000000000 -0500
@@ -0,0 +1,896 @@
+//-*-c++-*-
+
+/* Functions taken from the SUSAN edge detector package by Dr. Stephen Smith.
+   The original file can be found at susan2l.c
+   Ported to Tekkotsu/C++ by Matt Carson and Dave Touretzky, and
+   distributed here by the kind permission of Dr. Smith */
+
+#include <string.h>
+#include <stdlib.h>
+#include <math.h>
+
+#include "susan.h"
+
+/* {{{ Copyright etc. */
+
+/**********************************************************************\
+
+  SUSAN Version 2l by Stephen Smith
+  Oxford Centre for Functional Magnetic Resonance Imaging of the Brain,
+  Department of Clinical Neurology, Oxford University, Oxford, UK
+  (Previously in Computer Vision and Image Processing Group - now
+  Computer Vision and Electro Optics Group - DERA Chertsey, UK)
+  Email:    steve@fmrib.ox.ac.uk
+  WWW:      http://www.fmrib.ox.ac.uk/~steve
+
+  (C) Crown Copyright (1995-1999), Defence Evaluation and Research Agency,
+  Farnborough, Hampshire, GU14 6TD, UK
+  DERA WWW site:
+  http://www.dera.gov.uk/
+  DERA Computer Vision and Electro Optics Group WWW site:
+  http://www.dera.gov.uk/imageprocessing/dera/group_home.html
+  DERA Computer Vision and Electro Optics Group point of contact:
+  Dr. John Savage, jtsavage@dera.gov.uk, +44 1344 633203
+
+  A UK patent has been granted: "Method for digitally processing
+  images to determine the position of edges and/or corners therein for
+  guidance of unmanned vehicle", UK Patent 2272285. Proprietor:
+  Secretary of State for Defence, UK. 15 January 1997
+
+  This code is issued for research purposes only and remains the
+  property of the UK Secretary of State for Defence. This code must
+  not be passed on without this header information being kept
+  intact. This code must not be sold.
+
+\**********************************************************************/
+
+/* }}} */
+/* {{{ Readme First */
+
+/**********************************************************************\
+
+  SUSAN Version 2l
+  SUSAN = Smallest Univalue Segment Assimilating Nucleus
+
+  Email:    steve@fmrib.ox.ac.uk
+  WWW:      http://www.fmrib.ox.ac.uk/~steve
+
+  Related paper:
+  @article{Smith97,
+        author = "Smith, S.M. and Brady, J.M.",
+        title = "{SUSAN} - A New Approach to Low Level Image Processing",
+        journal = "Int. Journal of Computer Vision",
+        pages = "45--78",
+        volume = "23",
+        number = "1",
+        month = "May",
+        year = 1997}
+
+  To be registered for automatic (bug) updates of SUSAN, send an email.
+
+  Compile with:
+  gcc -O4 -o susan susan2l.c -lm
+
+  See following section for different machine information. Please
+  report any bugs (and fixes). There are a few optional changes that
+  can be made in the "defines" section which follows shortly.
+
+  Usage: type "susan" to get usage. Only PGM format files can be input
+  and output. Utilities such as the netpbm package and XV can be used
+  to convert to and from other formats. Any size of image can be
+  processed.
+
+  This code is written using an emacs folding mode, making moving
+  around the different sections very easy. This is why there are
+  various marks within comments and why comments are indented.
+
+
+  SUSAN QUICK:
+
+  This version of the SUSAN corner finder does not do all the
+  false-corner suppression and thus is faster and produced some false
+  positives, particularly on strong edges. However, because there are
+  less stages involving thresholds etc., the corners that are
+  correctly reported are usually more stable than those reported with
+  the full algorithm. Thus I recommend at least TRYING this algorithm
+  for applications where stability is important, e.g., tracking.
+
+  THRESHOLDS:
+
+  There are two thresholds which can be set at run-time. These are the
+  brightness threshold (t) and the distance threshold (d).
+
+  SPATIAL CONTROL: d
+
+  In SUSAN smoothing d controls the size of the Gaussian mask; its
+  default is 4.0. Increasing d gives more smoothing. In edge finding,
+  a fixed flat mask is used, either 37 pixels arranged in a "circle"
+  (default), or a 3 by 3 mask which gives finer detail. In corner
+  finding, only the larger 37 pixel mask is used; d is not
+  variable. In smoothing, the flat 3 by 3 mask can be used instead of
+  a larger Gaussian mask; this gives low smoothing and fast operation.
+
+  BRIGHTNESS CONTROL: t
+
+  In all three algorithms, t can be varied (default=20); this is the
+  main threshold to be varied. It determines the maximum difference in
+  greylevels between two pixels which allows them to be considered
+  part of the same "region" in the image. Thus it can be reduced to
+  give more edges or corners, i.e. to be more sensitive, and vice
+  versa. In smoothing, reducing t gives less smoothing, and vice
+  versa. Set t=10 for the test image available from the SUSAN web
+  page.
+
+  ITERATIONS:
+
+  With SUSAN smoothing, more smoothing can also be obtained by
+  iterating the algorithm several times. This has a different effect
+  from varying d or t.
+
+  FIXED MASKS:
+
+  37 pixel mask:    ooo       3 by 3 mask:  ooo
+                   ooooo                    ooo
+                  ooooooo                   ooo
+                  ooooooo
+                  ooooooo
+                   ooooo
+                    ooo
+
+  CORNER ATTRIBUTES dx, dy and I
+  (Only read this if you are interested in the C implementation or in
+  using corner attributes, e.g., for corner matching)
+
+  Corners reported in the corner list have attributes associated with
+  them as well as positions. This is useful, for example, when
+  attempting to match corners from one image to another, as these
+  attributes can often be fairly unchanged between images. The
+  attributes are dx, dy and I. I is the value of image brightness at
+  the position of the corner. In the case of susan_corners_quick, dx
+  and dy are the first order derivatives (differentials) of the image
+  brightness in the x and y directions respectively, at the position
+  of the corner. In the case of normal susan corner finding, dx and dy
+  are scaled versions of the position of the centre of gravity of the
+  USAN with respect to the centre pixel (nucleus).
+
+  BRIGHTNESS FUNCTION LUT IMPLEMENTATION:
+  (Only read this if you are interested in the C implementation)
+
+  The SUSAN brightness function is implemented as a LUT
+  (Look-Up-Table) for speed. The resulting pointer-based code is a
+  little hard to follow, so here is a brief explanation. In
+  setup_brightness_lut() the LUT is setup. This mallocs enough space
+  for *bp and then repositions the pointer to the centre of the
+  malloced space. The SUSAN function e^-(x^6) or e^-(x^2) is
+  calculated and converted to a uchar in the range 0-100, for all
+  possible image brightness differences (including negative
+  ones). Thus bp[23] is the output for a brightness difference of 23
+  greylevels. In the SUSAN algorithms this LUT is used as follows:
+
+  p=in + (i-3)*x_size + j - 1;
+  p points to the first image pixel in the circular mask surrounding
+  point (x,y).
+
+  cp=bp + in[i*x_size+j];
+  cp points to a position in the LUT corresponding to the brightness
+  of the centre pixel (x,y).
+
+  now for every pixel within the mask surrounding (x,y),
+  n+=*(cp-*p++);
+  the brightness difference function is found by moving the cp pointer
+  down by an amount equal to the value of the pixel pointed to by p,
+  thus subtracting the two brightness values and performing the
+  exponential function. This value is added to n, the running USAN
+  area.
+
+  in SUSAN smoothing, the variable height mask is implemented by
+  multiplying the above by the moving mask pointer, reset for each new
+  centre pixel.
+  tmp = *dpt++ * *(cp-brightness);
+
+\**********************************************************************/
+
+/* }}} */
+/* {{{ Machine Information */
+
+/**********************************************************************\
+
+  Success has been reported with the following:
+
+  MACHINE  OS         COMPILER
+
+  Sun      4.1.4      bundled C, gcc
+
+  Next
+
+  SGI      IRIX       SGI cc
+
+  DEC      Unix V3.2+ 
+
+  IBM RISC AIX        gcc
+
+  PC                  Borland 5.0
+
+  PC       Linux      gcc-2.6.3
+
+  PC       Win32      Visual C++ 4.0 (Console Application)
+
+  PC       Win95      Visual C++ 5.0 (Console Application)
+                      Thanks to Niu Yongsheng <niuysbit@163.net>:
+                      Use the FOPENB option below
+
+  PC       DOS        djgpp gnu C
+                      Thanks to Mark Pettovello <mpettove@umdsun2.umd.umich.edu>:
+                      Use the FOPENB option below
+
+  HP       HP-UX      bundled cc
+                      Thanks to Brian Dixon <briand@hpcvsgen.cv.hp.com>:
+                      in ksh:
+                      export CCOPTS="-Aa -D_HPUX_SOURCE | -lM"
+                      cc -O3 -o susan susan2l.c
+
+\**********************************************************************/
+
+/* }}} */
+/* {{{ History */
+
+/**********************************************************************\
+
+  SUSAN Version 2l, 12/2/99
+  Changed GNUDOS option to FOPENB.
+  (Thanks to Niu Yongsheng <niuysbit@163.net>.)
+  Took out redundant "sq=sq/2;".
+
+  SUSAN Version 2k, 19/8/98:
+  In corner finding:
+  Changed if(yy<sq) {...} else if(xx<sq) {...} to
+          if(yy<xx) {...} else {...}
+  (Thanks to adq@cim.mcgill.edu - Alain Domercq.)
+
+  SUSAN Version 2j, 22/10/97:
+  Fixed (mask_size>x_size) etc. tests in smoothing.
+  Added a couple of free() calls for cgx and cgy.
+  (Thanks to geoffb@ucs.ed.ac.uk - Geoff Browitt.)
+
+  SUSAN Version 2i, 21/7/97:
+  Added information about corner attributes.
+
+  SUSAN Version 2h, 16/12/96:
+  Added principle (initial enhancement) option.
+
+  SUSAN Version 2g, 2/7/96:
+  Minor superficial changes to code.
+
+  SUSAN Version 2f, 16/1/96:
+  Added GNUDOS option (now called FOPENB; see options below).
+
+  SUSAN Version 2e, 9/1/96:
+  Added -b option.
+  Fixed 1 pixel horizontal offset error for drawing edges.
+
+  SUSAN Version 2d, 27/11/95:
+  Fixed loading of certain PGM files in get_image (again!)
+
+  SUSAN Version 2c, 22/11/95:
+  Fixed loading of certain PGM files in get_image.
+  (Thanks to qu@San-Jose.ate.slb.com - Gongyuan Qu.)
+
+  SUSAN Version 2b, 9/11/95:
+  removed "z==" error in edges routines.
+
+  SUSAN Version 2a, 6/11/95:
+  Removed a few unnecessary variable declarations.
+  Added different machine information.
+  Changed "header" in get_image to char.
+
+  SUSAN Version 2, 1/11/95: first combined version able to take any
+  image sizes.
+
+  SUSAN "Versions 1", circa 1992: the various SUSAN algorithms were
+  developed during my doctorate within different programs and for
+  fixed image sizes. The algorithms themselves are virtually unaltered
+  between "versions 1" and the combined program, version 2.
+
+\**********************************************************************/
+
+namespace DualCoding {
+
+/* }}} */
+/* {{{ setup_brightness_lut(bp,thresh,form) */
+
+/*void setup_brightness_lut(bp,thresh,form)
+  uchar **bp;
+  int   thresh, form;*/
+void setup_brightness_lut(uchar **bp, int thresh, int form)
+{
+int   k;
+float temp;
+
+  *bp=(unsigned char *)malloc(516);
+  *bp=*bp+258;
+
+  for(k=-256;k<257;k++)
+  {
+    temp=((float)k)/((float)thresh);
+    temp=temp*temp;
+    if (form==6)
+      temp=temp*temp*temp;
+    temp=100.0*exp(-temp);
+    *(*bp+k)= (uchar)temp;
+  }
+}
+
+
+/* }}} */
+/* {{{ susan principle */
+
+/* {{{ susan_principle(in,r,bp,max_no,x_size,y_size) */
+
+/*void susan_principle(in,r,bp,max_no,x_size,y_size)
+  uchar *in, *bp;
+  int   *r, max_no, x_size, y_size;*/
+void susan_principle(uchar *in, int *r, uchar *bp, int max_no,
+		     int x_size, int y_size)
+{
+int   i, j, n;
+uchar *p,*cp;
+
+  memset (r,0,x_size * y_size * sizeof(int));
+
+
+  for (i=3;i<y_size-3;i++)
+    for (j=3;j<x_size-3;j++)
+    {
+      n=100;
+      p=in + (i-3)*x_size + j - 1;
+      cp=bp + in[i*x_size+j];
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=x_size-3; 
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=x_size-5;
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=x_size-6;
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=2;
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=x_size-6;
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=x_size-5;
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=x_size-3;
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+
+      if (n<=max_no)
+        r[i*x_size+j] = max_no - n;
+    }
+}
+
+/* }}} */
+/* {{{ susan_thin(r,mid,x_size,y_size) */
+
+/* only one pass is needed as i,j are decremented if necessary to go
+   back and do bits again */
+
+/*susan_thin(r,mid,x_size,y_size)
+  uchar *mid;
+  int   *r, x_size, y_size;*/
+void susan_thin(int *r, uchar *mid, int x_size, int y_size)
+{
+  int   l[9], centre, //nlinks, npieces,
+      b01, b12, b21, b10,
+      p1, p2, p3, p4,
+      b00, b02, b20, b22,
+      m, n, a=0, b=0, x, y, i, j;
+uchar *mp;
+
+  for (i=4;i<y_size-4;i++)
+    for (j=4;j<x_size-4;j++)
+      if (mid[i*x_size+j]<8)
+      {
+        centre = r[i*x_size+j];
+        /* {{{ count number of neighbours */
+
+        mp=mid + (i-1)*x_size + j-1;
+
+        n = (*mp<8) +
+            (*(mp+1)<8) +
+            (*(mp+2)<8) +
+            (*(mp+x_size)<8) +
+            (*(mp+x_size+2)<8) +
+            (*(mp+x_size+x_size)<8) +
+            (*(mp+x_size+x_size+1)<8) +
+            (*(mp+x_size+x_size+2)<8);
+
+/* }}} */
+        /* {{{ n==0 no neighbours - remove point */
+
+        if (n==0)
+          mid[i*x_size+j]=100;
+
+/* }}} */
+        /* {{{ n==1 - extend line if I can */
+
+        /* extension is only allowed a few times - the value of mid is used to control this */
+
+        if ( (n==1) && (mid[i*x_size+j]<6) )
+        {
+          /* find maximum neighbour weighted in direction opposite the
+             neighbour already present. e.g.
+             have: O O O  weight r by 0 2 3
+                   X X O              0 0 4
+                   O O O              0 2 3     */
+
+          l[0]=r[(i-1)*x_size+j-1]; l[1]=r[(i-1)*x_size+j]; l[2]=r[(i-1)*x_size+j+1];
+          l[3]=r[(i  )*x_size+j-1]; l[4]=0;                 l[5]=r[(i  )*x_size+j+1];
+          l[6]=r[(i+1)*x_size+j-1]; l[7]=r[(i+1)*x_size+j]; l[8]=r[(i+1)*x_size+j+1];
+
+          if (mid[(i-1)*x_size+j-1]<8)        { l[0]=0; l[1]=0; l[3]=0; l[2]*=2; 
+                                                l[6]*=2; l[5]*=3; l[7]*=3; l[8]*=4; }
+          else { if (mid[(i-1)*x_size+j]<8)   { l[1]=0; l[0]=0; l[2]=0; l[3]*=2; 
+                                                l[5]*=2; l[6]*=3; l[8]*=3; l[7]*=4; }
+          else { if (mid[(i-1)*x_size+j+1]<8) { l[2]=0; l[1]=0; l[5]=0; l[0]*=2; 
+                                                l[8]*=2; l[3]*=3; l[7]*=3; l[6]*=4; }
+          else { if (mid[(i)*x_size+j-1]<8)   { l[3]=0; l[0]=0; l[6]=0; l[1]*=2; 
+                                                l[7]*=2; l[2]*=3; l[8]*=3; l[5]*=4; }
+          else { if (mid[(i)*x_size+j+1]<8)   { l[5]=0; l[2]=0; l[8]=0; l[1]*=2; 
+                                                l[7]*=2; l[0]*=3; l[6]*=3; l[3]*=4; }
+          else { if (mid[(i+1)*x_size+j-1]<8) { l[6]=0; l[3]=0; l[7]=0; l[0]*=2; 
+                                                l[8]*=2; l[1]*=3; l[5]*=3; l[2]*=4; }
+          else { if (mid[(i+1)*x_size+j]<8)   { l[7]=0; l[6]=0; l[8]=0; l[3]*=2; 
+                                                l[5]*=2; l[0]*=3; l[2]*=3; l[1]*=4; }
+          else { if (mid[(i+1)*x_size+j+1]<8) { l[8]=0; l[5]=0; l[7]=0; l[6]*=2; 
+                                                l[2]*=2; l[1]*=3; l[3]*=3; l[0]*=4; } }}}}}}}
+
+          m=0;     /* find the highest point */
+          for(y=0; y<3; y++)
+            for(x=0; x<3; x++)
+              if (l[y+y+y+x]>m) { m=l[y+y+y+x]; a=y; b=x; }
+
+          if (m>0)
+          {
+            if (mid[i*x_size+j]<4)
+              mid[(i+a-1)*x_size+j+b-1] = 4;
+            else
+              mid[(i+a-1)*x_size+j+b-1] = mid[i*x_size+j]+1;
+            if ( (a+a+b) < 3 ) /* need to jump back in image */
+	    {
+              i+=a-1;
+              j+=b-2;
+              if (i<4) i=4;
+              if (j<4) j=4;
+	    }
+	  }
+        }
+
+/* }}} */
+        /* {{{ n==2 */
+
+        if (n==2)
+	{
+          /* put in a bit here to straighten edges */
+          b00 = mid[(i-1)*x_size+j-1]<8; /* corners of 3x3 */
+          b02 = mid[(i-1)*x_size+j+1]<8;
+	  b20 = mid[(i+1)*x_size+j-1]<8;
+          b22 = mid[(i+1)*x_size+j+1]<8;
+          if ( ((b00+b02+b20+b22)==2) && ((b00|b22)&(b02|b20)))
+	  {  /* case: move a point back into line.
+                e.g. X O X  CAN  become X X X
+                     O X O              O O O
+                     O O O              O O O    */
+            if (b00) 
+	    {
+              if (b02) { x=0; y=-1; }
+              else     { x=-1; y=0; }
+	    }
+            else
+	    {
+              if (b02) { x=1; y=0; }
+              else     { x=0; y=1; }
+	    }
+            if (((float)r[(i+y)*x_size+j+x]/(float)centre) > 0.7)
+	    {
+              if ( ( (x==0) && (mid[(i+(2*y))*x_size+j]>7) && (mid[(i+(2*y))*x_size+j-1]>7) && (mid[(i+(2*y))*x_size+j+1]>7) ) ||
+                   ( (y==0) && (mid[(i)*x_size+j+(2*x)]>7) && (mid[(i+1)*x_size+j+(2*x)]>7) && (mid[(i-1)*x_size+j+(2*x)]>7) ) )
+	      {
+                mid[(i)*x_size+j]=100;
+                mid[(i+y)*x_size+j+x]=3;  /* no jumping needed */
+	      }
+	    }
+	  }
+          else
+          {
+            b01 = mid[(i-1)*x_size+j  ]<8;
+            b12 = mid[(i  )*x_size+j+1]<8;
+            b21 = mid[(i+1)*x_size+j  ]<8;
+            b10 = mid[(i  )*x_size+j-1]<8;
+            /* {{{ right angle ends - not currently used */
+
+#ifdef IGNORETHIS
+            if ( (b00&b01)|(b00&b10)|(b02&b01)|(b02&b12)|(b20&b10)|(b20&b21)|(b22&b21)|(b22&b12) )
+	    { /* case; right angle ends. clean up.
+                 e.g.; X X O  CAN  become X X O
+                       O X O              O O O
+                       O O O              O O O        */
+              if ( ((b01)&(mid[(i-2)*x_size+j-1]>7)&(mid[(i-2)*x_size+j]>7)&(mid[(i-2)*x_size+j+1]>7)&
+                                    ((b00&((2*r[(i-1)*x_size+j+1])>centre))|(b02&((2*r[(i-1)*x_size+j-1])>centre)))) |
+                   ((b10)&(mid[(i-1)*x_size+j-2]>7)&(mid[(i)*x_size+j-2]>7)&(mid[(i+1)*x_size+j-2]>7)&
+                                    ((b00&((2*r[(i+1)*x_size+j-1])>centre))|(b20&((2*r[(i-1)*x_size+j-1])>centre)))) |
+                   ((b12)&(mid[(i-1)*x_size+j+2]>7)&(mid[(i)*x_size+j+2]>7)&(mid[(i+1)*x_size+j+2]>7)&
+                                    ((b02&((2*r[(i+1)*x_size+j+1])>centre))|(b22&((2*r[(i-1)*x_size+j+1])>centre)))) |
+                   ((b21)&(mid[(i+2)*x_size+j-1]>7)&(mid[(i+2)*x_size+j]>7)&(mid[(i+2)*x_size+j+1]>7)&
+                                    ((b20&((2*r[(i+1)*x_size+j+1])>centre))|(b22&((2*r[(i+1)*x_size+j-1])>centre)))) )
+	      {
+                mid[(i)*x_size+j]=100;
+                if (b10&b20) j-=2;
+                if (b00|b01|b02) { i--; j-=2; }
+  	      }
+	    }
+#endif
+
+/* }}} */
+            if ( ((b01+b12+b21+b10)==2) && ((b10|b12)&(b01|b21)) &&
+                 ((b01&((mid[(i-2)*x_size+j-1]<8)|(mid[(i-2)*x_size+j+1]<8)))|(b10&((mid[(i-1)*x_size+j-2]<8)|(mid[(i+1)*x_size+j-2]<8)))|
+                (b12&((mid[(i-1)*x_size+j+2]<8)|(mid[(i+1)*x_size+j+2]<8)))|(b21&((mid[(i+2)*x_size+j-1]<8)|(mid[(i+2)*x_size+j+1]<8)))) )
+	    { /* case; clears odd right angles.
+                 e.g.; O O O  becomes O O O
+                       X X O          X O O
+                       O X O          O X O     */
+              mid[(i)*x_size+j]=100;
+              i--;               /* jump back */
+              j-=2;
+              if (i<4) i=4;
+              if (j<4) j=4;
+	    }
+	  }
+	}
+
+/* }}} */
+        /* {{{ n>2 the thinning is done here without breaking connectivity */
+
+        if (n>2)
+        {
+          b01 = mid[(i-1)*x_size+j  ]<8;
+          b12 = mid[(i  )*x_size+j+1]<8;
+          b21 = mid[(i+1)*x_size+j  ]<8;
+          b10 = mid[(i  )*x_size+j-1]<8;
+          if((b01+b12+b21+b10)>1)
+          {
+            b00 = mid[(i-1)*x_size+j-1]<8;
+            b02 = mid[(i-1)*x_size+j+1]<8;
+	    b20 = mid[(i+1)*x_size+j-1]<8;
+	    b22 = mid[(i+1)*x_size+j+1]<8;
+            p1 = b00 | b01;
+            p2 = b02 | b12;
+            p3 = b22 | b21;
+            p4 = b20 | b10;
+
+            if( ((p1 + p2 + p3 + p4) - ((b01 & p2)+(b12 & p3)+(b21 & p4)+(b10 & p1))) < 2)
+            {
+              mid[(i)*x_size+j]=100;
+              i--;
+              j-=2;
+              if (i<4) i=4;
+              if (j<4) j=4;
+            }
+          }
+        }
+/* }}} */
+      }
+}
+
+
+
+/* }}} */
+/* {{{ susan_edges(in,r,sf,max_no,out) */
+
+/*susan_edges(in,r,mid,bp,max_no,x_size,y_size)
+  uchar *in, *bp, *mid;
+  int   *r, max_no, x_size, y_size;*/
+void susan_edges_internal(uchar *in, int *r, uchar *mid, uchar *bp, 
+	    int max_no, int x_size, int y_size)
+{
+float z;
+int   do_symmetry, i, j, m, n, a, b, x, y, w;
+uchar c,*p,*cp;
+
+  memset (r,0,x_size * y_size * sizeof(int));
+
+  for (i=3;i<y_size-3;i++)
+    for (j=3;j<x_size-3;j++)
+    {
+      n=100;
+      p=in + (i-3)*x_size + j - 1;
+      cp=bp + in[i*x_size+j];
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=x_size-3; 
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=x_size-5;
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=x_size-6;
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=2;
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=x_size-6;
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=x_size-5;
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+      p+=x_size-3;
+
+      n+=*(cp-*p++);
+      n+=*(cp-*p++);
+      n+=*(cp-*p);
+
+      if (n<=max_no)
+        r[i*x_size+j] = max_no - n;
+    }
+
+  for (i=4;i<y_size-4;i++)
+    for (j=4;j<x_size-4;j++)
+    {
+      if (r[i*x_size+j]>0)
+      {
+        m=r[i*x_size+j];
+        n=max_no - m;
+        cp=bp + in[i*x_size+j];
+
+        if (n>600)
+        {
+          p=in + (i-3)*x_size + j - 1;
+          x=0;y=0;
+
+          c=*(cp-*p++);x-=c;y-=3*c;
+          c=*(cp-*p++);y-=3*c;
+          c=*(cp-*p);x+=c;y-=3*c;
+          p+=x_size-3; 
+    
+          c=*(cp-*p++);x-=2*c;y-=2*c;
+          c=*(cp-*p++);x-=c;y-=2*c;
+          c=*(cp-*p++);y-=2*c;
+          c=*(cp-*p++);x+=c;y-=2*c;
+          c=*(cp-*p);x+=2*c;y-=2*c;
+          p+=x_size-5;
+    
+          c=*(cp-*p++);x-=3*c;y-=c;
+          c=*(cp-*p++);x-=2*c;y-=c;
+          c=*(cp-*p++);x-=c;y-=c;
+          c=*(cp-*p++);y-=c;
+          c=*(cp-*p++);x+=c;y-=c;
+          c=*(cp-*p++);x+=2*c;y-=c;
+          c=*(cp-*p);x+=3*c;y-=c;
+          p+=x_size-6;
+
+          c=*(cp-*p++);x-=3*c;
+          c=*(cp-*p++);x-=2*c;
+          c=*(cp-*p);x-=c;
+          p+=2;
+          c=*(cp-*p++);x+=c;
+          c=*(cp-*p++);x+=2*c;
+          c=*(cp-*p);x+=3*c;
+          p+=x_size-6;
+    
+          c=*(cp-*p++);x-=3*c;y+=c;
+          c=*(cp-*p++);x-=2*c;y+=c;
+          c=*(cp-*p++);x-=c;y+=c;
+          c=*(cp-*p++);y+=c;
+          c=*(cp-*p++);x+=c;y+=c;
+          c=*(cp-*p++);x+=2*c;y+=c;
+          c=*(cp-*p);x+=3*c;y+=c;
+          p+=x_size-5;
+
+          c=*(cp-*p++);x-=2*c;y+=2*c;
+          c=*(cp-*p++);x-=c;y+=2*c;
+          c=*(cp-*p++);y+=2*c;
+          c=*(cp-*p++);x+=c;y+=2*c;
+          c=*(cp-*p);x+=2*c;y+=2*c;
+          p+=x_size-3;
+
+          c=*(cp-*p++);x-=c;y+=3*c;
+          c=*(cp-*p++);y+=3*c;
+          c=*(cp-*p);x+=c;y+=3*c;
+
+          z = sqrt((float)((x*x) + (y*y)));
+          if (z > (0.9*(float)n)) /* 0.5 */
+	  {
+            do_symmetry=0;
+            if (x==0)
+              z=1000000.0;
+            else
+              z=((float)y) / ((float)x);
+            if (z < 0) { z=-z; w=-1; }
+            else w=1;
+            if (z < 0.5) { /* vert_edge */ a=0; b=1; }
+            else { if (z > 2.0) { /* hor_edge */ a=1; b=0; }
+            else { /* diag_edge */ if (w>0) { a=1; b=1; }
+                                   else { a=-1; b=1; }}}
+            if ( (m > r[(i+a)*x_size+j+b]) && (m >= r[(i-a)*x_size+j-b]) &&
+                 (m > r[(i+(2*a))*x_size+j+(2*b)]) && (m >= r[(i-(2*a))*x_size+j-(2*b)]) )
+              mid[i*x_size+j] = 1;
+          }
+          else
+            do_symmetry=1;
+        }
+        else 
+          do_symmetry=1;
+
+        if (do_symmetry==1)
+	{ 
+          p=in + (i-3)*x_size + j - 1;
+          x=0; y=0; w=0;
+
+          /*   |      \
+               y  -x-  w
+               |        \   */
+
+          c=*(cp-*p++);x+=c;y+=9*c;w+=3*c;
+          c=*(cp-*p++);y+=9*c;
+          c=*(cp-*p);x+=c;y+=9*c;w-=3*c;
+          p+=x_size-3; 
+  
+          c=*(cp-*p++);x+=4*c;y+=4*c;w+=4*c;
+          c=*(cp-*p++);x+=c;y+=4*c;w+=2*c;
+          c=*(cp-*p++);y+=4*c;
+          c=*(cp-*p++);x+=c;y+=4*c;w-=2*c;
+          c=*(cp-*p);x+=4*c;y+=4*c;w-=4*c;
+          p+=x_size-5;
+    
+          c=*(cp-*p++);x+=9*c;y+=c;w+=3*c;
+          c=*(cp-*p++);x+=4*c;y+=c;w+=2*c;
+          c=*(cp-*p++);x+=c;y+=c;w+=c;
+          c=*(cp-*p++);y+=c;
+          c=*(cp-*p++);x+=c;y+=c;w-=c;
+          c=*(cp-*p++);x+=4*c;y+=c;w-=2*c;
+          c=*(cp-*p);x+=9*c;y+=c;w-=3*c;
+          p+=x_size-6;
+
+          c=*(cp-*p++);x+=9*c;
+          c=*(cp-*p++);x+=4*c;
+          c=*(cp-*p);x+=c;
+          p+=2;
+          c=*(cp-*p++);x+=c;
+          c=*(cp-*p++);x+=4*c;
+          c=*(cp-*p);x+=9*c;
+          p+=x_size-6;
+    
+          c=*(cp-*p++);x+=9*c;y+=c;w-=3*c;
+          c=*(cp-*p++);x+=4*c;y+=c;w-=2*c;
+          c=*(cp-*p++);x+=c;y+=c;w-=c;
+          c=*(cp-*p++);y+=c;
+          c=*(cp-*p++);x+=c;y+=c;w+=c;
+          c=*(cp-*p++);x+=4*c;y+=c;w+=2*c;
+          c=*(cp-*p);x+=9*c;y+=c;w+=3*c;
+          p+=x_size-5;
+ 
+          c=*(cp-*p++);x+=4*c;y+=4*c;w-=4*c;
+          c=*(cp-*p++);x+=c;y+=4*c;w-=2*c;
+          c=*(cp-*p++);y+=4*c;
+          c=*(cp-*p++);x+=c;y+=4*c;w+=2*c;
+          c=*(cp-*p);x+=4*c;y+=4*c;w+=4*c;
+          p+=x_size-3;
+
+          c=*(cp-*p++);x+=c;y+=9*c;w-=3*c;
+          c=*(cp-*p++);y+=9*c;
+          c=*(cp-*p);x+=c;y+=9*c;w+=3*c;
+
+          if (y==0)
+            z = 1000000.0;
+          else
+            z = ((float)x) / ((float)y);
+          if (z < 0.5) { /* vertical */ a=0; b=1; }
+          else { if (z > 2.0) { /* horizontal */ a=1; b=0; }
+          else { /* diagonal */ if (w>0) { a=-1; b=1; }
+                                else { a=1; b=1; }}}
+          if ( (m > r[(i+a)*x_size+j+b]) && (m >= r[(i-a)*x_size+j-b]) &&
+               (m > r[(i+(2*a))*x_size+j+(2*b)]) && (m >= r[(i-(2*a))*x_size+j-(2*b)]) )
+            mid[i*x_size+j] = 2;	
+        }
+      }
+    }
+}
+
+
+/* {{{ edge_draw(in,corner_list,drawing_mode) */
+
+/*edge_draw(in,mid,x_size,y_size,drawing_mode)
+  uchar *in, *mid;
+  int x_size, y_size, drawing_mode;*/
+void edge_draw(uchar *in, uchar *mid, int x_size, int y_size, int drawing_mode)
+{
+int   i;
+uchar *inp, *midp;
+
+  if (drawing_mode==0)
+  {
+    /* mark 3x3 white block around each edge point */
+    midp=mid;
+    for (i=0; i<x_size*y_size; i++)
+    {
+      if (*midp<8) 
+      {
+        inp = in + (midp - mid) - x_size - 1;
+        *inp++=255; *inp++=255; *inp=255; inp+=x_size-2;
+        *inp++=255; *inp++;     *inp=255; inp+=x_size-2;
+        *inp++=255; *inp++=255; *inp=255;
+      }
+      midp++;
+    }
+  }
+
+  /* now mark 1 black pixel at each edge point */
+  midp=mid;
+  for (i=0; i<x_size*y_size; i++)
+  {
+    if (*midp<8) 
+      //*(in + (midp - mid)) = 0;
+      *(in + (midp - mid)) = 1;
+    midp++;
+  }
+}
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/susan.h ./DualCoding/susan.h
--- ../Tekkotsu_2.4.1/DualCoding/susan.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/susan.h	2006-01-16 04:11:57.000000000 -0500
@@ -0,0 +1,29 @@
+//-*-c++-*-
+#ifndef _SUSAN_H_
+#define _SUSAN_H_
+
+// Code imported from SUSAN Version 2l by Stephen Smith
+//
+// See the susan.cc file for full copyright information.
+
+namespace DualCoding {
+
+typedef unsigned char uchar;
+
+void susan_thin(int *r, uchar *mid, int x_size, int y_size);
+
+void susan_edges_internal(uchar *in, int *r, uchar *mid, uchar *bp, 
+	    int max_no, int x_size, int y_size);
+
+void susan_principle(uchar *in, int *r, uchar **bp, int max_no,
+		     int x_size, int y_size);
+
+void edge_draw(uchar *in, uchar *mid, int x_size, int y_size, int drawing_mode);
+
+
+/* bp gets initialized in here right now! need to have an init function */
+void setup_brightness_lut(uchar **bp, int thresh, int form);
+
+} // namespace
+
+#endif /* _SUSAN_H_ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/visops.cc ./DualCoding/visops.cc
--- ../Tekkotsu_2.4.1/DualCoding/visops.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/visops.cc	2006-08-10 23:09:36.000000000 -0400
@@ -0,0 +1,654 @@
+//-*-c++-*-
+
+#include <math.h>
+#include "susan.h"
+
+#include "visops.h"
+
+using namespace DualCoding;
+
+namespace visops {
+
+Sketch<bool> zeros(SketchSpace& space) {
+  Sketch<bool> result(space,"zeros()");
+  *result.pixels = 0;  // valarray assignment
+  return result;
+}
+
+Sketch<bool> zeros(const SketchRoot& other) {
+  const Sketch<bool>& fake = reinterpret_cast<const Sketch<bool>&>(other);
+  Sketch<bool> result("zeros("+fake->getName()+")", fake);
+  *result.pixels = 0;  // valarray assignment
+  return result;
+}
+
+Sketch<bool> colormask(const Sketch<uchar>& src, 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));
+  return result;
+}
+
+Sketch<usint> bdist(const Sketch<bool>& dest, 
+			    const Sketch<bool>& obst, 
+			    const int 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
+  result->setColorMap(jetMapScaled);
+  
+  // want to 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++) {
+    // 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] 
+      + frontier[*space.idxW] + frontier[*space.idxE]
+      - (obstInds + frontier + oldFrontier);
+    newFrontier.trimBounds(space);
+    // if no more frontier, done
+    if (newFrontier.table.empty())
+      break;
+    result.setIndices(newFrontier, dist);
+    oldFrontier = frontier;
+    frontier = newFrontier;
+  }
+  
+  return result;
+}
+
+Sketch<usint> 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;
+  // 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);
+  dist = maxdist;
+  dist->setColorMap(jetMapScaled);
+  
+  // find min distances within each row
+  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);
+      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)
+	cur_dist = dist(i,j);
+      else
+	dist(i,j) = cur_dist;
+      cur_dist++;
+    }
+  }
+  // find min distances within each column
+  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);
+      else
+	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);
+      else
+	dist(i,j) = cur_dist;
+      cur_dist++;
+    }
+  }
+  return dist;
+}
+
+Sketch<usint> labelcc(const Sketch<bool>& sketch, int minarea) {
+  Sketch<uchar> temp;
+  uchar *pixels;
+  if ( sizeof(bool) == sizeof(uchar) )
+    pixels = reinterpret_cast<uchar*>(&((*sketch.pixels)[0]));
+  else {
+    temp.bind((Sketch<uchar>)sketch);
+    pixels = &((*temp.pixels)[0]);
+  }
+
+  // convert pixel array to RLE
+  int const maxRuns = (sketch.width * sketch.height) / 8;
+  CMVision::run<uchar> *rle_buffer = new CMVision::run<uchar>[maxRuns];
+  unsigned int const numRuns = CMVision::EncodeRuns(rle_buffer, pixels, sketch.width, sketch.height, maxRuns);
+
+  // convert RLE to region list
+  CMVision::ConnectComponents(rle_buffer,numRuns);
+  int const maxRegions = (sketch.width * sketch.height) / 16;   // formula from RegionGenerator.h
+  CMVision::region *regions = new CMVision::region[maxRegions];
+  unsigned int numRegions = CMVision::ExtractRegions(regions, maxRegions, rle_buffer, numRuns);
+  int const numColors = 2;  // only two colors in a Sketch<bool>: 0 and 1
+  CMVision::color_class_state *ccs = new CMVision::color_class_state[numColors];
+  unsigned int const maxArea = CMVision::SeparateRegions(ccs, numColors, regions, numRegions);
+  CMVision::SortRegions(ccs, numColors, maxArea);
+  CMVision::MergeRegions(ccs, numColors, rle_buffer);
+
+  // extract regions from region list
+  NEW_SKETCH(result, usint, visops::zeros(sketch));
+  result->setColorMap(jetMapScaled);
+  const CMVision::region* list_head = ccs[1].list;
+  if ( list_head != NULL ) {
+    for (int label=1; list_head!=NULL && list_head->area >= minarea;
+	   list_head = list_head->next, label++) {
+      // the first run might be array element 0, so use -1 as end of list test
+      for (int runidx = list_head->run_start; runidx != -1;
+	   runidx = rle_buffer[runidx].next ? rle_buffer[runidx].next : -1) {
+	const CMVision::run<uchar> &this_run = rle_buffer[runidx];
+	const int xstop = this_run.x + this_run.width;
+	const int yi = this_run.y;
+	for ( int xi = this_run.x; xi < xstop; xi++ )
+	  result(xi,yi) = label * sketch(xi,yi); // the * undoes some of CMVision's noise removal
+      }
+    }
+  }
+
+  delete[] ccs;
+  delete[] regions;
+  delete[] rle_buffer;
+  return result;
+}
+
+// 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)
+{
+  bool conn8 = (connectivity == EightWayConnect);
+  const int width = source.width;
+  const int height = source.height;
+  Sketch<usint> 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
+  eq_classes.clear();
+  eq_classes.push_back(0); // added just so that indices match up with labels
+  int highest_label = 0;
+  int up_label = 0; // value above current pixel
+  int left_label = 0; // value to left of current pixel
+  int ul_label = 0; // value to upper-left of current pixel
+  int ur_label = 0; // value to upper-right of current pixel
+  for(int j = 0; j < height; j++) {
+    for(int i = 0; i < width; i++) {
+      if (source(i,j)) {
+	up_label = (j == 0) ? 0 : labels(i,j-1);
+	left_label = (i==0) ? 0 : labels(i-1,j); 
+	ul_label = (i==0||j==0) ? 0 : labels(i-1,j-1);
+	ur_label = (i==(width-1)||j==0) ? 0 : labels(i+1,j-1);
+	if (up_label == 0 && left_label == 0
+	    && (!conn8 || (ul_label == 0 && ur_label == 0))) {
+	  labels(i,j) = ++highest_label;  // create new label
+	  // push back a new root label
+	  eq_classes.push_back(highest_label); // label value will be equal to index
+	} else if (up_label && !left_label) {
+	  labels(i,j) = up_label;
+	} else if (conn8 && !up_label && ur_label) {
+	  labels(i,j) = ur_label;
+	} else if (left_label && !up_label) {
+	  labels(i,j) = left_label;
+	} else if (conn8 && !left_label && !up_label 
+		   && ur_label && !ul_label) {
+	  labels(i,j) = ur_label; 
+	} else if (conn8 && !left_label && !up_label
+		   && ul_label && !ur_label){
+	  labels(i,j) = ul_label;	
+	}
+	
+	if (up_label && left_label && (up_label != left_label)) {
+	  // form union between two equivalence classes
+	  // if upper-left, assume equivalence class already made
+	  
+	  int root = up_label;
+	  while (eq_classes[root] != root) {
+	    root = eq_classes[root]; // "FIND" of UNION-FIND
+	  }
+	  // should do path compression to make more efficient
+	  int tmp_root = up_label, next_root;
+	  while(eq_classes[tmp_root] != root) {
+	    next_root = eq_classes[tmp_root];
+	    eq_classes[tmp_root] = root; // compress
+	    tmp_root = next_root;
+	  }
+	  
+	  eq_classes[left_label] = root; // "UNION" of UNION-FIND
+	  labels(i,j) = root; // not sure why putting this here works, but it does
+	} else if (up_label && (up_label == left_label)) {
+	  labels(i,j) = up_label;	
+	} else if (conn8 && ur_label && left_label 
+		   && (ur_label != left_label)) {
+	  // form union between two equivalence classes
+	  int root = ur_label;
+	  while (eq_classes[root] != root) {
+	    root = eq_classes[root]; // "FIND" of UNION-FIND
+	  }
+	  // should do path compression to make more efficient
+	  int tmp_root = ur_label, next_root;
+	  while(eq_classes[tmp_root] != root) {
+	    next_root = eq_classes[tmp_root];
+	    eq_classes[tmp_root] = root; // compress
+	    tmp_root = next_root;
+	  }
+	  
+	  eq_classes[left_label] = root; // "UNION" of UNION-FIND
+	  labels(i,j) = root; // not sure why putting this here works, but it does
+	}
+      }
+    }
+  }
+  
+  // Second scan: 
+  int cur_label;
+  for(int j = 0; j < height; j++) {
+    for(int i = 0; i < width; i++) {
+      cur_label = labels(i,j);
+      if (cur_label != 0) {
+	while(eq_classes[cur_label] != cur_label) {
+	  cur_label = eq_classes[cur_label];	
+	}
+	labels(i,j) = cur_label;
+      }
+      
+    }
+  }
+  
+  return labels;
+}
+
+Sketch<usint> areacc(const Sketch<bool>& source, Connectivity_t connectivity) {
+  NEW_SKETCH_N(labels, usint, 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++)
+    ++areas[labels[i]];
+  areas[0] = 0;
+  Sketch<usint> result("areacc("+labels->getName()+")",labels);
+  for (usint 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(result, bool, areas >= minval);
+  return result;
+}
+
+Sketch<uchar> neighborSum(const Sketch<bool>& im, Connectivity_t connectivity) 
+{
+  // using index redirection method
+  SketchSpace &space = im->getSpace();
+
+  space.requireIdx4way();
+  if (connectivity == EightWayConnect)
+    space.requireIdx8way();
+
+  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];
+  }
+  return result;
+}
+
+Sketch<bool> fillin(const Sketch<bool>& im, int iter, 
+			    uchar min_thresh, uchar max_thresh, bool remove_only)
+{
+  Sketch<bool> result(im);
+  if ( remove_only )
+    result.bind(visops::copy(im));
+  Sketch<uchar> neighborCount(im);
+  if (remove_only) {
+    neighborCount.bind(neighborSum(result,EightWayConnect));
+    result &= (neighborCount <= max_thresh);
+    for (int i = 0; i < iter; i++)
+      result &= (neighborCount >= min_thresh);
+  }
+  else {
+    for (int i = 0; i < iter; i++) {
+      neighborCount.bind(neighborSum(result,EightWayConnect));
+      result.bind((neighborCount >= min_thresh) & (neighborCount <= max_thresh));
+    }
+  }
+  result->setName("fillin("+im->getName()+")");
+  result->setColor(im->getColor());
+  return result;
+}
+
+Sketch<bool> edge(const Sketch<bool> &im) {
+  im->getSpace().requireIdx4way();
+  SketchSpace &space = im->getSpace();
+  return (im != im[*space.idxS] | im != im[*space.idxE]);
+}
+
+
+Sketch<bool> horsym(const Sketch<bool> &im, int minskip, int maxskip)
+{
+  NEW_SKETCH_N(result, bool, visops::zeros(im));
+  result->setName("horsym("+im->getName()+")");
+  const int width = im->getWidth();
+  const int height = im->getHeight();
+
+  for (int j = 0; j < height; j++) {
+    for (int i = 0; i < width; i++) {
+      while (i < width && !im(i,j)) i++; // skip over empty pixels
+      for (int k = i+1; k <= width; k++) {
+	  if ( k==width || !im(k,j)) {
+	    if ( (k-i) >= minskip && (k-i) <= maxskip ) {
+	      const int u = (i+k)/2;
+	      result(u,j) = true;
+	    }
+	    i=k+1;
+	    break;
+	  }
+      }
+    }
+  }
+  return result;
+}
+
+Sketch<bool> versym(const Sketch<bool> &im, int minskip, int maxskip)
+{
+  NEW_SKETCH_N(result, bool, visops::zeros(im));
+  result->setName("horsym("+im->getName()+")");
+  const int width = im->getWidth();
+  const int height = im->getHeight();
+
+  for (int i = 0; i < width; i++) {
+    for (int j = 0; j < height; j++) {
+      while (j < height && !im(i,j)) j++; // skip over empty pixels
+      for (int k = j+1; k <= height; k++) {
+	  if ( k==height || !im(i,k)) {
+	    if ( (k-j) >= minskip && (k-j) <= maxskip ) {
+	      const int u = (j+k)/2;
+	      result(i,u) = true;
+	    }
+	    j=k+1;
+	    break;
+	  }
+      }
+    }
+  }
+  return result;
+}
+
+
+/*
+Sketch<bool> versym(const Sketch<bool>& im, int minskip, int maxskip)
+{
+  NEW_SKETCH_N(result, bool, visops::zeros(im));
+  result->setName("versym("+im->getName()+")");
+  int height = im->getWidth();
+  int width = im->getHeight();
+  
+  for (int j = 0; j < height; j++) {
+    for (int i = 0; i < width; i++) {
+      if (im(j,i)) {
+	while (i < width-1 && im(j,i+1)) {
+	  i++; // skip over contiguous pixels
+	}
+	for (int k = i+1; k < width; k++) {
+	  if (k-i > maxskip)
+	    break;
+	  else if (im(j,k)) {
+	    if ((k-i) < minskip)
+	      break;
+	    int u = (i+k)/2;
+	    if (!im(j,u))
+	      result(j,u) = true; // was result(j,u) = k-i when this returned a Sketch<int>
+	    break; // only works well for non-'donut' ellipses
+	  }
+	}
+      }
+    }
+  }
+  return result;
+}
+*/
+
+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)
+{
+  // 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(result, bool, regions == regions->at(index));  // use at() to do bounds checking
+  return result;
+}
+
+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 
+  int const x1 = (int)ln->end1Pt().coordX();
+  int const y1 = (int)ln->end1Pt().coordY();
+  int const x2 = (int)ln->end2Pt().coordX();
+  int const y2 = (int)ln->end2Pt().coordY();
+  float const m = (x1 == x2) ? BIG_SLOPE : (y2-y1) / (x2-x1);
+  int const b = (int) (y1 - x1*m);
+  int seed;
+  if ( x1 == x2 )
+    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;
+  if ( seed == -1 ) {
+    NEW_SKETCH_N(result, bool, visops::zeros(SkS));
+    result->inheritFrom(ln);
+    return result;
+  } else {
+    NEW_SHAPE_N(line_copy, LineData, ln->copy());
+    line_copy->setInfinite();
+    NEW_SKETCH_N(bounds, bool, line_copy->getRendering());
+    bounds->inheritFrom(ln);
+    return visops::seedfill(bounds,seed);
+  }
+}
+
+Sketch<bool> rightHalfPlane(const Shape<LineData> &ln) {
+    NEW_SHAPE_N(line_copy, LineData, ln->copy());
+    line_copy->setInfinite();
+    NEW_SKETCH_N(bounds, bool, line_copy->getRendering());
+    bounds->inheritFrom(ln);
+    return ! (visops::leftHalfPlane(ln) | bounds);
+}
+
+Sketch<bool> topHalfPlane(const Shape<LineData> &ln) {
+  SketchSpace &SkS = ln->getSpace().getDualSpace();
+  //! @todo **** visops::topHalfPlane needs to check the SketchSpace ReferenceFrameType because "left" means different things in different reference frames 
+  int const x1 = (int)ln->end1Pt().coordX();
+  int const y1 = (int)ln->end1Pt().coordY();
+  int const x2 = (int)ln->end2Pt().coordX();
+  int const y2 = (int)ln->end2Pt().coordY();
+  float const m = (x1 == x2) ? BIG_SLOPE : (y2-y1) / (x2-x1);
+  int const b = (int) (y1 - x1*m);
+  int seed;
+  if ( x1 == x2 )
+    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;
+  if ( seed == -1 ) {
+    NEW_SKETCH_N(result, bool, visops::zeros(SkS));
+    result->inheritFrom(ln);
+    return result;
+  } else {
+    NEW_SHAPE_N(line_copy, LineData, ln->copy());
+    line_copy->setInfinite();
+    NEW_SKETCH_N(bounds, bool, line_copy->getRendering());
+    bounds->inheritFrom(ln);
+    return visops::seedfill(bounds,seed);
+  }
+}
+
+Sketch<bool> bottomHalfPlane(const Shape<LineData> &ln) {
+    NEW_SHAPE_N(line_copy, LineData, ln->copy());
+    line_copy->setInfinite();
+    NEW_SKETCH_N(bounds, bool, line_copy->getRendering());
+    bounds->inheritFrom(ln);
+    return ! (visops::topHalfPlane(ln) | bounds);
+}
+
+Sketch<bool> non_bounds(const Sketch<bool>& im, int offset) {
+  const int width = im->getWidth();
+  const int height = im->getHeight();
+  NEW_SKETCH_N(nbresult,bool,visops::copy(im));
+  nbresult->setName("non_bounds("+im->getName()+")");
+
+  for (int i = 0; i < width; i++) {
+    for (int j = 0; j < offset; j++) {
+      nbresult(i,j) = false;
+      nbresult(i,height-j-1) = false;
+    }
+  }
+  for (int i = 0; i < offset; i++) {
+    for (int j = offset; j < height-offset; j++) {
+      nbresult(i,j) = false;
+      nbresult(width-i-1,j) = false;
+    }
+  }
+  return nbresult;
+}
+
+
+Sketch<uchar> susan_edges(const Sketch<uchar>& im, int brightness)
+{
+  const int width = im->getWidth();
+  const int height = im->getHeight();
+  unsigned char *bp;
+  Sketch<uchar> edges(visops::copy(im));
+
+  int *r = (int *)malloc(width*height*sizeof(int));
+
+  unsigned char *mid = (unsigned char *)malloc(width*height);
+  memset (mid,100,width * height); /* note not set to zero */
+
+  setup_brightness_lut(&bp,brightness,6);
+
+  // susan_principle(im->getRawPixels(),edges->getRawPixels(), &bp, 2650, width, height);
+
+  susan_edges_internal(edges->getRawPixels(), r, mid, bp, 2650, width, height);
+
+  susan_thin(r, mid, width, height);
+
+  edge_draw(edges->getRawPixels(),mid,width,height,0);
+
+   free(r);
+   free(mid);
+   free(bp-258);
+
+  return edges;
+}
+
+
+// Default brightness was 20 for original algorithm
+Sketch<bool> susan_edge_points(const Sketch<uchar>& im, int brightness)
+{
+  const int width = im->getWidth();
+  const int height = im->getHeight();
+  unsigned char *bp;
+  Sketch<uchar> orig(im);
+  Sketch<uchar> edges(visops::zeros(im));
+  int *r = (int *)malloc(width*height*sizeof(int));
+  unsigned char *mid = (unsigned char *)malloc(width*height);
+  memset(mid,100,width * height); /* note not set to zero */
+  setup_brightness_lut(&bp,brightness,6);
+  susan_edges_internal(orig->getRawPixels(), r, mid, bp, 2650, width, height);
+  susan_thin(r, mid, width, height);
+  edge_draw(edges->getRawPixels(),mid,width,height,1);
+  free(r);
+  free(mid);
+  Sketch<bool> result(edges);
+  return result;
+}
+
+Sketch<usint> convolve(const Sketch<uchar> &sketch, Sketch<uchar> &kernel, 
+		       int istart, int jstart, int width, int height) {
+  Sketch<usint> result("convolve("+sketch->getName()+")",sketch);
+  result->setColorMap(jetMapScaled);
+  int const di = - (int)(width/2);
+  int const dj = - (int)(height/2);
+  for (int si=0; si<sketch.width; si++)
+    for (int sj=0; sj<sketch.height; sj++) {
+      int sum = 0;
+      for (int ki=0; ki<width; ki++)
+	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);
+      result(si,sj) = sum/(width*height);
+    }
+  return result;      
+}
+
+Sketch<usint> templateMatch(const Sketch<uchar> &sketch, Sketch<uchar> &kernel, 
+		       int istart, int jstart, int width, int height) {
+  Sketch<usint> result("convolve0("+sketch->getName()+")",sketch);
+  result->setColorMap(jetMapScaled);
+  int const npix = width * height;
+  int const di = - (int)(width/2);
+  int const dj = - (int)(height/2);
+  for (int si=0; si<sketch.width; si++)
+    for (int sj=0; sj<sketch.height; sj++) {
+      int sum = 0;
+      for (int ki=0; ki<width; ki++)
+	for (int kj=0; kj<height; kj++) {
+	  int k_pix = kernel(istart+ki,jstart+kj);
+	  if ( si+di+ki >= 0 && si+di+ki < sketch.width &&
+	       sj+dj+kj >= 0 && sj+dj+kj < sketch.height ) {
+	    int s_pix = sketch(si+di+ki,sj+dj+kj);
+	    sum +=  (s_pix - k_pix) * (s_pix - k_pix);
+	  }
+	  else
+	    sum += k_pix * k_pix;
+	}
+      result(si,sj) =  65535 - usint(sqrt(sum/float(npix)));
+    }
+  result = result - result->min();
+  return result;
+}
+
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/DualCoding/visops.h ./DualCoding/visops.h
--- ../Tekkotsu_2.4.1/DualCoding/visops.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/visops.h	2006-09-15 03:09:49.000000000 -0400
@@ -0,0 +1,283 @@
+//-*-c++-*-
+#ifndef _VISOPS_H_
+#define _VISOPS_H_
+
+#include "SketchTypes.h"
+#include "Sketch.h"
+#include "SketchSpace.h"
+
+#include "ShapeLine.h"
+
+using namespace DualCoding;
+using DualCoding::uchar;
+
+class DualCoding::SketchIndices;
+
+//! Visual routines operators, used in DualCoding.
+namespace visops {
+  
+  //! Connectivity used by oldlabelcc and neighborsum.
+  enum Connectivity_t { FourWayConnect, EightWayConnect };
+
+  //!@name Sketch creation
+  //@{
+
+  //! Returns an all-zero Sketch<bool> in the specified sketch space
+  Sketch<bool> zeros(SketchSpace& space);
+
+  //! 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.
+  template<class T>
+  Sketch<T> copy(const Sketch<T>& other) {
+    Sketch<T> result("copy("+other->getName()+")", other);
+    *result.pixels = *other.pixels;  // valarray assignment
+    result->setColor(other->getColor());
+    result->setColorMap(other->getColorMap());
+    return result;
+  }
+
+  //@}
+
+  //!@name Min/max functions
+  //@{
+
+  //! Max of each pixel with a constant
+  template<class T>
+  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);
+    return result;
+  }
+
+  //! Max of each pixel with a constant
+  template<class T>
+  Sketch<T> max(const Sketch<T>& src, const int value) {
+    return visops::max(src, (T)(value));
+  }
+
+
+  //! 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);
+    for ( unsigned int i = 0; i < arg1.pixels->size()-1; i++ ) 
+      (*result.pixels)[i] = ::max((*arg1.pixels)[i],(*arg2.pixels)[i]);
+    return result;
+  }
+
+  //! Min of each pixel with a constant
+  template<class T>
+  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);
+    return result;
+  }
+
+  //! Min of each pixel with a constant
+  template<class T>
+  Sketch<T> min(const Sketch<T>& src, const int value) {
+    return visops::min(src, (T)(value));
+  }
+
+  //! 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);
+    for ( unsigned int i = 0; i < arg1.pixels->size()-1; i++ ) 
+      (*result.pixels)[i] = ::min((*arg1.pixels)[i],(*arg2.pixels)[i]);
+    return result;
+  }
+
+  //@}
+
+  //!@name Miscellaneous functions
+  //@{
+
+  //! Returns all the pixels of the named color.
+  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);
+
+  //! For each pixel, calculate the sum of its neighbors.
+  /*! @param im Sketch to use as input.
+   *  @param connectivity the type of neighbor connectivity to use */
+  Sketch<uchar> neighborSum(const Sketch<bool> &im, Connectivity_t connectivity=EightWayConnect);
+  
+  //! Produces a filled in image based on the Sketch, using 8-way connectivity.
+  /*! @param im The sketch to which to apply the function.
+   *  @param iter Number of times to perform the fillin operation.
+   *  @param min_thresh Fill in pixel if has at least this many neighbors.
+   *  @param max_thresh Fill in pixel if has fewer than this many neighbors.
+   *  @param remove_only Set to true if you know you will only be deleting pixels for a speedup */
+  Sketch<bool> fillin(const Sketch<bool> &im, int iter, 
+		      uchar min_thresh, uchar max_thresh,
+		      bool remove_only=false);
+  
+  //@}
+
+  //!@name Wavefront algorithms: distance, connected components
+  //@{
+
+  /*! @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);
+
+  //! 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);
+  
+  //! Connected components labeling using CMVision.  Components numbered sequentially from 1.
+  Sketch<usint> 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, 
+		      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);
+
+  //! Each pixel of the result is the area of that connected component.
+  Sketch<usint> areacc(const Sketch<usint>& labels);
+
+  //! Low-pass filter by eliminating small regions
+  Sketch<bool> minArea(const Sketch<bool>& sketch, int minval=5);
+
+  //@}
+
+  //! @name Conditional assignment
+  //@{
+  //! 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>
+  Sketch<T> ifNot(const Sketch<T> &A, const Sketch<T> &B) {
+    Sketch<T> result("ifNot("+A->getName()+","+B->getName()+")", A);
+    T* Aptr = &(*A.pixels)[0];
+    T* Bptr = &(*B.pixels)[0];
+    T* Rptr = &(*result.pixels)[0];
+    T* Rend = &(*result.pixels)[result->getNumPixels()];
+    while ( Rptr != Rend ) {
+      *Rptr++ = ( *Aptr != 0 ) ? *Aptr : * Bptr;
+      *Aptr++; Bptr++;
+    }
+    return result;
+  }
+
+  //! Returns a result where pixels of @a sketch for which @a mask is true have been replaced by @a value.
+  template<typename T, typename Tv>
+  Sketch<T> maskedAssign(const Sketch<T> &sketch, const Sketch<bool> &mask, const Tv value) {
+    Sketch<T> result("maskedAssign("+sketch->getName()+")",sketch);
+    T* Psrc = &(*sketch.pixels)[0];
+    T* Pdest = &(*result.pixels)[0];
+    T* Edest = &(*result.pixels)[sketch->getNumPixels()];
+    bool* Pmask =&(*mask.pixels)[0];
+    const T val = (T)value;
+    while ( Pdest != Edest ) {
+      *Pdest++ = *Pmask++ ? val : *Psrc;
+      Psrc++;
+    }
+    return result;
+  }
+
+  //! Returns a result where pixels of @a sketch for which @a mask is true have been replaced by corresponding pixels of @a value.
+  template<typename T>
+  Sketch<T> maskedAssign(const Sketch<T> &sketch, const Sketch<bool> &mask, const Sketch<T> &value) {
+    Sketch<T> result("maskedAssign("+sketch->getName()+")",sketch);
+    T* Psrc = &(*sketch.pixels)[0];
+    T* Pdest = &(*result.pixels)[0];
+    T* Edest = &(*result.pixels)[sketch->getNumPixels()];
+    bool* Pmask = &(*mask.pixels)[0];
+    T* Pval = &(*value.pixels)[0];
+    while ( Pdest != Edest ) {
+      *Pdest++ = *Pmask++ ? *Pval : *Psrc;
+      Pval++;
+      Psrc++;
+    }
+    return result;
+  }
+  //@}
+
+  //!@name Edge and symmetry detection
+  //@{
+
+  //! Simple edge finding.  Use SUSAN for more sophisticated edge detection.
+  /*! This edge-finding algorithm is inefficient, and produces offset results
+   *  for top and left edges.  Should replace it with something better. */
+  Sketch<bool> edge(const Sketch<bool> &im); 
+  
+  //! Horizontal symmetry points.
+  /*! @brief Returns non-zero values along points of horizontal symmetry, with
+   *  each of these values equal to the distance to the symmetric points.
+   *  @param sketch The sketch to which to apply the function.
+   *  @param minskip The min accepted distance between pixels for symmetry.
+   *  @param maxskip The max accepted distance between pixels for symmetry. */
+  Sketch<bool> horsym(const Sketch<bool>& sketch, 
+		     int minskip=3, int maxskip=80);
+
+  //! Vertical symmetry points.
+  /*! @brief Returns non-zero values along points of vertical symmetry, with
+   *  each of these values equal to the distance to the symmetric points.
+   *  @param sketch The sketch to which to apply the function.
+   *  @param minskip The min accepted distance between pixels for symmetry.
+   *  @param maxskip The max accepted distance between pixels for symmetry. */
+  Sketch<bool> versym(const Sketch<bool>& sketch, 
+		     int minskip=3, int maxskip=80);
+  
+  /*! @brief returns a skeleton of @a sketch, with pixel values corresponding to 
+   *  distance of symmetry */
+  Sketch<bool> skel(const Sketch<bool>& sketch); 
+
+  //@}
+  
+  //!@name Sketch dissection
+  //@{
+  //! Half-plane functions fill in the half plane on one side of a line.
+  //@{
+  Sketch<bool> leftHalfPlane(const Shape<LineData> &ln);
+
+  Sketch<bool> rightHalfPlane(const Shape<LineData> &ln);
+
+  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);
+  //@}
+
+  //!@name Image manipulation primitives
+  //@{
+  //! Runs the SUSAN edge detector on a grayscale image
+  Sketch<uchar> susan_edges(const Sketch<uchar>& im, int brightness);
+
+  //! Returns a Sketch<bool> indicating edge points found by SUSAN
+  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, 
+			 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, 
+			 int i, int j, int width, int height);
+
+  //@}
+
+} // namespace
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/EventBase.cc ./Events/EventBase.cc
--- ../Tekkotsu_2.4.1/Events/EventBase.cc	2005-06-01 01:47:46.000000000 -0400
+++ ./Events/EventBase.cc	2006-09-21 17:26:07.000000000 -0400
@@ -12,13 +12,18 @@
 	"erouterEGID",
 	"estopEGID",
 	"locomotionEGID",
+	"lookoutEGID",
+	"mapbuilderEGID",
 	"micOSndEGID",
 	"micRawEGID",
 	"micFFTEGID",
+	"micPitchEGID",
 	"motmanEGID",
+	"pilotEGID",
 	"powerEGID",
 	"sensorEGID",
 	"stateMachineEGID",
+	"stateSignalEGID",
 	"stateTransitionEGID",
 	"textmsgEGID",
 	"timerEGID",
@@ -26,6 +31,7 @@
 	"visRawCameraEGID",
 	"visInterleaveEGID",
 	"visJPEGEGID",
+	"visPNGEGID",
 	"visSegmentEGID",
 	"visRLEEGID",
 	"visRegionEGID",
@@ -113,71 +119,51 @@
 		return XMLLoadSave::getBinSize();
 	unsigned int used=0;
 	used+=creatorSize("EventBase");
-	used+=stim_id.size()+stringpad;
-	used+=sizeof(magnitude);
-	used+=sizeof(timestamp);
-	used+=sizeof(nameisgen);
-	used+=sizeof(char);
-	used+=sizeof(char);
-	used+=sizeof(sourceID);
-	used+=sizeof(duration);
+	used+=getSerializedSize(stim_id);
+	used+=getSerializedSize(magnitude);
+	used+=getSerializedSize(timestamp);
+	used+=getSerializedSize(nameisgen);
+	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(duration);
 	return used;
 }
 
 unsigned int
-EventBase::LoadBinaryBuffer(const char buf[], unsigned int len) {
+EventBase::loadBinaryBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
-	unsigned int used=0;
-	if(0==(used=checkCreator("EventBase",buf,len,true))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(stim_id,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(magnitude,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(timestamp,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(nameisgen,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkCreatorInc("EventBase",buf,len,true)) return 0;
+	if(!decodeInc(stim_id,buf,len)) return 0;
+	if(!decodeInc(magnitude,buf,len)) return 0;
+	if(!decodeInc(timestamp,buf,len)) return 0;
+	if(!decodeInc(nameisgen,buf,len)) return 0;
 	char tmp;
-	if(0==(used=decode(tmp,buf,len))) return 0;
+	if(!decodeInc(tmp,buf,len)) return 0;
 	genID=(EventGeneratorID_t)tmp;
-	len-=used; buf+=used;
-	if(0==(used=decode(tmp,buf,len))) return 0;
+	if(!decodeInc(tmp,buf,len)) return 0;
 	typeID=(EventTypeID_t)tmp;
-	len-=used; buf+=used;
-	if(0==(used=decode(sourceID,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(duration,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!decodeInc(sourceID,buf,len)) return 0;
+	if(!decodeInc(duration,buf,len)) return 0;
 	return origlen-len;	
 }
 
 unsigned int
-EventBase::SaveBinaryBuffer(char buf[], unsigned int len) const {
+EventBase::saveBinaryBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used=0;
-	if(0==(used=saveCreator("EventBase",buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(stim_id,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(magnitude,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(timestamp,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(nameisgen,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode((char)genID,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode((char)typeID,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(sourceID,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(duration,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!saveCreatorInc("EventBase",buf,len)) return 0;
+	if(!encodeInc(stim_id,buf,len)) return 0;
+	if(!encodeInc(magnitude,buf,len)) return 0;
+	if(!encodeInc(timestamp,buf,len)) return 0;
+	if(!encodeInc(nameisgen,buf,len)) return 0;
+	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(duration,buf,len)) return 0;
 	return origlen-len;
 }
 
-void EventBase::LoadXML(xmlNode* node) {
+void EventBase::loadXML(xmlNode* node) {
 	if(xmlStrcmp(node->name, (const xmlChar *)"event"))
 		throw bad_format(node,"Load of the wrong type -- expecting 'event' node");
 	unsigned int i;
@@ -232,11 +218,11 @@
 	} else
 		genName();
 }
-void EventBase::SaveXML(xmlNode * node) const {
+void EventBase::saveXML(xmlNode * node) const {
 	xmlNodeSetName(node,(const xmlChar*)"event");
 	xmlSetProp(node,(const xmlChar*)"egid",(const xmlChar*)EventGeneratorNames[genID]);
 	char buf[20];
-	snprintf(buf,20,"%x",sourceID);
+	snprintf(buf,20,"%lu",static_cast<unsigned long>(sourceID));
 	xmlSetProp(node,(const xmlChar*)"sid",(const xmlChar*)buf);
 	xmlSetProp(node,(const xmlChar*)"etid",(const xmlChar*)EventTypeAbbr[typeID]);
 	snprintf(buf,20,"%u",timestamp);
@@ -260,7 +246,7 @@
 	if(!nameisgen)
 		return;
 	char tmp[16];
-	snprintf(tmp,16,"%d",sourceID);
+	snprintf(tmp,16,"%lu",static_cast<unsigned long>(sourceID));
 	setName(tmp);
 	nameisgen=true;
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/EventBase.h ./Events/EventBase.h
--- ../Tekkotsu_2.4.1/Events/EventBase.h	2005-06-29 18:03:34.000000000 -0400
+++ ./Events/EventBase.h	2006-10-03 19:19:23.000000000 -0400
@@ -6,43 +6,70 @@
 #include "Shared/XMLLoadSave.h"
 #include <string>
 
-//! The basis of events passed around the high level system
-/*! Contains the list of 'known' event generators in #EventGeneratorID_t
- *  and #EventGeneratorNames[].  If you want to make a new generator, all
- *  you have to do is add a new entry to the ID list (#EventGeneratorID_t)
- *  and then put its name in the #EventGeneratorNames[] array.
+//! Forms the basis of communication between modules/behaviors in the framework
+/*! 
+ *  Events are defined by a 3-tuple:
+ *  - The @b generator indicates the class of the creator of the event, and in practice also generally implies the type (i.e. subclass) of the event itself.
+ *  - The @b source indicates the instance of the creator of the event, which differentiates when more than one generator is available.
+ *  - The @b type indicates the role of the event among other events from the source.
  *
- *  The #EventGeneratorID_t list should contain links to the
- *  generators' documentation, or will directly give information about
- *  what to expect in events from that generator.
+ *  Each of these is represented by an ID, the #EventGeneratorID_t (EGID) and #EventTypeID_t (ETID) are
+ *  defined here in EventBase.  Source IDs (SID) are defined separately by each generator, so the
+ *  documentation in each entry of EventGeneratorID_t describes how to interpret the source field.
+ *
+ *  So for example, the button event which results from initially pressing the head button on an ERS-7
+ *  robot would be:
+ *  <center>(EventBase::buttonEGID, ERS7Info::HeadButOffset, EventBase::activateETID)</center>
+ *
+ *  While the button is held down, additional #statusETID events are used to report varying pressure values (if the button
+ *  is pressure sensitive), and an event with #deactivateETID is sent when the button is released.
+ *  Alternatively, an SID value from a vision detector (say #visObjEGID) refers to seeing a particular object, a completely
+ *  different domain, values of which may overlap with other generators' source IDs.
+ *  Thus, interpreting the source field requires knowing the generator as well.
+ *
+ *  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>
  *  
- *  Alternatively, there is an 'unlicensed spectrum' available under
- *  the #unknownEGID.  You can send out events from that generator just
+ *  The #duration field is also generator specific - some may refer to
+ *  the time since the last activation event (e.g. button events)
+ *  where as others refer to time since last status (e.g. sensors
+ *  updates)
+ *
+ *  If you want to make a new generator, all you have to do is add a new entry
+ *  to the ID list (#EventGeneratorID_t) and then put its name in the 
+ *  #EventGeneratorNames[] array.  Alternatively, there is an 'unlicensed spectrum' available under
+ *  #unknownEGID.  You can send out events from that generator just
  *  like any other, but it should only be used for quick tests and hacking
  *  around...
  *
- *  The #sourceID (just an unsigned int) is generator specific.  A SID
- *  of @a i from the button generator (#buttonEGID) will refer to a
- *  particular button, whereas a SID from a vision detector (say
- *  #visObjEGID) refers to seeing a particular object.  These SIDs are
- *  usually defined in the generators themselves.
+ *  The generator ID number is only that -- an ID number.  
+ *  Events can be posted to the EventRouter anywhere, anytime,
+ *  and do not require anything of the sender.  However, there is an EventGeneratorBase which
+ *  can simplify some aspects of behaviors whose sole purpose is processing information
+ *  and generating events.
  *
  *  If more information needs to be sent along with the event, the
  *  cleanest solution is to create a subclass of EventBase to hold the
  *  additional information.  For example, you can see the existing
  *  subclasses in the inheritance diagram above.  If you want to use a
- *  quick hack however, you could assume the pointer size is the same
- *  as an unsigned int and just pass a pointer to data as the SID.
- *  Your funeral, err, I mean your call. ;)
- *
- *  The #duration field is also generator specific - some may refer to
- *  the time since the last activation event (e.g. button events)
- *  where as others refer to time since last status (e.g. sensors
- *  updates)
+ *  quick hack however, you could just pass a pointer to data as the SID if you
+ *  don't need that field for something else, or use a DataEvent.
  *
  *  @note All subclasses must override getClassTypeID() and provide
- *  a unique value to allow fast serialization for inter-process
- *  communication.
+ *  a unique value to allow fast polymorphic serialization for inter-process
+ *  communication.  Implementing the load/save functions
+ *  ({load,save}BinaryBuffer and {load,save}XML) for your addtional data fields
+ *  would also be necessary in order to allow your event to be sent between
+ *  processes, or eventually, between robots.
+ * 
+ *  @see EventRouter for discussion on sending and receiving of events
+ *  @see Tutorials:
+ *    - <a href="../FirstBehavior2.html">Steps 3, 4, & 5 of Tekkotsu's First Behavior Tutorial</a>
+ *    - <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>
+ *    - <a href="../media/TekkotsuQuickReference_ERS7.pdf">ERS-7 Quick Reference Sheet</a>
  */
 class EventBase : public XMLLoadSave {
  public:
@@ -58,20 +85,26 @@
 		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...)
+		lookoutEGID,      //!< Sends an event when Lookout request is complete; SID is the id for lookout request
+		mapbuilderEGID,  //!< Sends a status event when map is completed
 		micOSndEGID,      //!< Sends a DataEvent<OSoundVectorData> for every audio buffer received from the system; SID and duration are always 0 (This is generated by the MainObj instantiation of MMCombo)
 		micRawEGID,       //!< reserved for future use
 		micFFTEGID,       //!< reserved for future use
+		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
 		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
-		textmsgEGID,      //!< Sends status events when a text msg is received on console; generated by the Controller, SID is always -1; durations is always 0 (see Controller for more information)
+		textmsgEGID,      //!< Sends status events when a text msg is received on console; generated by the Controller, SID is 0 if broadcast from ControllerGUI, 1 if "private" from BehaviorSwitchControl; duration is always 0 (see Controller for more information)
 		timerEGID,        //!< Sends timer events; you set timers explicitly, you don't have to listen as well. (See EventRouter::addTimer()) There's no cross-talk, only the listener which requested the timer will receive it; SID is whatever you requested it to be; duration is the time (since boot, in ms) that the timer was supposed to go off; these are always status
 		visOFbkEGID,      //!< Sends a DataEvent < OFbkImageVectorData > for every camera image received from the system; SID and duration are always 0 (This is generated by the MainObj instantiation of MMCombo)
 		visRawCameraEGID, //!< Sends a FilterBankEvent when new raw camera images are available; SID is whatever value you gave during setup (typically in StartupBehavior_SetupVision.cc), duration is always 0
 		visInterleaveEGID,//!< Sends a FilterBankEvent when new interleaved images are available; SID is whatever value you gave during setup (typically in StartupBehavior_SetupVision.cc), duration is always 0
 		visJPEGEGID,      //!< Sends a FilterBankEvent when JPEG compressed images are available; SID is whatever value you gave during setup (typically in StartupBehavior_SetupVision.cc), duration is always 0
+		visPNGEGID,      //!< Sends a FilterBankEvent when PNG compressed images are available; SID is whatever value you gave during setup (typically in StartupBehavior_SetupVision.cc), duration is always 0
 		visSegmentEGID,   //!< Sends a SegmentedColorFilterBankEvent when color segmentated images are available; SID is whatever value you gave during setup (typically in StartupBehavior_SetupVision.cc), duration is always 0
 		visRLEEGID,       //!< Sends a SegmentedColorFilterBankEvent when RLE encoded color segmentated images are available; SID is whatever value you gave during setup (typically in StartupBehavior_SetupVision.cc), duration is always 0
 		visRegionEGID,    //!< Sends a SegmentedColorFilterBankEvent when color regions are available; SID is whatever value you gave during setup (typically in StartupBehavior_SetupVision.cc), duration is always 0
@@ -125,6 +158,7 @@
 	virtual EventBase& setMagnitude(float m) { magnitude=m; return *this; }//!< sets "strength" of event - you may want to override the default values (see getMagnitude())
 
 	virtual unsigned int getTimeStamp() const { return timestamp; } //!< time event was created
+	virtual void setTimeStamp(unsigned int t) { timestamp=t; } //!< resets time event was created
 
 	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 */
@@ -133,7 +167,7 @@
 	virtual EventBase& setSourceID(unsigned int 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; genName(); return *this; } /*!< @brief sets 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 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 */
@@ -178,30 +212,38 @@
 	 *  identification of the class type by the receiver. */
 	virtual unsigned int getClassTypeID() const { return makeClassTypeID("BASE"); }
 
-	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;
-
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len)  {
-		unsigned int test = saveFormat!=BINARY ? XMLLoadSave::LoadBuffer(buf,len) : LoadBinaryBuffer(buf,len);
+	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
+	virtual unsigned int saveBinaryBuffer(char buf[], unsigned int len) const; //!< save to binary format
+	virtual void loadXML(xmlNode* node); //!< load from XML format
+	virtual void saveXML(xmlNode * node) const; //!< save to XML format
+	
+	//! no longer need to override this -- will automatically call either loadXML() or loadBinaryBuffer() based on #saveFormat
+	/*! tries to be smart so if the load based on the current #saveFormat fails, retries with the alternative format */
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len)  {
+		unsigned int test = saveFormat!=BINARY ? XMLLoadSave::loadBuffer(buf,len) : loadBinaryBuffer(buf,len);
 		if(test!=0) //if the default didn't work, try the other format too...
 			return test;
-		return saveFormat!=BINARY ? LoadBinaryBuffer(buf,len) : XMLLoadSave::LoadBuffer(buf,len);
+		return saveFormat!=BINARY ? loadBinaryBuffer(buf,len) : XMLLoadSave::loadBuffer(buf,len);
 	}
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const { return saveFormat!=BINARY ? XMLLoadSave::SaveBuffer(buf,len) : SaveBinaryBuffer(buf,len); }
+	//! no longer need to override this -- will automatically call either saveXML() or saveBinaryBuffer() based on #saveFormat
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const { return saveFormat!=BINARY ? XMLLoadSave::saveBuffer(buf,len) : saveBinaryBuffer(buf,len); }
 
-	virtual	unsigned int LoadFile(const char* filename) {
-		unsigned int test = saveFormat!=BINARY ? XMLLoadSave::LoadFile(filename) : LoadSave::LoadFile(filename);
+	//! automatically calls either XMLLoadSave::loadFile or LoadSave::loadFile based on #saveFormat
+	/*! tries to be smart so if the load based on the current #saveFormat fails, retries with the alternative format */
+	virtual unsigned int loadFile(const char* filename) {
+		unsigned int test = saveFormat!=BINARY ? XMLLoadSave::loadFile(filename) : LoadSave::loadFile(filename);
 		if(test!=0) //if the default didn't work, try the other format too...
 			return test;
-		return saveFormat!=BINARY ? LoadSave::LoadFile(filename) : XMLLoadSave::LoadFile(filename);
+		return saveFormat!=BINARY ? LoadSave::loadFile(filename) : XMLLoadSave::loadFile(filename);
 	}
-	virtual unsigned int SaveFile(const char* filename) const { return saveFormat!=BINARY ? XMLLoadSave::SaveFile(filename) : LoadSave::SaveFile(filename); }
+	//! automatically calls either XMLLoadSave::saveFile or LoadSave::saveFile based on #saveFormat
+	virtual unsigned int saveFile(const char* filename) const { return saveFormat!=BINARY ? XMLLoadSave::saveFile(filename) : LoadSave::saveFile(filename); }
 	
-	virtual unsigned int LoadFileStream(FILE* f) { return saveFormat!=BINARY ? XMLLoadSave::LoadFileStream(f) : LoadSave::LoadFileStream(f); }
-	virtual unsigned int SaveFileStream(FILE* f) const { return saveFormat!=BINARY ? XMLLoadSave::SaveFileStream(f) : LoadSave::SaveFileStream(f); }
+	//! automatically calls either XMLLoadSave::loadFileStream or LoadSave::loadFileStream based on #saveFormat
+	virtual unsigned int loadFileStream(FILE* f) { return saveFormat!=BINARY ? XMLLoadSave::loadFileStream(f) : LoadSave::loadFileStream(f); }
+	//! automatically calls either XMLLoadSave::loadFileStream or LoadSave::loadFileStream based on #saveFormat
+	virtual unsigned int saveFileStream(FILE* f) const { return saveFormat!=BINARY ? XMLLoadSave::saveFileStream(f) : LoadSave::saveFileStream(f); }
 	
 	//! values to pass to setSaveFormat()
 	enum SaveFormat {
@@ -223,14 +265,14 @@
 	float magnitude; //!< the current "strength" of the event/stimuli... MAKE SURE this gets set to ZERO IF event is DEACTIVATE
 	unsigned int timestamp; //!< the time the event was created - set automatically by constructor
 
-	mutable SaveFormat saveFormat; //!< controls the format used during the next call to SaveBuffer() (packed binary or XML)
+	mutable SaveFormat saveFormat; //!< controls the format used during the next call to saveBuffer() (packed binary or XML)
 
 	bool nameisgen; //!< tracks whether the current name (stim_id) was generated by genName() (true) or setName() (false)
 	virtual void genName(); //!< calls setName() with a string version of sourceID, decimal notation
 
 	EventGeneratorID_t genID; //!< generator ID, see EventGeneratorID_t
 	EventTypeID_t typeID; //!< type ID, see EventTypeID_t
-	unsigned int sourceID; /*!< @brief the source ID for this event
+	size_t sourceID;       /*!< @brief the source ID for this event
 													* 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 */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/EventGeneratorBase.cc ./Events/EventGeneratorBase.cc
--- ../Tekkotsu_2.4.1/Events/EventGeneratorBase.cc	2005-06-01 01:47:46.000000000 -0400
+++ ./Events/EventGeneratorBase.cc	2006-09-22 18:29:02.000000000 -0400
@@ -99,6 +99,7 @@
 EventGeneratorBase::addSrcListener() {
 	if(isListening || getListenGeneratorID()==EventBase::numEGIDs)
 		return;
+	isListening=true;
 	switch(specificity) {
 	case GENERATOR:
 		erouter->addListener(this,getListenGeneratorID());
@@ -112,13 +113,13 @@
 		erouter->addListener(this,getListenGeneratorID(),getListenSourceID(),getListenTypeID());
 		break;
 	}
-	isListening=true;
 }
 
 void
 EventGeneratorBase::removeSrcListener() {
 	if(!isListening)
 		return;
+	isListening=false;
 	switch(specificity) {
 	case GENERATOR:
 		erouter->removeListener(this,getListenGeneratorID());
@@ -130,7 +131,6 @@
 		erouter->removeListener(this,getListenGeneratorID(),getListenSourceID(),getListenTypeID());
 		break;
 	}
-	isListening=false;
 }
 
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/EventRouter.cc ./Events/EventRouter.cc
--- ../Tekkotsu_2.4.1/Events/EventRouter.cc	2005-08-16 14:43:04.000000000 -0400
+++ ./Events/EventRouter.cc	2006-09-27 17:15:51.000000000 -0400
@@ -3,33 +3,35 @@
 #include "Behaviors/BehaviorBase.h"
 #include "Shared/ProjectInterface.h"
 #include <algorithm>
+#include "Events/TimerEvent.h"
 
 EventRouter * erouter=NULL;
 
 EventRouter::EventRouter()
-	: timers(), events(), doSendBufferLock(false), lastBufClear(0), buffertime(0), trappers(), listeners()
+	: timers(), trappers(), listeners(), postings()
 {}
 
+void EventRouter::postEvent(EventBase* e) { processEvent(*e); delete e; }
+
 //! @todo handle recursive calls
 void EventRouter::processTimers() {
 	//		cout << "processTimers..." << flush;
 	unsigned int curtime=get_time();
-	if(curtime-lastBufClear>=buffertime || buffertime==1)
-		processEventBuffer();
-
 	TimerEntry curTimer(curtime);
 	timer_it_t last_it=upper_bound(timers.begin(),timers.end(),&curTimer,TimerEntryPtrCmp());
 	std::vector<TimerEntry*> process(timers.begin(),last_it); //copy these out for safe keeping
 	for(timer_it_t it=process.begin(); it!=process.end(); it++) //increment the timers we're processing
-		if((*it)->repeat)
-			(*it)->next+=(*it)->delay;
-		else
+		if(!(*it)->repeat)
 			(*it)->next=(unsigned int)-1;
+		else if((*it)->delay==0)
+			(*it)->next=curtime+1;
+		else while((*it)->next<=curtime)
+			(*it)->next+=(*it)->delay;
 	sort(timers.begin(),last_it,TimerEntryPtrCmp()); //re-sort the timers we're processing (at the beginning of timers)
 	inplace_merge(timers.begin(),last_it,timers.end(),TimerEntryPtrCmp()); //now do a merge of the sorted processed stuff and the rest of the list (which is still sorted)
 	//	if(process.size()>0) chkTimers();
 	for(timer_it_t it=process.begin(); it!=process.end(); it++) { // process the timers we say we're going to, can no longer assume anything about the state of the world
-		EventBase e(EventBase::timerEGID,(*it)->sid,EventBase::statusETID,(*it)->next);
+		TimerEvent e((*it)->el,EventBase::timerEGID,(*it)->sid,EventBase::statusETID,(*it)->next-(*it)->delay);
 		try {
 			(*it)->el->processEvent(e);
 		} catch(const std::exception& ex) {
@@ -49,6 +51,7 @@
 			if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,msg.c_str(),NULL))
 				throw;
 		}
+		postEvent(e);
 	}
 	//	if(process.size()>0) chkTimers();
 	static const TimerEntry deadTimer((unsigned int)-1); // matches all the dead ones as set in the incrementation phase
@@ -64,10 +67,6 @@
  *  a delay of 0 with repeating will cause an event to be sent at every opportunity, use sparingly\n
  *  a delay of -1U will call removeTimer() if it already exists, otherwise is ignored\n
  *
- *  To add a timer, you can also call addListener() with EventBase::timerEGID and the sid
- *  and delay (in the EventBase::duration field) - this method will simply cause this
- *  function to be called internally.
- *
  *  @param el the EventListener to send the timer event to
  *  @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
@@ -99,7 +98,7 @@
 			delete *it;
 			*it=NULL;
 		}
-	timers.erase(remove(timers.begin(),timers.end(),(const TimerEntry*)NULL),timers.end());
+	timers.erase(std::remove(timers.begin(),timers.end(),(const TimerEntry*)NULL),timers.end());
 }
 
 void EventRouter::removeTimer(EventListener* el, unsigned int sid) {
@@ -118,52 +117,37 @@
 }
 
 void EventRouter::addListener(EventListener* el, EventBase::EventGeneratorID_t egid) {
-	if(egid==EventBase::timerEGID)
-		printf("WARNING: The use of addListener with timerEGID is deprecated,\n"
-								 "         please see http://bugs.tekkotsu.org/show_bug.cgi?id=89\n");
 	bool hadListener=hasListeners(egid);
 	listeners.addMapping(el,egid); 
 	if(!hadListener)
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::activateETID,0,EventBase::EventGeneratorNames[egid],1));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::activateETID,0,EventBase::EventGeneratorNames[egid],1));
 	else
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
 }
 void EventRouter::addListener(EventListener* el, EventBase::EventGeneratorID_t egid, unsigned int sid) {
-	if(egid==EventBase::timerEGID)
-		printf("WARNING: The use of addListener with timerEGID is deprecated,\n"
-								 "         please see http://bugs.tekkotsu.org/show_bug.cgi?id=89\n");
 	bool hadListener=hasListeners(egid);
 	for(unsigned int et=0; et<EventBase::numETIDs; et++)
 		listeners.addMapping(el,egid,sid,(EventBase::EventTypeID_t)et);
 	if(!hadListener)
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::activateETID,0,EventBase::EventGeneratorNames[egid],1));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::activateETID,0,EventBase::EventGeneratorNames[egid],1));
 	else
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
+		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) {
-	if(egid==EventBase::timerEGID)
-		printf("WARNING: The use of addListener with timerEGID is deprecated,\n"
-								 "         please see http://bugs.tekkotsu.org/show_bug.cgi?id=89\n");
 	bool hadListener=hasListeners(egid);
 	listeners.addMapping(el,egid,sid,etid);
 	if(!hadListener)
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::activateETID,0,EventBase::EventGeneratorNames[egid],1));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::activateETID,0,EventBase::EventGeneratorNames[egid],1));
 	else
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
 }
 void EventRouter::addListener(EventListener* el, const EventBase& e) {
-	if(e.getGeneratorID()==EventBase::timerEGID) {
-		printf("WARNING: The use of addListener with timerEGID is deprecated,\n"
-								 "         please see http://bugs.tekkotsu.org/show_bug.cgi?id=89\n");
-		addTimer(el,e.getSourceID(),e.getDuration());
-	} else {
-		bool hadListener=hasListeners(e.getGeneratorID());
-		listeners.addMapping(el,e.getGeneratorID(),e.getSourceID(),e.getTypeID());
-		if(!hadListener)
-			postEvent(new EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::activateETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],1));
-		else
-			postEvent(new EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::statusETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],1));
-	}
+	bool hadListener=hasListeners(e.getGeneratorID());
+	listeners.addMapping(el,e.getGeneratorID(),e.getSourceID(),e.getTypeID());
+	if(!hadListener)
+		postEvent(EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::activateETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],1));
+	else
+		postEvent(EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::statusETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],1));
 }
 
 void EventRouter::removeListener(EventListener* el) {
@@ -173,93 +157,67 @@
 			continue; //nothing was removed, don't want to clean up or throw an event
 		listeners.clean(egid);
 		if(!hasListeners(egid))
-			postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
+			postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
 		else
-			postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
+			postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
 	}
-	removeTimer(el); //this should go away when we implement bug 89
 }
 void EventRouter::removeListener(EventListener* el, EventBase::EventGeneratorID_t egid) {
-	if(egid==EventBase::timerEGID) {
-		printf("WARNING: The use of removeListener with timerEGID is deprecated,\n"
-		       "         please see http://bugs.tekkotsu.org/show_bug.cgi?id=89\n");
-		removeTimer(el);
-	} else {
-		if(!listeners.removeMapping(el,egid))
-			return; //nothing was removed, don't want to clean up or throw an event
-		listeners.clean(egid);
-		if(!hasListeners(egid))
-			postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
-		else
-			postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
-	}
+	if(!listeners.removeMapping(el,egid))
+		return; //nothing was removed, don't want to clean up or throw an event
+	listeners.clean(egid);
+	if(!hasListeners(egid))
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
+	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) {
-	if(egid==EventBase::timerEGID) {
-		printf("WARNING: The use of removeListener with timerEGID is deprecated,\n"
-		       "         please see http://bugs.tekkotsu.org/show_bug.cgi?id=89\n");
-		removeTimer(el,sid);
-	} else {
-		unsigned int removed=0;
-		for(unsigned int et=0; et<EventBase::numETIDs; et++)
-			removed+=listeners.removeMapping(el,egid,sid,(EventBase::EventTypeID_t)et);
-		if(!removed)
-			return; //nothing was removed, don't want to clean up or throw an event
-		listeners.clean(egid);
-		if(!hasListeners(egid))
-			postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
-		else
-			postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
-	}
+	unsigned int removed=0;
+	for(unsigned int et=0; et<EventBase::numETIDs; et++)
+		removed+=listeners.removeMapping(el,egid,sid,(EventBase::EventTypeID_t)et);
+	if(!removed)
+		return; //nothing was removed, don't want to clean up or throw an event
+	listeners.clean(egid);
+	if(!hasListeners(egid))
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
+	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) {
-	if(egid==EventBase::timerEGID) {
-		printf("WARNING: The use of removeListener with timerEGID is deprecated,\n"
-		       "         please see http://bugs.tekkotsu.org/show_bug.cgi?id=89\n");
-		if(etid==EventBase::statusETID)
-			removeTimer(el,sid);
-	} else {
-		if(!listeners.removeMapping(el,egid,sid,etid))
-			return; //nothing was removed, don't want to clean up or throw an event
-		listeners.clean(egid);
-		if(!hasListeners(egid))
-			postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
-		else
-			postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
-	}
+	if(!listeners.removeMapping(el,egid,sid,etid))
+		return; //nothing was removed, don't want to clean up or throw an event
+	listeners.clean(egid);
+	if(!hasListeners(egid))
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
+	else
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
 }
 void EventRouter::removeListener(EventListener* el, const EventBase& e) {
-	if(e.getGeneratorID()==EventBase::timerEGID) {
-		printf("WARNING: The use of removeListener with timerEGID is deprecated,\n"
-		       "         please see http://bugs.tekkotsu.org/show_bug.cgi?id=89\n");
-		removeTimer(el,e.getSourceID());
-	} else {
-		if(!listeners.removeMapping(el,e.getGeneratorID(),e.getSourceID(),e.getTypeID()))
-			return; //nothing was removed, don't want to clean up or throw an event
-		listeners.clean(e.getGeneratorID());
-		if(!hasListeners(e.getGeneratorID()))
-			postEvent(new EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::deactivateETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],0));
-		else
-			postEvent(new EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::statusETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],1));
-	}
+	if(!listeners.removeMapping(el,e.getGeneratorID(),e.getSourceID(),e.getTypeID()))
+		return; //nothing was removed, don't want to clean up or throw an event
+	listeners.clean(e.getGeneratorID());
+	if(!hasListeners(e.getGeneratorID()))
+		postEvent(EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::deactivateETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],0));
+	else
+		postEvent(EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::statusETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],1));
 }
 
 void EventRouter::addTrapper(EventTrapper* el, const EventBase& e) {
 	bool hadListener=hasListeners(e.getGeneratorID());
 	trappers.addMapping(el,e.getGeneratorID(),e.getSourceID(),e.getTypeID());
 	if(!hadListener)
-		postEvent(new EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::activateETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],1));
+		postEvent(EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::activateETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],1));
 	else
-		postEvent(new EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::statusETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],1));
+		postEvent(EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::statusETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],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) {
 	bool hadListener=hasListeners(egid);
 	trappers.addMapping(el,egid);
 	if(!hadListener)
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::activateETID,0,EventBase::EventGeneratorNames[egid],1));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::activateETID,0,EventBase::EventGeneratorNames[egid],1));
 	else
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
+		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) {
@@ -267,18 +225,18 @@
 	for(unsigned int et=0; et<EventBase::numETIDs; et++)
 		trappers.addMapping(el,egid,sid,(EventBase::EventTypeID_t)et);
 	if(!hadListener)
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::activateETID,0,EventBase::EventGeneratorNames[egid],1));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::activateETID,0,EventBase::EventGeneratorNames[egid],1));
 	else
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
+		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) {
 	bool hadListener=hasListeners(egid);
 	trappers.addMapping(el,egid,sid,etid);
 	if(!hadListener)
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::activateETID,0,EventBase::EventGeneratorNames[egid],1));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::activateETID,0,EventBase::EventGeneratorNames[egid],1));
 	else
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
+		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. */
@@ -293,18 +251,18 @@
 		return; //nothing was removed, don't want to clean up or throw an event
 	trappers.clean(e.getGeneratorID());
 	if(!hasListeners(e.getGeneratorID()))
-		postEvent(new EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::deactivateETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],0));
+		postEvent(EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::deactivateETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],0));
 	else
-		postEvent(new EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::statusETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],1));
+		postEvent(EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::statusETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],1));
 }
 void EventRouter::removeTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid) {
 	if(!trappers.removeMapping(el,egid))
 		return; //nothing was removed, don't want to clean up or throw an event
 	trappers.clean(egid);
 	if(!hasListeners(egid))
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
 	else
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
 }
 void EventRouter::removeTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, unsigned int sid) {
 	int removed=0;
@@ -314,18 +272,18 @@
 		return; //nothing was removed, don't want to clean up or throw an event
 	trappers.clean(egid);
 	if(!hasListeners(egid))
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
 	else
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
+		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) {
 	if(!trappers.removeMapping(el,egid,sid,etid))
 		return; //nothing was removed, don't want to clean up or throw an event
 	trappers.clean(egid);
 	if(!hasListeners(egid))
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::deactivateETID,0,EventBase::EventGeneratorNames[egid],0));
 	else
-		postEvent(new EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
+		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
 }
 
 void EventRouter::removeTrapper(EventTrapper* el) {
@@ -333,87 +291,74 @@
 		removeTrapper(el,(EventBase::EventGeneratorID_t)eg);
 }
 
-void EventRouter::processEventBuffer() { //clears buffered events
-	if(events.size()>0)
-		doSendBuffer();
-}
-void EventRouter::doSendBuffer() {
-	if(doSendBufferLock) {
-		std::cout << "*** WARNING recursive call to doSendBuffer()" << std::endl;
-		return;
-	}
-	doSendBufferLock=true;
-	unsigned int start=get_time();
-	//	doSendEvent(EventBase(EventBase::eventRouterEGID,0,EventBase::activateETID,0));
-	//important to use indexes instead of iterators in case the event listeners decide to post more events during processing
-	for(unsigned int i=0; i<events.size(); i++) {
-		doSendEvent(*events[i]);
-		delete events[i];
+void EventRouter::processEvent(const EventBase& e) {
+	PostingStatus ps(trappers,listeners,e);
+	postings.push(&ps);
+	while(postings.size()>0) {
+#ifdef DEBUG
+		unsigned int presize=postings.size();
+		postings.front()->process();
+		ASSERT(postings.size()==0 || postings.size()==presize,"partial queue completion?");
+#else
+		postings.front()->process();
+#endif
+		if(postings.size()>0) // in case a sub-post took over and finished off the queue
+			postings.pop();
 	}
-	events.erase(events.begin(),events.end());
-	doSendBufferLock=false;
-	lastBufClear=start;
-	//	doSendEvent(EventBase(EventBase::eventRouterEGID,0,EventBase::deactivateETID,get_time()-start));
 }
 
-void EventRouter::processEvent(const EventBase& e) {
-	// want to make sure we don't send events out of order...
-	if(events.size()>0)
-		doSendBuffer();
-	doSendEvent(e);
-}
-void EventRouter::doSendEvent(const EventBase& e) {
-	//	cout << "doSendEvent("<<e.getName()<<")..." << flush;
-	std::vector<EventTrapper*> t;
-	trappers.getMapping(e,t);
-	for(std::vector<EventTrapper*>::iterator it=t.begin(); it!=t.end(); it++)
-		if(trappers.verifyMapping(*it,e)) {
-			try {
-				if((*it)->trapEvent(e))
-					return;
-			} catch(const std::exception& ex) {
-				std::string msg="Occurred while processing event "+e.getName()+" by ";
-				if(BehaviorBase * beh=dynamic_cast<BehaviorBase*>(*it))
-					msg+="trapper "+beh->getName();
-				else
-					msg+="unnamed EventTrapper";
-				if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,msg.c_str(),&ex))
-					throw;
-			} catch(...) {
-				std::string msg="Occurred while processing event "+e.getName()+" by ";
-				if(BehaviorBase * beh=dynamic_cast<BehaviorBase*>(*it))
-					msg+="trapper "+beh->getName();
-				else
-					msg+="unnamed EventTrapper";
-				if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,msg.c_str(),NULL))
-					throw;
-			}
+void EventRouter::PostingStatus::process() {
+	while(tit!=t.end()) {
+		// increment before processing so if a new post is done during the processing, we pick up on the *next* entry
+		EventTrapper * et=*tit++;
+		if(!trappers.verifyMapping(et,e))
+			continue;
+		try {
+			if(et->trapEvent(e))
+				return;
+		} catch(const std::exception& ex) {
+			std::string msg="Occurred while processing event "+e.getName()+" by ";
+			if(BehaviorBase * beh=dynamic_cast<BehaviorBase*>(et))
+				msg+="trapper "+beh->getName();
+			else
+				msg+="unnamed EventTrapper";
+			if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,msg.c_str(),&ex))
+				throw;
+		} catch(...) {
+			std::string msg="Occurred while processing event "+e.getName()+" by ";
+			if(BehaviorBase * beh=dynamic_cast<BehaviorBase*>(et))
+				msg+="trapper "+beh->getName();
+			else
+				msg+="unnamed EventTrapper";
+			if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,msg.c_str(),NULL))
+				throw;
 		}
-	std::vector<EventListener*> l;
-	listeners.getMapping(e,l);
-	for(std::vector<EventListener*>::iterator it=l.begin(); it!=l.end(); it++)
-		if(listeners.verifyMapping(*it,e)) {
-			try {
-				(*it)->processEvent(e);
-			} catch(const std::exception& ex) {
-				std::string msg="Occurred while processing event "+e.getName()+" by ";
-				if(BehaviorBase * beh=dynamic_cast<BehaviorBase*>(*it))
-					msg+="listener "+beh->getName();
-				else
-					msg+="unnamed EventListener";
-				if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,msg.c_str(),&ex))
-					throw;
-			} catch(...) {
-				std::string msg="Occurred while processing event "+e.getName()+" by ";
-				if(BehaviorBase * beh=dynamic_cast<BehaviorBase*>(*it))
-					msg+="listener "+beh->getName();
-				else
-					msg+="unnamed EventListener";
-				if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,msg.c_str(),NULL))
-					throw;
-			}
+	}
+	while(lit!=l.end()) {
+		// increment before processing so if a new post is done during the processing, we pick up on the *next* entry
+		EventListener * el=*lit++;
+		if(!listeners.verifyMapping(el,e))
+			continue;
+		try {
+			el->processEvent(e);
+		} catch(const std::exception& ex) {
+			std::string msg="Occurred while processing event "+e.getName()+" by ";
+			if(BehaviorBase * beh=dynamic_cast<BehaviorBase*>(el))
+				msg+="listener "+beh->getName();
+			else
+				msg+="unnamed EventListener";
+			if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,msg.c_str(),&ex))
+				throw;
+		} catch(...) {
+			std::string msg="Occurred while processing event "+e.getName()+" by ";
+			if(BehaviorBase * beh=dynamic_cast<BehaviorBase*>(el))
+				msg+="listener "+beh->getName();
+			else
+				msg+="unnamed EventListener";
+			if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,msg.c_str(),NULL))
+				throw;
 		}
-	//	cout << "done." << flush;
+	}
 }
 
 EventRouter::EventMapper::EventMapper() {
@@ -441,7 +386,7 @@
 bool EventRouter::EventMapper::removeMapping(void* el, EventBase::EventGeneratorID_t egid) {
 	// remove listener from allevents
 	unsigned int numlist=allevents[egid].size();
-	allevents[egid].erase(remove(allevents[egid].begin(),allevents[egid].end(),el),allevents[egid].end());
+	allevents[egid].erase(std::remove(allevents[egid].begin(),allevents[egid].end(),el),allevents[egid].end());
 	bool hadListener=allevents[egid].size()!=numlist;
 	
 	// now remove listener from all of the filtered events
@@ -451,7 +396,7 @@
 			SIDtoListenerVectorMap_t::iterator mapit=mapping->begin();
 			for(mapit=mapping->begin(); mapit!=mapping->end(); mapit++) {// go through each sourceID, delete EL
 				std::vector<void*> * v=&(*mapit).second;
-				std::vector<void*>::iterator last=remove(v->begin(),v->end(),el);
+				std::vector<void*>::iterator last=std::remove(v->begin(),v->end(),el);
 				if(last!=v->end()) {
 					hadListener=true;
 					v->erase(last,v->end());
@@ -469,7 +414,7 @@
 		SIDtoListenerVectorMap_t::iterator mapit=mapping->find(sid);
 		if(mapit!=mapping->end()) {
 			std::vector<void*> * v=&(*mapit).second;
-			std::vector<void*>::iterator last=remove(v->begin(),v->end(),el);
+			std::vector<void*>::iterator last=std::remove(v->begin(),v->end(),el);
 			if(last!=v->end()) {
 				hadListener=true;
 				v->erase(last,v->end());
@@ -527,13 +472,13 @@
 	}
 }
 
-bool EventRouter::EventMapper::hasMapping(EventBase::EventGeneratorID_t egid) {
+bool EventRouter::EventMapper::hasMapping(EventBase::EventGeneratorID_t egid) const {
 	if(allevents[egid].size()>0)
 		return true;
 	for(unsigned int et=0; et<EventBase::numETIDs; et++) {
-		SIDtoListenerVectorMap_t* mapping=filteredevents[egid][et];
+		const SIDtoListenerVectorMap_t* mapping=filteredevents[egid][et];
 		if(mapping!=NULL) {
-			SIDtoListenerVectorMap_t::iterator mapit=mapping->begin();
+			SIDtoListenerVectorMap_t::const_iterator mapit=mapping->begin();
 			for(mapit=mapping->begin(); mapit!=mapping->end(); mapit++)
 				if((*mapit).second.size()>0)
 					return true;
@@ -542,13 +487,13 @@
 	return false;
 }
 
-bool EventRouter::EventMapper::hasMapping(EventBase::EventGeneratorID_t egid, unsigned int sid) {
+bool EventRouter::EventMapper::hasMapping(EventBase::EventGeneratorID_t egid, unsigned int sid) const {
 	if(allevents[egid].size()>0)
 		return true;
 	for(unsigned int et=0; et<EventBase::numETIDs; et++) {
-		SIDtoListenerVectorMap_t* mapping=filteredevents[egid][et];
+		const SIDtoListenerVectorMap_t* mapping=filteredevents[egid][et];
 		if(mapping!=NULL) {
-			SIDtoListenerVectorMap_t::iterator mapit=mapping->find(sid);
+			SIDtoListenerVectorMap_t::const_iterator mapit=mapping->find(sid);
 			if(mapit!=mapping->end() && (*mapit).second.size()>0)
 				return true;
 		}
@@ -556,12 +501,12 @@
 	return false;
 }
 
-bool EventRouter::EventMapper::hasMapping(EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) {
+bool EventRouter::EventMapper::hasMapping(EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) const {
 	if(allevents[egid].size()>0)
 		return true;
-	SIDtoListenerVectorMap_t* mapping=filteredevents[egid][etid];
+	const SIDtoListenerVectorMap_t* mapping=filteredevents[egid][etid];
 	if(mapping!=NULL) {
-		SIDtoListenerVectorMap_t::iterator mapit=mapping->find(sid);
+		SIDtoListenerVectorMap_t::const_iterator mapit=mapping->find(sid);
 		if(mapit!=mapping->end())
 			return ((*mapit).second.size()>0);
 	}
@@ -569,38 +514,38 @@
 }
 
 template<class T>
-void EventRouter::EventMapper::getMapping(const EventBase& e, std::vector<T*>& ls) {
+void EventRouter::EventMapper::getMapping(const EventBase& e, std::vector<T*>& ls) const {
 	// first get all the filtered subscribers (tricky!)
-	std::vector<void*>* elv=NULL;
-	SIDtoListenerVectorMap_t* sidtovm=filteredevents[e.getGeneratorID()][e.getTypeID()];
+	const std::vector<void*>* elv=NULL;
+	const SIDtoListenerVectorMap_t* sidtovm=filteredevents[e.getGeneratorID()][e.getTypeID()];
 	if(sidtovm!=NULL) { // if there's a map (at least one EL is filtering on this EGID and ETID)
-		SIDtoListenerVectorMap_t::iterator mapit=sidtovm->find(e.getSourceID()); // find listening for this source id
+		SIDtoListenerVectorMap_t::const_iterator mapit=sidtovm->find(e.getSourceID()); // find listening for this source id
 		if(mapit!=sidtovm->end()) { // if there's at least one is filtering on this sourceID as well
 			elv=&(*mapit).second; // now go through them all
-			for(std::vector<void*>::iterator elit=elv->begin(); elit!=elv->end(); elit++)
+			for(std::vector<void*>::const_iterator elit=elv->begin(); elit!=elv->end(); elit++)
 				ls.push_back(static_cast<T*>(*elit));
 		}
 	}
 	// now get the 'all events' subscribers
 	elv=&allevents[e.getGeneratorID()];
-	for(std::vector<void*>::iterator elit=elv->begin(); elit!=elv->end(); elit++)
+	for(std::vector<void*>::const_iterator elit=elv->begin(); elit!=elv->end(); elit++)
 		ls.push_back(static_cast<T*>(*elit));
 }
 
-bool EventRouter::EventMapper::verifyMapping(void * listener, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) {
+bool EventRouter::EventMapper::verifyMapping(void * listener, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) const {
 	// first check the 'all events' subscribers
-	std::vector<void*>* elv=&allevents[egid];
-	for(std::vector<void*>::iterator elit=elv->begin(); elit!=elv->end(); elit++)
+	const std::vector<void*>* elv=&allevents[egid];
+	for(std::vector<void*>::const_iterator elit=elv->begin(); elit!=elv->end(); elit++)
 		if(*elit==listener)
 			return true;
 	
 	// then check all the filtered subscribers (tricky!)
-	SIDtoListenerVectorMap_t* sidtovm=filteredevents[egid][etid];
+	const SIDtoListenerVectorMap_t* sidtovm=filteredevents[egid][etid];
 	if(sidtovm!=NULL) { // if there's a map (at least one EL is filtering on this EGID and ETID)
-		SIDtoListenerVectorMap_t::iterator mapit=sidtovm->find(sid); // find listening for this source id
+		const SIDtoListenerVectorMap_t::const_iterator mapit=sidtovm->find(sid); // find listening for this source id
 		if(mapit!=sidtovm->end()) { // if there's at least one is filtering on this sourceID as well
 			elv=&(*mapit).second; // now go through them all
-			for(std::vector<void*>::iterator elit=elv->begin(); elit!=elv->end(); elit++)
+			for(std::vector<void*>::const_iterator elit=elv->begin(); elit!=elv->end(); elit++)
 				if(*elit==listener)
 					return true;
 		}
@@ -610,30 +555,30 @@
 	return false;
 }
 
-bool EventRouter::EventMapper::verifyMappingAll(void* listener, EventBase::EventGeneratorID_t egid) {
-	std::vector<void*>* elv=&allevents[egid];
-	for(std::vector<void*>::iterator elit=elv->begin(); elit!=elv->end(); elit++)
+bool EventRouter::EventMapper::verifyMappingAll(void* listener, EventBase::EventGeneratorID_t egid) const {
+	const std::vector<void*>* elv=&allevents[egid];
+	for(std::vector<void*>::const_iterator elit=elv->begin(); elit!=elv->end(); elit++)
 		if(*elit==listener)
 			return true;
 	// if not in the all listeners, can't be listening for *every* source id
 	return false;
 }
 
-bool EventRouter::EventMapper::verifyMappingAny(void* listener, EventBase::EventGeneratorID_t egid) {
+bool EventRouter::EventMapper::verifyMappingAny(void* listener, EventBase::EventGeneratorID_t egid) const {
 	// first check the 'all events' subscribers
-	std::vector<void*>* elv=&allevents[egid];
-	for(std::vector<void*>::iterator elit=elv->begin(); elit!=elv->end(); elit++)
+	const std::vector<void*>* elv=&allevents[egid];
+	for(std::vector<void*>::const_iterator elit=elv->begin(); elit!=elv->end(); elit++)
 		if(*elit==listener)
 			return true;
 	
 	// then check all the filtered subscribers (tricky!)
 	for(unsigned int et=0; et<EventBase::numETIDs; et++) {
-		SIDtoListenerVectorMap_t* sidtovm=filteredevents[egid][et];
+		const SIDtoListenerVectorMap_t* sidtovm=filteredevents[egid][et];
 		if(sidtovm!=NULL) { // if there's a map (at least one EL is filtering on this EGID and ETID)
-			SIDtoListenerVectorMap_t::iterator mapit=sidtovm->begin(); // for each of the source ids
+			SIDtoListenerVectorMap_t::const_iterator mapit=sidtovm->begin(); // for each of the source ids
 			for(;mapit!=sidtovm->end();mapit++) {
 				elv=&(*mapit).second; // now go through them all
-				for(std::vector<void*>::iterator elit=elv->begin(); elit!=elv->end(); elit++)
+				for(std::vector<void*>::const_iterator elit=elv->begin(); elit!=elv->end(); elit++)
 					if(*elit==listener)
 						return true;
 			}
@@ -644,26 +589,26 @@
 	return false;
 }
 
-bool EventRouter::EventMapper::verifyMappingAll(void* listener, EventBase::EventGeneratorID_t egid, unsigned int sid) {
+bool EventRouter::EventMapper::verifyMappingAll(void* listener, EventBase::EventGeneratorID_t egid, unsigned int sid) const {
 	// first check the 'all events' subscribers
-	std::vector<void*>* elv=&allevents[egid];
-	for(std::vector<void*>::iterator elit=elv->begin(); elit!=elv->end(); elit++)
+	const std::vector<void*>* elv=&allevents[egid];
+	for(std::vector<void*>::const_iterator elit=elv->begin(); elit!=elv->end(); elit++)
 		if(*elit==listener)
 			return true;
 	
 	// then check all the filtered subscribers (tricky!)
 	// must be found in ALL etids
 	for(unsigned int et=0; et<EventBase::numETIDs; et++) {
-		SIDtoListenerVectorMap_t* sidtovm=filteredevents[egid][et];
+		const SIDtoListenerVectorMap_t* sidtovm=filteredevents[egid][et];
 		if(sidtovm==NULL)
 			return false;
 		// there's a map (at least one EL is filtering on this EGID and ETID)
-		SIDtoListenerVectorMap_t::iterator mapit=sidtovm->find(sid); // find listening for this source id
+		const SIDtoListenerVectorMap_t::const_iterator mapit=sidtovm->find(sid); // find listening for this source id
 		if(mapit==sidtovm->end())
 			return false;
 		// there's at least one is filtering on this sourceID as well
 		elv=&(*mapit).second; // now go through them all
-		std::vector<void*>::iterator elit=elv->begin();
+		std::vector<void*>::const_iterator elit=elv->begin();
 		while(elit!=elv->end() && *elit!=listener)
 			elit++;
 		if(elit==elv->end())
@@ -675,21 +620,21 @@
 	return true;
 }
 
-bool EventRouter::EventMapper::verifyMappingAny(void* listener, EventBase::EventGeneratorID_t egid, unsigned int sid) {
+bool EventRouter::EventMapper::verifyMappingAny(void* listener, EventBase::EventGeneratorID_t egid, unsigned int sid) const {
 	// first check the 'all events' subscribers
-	std::vector<void*>* elv=&allevents[egid];
-	for(std::vector<void*>::iterator elit=elv->begin(); elit!=elv->end(); elit++)
+	const std::vector<void*>* elv=&allevents[egid];
+	for(std::vector<void*>::const_iterator elit=elv->begin(); elit!=elv->end(); elit++)
 		if(*elit==listener)
 			return true;
 	
 	// then check all the filtered subscribers (tricky!)
 	for(unsigned int et=0; et<EventBase::numETIDs; et++) {
-		SIDtoListenerVectorMap_t* sidtovm=filteredevents[egid][et];
+		const SIDtoListenerVectorMap_t* sidtovm=filteredevents[egid][et];
 		if(sidtovm!=NULL) { // if there's a map (at least one EL is filtering on this EGID and ETID)
-			SIDtoListenerVectorMap_t::iterator mapit=sidtovm->find(sid); // find listening for this source id
+			SIDtoListenerVectorMap_t::const_iterator mapit=sidtovm->find(sid); // find listening for this source id
 			if(mapit!=sidtovm->end()) { // if there's at least one is filtering on this sourceID as well
 				elv=&(*mapit).second; // now go through them all
-				for(std::vector<void*>::iterator elit=elv->begin(); elit!=elv->end(); elit++)
+				for(std::vector<void*>::const_iterator elit=elv->begin(); elit!=elv->end(); elit++)
 					if(*elit==listener)
 						return true;
 			}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/EventRouter.h ./Events/EventRouter.h
--- ../Tekkotsu_2.4.1/Events/EventRouter.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Events/EventRouter.h	2006-10-03 17:09:04.000000000 -0400
@@ -3,47 +3,50 @@
 #define INCLUDED_EventRouter_h
 
 #include <vector>
-#include <list>
+#include <queue>
 #include <map>
 #include <algorithm>
 #include "EventListener.h"
 #include "EventTrapper.h"
 #include "Shared/get_time.h"
 #include "Shared/debuget.h"
+#include "Shared/attributes.h"
 #include <iostream>
 
 //! This class will handle distribution of events as well as management of timers
 /*! Classes must inherit from EventListener and/or EventTrapper in order to
  *  receive events.
  *
- *  Use the global @c ::erouter EventRouter to post and subscribe to
- *  events, except if you are posting from within a MotionCommand, in
- *  which case you should use MotionCommand::postEvent() so that it
- *  will automatically be sent from the Motion process to the Main
- *  process.
+ *  Use the global ::erouter instance of EventRouter to both send (post) and receive (subscribe/listen) to
+ *  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.)
+ *
+ *  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
+ *  you can expect events with that generator ID to be of a subclass of EventBase,
+ *  such as TextMsgEvent or LocomotionEvent.  Many generators send plain
+ *  EventBase instances.
  *
  *  When multiple listeners are subscribed, the order in which an event is
- *  distributed among them looks like this:
+ *  distributed among them is:
  *  -# "Specific" listeners: any listener which specifies a particular source id.
- *     (It doesn't matter if they specify a type id or not.)
- *    - older listeners get events before younger listeners
+ *     (doesn't matter if they specified type id as well)
+ *    - older listeners get events before more recently added listeners ("FIFO")
  *  -# "General" listeners: those that subscribe to an entire generator
- *    - older listeners get events before younger listeners
+ *    - older listeners get events before more recently added listeners ("FIFO")
  *
- *  ...but if you're relying on that ordering, there should be a cleaner
+ *  ...but if you're relying on that ordering, there probably should be a cleaner
  *  way to do whatever you're doing.
  *
- *  If one behaviors unsubscribes another one during a processEvent(),
- *  that behavior may still get the "current" event before the
- *  unsubscription takes place.  This is not a prescribed behavior,
- *  and also should not be relied on one way or the other.
- *
- *  Timer events are only sent to the generator which requested them.  So if 
- *  EventListener @e A requests a timer with ID 0 at two second intervals,
- *  and EventListener @e B requests a timer with ID 0 at three second intervals,
+ *  TimerEvents are generally only sent to the generator which requested them.  So if 
+ *  EventListener @e A requests a timer (see addTimer()) with ID 0 at two second intervals,
+ *  and @e B requests a timer with ID 0 at three second intervals,
  *  each will still only receive the timers they requested - no cross talk.
  *  The timer generator is unique in this regard, which is why it is built in
- *  as an integral component of the EventRouter.  All other events are broadcast.
+ *  as an integral component of the EventRouter.  However, EventListener @e A
+ *  <b>can</b> receive @e B's timers if it specifically wants to, via addListener().  See "Timers" below.
  *
  *  If an EventListener/EventTrapper subscribes to the same event source multiple
  *  times, it will receive multiple copies of the event.  However, the first call
@@ -57,36 +60,128 @@
  *    - If removeListener(&A,buttonEGID,0) is called, both of (buttonEGID,0,*)
  *      are removed, but (buttonEGID,*,*) would be untouched.
  *
- *  The buffered event distribution has not been tested thoroughly,
- *  and should be considered deprecated.
+ *  <h3>Timers</h3>
+ *  addTimer() allows you to request an TimerEvent to be sent at some later point in time,
+ *  possibly on a repeating basis.  Timers are specific to the behavior which requests
+ *  them, and you @e do @e not (and usually should not) call addListener() in order to receive a timer
+ *  event.
+ *
+ *  There is an important different between addTimer() and #addListener(timerEGID,...)!
+ *  addTimer will "create" the timer, and will send the timer to the listener
+ *  which created it when the timer expires.  This means that as long as the listener in
+ *  question does @e not call addListener(timerEGID), it will @e only receive its own timers.
+ *  In other words, with this usage there is no confusion with timer cross-talk between
+ *  listeners, because each listener is only receiving its own timers.
+ *
+ *  However, if a listener calls addListener(timerEGID), it will begin receiving @e all timer events
+ *  from throughout the system.  This allows you to have one behavior "eavesdrop" on
+ *  another's timers.  In order to determine which listener requested/created the timer,
+ *  you can use the TimerEvent::getTarget() value.
+ *
+ *  So beware that if you call both addTimer() and addListener(foo,timerEGID), 'foo' will get
+ *  two calls to processEvent() for its own timers, and one call for all other timers, and will
+ *  have to know to call TimerEvent::getTarget() to distinguish its timers from other
+ *  listener's timers (if it cares about the difference...)
+ *
+ *  Timers are sent to the requesting listener before being broadcast -- EventTrappers cannot
+ *  filter a listener's own timers, but can prevent the timer from being broadcast to other listeners.
+ *
+ *  <h3>Event processing examples:</h3>
+ *
+ *  Posting events:
+ *  @code
+ *  //method A: basic event posting (EventBase instance is sent)
+ *  erouter->postEvent(EventBase::aiEGID, 1234, EventBase::statusETID);
+ *
+ *  //method B: specific event instance is posted (have to use this style to post a subclass)
+ *  TextMsgEvent txt("hello world");
+ *  erouter->postEvent(txt);
+ *  // or can be done in one line:
+ *  erouter->postEvent(TextMsgEvent("hello world"))
+ *  @endcode
+ *
+ *  Receiving events:
+ *  @code
+ *  //given an EventListener subclass:
+ *  class YourListener : public EventListener {
+ *  public:
+ *    virtual void processEvent(const EventBase& e) {
+ *      std::cout << "Got: " << e.getName() << std::endl;
+ *    }
+ *  };
+ *
+ *  YourListener yourList;
+ *
+ *  // subscribes it to all EventBase::aiEGID events:
+ *  erouter->addListener(&yourList, EventBase::aiEGID);
+ *
+ *  // subscribes only to button activity from the head, but not other buttons:
+ *  erouter->addListener(&yourList, EventBase::buttonEGID, ERS7Info::HeadButOffset);
+ *  @endcode
+ *  Typically in a BehaviorBase subclass, you would just specify 'this' instead of '&yourList'.
+ *
+ *  <h3>Timer processing examples:</h3>
+ *
+ *  Requesting/Creating timers:
+ *  @code
+ *  YourListener yourList; // (any EventListener subclass)
+ *
+ *  // sends a timer with source ID 123 every 5 seconds to yourList:
+ *  erouter->addTimer(&yourList, 123, 5000);
+ *
+ *  // sends a timer with ID 456 after 1 second, *no repeat, one time only*
+ *  erouter->addTimer(&yourList, 456, 1000, false);
+ *
+ *  // cancels the first timer
+ *  erouter->removeTimer(&yourList, 123);
+ *
+ *  // postpone/update the second timer's settings (*doesn't* create two timers with the same ID)
+ *  erouter->addTimer(&yourList, 456, 2500, false);
+ *
+ *  @endcode
+ *  Again, typically in a BehaviorBase subclass, you would just specify 'this' instead of '&yourList'.
  *
  *  @see EventBase::EventGeneratorID_t for a complete listing of all generators,
  *  as well as instructions on how to add new generators.
+ *  @see Tutorials:
+ *    - <a href="../FirstBehavior2.html">Steps 3, 4, & 5 of Tekkotsu's First Behavior Tutorial</a>
+ *    - <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 {
  public:
-	EventRouter(); //!< Constructs the router, #buffertime defaults to 1
+	EventRouter(); //!< Constructs the router
 	virtual ~EventRouter() { reset(); removeAllTimers(); } //!< just calls reset and removeAllTimers()
+	
 	void reset() { listeners.clear(); trappers.clear(); removeAllTimers(); } //!< erases all listeners, trappers and timers, resets EventRouter
 	
-	void setBufferTime(unsigned int t) { buffertime=t; } /*!< @brief sets the time to wait between buffer clears, see EventRouter::buffertime. @param t time to wait between buffer clears @see buffertime */
-	unsigned int getBufferTime() { return buffertime; } /*!< @brief returns the time to wait between buffer clears, see EventRouter::buffertime. @return time to wait between buffer clears @see buffertime */
-
+	
 	//!@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) { if(buffertime>0) events.push_back(new EventBase(egid,sid,etid,dur)); else 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) { if(buffertime>0) events.push_back(new EventBase(egid,sid,etid,dur,n,m)); else processEvent(EventBase(egid,sid,etid,dur,n,m)); }
-	void postEvent(EventBase* e) { if(buffertime>0) events.push_back(e); else { processEvent(*e); delete e; } }
+	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)); }
+	//! 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. */
+	void postEvent(EventBase* e) ATTR_deprecated;
+	//! posts the specified event, but doesn't delete it at the end -- equivalent to processEvent(e)
+	void postEvent(const EventBase& e) { processEvent(e); }
 
 	//! determines if timers need to be posted, and posts them if so.
-	/*! Call this often to ensure accurate timers.  Also, will clear event buffer before sending
-			timer events in order to ensure correct ordering of event reception */
+	/*! Call this often to ensure accurate timers. */
 	void processTimers();
-	void processEventBuffer(); //!< clears the event buffer, deletes events as it does so.
-	void processEvent(const EventBase& e); //!< forces unbuffered - sends event *now*.  Will clear the buffer first if needed to ensure proper event ordering
+	//! sends event to its trappers & listeners, but doesn't delete the event at the end (see also postEvent())
+	/*! this posting method is supplied to allow an EventRouter to behave as a listener as 
+	 *  well -- the 'routers' really can form a sort of network, if desired.  postEvent() is
+	 *  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);
 	//@}
 
+	
 	//!@name Listener/Trapper Recall
+	
 	//! 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); }
@@ -102,7 +197,9 @@
 	bool isTrapping(EventTrapper* el, const EventBase& e) { return trappers.verifyMapping(el,e.getGeneratorID(),e.getSourceID(),e.getTypeID()); }
 	//@}
 	
+	
 	//!@name Listener/Trapper Detection
+	
 	/*!@brief <b>counts both listeners and trappers</b>, so generators can tell if it even needs to bother generating an event...*/
 	/* Generators can also subscribe to the EventBase::erouterEGID event stream if
 	 * they wish to be notified when they gain or lose listeners (particularly the
@@ -111,42 +208,52 @@
 	 * it make a sound?\n
 	 * ... 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 (egid==EventBase::timerEGID) ? timers.size()>0 : trappers.hasMapping(egid) || listeners.hasMapping(egid); }
-	bool hasListeners(EventBase::EventGeneratorID_t egid, unsigned int sid) { return (egid==EventBase::timerEGID) ? timers.size()>0 : trappers.hasMapping(egid,sid) || listeners.hasMapping(egid,sid); }
-	bool hasListeners(EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) { return (egid==EventBase::timerEGID) ? timers.size()>0 : trappers.hasMapping(egid,sid,etid) || listeners.hasMapping(egid,sid,etid); }
-	bool hasListeners(const EventBase& e) { return (e.getGeneratorID()==EventBase::timerEGID) ? timers.size()>0 : hasListeners(e.getGeneratorID(),e.getSourceID(),e.getTypeID()); }
+	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(const EventBase& e) { return hasListeners(e.getGeneratorID(),e.getSourceID(),e.getTypeID()); }
 	//@}
 
+	
 	//!@name Timer Management
-	void addTimer(EventListener* el, unsigned int sid, unsigned int delay, bool repeat=true); //!< adds a timer if it doesn't exist, or resets the timer if it already exists.
+	
+	//! 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, 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
-	void removeTimer(EventListener* el); //!< clears all pending timers for listener @a el
+	
+	//! 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 removeAllTimers(); //!< clears all timers for all listeners
+	unsigned int getNextTimer() { return (timers.size()==0 ? -1U : timers.front()->next); } //!< returns time of next timer activation
 	//@}
 
+	
 	//!@name Listener Management
+	
 	//! 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
-	//! Adds a listener for a specific source id and type from a given event generator, adding a Timer event will invoke addTimer(@a el, @a e.getSourceID(), @a e.getDuration(), @c true)
-	void addListener(EventListener* el, const EventBase& e); 
+	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
 
-	//! stops sending ALL events to the listener, including timers
+	//! 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.
-	//! stops sending specified events from the generator to the listener.  If a timer is passed it will invoke removeTimer(@a el, @a e.getSourceID())
-	void removeListener(EventListener* el, const EventBase& e);
+	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
+	
 	//! Adds a trapper for a specific source id and type from a given event generator
-	/*! Note that since timers are not broadcast, they cannot be trapped.  Only the EventListener which requested the timer will receive that timer. */
+	/*! 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
@@ -164,18 +271,9 @@
 	//@}
 
  protected:
-	void doSendBuffer(); //!< does the work of clearing the buffer (calls doSendEvent() )
-	
-	//! does the work of sending an event
-	/*! Be aware this is an O(n^2) where n is the number of listeners for a particular event.
-	 *  This is because after each call to processEvent, the list of listeners could have changed
-	 *  so each listener much be verified before it is sent an event.  New listeners won't get the
-	 *  current event, but neither should listeners which have just be removed */
-	void doSendEvent(const EventBase& e); 
-
 	//! Contains all the information needed to maintain a timer by the EventRouter
 	struct TimerEntry {
-		//! constructors an entry using the given value for next - useful for with TimerEntryPtrCmp
+		//! 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) {}
@@ -227,14 +325,6 @@
 		}
 		std::cout << std::endl;
 	}
-
-	std::vector<EventBase*> events;     //!< used to store buffered events
-	bool doSendBufferLock;              //!< in case of recursive calls to processEventBuffer()/doSendBuffer()
-	unsigned int lastBufClear;          //!< time of last event buffer clear
-	unsigned int buffertime;            //!< The time between clearings of the buffer
-																			/*!< - 0 will not use the buffer, events are routed upon posting
-																			 *   - 1 will clear the buffer at next call to processTimers() or processEventBuffer()
-																			 *   - a larger value will cause a delay of that number of milliseconds since the last clearing */
 	
 	//! Does the actual storage of the mapping between EventBase's and the EventListeners/EventTrappers who should receive them
 	/*! Actually only stores void*'s, so it's more general than just Listeners or Trappers */
@@ -263,9 +353,9 @@
 		/*! ... if a tree falls in a forest, and there's no one around to see it, does it make a sound?\n
 			  ... 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);
-		bool hasMapping(EventBase::EventGeneratorID_t egid, unsigned int sid);
-		bool hasMapping(EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid);
+		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;
 		//@}
 
 		//! builds a list of all listeners which should receive the event, templated to typecast the pointers for you
@@ -274,34 +364,34 @@
 		 *  @a listeners is not cleared prior to building, new listeners are pushed on end\n
 		 *  Results are in the order: all specific matches first, all generator listeners second, in order they were added to the EventMapper.*/
 		template<class T>
-		void getMapping(const EventBase& e, std::vector<T*>& listeners);
+		void getMapping(const EventBase& e, std::vector<T*>& listeners) const;
 
 		//! Used to make sure that the specified listener exists for the given event
 		/*! This is needed because after we call processEvent on a lister, we can't assume
 		 *  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, const EventBase& e) { return verifyMapping(listener,e.getGeneratorID(),e.getSourceID(),e.getTypeID()); }
+		bool verifyMapping(void * listener, const EventBase& e) const { return verifyMapping(listener,e.getGeneratorID(),e.getSourceID(),e.getTypeID()); }
 		//! Used to make sure that the specified listener exists for the given event
 		/*! This is needed because after we call processEvent on a lister, we can't assume
 		 *  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);
+		bool verifyMapping(void * listener, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) const;
 
 		//! Needed to complete EventRouter::isListening suite
 		/*! Only checks #allevents */
-		bool verifyMappingAll(void * listener, EventBase::EventGeneratorID_t egid);
+		bool verifyMappingAll(void * listener, EventBase::EventGeneratorID_t egid) const;
 		//! Needed to complete EventRouter::isListening suite
 		/*! Checks both #allevents and #filteredevents */
-		bool verifyMappingAny(void * listener, EventBase::EventGeneratorID_t egid);
+		bool verifyMappingAny(void * listener, EventBase::EventGeneratorID_t egid) const;
 
 		//! 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);
+		bool verifyMappingAll(void * listener, EventBase::EventGeneratorID_t egid, unsigned int 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);
+		bool verifyMappingAny(void * listener, EventBase::EventGeneratorID_t egid, unsigned int sid) const;
 
 	protected:
 		//! a mapping from source IDs (unsigned ints), each to a vector of pointers to listeners
@@ -315,12 +405,32 @@
 
 	private:
 		EventMapper(const EventMapper&);           //!< this shouldn't be called...
-		EventMapper operator=(const EventMapper&); //!< this shouldn't be called...
+		EventMapper& operator=(const EventMapper&); //!< this shouldn't be called...
 	};
 
 	EventMapper trappers;  //!< A mapping of which EventTrapper's should get a chance to trap the event
 	EventMapper listeners; //!< A mapping of which EventListener's should receive events
 
+	//! contains information regarding the progress of posting an event
+	/*! This allows us to resume and complete the posting of the "current" event before processing a new incoming event */
+	class PostingStatus {
+	public:
+		//! constructor
+		PostingStatus(const EventMapper& eventTrappers, const EventMapper& eventListeners, const EventBase& event)
+			: trappers(eventTrappers), listeners(eventListeners), t(), tit(), l(), lit(), e(event)
+		{ trappers.getMapping(e,t); tit=t.begin(); listeners.getMapping(e,l); lit=l.begin(); }
+		//! begins or resumes sending the event #e to trappers and listeners in #t and #l
+		void process();
+	protected:
+		const EventMapper& trappers; //!< the current trapper mapping, used to verify each entry in #t is still valid before processing it
+		const EventMapper& listeners; //!< the current listener mapping, used to verify each entry in #l is still valid before processing it
+		std::vector<EventTrapper*> t; //!< list of trappers which were subscribed when the PostingStatus instance was constructed
+		std::vector<EventTrapper*>::const_iterator tit; //!< current position within #t
+		std::vector<EventListener*> l; //!< list of listeners which were subscribed when the PostingStatus instance was constructed
+		std::vector<EventListener*>::const_iterator lit; //!< current position within #l
+		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.
 };
 
 //! 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_2.4.1/Events/EventTranslator.cc ./Events/EventTranslator.cc
--- ../Tekkotsu_2.4.1/Events/EventTranslator.cc	2005-07-25 23:11:23.000000000 -0400
+++ ./Events/EventTranslator.cc	2006-09-28 17:00:27.000000000 -0400
@@ -4,6 +4,7 @@
 #include "Events/TextMsgEvent.h"
 #include "Events/EventRouter.h"
 #include "Shared/debuget.h"
+#include "Shared/ProjectInterface.h"
 #include <iostream>
 
 #ifdef PLATFORM_APERIOS
@@ -24,7 +25,7 @@
 }
 
 void
-EventTranslator::encodeEvent(const EventBase& event) {
+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();
@@ -35,13 +36,13 @@
 	}
 	unsigned int header=event.getClassTypeID();
 	memcpy(buf,&header,headerlen);
-	unsigned int used=event.SaveBuffer(buf+headerlen,bufsize-headerlen);
+	unsigned int used=event.saveBuffer(buf+headerlen,bufsize-headerlen);
 	if(used==0) {
-		cerr << "ERROR: EventTranslator unable to transmit event because EventBase::SaveBuffer failed (buffer==" << (void*)(buf+headerlen) << ", size==" << bufsize-headerlen << ")" << endl;
-		post(buf,0);
+		cerr << "ERROR: EventTranslator unable to transmit event because EventBase::saveBuffer failed (buffer==" << (void*)(buf+headerlen) << ", size==" << bufsize-headerlen << ")" << endl;
+		post(buf,0,onlyReady);
 		return;
 	}
-	post(buf,used);
+	post(buf,used,onlyReady);
 	return;
 }
 
@@ -50,6 +51,7 @@
 	const unsigned int headerlen=sizeof(unsigned int);
 	unsigned int header=0;
 	memcpy(&header,entry,headerlen);
+	//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()) {
 		cerr << "ERROR: EventTranslator unable to translate buffer because header does not match a previously registered class type id" << endl;
@@ -57,42 +59,66 @@
 	}
 	EventBase* evt=static_cast<EventBase*>((*it).second->constructTemplate());
 	evt->setSaveFormat(EventBase::BINARY);
-	if(evt->LoadBuffer(entry+headerlen,size-headerlen)==0) {
-		cerr << "ERROR: EventTranlator unable to translate buffer because data is malformed (EventBase::LoadBuffer failed)" << endl;
+	if(evt->loadBuffer(entry+headerlen,size-headerlen)==0) {
+		cerr << "ERROR: EventTranlator unable to translate buffer because data is malformed (EventBase::loadBuffer failed)" << endl;
 		return NULL;
 	}
+	//cout << "decodes to " << evt->getDescription() << endl;
 	return evt;
 }
 
 void
-NoOpEventTranslator::encodeEvent(const EventBase& event) {
-	evtRouter.postEvent(event.clone());
+NoOpEventTranslator::encodeEvent(const EventBase& event, bool /*onlyReady=false*/) {
+	evtRouter.postEvent(event);
 }
 
 char*
 IPCEventTranslator::bufferRequest(unsigned int size) {
 	ASSERT(curRegion==NULL,"WARNING: IPCEventTranslator::bufferRequest() curRegion was not NULL");
-	curRegion = new RCRegion(size);
-	return curRegion->Base();
+	try {
+		curRegion = new RCRegion(size);
+		return curRegion->Base();
+	} catch(...) {
+		curRegion=NULL;
+		throw;
+	}
 }
 
-//#include "Shared/TimeET.h"
-
 void
-IPCEventTranslator::post(const char* buf, unsigned int /*size*/) {
+IPCEventTranslator::post(const char* buf, unsigned int /*size*/, bool onlyReady) {
 	ASSERTRET(curRegion!=NULL,"ERROR: IPCEventTranslator::post(buf,size) was NULL");
 	if(buf!=curRegion->Base()) {
 		cerr << "ERROR: IPCEventTranslator::post(buf,size) buf does not match value given from previous bufferRequest()" << endl;
 		return;
 	}
-	//cout << TimeET() << endl;
 #ifdef PLATFORM_APERIOS
-	subject.SetData(curRegion);
-	subject.NotifyObservers();
+	if(!onlyReady) {
+		subject.SetData(curRegion);
+		subject.NotifyObservers();
+	} else {
+		for(ObserverConstIterator it=subject.begin(); it!=subject.end(); ++it) {
+			if(subject.IsReady(*it)) {
+				subject.SetData(*it,curRegion);
+				subject.NotifyObserver(*it);
+			}
+		}
+	}
 #else
-	subject.sendMessage(curRegion);
-	curRegion->RemoveReference();
+	if(!onlyReady || subject.getMessageSN(subject.newest())==subject.getMessagesRead()) {
+		try {
+			subject.sendMessage(curRegion);
+		} catch(const std::exception& ex) {
+			static char errmsg[256];
+			strncpy(errmsg,("Occurred during IPCEventTranslator::post(), dropping interprocess event "+curName).c_str(),256);
+			ProjectInterface::uncaughtException(__FILE__,__LINE__,errmsg,&ex);
+		} catch(...) {
+			static char errmsg[256];
+			strncpy(errmsg,("Occurred during IPCEventTranslator::post(), dropping interprocess event "+curName).c_str(),256);
+			ProjectInterface::uncaughtException(__FILE__,__LINE__,errmsg,NULL);
+		}
+	}
 #endif
+	curRegion->RemoveReference();
 	curRegion=NULL;
 }
 	
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/EventTranslator.h ./Events/EventTranslator.h
--- ../Tekkotsu_2.4.1/Events/EventTranslator.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Events/EventTranslator.h	2006-09-25 19:28:12.000000000 -0400
@@ -17,7 +17,9 @@
 	virtual ~EventTranslator();
 
 	//! Call this with events which should be forwarded to other processes
-	virtual void encodeEvent(const EventBase& event);
+	/*! @param event the event to serialize and send
+	 *  @param onlyReady if true, only send the event to observers which do not have any message backlog (if supported by transfer mechanism) */
+	virtual void encodeEvent(const EventBase& event, bool onlyReady=false);
 
 	//! Call this with events which should be forwarded to other processes (redirects to encodeEvent())
 	/*! By providing an EventTrapper interface, you can directly
@@ -67,11 +69,12 @@
 	//! Called by encodeEvent() after serialization is complete for communication to other processes
 	/*! @param buf the data to be sent, will be a buffer previously requested from #bufferRequest
 	 *  @param size the number of bytes to send
+	 *  @param onlyReady if true, only send the event to observers which do not have any message backlog (if supported by transfer mechanism)
 	 *
 	 *  You will always get this callback after each call to bufferRequest(), even
 	 *  in the event of an error during saving.  If an error occured, the callback
 	 *  will receive 0 for size.*/
-	virtual void post(const char* buf, unsigned int size)=0;
+	virtual void post(const char* buf, unsigned int size, bool onlyReady)=0;
 
 	//! The value which trapEvent() should return
 	bool trapRet;
@@ -98,13 +101,13 @@
 	//! constructor
 	explicit NoOpEventTranslator(EventRouter& er) : EventTranslator(), evtRouter(er) {}
 
-	virtual void encodeEvent(const EventBase& event);
+	virtual void encodeEvent(const EventBase& event, bool onlyReady=false);
 
 protected:
 	//! should never be called, only included to satisfy interface
 	virtual char* bufferRequest(unsigned int /*size*/) { return NULL; }
 	//! should never be called, only included to satisfy interface
-	virtual void post(const char* /*buf*/, unsigned int /*size*/) { }
+	virtual void post(const char* /*buf*/, unsigned int /*size*/, bool /*onlyReady*/) { }
 	
 	EventRouter& evtRouter; //!< the EventRouter to send events to
 };
@@ -132,14 +135,21 @@
 #endif
 
 	//! constructor
-	explicit IPCEventTranslator(IPCSender_t& subj) : EventTranslator(), subject(subj), curRegion(NULL) {}
+	explicit IPCEventTranslator(IPCSender_t& subj) : EventTranslator(), subject(subj), curRegion(NULL), curName() {}
+	
+	//! extends base class's implementation to store @a event.getName() into #curName 
+	virtual void encodeEvent(const EventBase& event, bool onlyReady=false) {
+		curName=event.getName();
+		EventTranslator::encodeEvent(event,onlyReady);
+	}
 
 protected:
 	virtual char* bufferRequest(unsigned int size);
-	virtual void post(const char* buf, unsigned int size);
+	virtual void post(const char* buf, unsigned int size, bool onlyReady);
 	
 	IPCSender_t& subject; //!< where to post messages upon serialization, set by constructor
 	RCRegion* curRegion; //!< the region currently being serialized into, only valid between call to bufferRequest() and following post()
+	std::string curName; //!< name of current event being posted (for error messages)
 
 private:
 	IPCEventTranslator(const IPCEventTranslator&); //!< don't call
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/LocomotionEvent.cc ./Events/LocomotionEvent.cc
--- ../Tekkotsu_2.4.1/Events/LocomotionEvent.cc	2005-06-29 18:03:35.000000000 -0400
+++ ./Events/LocomotionEvent.cc	2006-09-21 17:14:47.000000000 -0400
@@ -21,51 +21,40 @@
 		return used; //if using XML, the XMLLoadSave::getBinSize (called by EventBase::getBinSize) is all we need
 	//otherwise need to add our own fields
 	used+=creatorSize("EventBase::LocomotionEvent");
-	used+=sizeof(x);
-	used+=sizeof(y);
-	used+=sizeof(a);
+	used+=getSerializedSize(x);
+	used+=getSerializedSize(y);
+	used+=getSerializedSize(a);
 	return used;
 }
 
 unsigned int
-LocomotionEvent::LoadBinaryBuffer(const char buf[], unsigned int len) {
+LocomotionEvent::loadBinaryBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=EventBase::LoadBinaryBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=checkCreator("EventBase::LocomotionEvent",buf,len,true))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(x,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(y,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(a,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkInc(EventBase::loadBinaryBuffer(buf,len),buf,len)) return 0;
+	if(!checkCreatorInc("EventBase::LocomotionEvent",buf,len,true)) return 0;
+	if(!decodeInc(x,buf,len)) return 0;
+	if(!decodeInc(y,buf,len)) return 0;
+	if(!decodeInc(a,buf,len)) return 0;
 	return origlen-len;	
 }
 
 unsigned int
-LocomotionEvent::SaveBinaryBuffer(char buf[], unsigned int len) const {
+LocomotionEvent::saveBinaryBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=EventBase::SaveBinaryBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=saveCreator("EventBase::LocomotionEvent",buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(x,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(y,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(a,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkInc(EventBase::saveBinaryBuffer(buf,len),buf,len)) return 0;
+	if(!saveCreatorInc("EventBase::LocomotionEvent",buf,len)) return 0;
+	if(!encodeInc(x,buf,len)) return 0;
+	if(!encodeInc(y,buf,len)) return 0;
+	if(!encodeInc(a,buf,len)) return 0;
 	return origlen-len;
 }
 
-void LocomotionEvent::LoadXML(xmlNode* node) {
+void
+LocomotionEvent::loadXML(xmlNode* node) {
 	if(node==NULL)
 		return;
 	
-	EventBase::LoadXML(node);
+	EventBase::loadXML(node);
 	
 	for(xmlNode* cur = skipToElement(node->children); cur!=NULL; cur = skipToElement(cur->next)) {
 		if(xmlStrcmp(cur->name, (const xmlChar *)"param"))
@@ -79,7 +68,7 @@
 		if(val==NULL)
 			throw bad_format(cur,"property missing value");
 		
-		cout << "LoadXML: " << name << "=" << val << endl;
+		//cout << "loadXML: " << name << "=" << val << endl;
 		
 		if(xmlStrcmp(name, (const xmlChar *)"x")==0)
 			x=atof((const char*)val);
@@ -103,10 +92,11 @@
 snprintf(valbuf,20,"%g",name); \
 xmlSetProp(cur,(const xmlChar*)"value",(const xmlChar*)valbuf); }
 
-void LocomotionEvent::SaveXML(xmlNode * node) const {
+void
+LocomotionEvent::saveXML(xmlNode * node) const {
 	if(node==NULL)
 		return;
-	EventBase::SaveXML(node);
+	EventBase::saveXML(node);
 	
 	//clear old params first
 	for(xmlNode* cur = skipToElement(node->children); cur!=NULL; ) {
@@ -118,7 +108,7 @@
 			cur = skipToElement(cur->next);
 	}
 	
-	cout << "SaveXML: " << x << ' ' << y << ' ' << a << endl;
+	//cout << "saveXML: " << x << ' ' << y << ' ' << a << endl;
 
 	SAVE_PARAM(x);
 	SAVE_PARAM(y);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/LocomotionEvent.h ./Events/LocomotionEvent.h
--- ../Tekkotsu_2.4.1/Events/LocomotionEvent.h	2005-06-29 18:03:35.000000000 -0400
+++ ./Events/LocomotionEvent.h	2006-09-09 00:32:46.000000000 -0400
@@ -37,10 +37,10 @@
 	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;
+	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;
 
 	float x; //!< the new x component (body relative)
 	float y; //!< the new y component (body relative)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/LookoutEvents.cc ./Events/LookoutEvents.cc
--- ../Tekkotsu_2.4.1/Events/LookoutEvents.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Events/LookoutEvents.cc	2006-09-09 00:32:46.000000000 -0400
@@ -0,0 +1,228 @@
+#include "LookoutEvents.h"
+
+#include <sstream>
+#include <libxml/tree.h>
+#include <iostream>
+
+using namespace std;
+
+//================ LookoutPointAtEvent
+
+std::string
+LookoutPointAtEvent::getDescription(bool showTypeSpecific/*=true*/, unsigned int verbosity/*=0*/) const {
+  if(!showTypeSpecific)
+    return EventBase::getDescription(showTypeSpecific,verbosity);
+  std::ostringstream logdata;
+  logdata << EventBase::getDescription(showTypeSpecific,verbosity)
+	  << "toBaseMatrix=" << NEWMAT::printmat(toBaseMatrix);
+  return logdata.str();
+}
+
+unsigned int
+LookoutPointAtEvent::getBinSize() const {
+  unsigned int used=EventBase::getBinSize();
+  if(saveFormat==XML)
+    return used; //if using XML, the XMLLoadSave::getBinSize (called by EventBase::getBinSize) is all we need
+  //otherwise need to add our own fields
+  used+=creatorSize("EventBase::LookoutPointAtEvent");
+  used+=sizeof(toBaseMatrix);
+  return used;
+}
+
+unsigned int
+LookoutPointAtEvent::loadBinaryBuffer(const char buf[], unsigned int len) {
+  unsigned int origlen=len;
+  unsigned int used;
+  if(0==(used=EventBase::loadBinaryBuffer(buf,len))) return 0;
+  len-=used; buf+=used;
+  if(0==(used=checkCreator("EventBase::LookoutPointAtEvent",buf,len,true))) return 0;
+  len-=used; buf+=used;
+  for (int i = 0; i < 16; i++) {
+    if(0==(used=decode(toBaseMatrix(1+i/4,1+(i%4)),buf,len))) return 0;
+    len-=used; buf+=used;
+  }
+  return origlen-len;	
+}
+
+unsigned int
+LookoutPointAtEvent::saveBinaryBuffer(char buf[], unsigned int len) const {
+  unsigned int origlen=len;
+  unsigned int used;
+  if(0==(used=EventBase::saveBinaryBuffer(buf,len))) return 0;
+  len-=used; buf+=used;
+  if(0==(used=saveCreator("EventBase::LookoutPointAtEvent",buf,len))) return 0;
+  len-=used; buf+=used;
+  for (int i = 0; i < 16; i++) {
+    if(0==(used=encode(toBaseMatrix(1+i/4,1+(i%4)),buf,len))) return 0;
+    len-=used; buf+=used;
+  }
+  return origlen-len;
+}
+
+void LookoutPointAtEvent::loadXML(xmlNode* node) {
+  if(node==NULL)
+    return;
+  
+  EventBase::loadXML(node);
+  
+  for(xmlNode* cur = skipToElement(node->children); cur!=NULL; cur = skipToElement(cur->next)) {
+    if(xmlStrcmp(cur->name, (const xmlChar *)"param"))
+      continue;
+    
+    xmlChar * name = xmlGetProp(cur,(const xmlChar*)"name");
+    if(name==NULL)
+      throw bad_format(cur,"property missing name");
+    
+    xmlChar * val = xmlGetProp(cur,(const xmlChar*)"value");
+    if(val==NULL)
+      throw bad_format(cur,"property missing value");
+    
+    cout << "loadXML: " << name << "=" << val << endl;
+    
+    if(xmlStrcmp(name, (const xmlChar *)"toBaseMatrix")==0) {
+      const string valStr = (const char*) val;
+      string::size_type pos = valStr.find_first_of(' ', 0);
+      string::size_type prev_pos = ++pos;
+      for (unsigned int i = 0; i < 16; i++) {
+	pos = valStr.find_first_of(' ', pos);
+	toBaseMatrix(1+i/4,1+(i%4)) = atof(valStr.substr(prev_pos, pos-prev_pos).c_str());
+	prev_pos = ++pos;
+	if (prev_pos == string::npos)
+	  break;
+      }
+    }
+    
+    xmlFree(val);
+    xmlFree(name);
+  }
+}
+
+void LookoutPointAtEvent::saveXML(xmlNode * node) const {
+  if(node==NULL)
+    return;
+  EventBase::saveXML(node);
+	
+  //clear old params first
+  for(xmlNode* cur = skipToElement(node->children); cur!=NULL; ) {
+    if(xmlStrcmp(cur->name, (const xmlChar *)"param")==0) {
+      xmlUnlinkNode(cur);
+      xmlFreeNode(cur);
+      cur = skipToElement(node->children); //restart the search (boo)
+    } else
+      cur = skipToElement(cur->next);
+  }
+	
+  //  cout << "saveXML: " << toBaseMatrix << endl;
+
+  xmlNode* cur=xmlNewChild(node,NULL,(const xmlChar*)"param",NULL);
+  if(cur==NULL)
+    throw bad_format(node,"Error: LookoutPointAtEvent xml error on saving param");
+  xmlSetProp(cur,(const xmlChar*)"name",(const xmlChar*)"toBaseMatrix");
+  std::ostringstream valbuf;
+  for (int i = 0; i < 16; i++)
+    valbuf << toBaseMatrix(1+i/4,1+(i%4)) << ' ';
+  xmlSetProp(cur,(const xmlChar*)"value",(const xmlChar*)valbuf.str().c_str());
+}
+
+
+//================ LookoutIREvent
+
+std::string
+LookoutIREvent::getDescription(bool showTypeSpecific/*=true*/, unsigned int verbosity/*=0*/) const {
+  if(!showTypeSpecific)
+    return LookoutPointAtEvent::getDescription(showTypeSpecific,verbosity);
+  std::ostringstream logdata;
+  logdata << LookoutPointAtEvent::getDescription(showTypeSpecific,verbosity)
+	  << '\t' << distance;
+  return logdata.str();
+}
+
+unsigned int
+LookoutIREvent::getBinSize() const {
+  unsigned int used=LookoutPointAtEvent::getBinSize();
+  if(saveFormat==XML)
+    return used; //if using XML, the XMLLoadSave::getBinSize (called by LookoutPointAtEvent::getBinSize) is all we need
+  //otherwise need to add our own fields
+  used+=creatorSize("LookoutPointAtEvent::LookoutIREvent");
+  used+=sizeof(distance);
+  return used;
+}
+
+unsigned int
+LookoutIREvent::loadBinaryBuffer(const char buf[], unsigned int len) {
+  unsigned int origlen=len;
+  unsigned int used;
+  if(0==(used=LookoutPointAtEvent::loadBinaryBuffer(buf,len))) return 0;
+  len-=used; buf+=used;
+  if(0==(used=checkCreator("LookoutPointAtEvent::LookoutIREvent",buf,len,true))) return 0;
+  len-=used; buf+=used;
+  if(0==(used=decode(distance,buf,len))) return 0;
+  len-=used; buf+=used;
+  return origlen-len;	
+}
+
+unsigned int
+LookoutIREvent::saveBinaryBuffer(char buf[], unsigned int len) const {
+  unsigned int origlen=len;
+  unsigned int used;
+  if(0==(used=LookoutPointAtEvent::saveBinaryBuffer(buf,len))) return 0;
+  len-=used; buf+=used;
+  if(0==(used=saveCreator("LookoutPointAtEvent::LookoutIREvent",buf,len))) return 0;
+  len-=used; buf+=used;
+  if(0==(used=encode(distance,buf,len))) return 0;
+  len-=used; buf+=used;
+  return origlen-len;
+}
+
+void LookoutIREvent::loadXML(xmlNode* node) {
+  if(node==NULL)
+    return;
+  
+  LookoutPointAtEvent::loadXML(node);
+  
+  for(xmlNode* cur = skipToElement(node->children); cur!=NULL; cur = skipToElement(cur->next)) {
+    if(xmlStrcmp(cur->name, (const xmlChar *)"param"))
+      continue;
+    
+    xmlChar * name = xmlGetProp(cur,(const xmlChar*)"name");
+    if(name==NULL)
+      throw bad_format(cur,"property missing name");
+    
+    xmlChar * val = xmlGetProp(cur,(const xmlChar*)"value");
+    if(val==NULL)
+      throw bad_format(cur,"property missing value");
+    
+    cout << "loadXML: " << name << "=" << val << endl;
+    
+    
+    if(xmlStrcmp(name, (const xmlChar *)"distance")==0)
+      distance=atof((const char*)val);
+    
+    xmlFree(val);
+    xmlFree(name);
+  }
+}
+
+void LookoutIREvent::saveXML(xmlNode * node) const {
+  if(node==NULL)
+    return;
+  LookoutPointAtEvent::saveXML(node);
+	
+  //clear old params first
+  for(xmlNode* cur = skipToElement(node->children); cur!=NULL; ) {
+    if(xmlStrcmp(cur->name, (const xmlChar *)"param")==0) {
+      xmlUnlinkNode(cur);
+      xmlFreeNode(cur);
+      cur = skipToElement(node->children); //restart the search (boo)
+    } else
+      cur = skipToElement(cur->next);
+  }
+
+  xmlNode* cur=xmlNewChild(node,NULL,(const xmlChar*)"param",NULL);
+  if(cur==NULL)
+    throw bad_format(node,"Error: LocomotionEvent xml error on saving param");
+  xmlSetProp(cur,(const xmlChar*)"name",(const xmlChar*)"distance");
+  char valbuf[20];
+  snprintf(valbuf,20,"%g",distance);
+  xmlSetProp(cur,(const xmlChar*)"value",(const xmlChar*)valbuf);
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/LookoutEvents.h ./Events/LookoutEvents.h
--- ../Tekkotsu_2.4.1/Events/LookoutEvents.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Events/LookoutEvents.h	2006-09-09 00:32:47.000000000 -0400
@@ -0,0 +1,125 @@
+//-*-c++-*-
+#ifndef INCLUDED_LookoutEvents_h_
+#define INCLUDED_LookoutEvents_h_
+
+#include <iostream>
+
+#include "EventBase.h"
+#include "DualCoding/LookoutRequests.h"
+#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 };
+  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) {}
+  //}
+};
+
+// This event gives access to transformation matrix from joint specified from LookoutRequest to Base Frame
+class LookoutPointAtEvent : public LookoutEvent {
+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) {}
+  virtual EventBase* clone() const { return new LookoutPointAtEvent(*this); }
+  virtual unsigned int getClassTypeID() const { return makeClassTypeID("LOLA"); }
+  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;
+};
+
+
+// Event which gives you access to the sketch stored as a result of StoreImage request
+class LookoutSketchEvent : public LookoutPointAtEvent {
+protected:
+  DualCoding::Sketch<DualCoding::uchar> *img; // pointer to sketch existing inside lookout's requests queue
+  
+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, 
+		     EventTypeID_t tid, unsigned int dur, const std::string& n, float mag)
+    : LookoutPointAtEvent(mat,gid,sid,tid,dur,n,mag), img(&_img) {}
+  //! copy constructor (shallow copy)
+  LookoutSketchEvent(const LookoutSketchEvent& lose)
+    : LookoutPointAtEvent(lose), img(lose.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;
+private:
+  LookoutSketchEvent& operator=(const LookoutSketchEvent&);
+};
+
+class LookoutIREvent : public LookoutPointAtEvent {
+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, 
+		 EventTypeID_t tid, unsigned int dur, const std::string& n, float mag)
+    : LookoutPointAtEvent(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 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;
+};
+
+class LookoutScanEvent : public LookoutEvent {
+protected:
+  //! pointer to tasks implemented during the scan
+  vector<ScanRequest::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, 
+		   EventTypeID_t tid, unsigned int dur, const std::string& n, float mag)
+    : LookoutEvent(gid,sid,tid,dur,n,mag), tasks(&_tasks) {}
+  //! copy constructor (shallow copy)
+  LookoutScanEvent(const LookoutScanEvent& lose)
+    : LookoutEvent(lose), tasks(lose.tasks) {}
+  //! assignment operator (shallow copy)
+  const LookoutScanEvent& operator=(const LookoutScanEvent& lose) {
+    if (this == &lose) return *this;
+    LookoutEvent::operator=(lose);
+    tasks = lose.tasks;
+    return *this;
+  }
+  virtual EventBase* clone() const { return new LookoutScanEvent(*this); }
+  const vector<ScanRequest::Task*>& getTasks() const { return *tasks; }
+};
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/PitchEvent.cc ./Events/PitchEvent.cc
--- ../Tekkotsu_2.4.1/Events/PitchEvent.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Events/PitchEvent.cc	2006-09-21 17:45:47.000000000 -0400
@@ -0,0 +1,130 @@
+#include "PitchEvent.h"
+#include <sstream>
+#include <libxml/tree.h>
+
+//better to put this here instead of the header
+using namespace std; 
+
+std::string
+PitchEvent::getDescription(bool showTypeSpecific/*=true*/, unsigned int verbosity/*=0*/) const {
+	if(!showTypeSpecific)
+		return EventBase::getDescription(showTypeSpecific,verbosity);
+	std::ostringstream logdata;
+	logdata << EventBase::getDescription(showTypeSpecific,verbosity) << '\t' << freq << '\t' << amplitude << '\t' << confidence;
+	return logdata.str();
+}
+
+unsigned int
+PitchEvent::getBinSize() const {
+	unsigned int used=EventBase::getBinSize();
+	if(saveFormat==XML)
+		return used; //if using XML, the XMLLoadSave::getBinSize (called by EventBase::getBinSize) is all we need
+	//otherwise need to add our own fields
+	used+=creatorSize("EventBase::PitchEvent");
+	used+=getSerializedSize(freq);
+	used+=getSerializedSize(amplitude);
+	used+=getSerializedSize(confidence);
+	return used;
+}
+
+unsigned int
+PitchEvent::loadBinaryBuffer(const char buf[], unsigned int len) {
+	unsigned int origlen=len;
+	if(!checkInc(EventBase::loadBinaryBuffer(buf,len),buf,len)) return 0;
+	if(!checkCreatorInc("EventBase::PitchEvent",buf,len,true)) return 0;
+	if(!decodeInc(freq,buf,len)) return 0;
+	if(!decodeInc(amplitude,buf,len)) return 0;
+	if(!decodeInc(confidence,buf,len)) return 0;
+	return origlen-len;	
+}
+
+unsigned int
+PitchEvent::saveBinaryBuffer(char buf[], unsigned int len) const {
+	unsigned int origlen=len;
+	if(!checkInc(EventBase::saveBinaryBuffer(buf,len),buf,len)) return 0;
+	if(!saveCreatorInc("EventBase::PitchEvent",buf,len)) return 0;
+	if(!encodeInc(freq,buf,len)) return 0;
+	if(!encodeInc(amplitude,buf,len)) return 0;
+	if(!encodeInc(confidence,buf,len)) return 0;
+	return origlen-len;
+}
+
+void
+PitchEvent::loadXML(xmlNode* node) {
+	if(node==NULL)
+		return;
+	
+	EventBase::loadXML(node);
+	
+	for(xmlNode* cur = skipToElement(node->children); cur!=NULL; cur = skipToElement(cur->next)) {
+		if(xmlStrcmp(cur->name, (const xmlChar *)"param"))
+			continue;
+		
+		xmlChar * name = xmlGetProp(cur,(const xmlChar*)"name");
+		if(name==NULL)
+			throw bad_format(cur,"property missing name");
+		
+		xmlChar * val = xmlGetProp(cur,(const xmlChar*)"value");
+		if(val==NULL)
+			throw bad_format(cur,"property missing value");
+		
+		//cout << "loadXML: " << name << "=" << val << endl;
+		
+		if(xmlStrcmp(name, (const xmlChar *)"freq")==0)
+			freq=atof((const char*)val);
+		else if(xmlStrcmp(name, (const xmlChar *)"amplitude")==0)
+			amplitude=atof((const char*)val);
+		else if(xmlStrcmp(name, (const xmlChar *)"confidence")==0)
+			confidence=atof((const char*)val);
+		
+		xmlFree(val);
+		xmlFree(name);
+	}
+}
+
+//! a little local macro to make saving fields easier
+#define SAVE_PARAM(name) { \
+	xmlNode* cur=xmlNewChild(node,NULL,(const xmlChar*)"param",NULL); \
+	if(cur==NULL) \
+		throw bad_format(node,"Error: LocomotionEvent xml error on saving param"); \
+	xmlSetProp(cur,(const xmlChar*)"name",(const xmlChar*)#name); \
+	char valbuf[20]; \
+	snprintf(valbuf,20,"%g",name); \
+	xmlSetProp(cur,(const xmlChar*)"value",(const xmlChar*)valbuf); }
+
+void
+PitchEvent::saveXML(xmlNode * node) const {
+	if(node==NULL)
+		return;
+	EventBase::saveXML(node);
+	
+	//clear old params first
+	for(xmlNode* cur = skipToElement(node->children); cur!=NULL; ) {
+		if(xmlStrcmp(cur->name, (const xmlChar *)"param")==0) {
+			xmlUnlinkNode(cur);
+			xmlFreeNode(cur);
+			cur = skipToElement(node->children); //restart the search (boo)
+		} else
+			cur = skipToElement(cur->next);
+	}
+	
+	//cout << "saveXML: " << x << ' ' << y << ' ' << a << endl;
+	
+	SAVE_PARAM(freq);
+	SAVE_PARAM(amplitude);
+	SAVE_PARAM(confidence);
+}
+
+/*! @file
+ * @brief Implements PitchEvent, which provides information about a tone detected from the microphone(s)
+ * @author Matus Telgarsky and Jonah Sherman (Creators)
+ * @author Ethan Tira-Thompson (imported into framework)
+ *
+ * Originally written as a part of a final project at Carnegie Mellon (15-494 Cognitive Robotics, Spring 2006)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/PitchEvent.h ./Events/PitchEvent.h
--- ../Tekkotsu_2.4.1/Events/PitchEvent.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Events/PitchEvent.h	2006-09-25 16:49:24.000000000 -0400
@@ -0,0 +1,60 @@
+//-*-c++-*-
+#ifndef INCLUDED_PitchEvent_h_
+#define INCLUDED_PitchEvent_h_
+
+#include "EventBase.h"
+
+//! Provides information about a tone detected from the microphone(s)
+class PitchEvent : public EventBase {
+public:
+	//!constructor
+	PitchEvent(unsigned int 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)
+	{}
+	
+	//! assignment operator (does what you'd expect, explicit to satisify compiler warning)
+	PitchEvent & operator=(const PitchEvent &p) {
+		EventBase::operator=(p); freq=p.freq; amplitude=p.amplitude; confidence=p.confidence;
+		return *this;
+	}
+	
+	virtual EventBase* clone() const { return new PitchEvent(*this); }
+	
+	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;
+	
+	float getFreq(void) const { return freq; } //!< returns #freq
+	float getAmplitude(void) const { return amplitude; } //!< returns #amplitude
+	float getConfidence(void) const { return confidence; } //!< returns #confidence
+	
+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
+};
+
+/*! @file
+ * @brief Describes PitchEvent, which provides information about a tone detected from the microphone(s)
+ * @author Matus Telgarsky and Jonah Sherman (Creators)
+ * @author Ethan Tira-Thompson (imported into framework)
+ *
+ * Originally written as a part of a final project at Carnegie Mellon (15-494 Cognitive Robotics, Spring 2006)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/TextMsgEvent.cc ./Events/TextMsgEvent.cc
--- ../Tekkotsu_2.4.1/Events/TextMsgEvent.cc	2005-06-10 13:26:30.000000000 -0400
+++ ./Events/TextMsgEvent.cc	2006-09-09 00:32:48.000000000 -0400
@@ -18,46 +18,37 @@
 		return used; //if using XML, the XMLLoadSave::getBinSize (called by EventBase::getBinSize) is all we need
 	//otherwise need to add our own fields
 	used+=creatorSize("EventBase::TextMsgEvent");
-	used+=_text.size()+stringpad;
+	used+=getSerializedSize(_text);
 	//used+=sizeof(_token);
 	return used;
 }
 
 unsigned int
-TextMsgEvent::LoadBinaryBuffer(const char buf[], unsigned int len) {
+TextMsgEvent::loadBinaryBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=EventBase::LoadBinaryBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=checkCreator("EventBase::TextMsgEvent",buf,len,true))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(_text,buf,len))) return 0;
-	len-=used; buf+=used;
-	//if(0==(used=decode(_token,buf,len))) return 0;
+	if(!checkInc(EventBase::loadBinaryBuffer(buf,len),buf,len)) return 0;
+	if(!checkCreatorInc("EventBase::TextMsgEvent",buf,len,true)) return 0;
+	if(!decodeInc(_text,buf,len)) return 0;
+	//if(!decodeInc(_token,buf,len)) return 0;
 	//len-=used; buf+=used;
 	return origlen-len;	
 }
 
 unsigned int
-TextMsgEvent::SaveBinaryBuffer(char buf[], unsigned int len) const {
+TextMsgEvent::saveBinaryBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=EventBase::SaveBinaryBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=saveCreator("EventBase::TextMsgEvent",buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(_text,buf,len))) return 0;
-	len-=used; buf+=used;
-	//if(0==(used=encode(_token,buf,len))) return 0;
-	//len-=used; buf+=used;
+	if(!checkInc(EventBase::saveBinaryBuffer(buf,len),buf,len)) return 0;
+	if(!saveCreatorInc("EventBase::TextMsgEvent",buf,len)) return 0;
+	if(!encodeInc(_text,buf,len)) return 0;
+	//if(!encodeInc(_token,buf,len)) return 0;
 	return origlen-len;
 }
 
-void TextMsgEvent::LoadXML(xmlNode* node) {
+void TextMsgEvent::loadXML(xmlNode* node) {
 	if(node==NULL)
 		return;
 	
-	EventBase::LoadXML(node);
+	EventBase::loadXML(node);
 	
 	for(xmlNode* cur = skipToElement(node->children); cur!=NULL; cur = skipToElement(cur->next)) {
 		if(xmlStrcmp(cur->name, (const xmlChar *)"param"))
@@ -79,10 +70,10 @@
 	}
 }
 
-void TextMsgEvent::SaveXML(xmlNode * node) const {
+void TextMsgEvent::saveXML(xmlNode * node) const {
 	if(node==NULL)
 		return;
-	EventBase::SaveXML(node);
+	EventBase::saveXML(node);
 	
 	//clear old params first
 	for(xmlNode* cur = skipToElement(node->children); cur!=NULL; ) {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/TextMsgEvent.h ./Events/TextMsgEvent.h
--- ../Tekkotsu_2.4.1/Events/TextMsgEvent.h	2005-06-29 18:03:35.000000000 -0400
+++ ./Events/TextMsgEvent.h	2006-09-09 00:32:48.000000000 -0400
@@ -11,7 +11,7 @@
   TextMsgEvent() : EventBase(EventBase::textmsgEGID,(unsigned int)-1, EventBase::statusETID,0),_text("")/*,_token(0)*/ {  }
 
   //! Constructor, pass a text msg
-  TextMsgEvent(const std::string& text) : EventBase(EventBase::textmsgEGID,(unsigned int)-1, EventBase::statusETID,0),_text(text)/*,_token(0)*/ { }
+  TextMsgEvent(const std::string& text, unsigned int srcID=-1U) : EventBase(EventBase::textmsgEGID,srcID, EventBase::statusETID,0),_text(text)/*,_token(0)*/ { }
   
 	virtual EventBase* clone() const { return new TextMsgEvent(*this); }
 
@@ -26,10 +26,10 @@
 	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;
+	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:
   std::string _text; //!< the unmodified arguments passed to the command
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/TimerEvent.cc ./Events/TimerEvent.cc
--- ../Tekkotsu_2.4.1/Events/TimerEvent.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Events/TimerEvent.cc	2006-09-09 00:32:49.000000000 -0400
@@ -0,0 +1,114 @@
+#include "TimerEvent.h"
+#include "Behaviors/BehaviorBase.h"
+#include <sstream>
+#include <libxml/tree.h>
+
+//better to put this here instead of the header
+using namespace std; 
+
+std::string
+TimerEvent::getDescription(bool showTypeSpecific/*=true*/, unsigned int verbosity/*=0*/) const {
+	if(!showTypeSpecific)
+		return EventBase::getDescription(showTypeSpecific,verbosity);
+	std::ostringstream logdata;
+	logdata << EventBase::getDescription(showTypeSpecific,verbosity) << '\t';
+	if(BehaviorBase * beh=dynamic_cast<BehaviorBase*>(target)) {
+		logdata << beh->getClassName() << "(" << beh->getName() << ")@" << beh;
+	} else {
+		logdata << "Listener@" << target << endl;
+	}
+	return logdata.str();
+}
+
+unsigned int
+TimerEvent::getBinSize() const {
+	unsigned int used=EventBase::getBinSize();
+	if(saveFormat==XML)
+		return used; //if using XML, the XMLLoadSave::getBinSize (called by EventBase::getBinSize) is all we need
+	//otherwise need to add our own fields
+	used+=creatorSize("EventBase::TimerEvent");
+	used+=getSerializedSize(target); // not that a pointer is of any direct use once loaded externally, but still useful as an identifier
+	return used;
+}
+
+unsigned int
+TimerEvent::loadBinaryBuffer(const char buf[], unsigned int len) {
+	unsigned int origlen=len;
+	if(!checkInc(EventBase::loadBinaryBuffer(buf,len),buf,len)) return 0;
+	if(!checkCreatorInc("EventBase::TimerEvent",buf,len,true)) return 0;
+	unsigned long long tgt;
+	if(!decodeInc(tgt,buf,len)) return 0;
+	target=reinterpret_cast<EventListener*>(tgt);
+	return origlen-len;	
+}
+
+unsigned int
+TimerEvent::saveBinaryBuffer(char buf[], unsigned int len) const {
+	unsigned int origlen=len;
+	if(!checkInc(EventBase::saveBinaryBuffer(buf,len),buf,len)) return 0;
+	if(!saveCreatorInc("EventBase::TimerEvent",buf,len)) return 0;
+	if(!encodeInc(reinterpret_cast<unsigned long long>(target),buf,len)) return 0;
+	return origlen-len;
+}
+
+void TimerEvent::loadXML(xmlNode* node) {
+	if(node==NULL)
+		return;
+	
+	EventBase::loadXML(node);
+	
+	for(xmlNode* cur = skipToElement(node->children); cur!=NULL; cur = skipToElement(cur->next)) {
+		if(xmlStrcmp(cur->name, (const xmlChar *)"param"))
+			continue;
+		
+		xmlChar * name = xmlGetProp(cur,(const xmlChar*)"name");
+		if(name==NULL)
+			throw bad_format(cur,"property missing name");
+		
+		xmlChar * val = xmlGetProp(cur,(const xmlChar*)"value");
+		if(val==NULL)
+			throw bad_format(cur,"property missing value");
+		
+		if(xmlStrcmp(name, (const xmlChar *)"target")==0)
+			target=reinterpret_cast<EventListener*>(strtol((char*)val,NULL,0));
+		
+		xmlFree(val);
+		xmlFree(name);
+	}
+}
+
+void TimerEvent::saveXML(xmlNode * node) const {
+	if(node==NULL)
+		return;
+	EventBase::saveXML(node);
+	
+	//clear old params first
+	for(xmlNode* cur = skipToElement(node->children); cur!=NULL; ) {
+		if(xmlStrcmp(cur->name, (const xmlChar *)"param")==0) {
+			xmlUnlinkNode(cur);
+			xmlFreeNode(cur);
+			cur = skipToElement(node->children); //restart the search (boo)
+		} else
+			cur = skipToElement(cur->next);
+	}
+	
+	xmlNode* cur=xmlNewChild(node,NULL,(const xmlChar*)"param",NULL);
+	if(cur==NULL)
+		throw bad_format(node,"Error: VisionObjectEvent xml error on saving param");
+	xmlSetProp(cur,(const xmlChar*)"name",(const xmlChar*)"target");
+	char tmp[20];
+	snprintf(tmp,20,"%p",target);
+	xmlSetProp(cur,(const xmlChar*)"value",(const xmlChar*)tmp);
+}
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/TimerEvent.h ./Events/TimerEvent.h
--- ../Tekkotsu_2.4.1/Events/TimerEvent.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Events/TimerEvent.h	2006-09-16 16:11:51.000000000 -0400
@@ -0,0 +1,53 @@
+//-*-c++-*-
+#ifndef INCLUDED_TimerEvent_h_
+#define INCLUDED_TimerEvent_h_
+
+#include "Events/EventBase.h"
+
+class EventListener;
+
+//! Adds a target field to EventBase so listeners can resolve source ID conflict between different behaviors
+/*! See EventRouter's class documentation for discussion of how to request
+ *  and use timers. */
+class TimerEvent : public EventBase {
+public:
+	//! 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) {}
+	//! 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!)
+	TimerEvent& operator=(const TimerEvent& te) { target=te.target; EventBase::operator=(te); return *this; }
+
+	virtual EventBase* clone() const { return new TimerEvent(*this); }
+	
+	virtual unsigned int getClassTypeID() const { return makeClassTypeID("TIMR"); }
+	
+	EventListener * getTarget() const { return target; } //!< returns #target
+	void setTarget(EventListener* tgt) { target=tgt; } //!< assigns @a tgt to #target
+
+	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:
+	EventListener * target; //!< indicates the listener for which the timer was created
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/VisionObjectEvent.cc ./Events/VisionObjectEvent.cc
--- ../Tekkotsu_2.4.1/Events/VisionObjectEvent.cc	2005-08-07 00:11:03.000000000 -0400
+++ ./Events/VisionObjectEvent.cc	2006-09-09 00:32:50.000000000 -0400
@@ -1,4 +1,5 @@
 #include "VisionObjectEvent.h"
+#include "Shared/RobotInfo.h"
 #include <sstream>
 #include <libxml/tree.h>
 
@@ -13,6 +14,38 @@
 	return logdata.str();
 }
 
+float
+VisionObjectEvent::getDistanceEstimate(float diaMajor, float diaMinor) const {
+	float diaX,diaY;
+	float w=getWidth();
+	float h=getHeight();
+	if(w>h) {
+		diaX=diaMajor;
+		diaY=diaMinor;
+	} else {
+		diaX=diaMinor;
+		diaY=diaMajor;
+	}
+	float xest=diaX>0?calcDistance(getWidth()/2*CameraFOV,diaX):0;
+	float yest=diaY>0?calcDistance(getHeight()/2*CameraFOV,diaY):0;
+	if(xest>0 && yest>0) {
+		return (xest+yest)/2;
+	} else if(xest>0) {
+		return xest;
+	} else if(yest>0) {
+		return yest;
+	}
+	return 0;
+}
+
+float
+VisionObjectEvent::calcDistance(float visArc, float physDia) {
+	float r=tan(visArc/2);
+	if(r==0)
+		return 0;
+	return physDia/r;
+}
+
 unsigned int
 VisionObjectEvent::getBinSize() const {
 	unsigned int used=EventBase::getBinSize();
@@ -20,56 +53,42 @@
 		return used; //if using XML, the XMLLoadSave::getBinSize (called by EventBase::getBinSize) is all we need
 	//otherwise need to add our own fields
 	used+=creatorSize("EventBase::VisionObjectEvent");
-	used+=sizeof(_x1);
-	used+=sizeof(_x2);
-	used+=sizeof(_y1);
-	used+=sizeof(_y2);
+	used+=getSerializedSize(_x1);
+	used+=getSerializedSize(_x2);
+	used+=getSerializedSize(_y1);
+	used+=getSerializedSize(_y2);
 	return used;
 }
 
 unsigned int
-VisionObjectEvent::LoadBinaryBuffer(const char buf[], unsigned int len) {
+VisionObjectEvent::loadBinaryBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=EventBase::LoadBinaryBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=checkCreator("EventBase::VisionObjectEvent",buf,len,true))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(_x1,buf,len))) return 0;
-	len-=used; buf+=used;	
-	if(0==(used=decode(_x2,buf,len))) return 0;
-	len-=used; buf+=used;	
-	if(0==(used=decode(_y1,buf,len))) return 0;
-	len-=used; buf+=used;	
-	if(0==(used=decode(_y2,buf,len))) return 0;
-	len-=used; buf+=used;	
+	if(!checkInc(EventBase::loadBinaryBuffer(buf,len),buf,len)) return 0;
+	if(!checkCreatorInc("EventBase::VisionObjectEvent",buf,len,true)) return 0;
+	if(!decodeInc(_x1,buf,len)) return 0;
+	if(!decodeInc(_x2,buf,len)) return 0;
+	if(!decodeInc(_y1,buf,len)) return 0;
+	if(!decodeInc(_y2,buf,len)) return 0;
 	return origlen-len;	
 }
 
 unsigned int
-VisionObjectEvent::SaveBinaryBuffer(char buf[], unsigned int len) const {
+VisionObjectEvent::saveBinaryBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=EventBase::SaveBinaryBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=saveCreator("EventBase::VisionObjectEvent",buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(_x1,buf,len))) return 0;
-	len-=used; buf+=used;	
-	if(0==(used=encode(_x2,buf,len))) return 0;
-	len-=used; buf+=used;	
-	if(0==(used=encode(_y1,buf,len))) return 0;
-	len-=used; buf+=used;	
-	if(0==(used=encode(_y2,buf,len))) return 0;
-	len-=used; buf+=used;	
+	if(!checkInc(EventBase::saveBinaryBuffer(buf,len),buf,len)) return 0;
+	if(!saveCreatorInc("EventBase::VisionObjectEvent",buf,len)) return 0;
+	if(!encodeInc(_x1,buf,len)) return 0;
+	if(!encodeInc(_x2,buf,len)) return 0;
+	if(!encodeInc(_y1,buf,len)) return 0;
+	if(!encodeInc(_y2,buf,len)) return 0;
 	return origlen-len;
 }
 
-void VisionObjectEvent::LoadXML(xmlNode* node) {
+void VisionObjectEvent::loadXML(xmlNode* node) {
 	if(node==NULL)
 		return;
 	
-	EventBase::LoadXML(node);
+	EventBase::loadXML(node);
 
 	for(xmlNode* cur = skipToElement(node->children); cur!=NULL; cur = skipToElement(cur->next)) {
 		if(xmlStrcmp(cur->name, (const xmlChar *)"param"))
@@ -105,6 +124,7 @@
 	}
 }
 
+
 //! a little local macro to make saving fields easier
 #define SAVE_PARAM(strname,varname,format) {\
 xmlNode* cur=xmlNewChild(node,NULL,(const xmlChar*)"param",NULL); \
@@ -115,10 +135,10 @@
 snprintf(valbuf,20,format,varname); \
 xmlSetProp(cur,(const xmlChar*)"value",(const xmlChar*)valbuf); }
 
-void VisionObjectEvent::SaveXML(xmlNode * node) const {
+void VisionObjectEvent::saveXML(xmlNode * node) const {
 	if(node==NULL)
 		return;
-	EventBase::SaveXML(node);
+	EventBase::saveXML(node);
 	
 	//clear old params first
 	for(xmlNode* cur = skipToElement(node->children); cur!=NULL; ) {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Events/VisionObjectEvent.h ./Events/VisionObjectEvent.h
--- ../Tekkotsu_2.4.1/Events/VisionObjectEvent.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Events/VisionObjectEvent.h	2006-09-09 00:32:50.000000000 -0400
@@ -63,61 +63,63 @@
 	virtual unsigned int getClassTypeID() const { return makeClassTypeID("VISO"); }
 
 	//!@name Attribute Accessors
-  float getLeft() const { return _x1;} //!< returns the initial x (#_x1) coordinate of the Bounding Box (inclusive value)
-  VisionObjectEvent& setLeft(float x1) { _x1=x1; return *this;} //!< sets the initial x (#_x1) coordinate of the Bounding Box
-  
-  float getRight() const { return _x2;} //!< returns the final x (#_x2) coordinate of the Bounding Box (inclusive value)
-  VisionObjectEvent& setRight(float x2) { _x2=x2; return *this;} //!< sets the final x (#_x2) coordinate of the Bounding Box
-  
+	float getLeft() const { return _x1;} //!< returns the initial x (#_x1) coordinate of the Bounding Box (inclusive value)
+	VisionObjectEvent& setLeft(float x1) { _x1=x1; return *this;} //!< sets the initial x (#_x1) coordinate of the Bounding Box
+	
+	float getRight() const { return _x2;} //!< returns the final x (#_x2) coordinate of the Bounding Box (inclusive value)
+	VisionObjectEvent& setRight(float x2) { _x2=x2; return *this;} //!< sets the final x (#_x2) coordinate of the Bounding Box
+	
 	float getTop() const { return _y1;} //!< returns the initial y (#_y1) coordinate of the Bounding Box (inclusive value)
-  VisionObjectEvent& setTop(float y1) { _y1=y1; return *this;} //!< sets the initial y (#_y1) coordinate of the Bounding Box
-  
-  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 major camera resolution to get pixel area)
-	VisionObjectEvent& setObjectArea(float objarea) { _area=objarea; return *this; } //!< returns the object's #_area within the camera, in squared generalized coordinates (multiply by the major camera resolution to get pixel area)
+	VisionObjectEvent& setTop(float y1) { _y1=y1; return *this;} //!< sets the initial y (#_y1) coordinate of the Bounding Box
+	
+	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.
+	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)
 	//@}
  
 	//!@name Calculated Attributes
-  float getCenterX() const { return (_x1+_x2)/2; } //!< returns the center along x
-  float getCenterY() const { return (_y1+_y2)/2; } //!< returns the center along y
-  float getWidth() const { return _x2-_x1; } //!< return width along x
-  float getHeight() const { return _y2-_y1; } //!< return height along y
-  float getBoundaryArea() const { return (_x2-_x1)*(_y2-_y1); } //!< returns the area of the bounding box, just multiplication of width*height, (multiply by the major camera resolution to get pixel area)
-  float getXrange() const{ return  _xRange;}//!< returns the maximum x value
-  float getYrange() const{return _yRange;}//!< returns the maximum y value
-  unsigned int getFrame() const{return _frame;}//!< returns number of frame when the event was generated
+	float getDistanceEstimate(float diaMajor, float diaMinor=0) const; //!< returns an estimate of how far away the object is if its major (larger) physical dimension is @a diaMajor and the other dimension is @a diaMinor; pass 0 if to only use the major dimension
+	static float calcDistance(float visArc, float physDia); //!< returns the distance of an object, given that it takes up @a visArc of the camera's visual arc, and the physical crossection is @a physDia
+	float getCenterX() const { return (_x1+_x2)/2; } //!< returns the center along x
+	float getCenterY() const { return (_y1+_y2)/2; } //!< returns the center along y
+	float getWidth() const { return _x2-_x1; } //!< return width along x
+	float getHeight() const { return _y2-_y1; } //!< return height along y
+	float getBoundaryArea() const { return (_x2-_x1)*(_y2-_y1); } //!< returns the area of the bounding box, just multiplication of width*height, (multiply by the major camera resolution to get pixel area)
+	float getXrange() const{ return  _xRange;}//!< returns the maximum x value
+	float getYrange() const{return _yRange;}//!< returns the maximum y value
+	unsigned int getFrame() const{return _frame;}//!< returns number of frame when the event was generated
 	//@}
 
-  //!@name Object out of bounds Detection Functions
-  bool isClippedLeft() const { return _clipLeft; } //!< returns #_clipLeft
-  bool isClippedRight() const { return _clipRight; }  //!< returns #_clipRight
-  bool isClippedTop() const { return _clipTop; } //!< returns #_clipTop
-  bool isClippedBottom() const {return _clipBottom; } //!< returns #_clipBottom
+	//!@name Object out of bounds Detection Functions
+	bool isClippedLeft() const { return _clipLeft; } //!< returns #_clipLeft
+	bool isClippedRight() const { return _clipRight; }  //!< returns #_clipRight
+	bool isClippedTop() const { return _clipTop; } //!< returns #_clipTop
+	bool isClippedBottom() const {return _clipBottom; } //!< returns #_clipBottom
 	void setClipping(bool left, bool right, bool top, bool bottom) { _clipLeft=left; _clipRight=right; _clipTop=top; _clipBottom=bottom; } //!< sets clipping boundaries
 	//@}
       
 	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;
+	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:
 	float _x1;  //!< a value representing location in visual field - from -1 if on the left edge to 1 if it's on the right edge
 	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() (squared generalized coordinates -- multiply by the major camera resolution 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
 	bool _clipBottom; //!< flag to indicate bottom boundary is on or beyond the camera image's boundary
-	float _xRange; //!< Max range of X dimension
-	float _yRange; //!< Max range of Y dimension
+	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.
 };
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/LockScope.h ./IPC/LockScope.h
--- ../Tekkotsu_2.4.1/IPC/LockScope.h	2005-06-01 01:47:46.000000000 -0400
+++ ./IPC/LockScope.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,34 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_LockScope_h_
-#define INCLUDED_LockScope_h_
-
-#include "MutexLock.h"
-#include "ProcessID.h"
-
-//! Locks a MutexLock until the LockScope goes out of scope
-/*! This can help prevent forgetting to do it if you function has multiple return points */
-template<unsigned int num_doors>
-class LockScope {
-public:
-	//!constructor, locks @a lock with the current process's id (ProcessID::getID())
-	LockScope(MutexLock<num_doors>& lock) : l(lock) {l.lock(ProcessID::getID());}
-	//!constructor, locks @a lock with @a id
-	LockScope(MutexLock<num_doors>& lock, int id) : l(lock) {l.lock(id);}
-	//!destructor, releases lock received in constructor
-	~LockScope() { l.unlock(); }
-protected:
-	MutexLock<num_doors>& l; //!< the lock
-};
-
-/*! @file
- * @brief Defines LockScope, which locks a MutexLock until the LockScope goes out of scope
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/MessageQueue.cc ./IPC/MessageQueue.cc
--- ../Tekkotsu_2.4.1/IPC/MessageQueue.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./IPC/MessageQueue.cc	2006-03-09 13:28:08.000000000 -0500
@@ -0,0 +1,17 @@
+#ifndef PLATFORM_APERIOS
+#include "MessageQueue.h"
+
+SemaphoreManager* MessageQueueBase::semgr=NULL;
+
+/*! @file
+* @brief Defines MessageQueue, which provides mechanisms for sending shared memory regions between processes
+* @author ejt (Creator)
+*
+* $Author: ejt $
+* $Name: HEAD $
+* $Revision: 1.1 $
+* $State: Exp $
+* $Date: 2006/10/04 04:21:12 $
+*/
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/MessageQueue.h ./IPC/MessageQueue.h
--- ../Tekkotsu_2.4.1/IPC/MessageQueue.h	2005-08-04 17:32:16.000000000 -0400
+++ ./IPC/MessageQueue.h	2006-09-19 18:52:01.000000000 -0400
@@ -8,9 +8,13 @@
 
 #include "ListMemBuf.h"
 #include "RCRegion.h"
-#include "LockScope.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
  *  operations on MessageQueues.  The templated version of MessageQueue provides
@@ -19,49 +23,33 @@
  *  Each message entails its own shared memory region, as compared to
  *  SharedQueue, where a single large buffer is maintained, and all messages are
  *  copied into the common buffer.  This class is better for large regions since
- *  it can avoid copying data around. */
+ *  it can avoid copying data around.
+ * 
+ *  @see MessageQueue, MessageQueueStatusListener, MessageReceiver */
 class MessageQueueBase {
 public:
 
+	//! an interface for filtering (or otherwise monitoring) messages being sent through a MessageQueue, see MessageQueueBase::addMessageFilter()
+	class MessageFilter {
+	public:
+		//! called immediately prior to sending a message -- return true to pass the message into the queue, false to drop it
+		virtual bool filterSendRequest(RCRegion* rcr)=0;
+		//! to make compiler warning happy
+		virtual ~MessageFilter() {}
+	};
+	
 	//!constructor
 	MessageQueueBase()
 		: lock(), overflowPolicy(THROW_BAD_ALLOC), isClosed(false), reportDroppings(false), numMessages(0),
-			numReceivers(0), messagesRead()
-	{}
+			numReceivers(0), messagesRead(0)
+	{
+		for(unsigned int i=0; i<ProcessID::NumProcesses; ++i)
+			filters[i]=NULL;
+	}
 	//!destructor
 	virtual ~MessageQueueBase() {}
 	
 	
-	//!An interface to allow you to receive callbacks when a message has been read from a MessageQueue, subscribed via an external calss which is monitoring the queue's MessageQueueBase::pollStatus() (e.g. LoadFileThread)
-	class StatusListener {
-	public:
-		//! destructor -- does nothing
-		virtual ~StatusListener() {}
-		
-		//! Called after a message has been read by all receivers, and thus has been removed from the queue
-		/*! In order to allow this to happen, a thread must repeatedly call
-		 *  MessageQueueBase::pollStatus() in order to check if other processes have
-		 *  read their messages since the last pollStatus call.
-		 *
-		 *  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
-		 *
-		 *  @param which The MessageQueueBase which has had message(s) read
-		 *  @param howmany The number of message which have been cleared */
-		virtual void messagesRead(MessageQueueBase& which, unsigned int howmany)=0;
-	};
-
-	//! Checks to see how many messages have been processed (read by all receivers and removed from queue) since the last call to pollStatus()
-	virtual unsigned int pollStatus() {
-		AutoLock autolock(lock);
-		unsigned int read=messagesRead;
-		messagesRead=0;
-		return read;
-	}
-
-	
 	//! The storage type for message entry indicies
 	/*! This index is to be used with accessor functions, but may be recycled for
 	 *  a new message after all receivers have read the previous message.  If you
@@ -70,33 +58,48 @@
 	
 	
 	//!< add one to the receiver reference count
-	virtual void addReceiver()=0;
+	virtual SemaphoreManager::semid_t addReceiver() ATTR_must_check =0;
 	//!< remove one from the receiver reference count
-	virtual void removeReceiver()=0;
+	virtual void removeReceiver(SemaphoreManager::semid_t rcvr)=0;
 	//! return the receiver reference count
 	virtual unsigned int getNumReceivers() const { return numReceivers; }
 
-
+	//! registers a semaphore which should be raised whenever a message is marked read
+	/*! The number of these are limited to the MAX_SENDERS template parameter of
+		*  MessageQueue... returns false if too many are already registered
+		*  
+		*  You probably don't want to call this directly, use a MessageQueueStatusThread */
+	virtual SemaphoreManager::semid_t addReadStatusListener() ATTR_must_check =0;
+	//! removes a semaphore from the status listener list
+	virtual void removeReadStatusListener(SemaphoreManager::semid_t sem)=0;
+	
+	
 	//! post a message into the queue -- a shared reference is added, the caller retains control current reference
-	/*! Thus, if you are sending a region and do not intend to use it again, call
-	 *  RCRegion::RemoveReference() after sending to free the sender's memory.
-	 *  Otherwise, you can continue to access the region, even as the receiver
-	 *  accesses it as well.  If both sides retain references, you can use the
-	 *  region as a shared memory area for future communication.  (beware of race
-	 *  conditions!) */
-	virtual void sendMessage(RCRegion * rcr)=0;
+	/*! Thus, if you are sending a region and do not intend to use it again, either pass
+	 *  true for autoDereference or call RCRegion::RemoveReference() after sending
+	 *  to free the sender's memory.
+	 *  
+	 *  If no one dereferences the region, you can continue to access the region,
+	 *  even as the receiver accesses it as well.  Thus if both sides retain references,
+	 *  you can use the region as a shared memory area for future communication.
+	 *  (beware of race conditions!)
+	 *
+	 *  If @a rcr is NULL, an empty message will be sent (there's still some overhead
+	 *  to this -- may want to consider a semaphore instead of a MessageQueue if all
+	 *  you're going to do is 'ping' another process with empty messages) */
+	virtual void sendMessage(RCRegion * rcr, bool autoDereference=false)=0;
 	//! request access to a particular message, increments read counter -- do not call more than once per receiver!
 	/*! The message is marked read and will be popped from the queue if all
 	 *  receivers have read the message as well.  The caller inherits a reference
 	 *  to the returned region -- call RemoveReference when you are done with
 	 *  it */
-	virtual RCRegion * readMessage(index_t msg)=0;
+	virtual RCRegion * readMessage(index_t msg, SemaphoreManager::semid_t rcvr)=0;
 	//! request access to a particular message, does not mark message -- call as often as you like
 	/*! The caller inherits a reference to the returned region -- call
 	 *  RemoveReference when you are done with it */
 	virtual RCRegion * peekMessage(index_t msg)=0;
-	//! increments read counter -- do not call more than once per receiver!
-	virtual void markRead(index_t msg)=0;
+	//! increments read counter -- do not call more than once per receiver per message!
+	virtual void markRead(index_t msg, SemaphoreManager::semid_t rcvr)=0;
 	//! do not allow any new messages to be posted
 	virtual void close() { AutoLock autolock(lock); isClosed=true; }
 
@@ -107,11 +110,19 @@
 	//! Each message gets a unique, monotonically increasing serial number; this function returns that number (#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)
+	virtual unsigned int getMessagesRead() { return messagesRead; }
+	
+	//! Returns the number of messages which have been sent
+	virtual unsigned int getMessagesSent() { return numMessages; }
+	
+	//! Returns the number of messages which have been sent
+	virtual unsigned int getMessagesUnread() { return getMessagesSent() - getMessagesRead(); }
 	
 	//! a typedef to make it easier to obtain a lock on the queue for the extent of a scope
-	typedef LockScope<ProcessID::NumProcesses> AutoLock;
-	//! returns a lock on the queue for the scope of the returned storage
-	AutoLock getLock() const { return AutoLock(lock); }
+	typedef MarkScope AutoLock;
+	//! returns a reference to the queue's inter-process lock
+	MutexLock<ProcessID::NumProcesses>& getLock() const { return lock; }
 
 	
 	virtual index_t oldest() const=0;          //!< return oldest message still in the queue (may or may not have been read by this process)
@@ -132,37 +143,113 @@
 	//! 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;
+	}
+	
+	//! 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 */
+	void addMessageFilter(MessageFilter& filter) {
+		filters[ProcessID::getID()]=&filter;
+	}
+	//! removes the current filter in place, if any
+	void removeMessageFilter() {
+		filters[ProcessID::getID()]=NULL;
+	}
 protected:
-	//! data storage needed for each message
-	struct entry {
-		entry() : id(), sn(), numRead(0) {} //!< constructor
-		entry(unsigned int serialNumber, RCRegion* r)
-			: id(r->ID()), sn(serialNumber), numRead(0) {} //!< constructor, pass message info
-		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
-		unsigned int numRead; //!< a count of the number of receivers which have read this message
-	};
+	//! the global semaphore manager, needs to be set (once, globally) via setSemaphoreManager() before any receivers are added
+	static SemaphoreManager* semgr;
+	
 	mutable MutexLock<ProcessID::NumProcesses> lock; //!< a lock to grant serial access to the queue
-	OverflowPolicy_t overflowPolicy; //!< the choice of how to handle message overflow -- see OverflowPolicy_t
+	volatile OverflowPolicy_t overflowPolicy; //!< the choice of how to handle message overflow -- see OverflowPolicy_t
 	bool isClosed; //!< if true, new messages will be rejected
 	bool reportDroppings; //!< if true, output will be sent on cerr when overflow occurs
 	unsigned int numMessages; //!< number of messages which have been sent (serial number of next message)
 	unsigned int numReceivers; //!< how many receivers to expect
-	unsigned int messagesRead; //!< number of messages which have been read and removed from queue since last call to pollStatus()
+	unsigned int messagesRead; //!< number of messages which have been read and removed from queue
+	MessageFilter* filters[ProcessID::NumProcesses]; //!< provides storage of one message filter per process
+private:
+	MessageQueueBase(const MessageQueueBase&); //!< this shouldn't be called...
+	MessageQueueBase& operator=(const MessageQueueBase&); //!< this shouldn't be called...
 };
 
 //! An implementation of MessageQueueBase, which provides mechanisms for sending shared memory regions between processes
-/*! @see MessageQueueBase */
-template<unsigned int MAX_UNREAD>
+/*! MAX_UNREAD is assigned to #CAPACITY, MAX_RECEIVERS is assigned to #RECEIVER_CAPACITY, and MAX_SENDERS is assigned to #SENDER_CAPACITY
+ *  @see MessageQueueBase, MessageQueueStatusListener, MessageReceiver */
+template<unsigned int MAX_UNREAD, unsigned int MAX_RECEIVERS=10, unsigned int MAX_SENDERS=10>
 class MessageQueue : public MessageQueueBase {
 public:
 	//! total number of messages which can be backed up in the queue
 	static const unsigned int CAPACITY=MAX_UNREAD;
+	//! total number of receivers which can be registered
+	static const unsigned int RECEIVER_CAPACITY=MAX_RECEIVERS;
+	//! total number of senders which can be registered
+	/*! More specifically, this is the maximum number of StatusListeners -- anyone
+	 *  can call sendMessage(), but only this number can get direct notification when
+	 *  messages are received. */
+	static const unsigned int SENDER_CAPACITY=MAX_SENDERS;
 	
 	//! constructor
-	MessageQueue() : MessageQueueBase(), mq() {}
+	MessageQueue() : MessageQueueBase(), mq(), rcvrs(), sndrs() {}
 	
-	virtual ~MessageQueue() {
+	//! destructor
+	virtual ~MessageQueue();
+	
+	virtual SemaphoreManager::semid_t addReadStatusListener() ATTR_must_check;
+	virtual void removeReadStatusListener(SemaphoreManager::semid_t sem);
+
+	virtual SemaphoreManager::semid_t addReceiver() ATTR_must_check;
+	virtual void removeReceiver(SemaphoreManager::semid_t rcvr);
+	
+	virtual void sendMessage(RCRegion * rcr, bool autoDereference=false);
+	virtual RCRegion * readMessage(index_t msg, SemaphoreManager::semid_t rcvr);
+	virtual RCRegion * peekMessage(index_t msg);
+	virtual void markRead(index_t msg, SemaphoreManager::semid_t rcvr);
+
+	virtual unsigned int getMessageSN(index_t msg) { /*AutoLock autolock(lock);*/ return mq[msg].sn; }
+	
+	virtual index_t oldest() const { AutoLock autolock(lock); return mq.begin(); }
+	virtual index_t newer(index_t it) const { AutoLock autolock(lock); return mq.next(it); }
+	virtual index_t older(index_t it) const { AutoLock autolock(lock); return mq.prev(it); }
+	virtual index_t newest() const { AutoLock autolock(lock); return mq.prev(mq.end()); }
+	virtual bool isEnd(index_t it) const { AutoLock autolock(lock); return it==mq.end() || it>=mq_t::MAX_ENTRIES; }
+	
+protected:
+	//! data storage needed for each message
+	struct entry {
+		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
+		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))
+	};
+	
+	//! shorthand for the type of data storage of message entries
+	typedef ListMemBuf<entry,MAX_UNREAD,index_t> mq_t;
+	//! the data storage of message entries
+	mq_t mq;
+
+	//! shorthand for the type of data storage of message entries
+	typedef ListMemBuf<SemaphoreManager::semid_t,MAX_RECEIVERS,index_t> rcvrs_t;
+	//! the data storage of receiver semaphores
+	rcvrs_t rcvrs;
+
+	//! returns the index within #rcvrs of the receiver id #rcvr
+	typename rcvrs_t::index_t lookupReceiver(SemaphoreManager::semid_t rcvr) const;
+	
+	//! shorthand for the type of data storage of message entries
+	typedef ListMemBuf<SemaphoreManager::semid_t,MAX_SENDERS,index_t> sndrs_t;
+	//! the data storage of receiver semaphores
+	sndrs_t sndrs;
+};
+
+template<unsigned int MAX_UNREAD, unsigned int MAX_RECEIVERS, unsigned int MAX_SENDERS>
+MessageQueue<MAX_UNREAD,MAX_RECEIVERS,MAX_SENDERS>::~MessageQueue() {
 		//lock shouldn't be necessary -- refcount should ensure the containing
 		//region isn't deleted until only one process has access anyway
 		//AutoLock autolock(lock);
@@ -172,18 +259,72 @@
 			rcr->RemoveReference();
 			mq.pop_front();
 		}
-	}
-	
-	virtual void addReceiver() {
+}
+
+template<unsigned int MAX_UNREAD, unsigned int MAX_RECEIVERS, unsigned int MAX_SENDERS>
+SemaphoreManager::semid_t MessageQueue<MAX_UNREAD,MAX_RECEIVERS,MAX_SENDERS>::addReadStatusListener() {
 		AutoLock autolock(lock);
+		SemaphoreManager::semid_t sem=semgr->getSemaphore();
+		if(sem==semgr->invalid()) {
+			std::cerr << "ERROR: unable to add read status listener to message queue because semaphore manager is out of semaphores" << std::endl;
+			return semgr->invalid();
+		}
+		if(sndrs.push_back(sem)==sndrs.end()) {
+			std::cerr << "ERROR: unable to add read status listener to message queue because message queue can't register any more senders (MAX_SENDERS)" << std::endl;
+			semgr->releaseSemaphore(sem);
+			return semgr->invalid();
+		}
+		return sem;
+}
+
+template<unsigned int MAX_UNREAD, unsigned int MAX_RECEIVERS, unsigned int MAX_SENDERS>
+void MessageQueue<MAX_UNREAD,MAX_RECEIVERS,MAX_SENDERS>::removeReadStatusListener(SemaphoreManager::semid_t sem) {
+		AutoLock autolock(lock);
+		for(index_t it=sndrs.begin(); it!=sndrs.end(); it=sndrs.next(it))
+			if(sndrs[it]==sem) {
+				sndrs.erase(it);
+				semgr->releaseSemaphore(sem);
+				break;
+			}
+}
+
+template<unsigned int MAX_UNREAD, unsigned int MAX_RECEIVERS, unsigned int MAX_SENDERS>
+SemaphoreManager::semid_t MessageQueue<MAX_UNREAD,MAX_RECEIVERS,MAX_SENDERS>::addReceiver() {
+		AutoLock autolock(lock);
+		SemaphoreManager::semid_t sem=semgr->getSemaphore();
+		if(sem==semgr->invalid()) {
+			std::cerr << "ERROR: unable to add receiver to message queue because semaphore manager is out of semaphores" << std::endl;
+			return semgr->invalid();
+		}
+		if(rcvrs.push_back(sem)==rcvrs.end()) {
+			std::cerr << "ERROR: unable to add receiver to message queue because message queue can't register any more receivers (MAX_RECEIVERS)" << std::endl;
+			semgr->releaseSemaphore(sem);
+			return semgr->invalid();
+		}
 		numReceivers++;
-	}
-	
-	virtual void removeReceiver() {
+		return sem;
+}
+
+template<unsigned int MAX_UNREAD, unsigned int MAX_RECEIVERS, unsigned int MAX_SENDERS>
+void MessageQueue<MAX_UNREAD,MAX_RECEIVERS,MAX_SENDERS>::removeReceiver(SemaphoreManager::semid_t rcvr) {
 		AutoLock autolock(lock);
+		index_t rcvr_id=rcvrs.begin();
+		for(; rcvr_id!=rcvrs.end(); rcvr_id=rcvrs.next(rcvr_id))
+			if(rcvrs[rcvr_id]==rcvr)
+				break;
+		if(rcvr_id==rcvrs.end()) {
+			std::cerr << "WARNING: tried to remove message queue receiver " << rcvr << ", which is not registered as a receiver for this queue" << std::endl;
+			return;
+		}
+		rcvrs.erase(rcvr_id);
+		semgr->releaseSemaphore(rcvr);
 		numReceivers--;
 		for(index_t it=mq.begin(); it!=mq.end(); it=mq.next(it)) {
-			if(mq[it].numRead==numReceivers) {
+			if(mq[it].readFlags[rcvr_id]) {
+				// the removed receiver had read this message, decrement the read count
+				mq[it].readFlags[rcvr_id]=false;
+				mq[it].numRead--;
+			} else if(mq[it].numRead==numReceivers) {
 				//all *remaining* processes have gotten a look, remove the neutral MessageQueue reference
 				RCRegion * rcr = RCRegion::attach(mq[it].id);
 				rcr->RemoveSharedReference();
@@ -191,15 +332,27 @@
 				it=mq.prev(it);
 				mq.erase(mq.next(it));
 				messagesRead++;
+				for(index_t sit=sndrs.begin(); sit!=sndrs.end(); sit=sndrs.next(sit))
+					semgr->raise(sndrs[sit],1);
 			}
 		}
-	}
-	
-	virtual void sendMessage(RCRegion * rcr) {
+}
+
+template<unsigned int MAX_UNREAD, unsigned int MAX_RECEIVERS, unsigned int MAX_SENDERS>
+void MessageQueue<MAX_UNREAD,MAX_RECEIVERS,MAX_SENDERS>::sendMessage(RCRegion * rcr, bool autoDereference/*=false*/) {
 		AutoLock autolock(lock);
+		if(rcr==NULL) {
+			rcr=new RCRegion(0);
+			autoDereference=true;
+		}
+		if(filters[ProcessID::getID()]!=NULL && !filters[ProcessID::getID()]->filterSendRequest(rcr))
+			return;
 		if(numReceivers==0) {
 			//if(reportDroppings)
 			//std::cerr << "Warning: MessageQueue dropping " << rcr->ID().key << " because there are no receivers" << std::endl;
+			messagesRead++; // counts as a read message (read by all 0 readers is still read by all readers!)
+			for(index_t sit=sndrs.begin(); sit!=sndrs.end(); sit=sndrs.next(sit))
+				semgr->raise(sndrs[sit],1);
 			return;
 		}
 		if(isClosed) {
@@ -207,7 +360,6 @@
 				std::cerr << "Warning: MessageQueue dropping " << rcr->ID().key << " because queue is closed" << std::endl;
 			return;
 		}
-		rcr->AddSharedReference();
 		if(mq.size()==mq.getMaxCapacity()) {
 			switch(overflowPolicy) {
 				case DROP_OLDEST: {
@@ -221,7 +373,6 @@
 				case DROP_NEWEST:
 					if(reportDroppings)
 						std::cerr << "WARNING: MessageQueue full, dropping newest unread message (" << rcr->ID().key << ")" << std::endl;
-					rcr->RemoveSharedReference();
 					return;
 				case WAIT:
 					if(reportDroppings)
@@ -233,43 +384,76 @@
 						usleep(MutexLockBase::usleep_granularity*15);
 						for(unsigned int i=0; i<ll; i++)
 							lock.lock(ProcessID::getID());
+						if(overflowPolicy!=WAIT) { //may have been changed by a different thread while we were waiting
+							sendMessage(rcr); //retry with the new policy
+							return;
+						}
 					}
-					break;
+						break;
 				case THROW_BAD_ALLOC:
 					if(reportDroppings)
 						std::cerr << "WARNING: MessageQueue full, throwing bad_alloc exception" << std::endl;
-					rcr->RemoveSharedReference();
 					throw std::bad_alloc();
 					break;
 			}
 		}
+		rcr->AddSharedReference();
 		if(mq.push_back(entry(numMessages++,rcr))==mq.end()) {
 			//our overflow policy should've prevented this
 			std::cerr << "ERROR: MessageQueue unable to add message; buggy overflow policy?" << std::endl;
 			exit(EXIT_FAILURE);
 		}
-	}
-	
-	virtual RCRegion * readMessage(index_t msg) {
+		
+		//std::cout << Process::getName() << " sent " << (numMessages-1) << " at " << TimeET() << std::endl;
+		//notify receivers
+		for(index_t it=rcvrs.begin(); it!=rcvrs.end(); it=rcvrs.next(it))
+			semgr->raise(rcvrs[it],1);
+		
+		if(autoDereference)
+			rcr->RemoveReference();
+}
+
+template<unsigned int MAX_UNREAD, unsigned int MAX_RECEIVERS, unsigned int MAX_SENDERS>
+RCRegion * MessageQueue<MAX_UNREAD,MAX_RECEIVERS,MAX_SENDERS>::readMessage(index_t msg, SemaphoreManager::semid_t rcvr) {
 		AutoLock autolock(lock);
 		RCRegion * rcr = RCRegion::attach(mq[msg].id);
+		index_t rcvr_id=lookupReceiver(rcvr);
+		if(rcvr_id==rcvrs.end())
+			return rcr;
+		if(mq[msg].readFlags[rcvr_id]) {
+			std::cerr << "WARNING: MessageQueue::readMessage(): Receiver re-reading message, could be recycled/invalidated any time" << std::endl;
+			return rcr; // already read, just return it
+		}
+		mq[msg].readFlags[rcvr_id]=true;
 		mq[msg].numRead++;
 		if(mq[msg].numRead==numReceivers) {
 			//all processes have gotten a look, remove the neutral MessageQueue reference
 			rcr->RemoveSharedReference();
 			mq.erase(msg);
 			messagesRead++;
+			for(index_t sit=sndrs.begin(); sit!=sndrs.end(); sit=sndrs.next(sit))
+				semgr->raise(sndrs[sit],1);
 		}
 		return rcr;
-	}
-	
-	virtual RCRegion * peekMessage(index_t msg) {
+}
+
+template<unsigned int MAX_UNREAD, unsigned int MAX_RECEIVERS, unsigned int MAX_SENDERS>
+RCRegion * MessageQueue<MAX_UNREAD,MAX_RECEIVERS,MAX_SENDERS>::peekMessage(index_t msg) {
 		//AutoLock autolock(lock); //I don't think a lock is necessary here
 		return RCRegion::attach(mq[msg].id);
-	}
-	
-	virtual void markRead(index_t msg) {
+}
+
+template<unsigned int MAX_UNREAD, unsigned int MAX_RECEIVERS, unsigned int MAX_SENDERS>
+void MessageQueue<MAX_UNREAD,MAX_RECEIVERS,MAX_SENDERS>::markRead(index_t msg, SemaphoreManager::semid_t rcvr) {
 		AutoLock autolock(lock);
+		index_t rcvr_id=lookupReceiver(rcvr);
+		if(rcvr_id==rcvrs.end())
+			return;
+		if(mq[msg].readFlags[rcvr_id]) {
+			std::cerr << "WARNING: MessageQueue::markRead(): Receiver re-reading message, could be recycled/invalidated any time" << std::endl;
+			return; // already read, just return it
+		}
+		mq[msg].readFlags[rcvr_id]=true;
 		mq[msg].numRead++;
 		if(mq[msg].numRead==numReceivers) {
 			//all processes have gotten a look, remove the neutral MessageQueue reference
@@ -278,24 +462,20 @@
 			rcr->RemoveReference();
 			mq.erase(msg);
 			messagesRead++;
+			for(index_t sit=sndrs.begin(); sit!=sndrs.end(); sit=sndrs.next(sit))
+				semgr->raise(sndrs[sit],1);
 		}
-	}
+}
 
-	virtual unsigned int getMessageSN(index_t msg) { /*AutoLock autolock(lock);*/ return mq[msg].sn; }
-	
-	virtual index_t oldest() const { AutoLock autolock(lock); return mq.begin(); }
-	virtual index_t newer(index_t it) const { AutoLock autolock(lock); return mq.next(it); }
-	virtual index_t older(index_t it) const { AutoLock autolock(lock); return mq.prev(it); }
-	virtual index_t newest() const { AutoLock autolock(lock); return mq.prev(mq.end()); }
-	virtual bool isEnd(index_t it) const { AutoLock autolock(lock); return it==mq.end() || it>=mq_t::MAX_ENTRIES; }
-	
-protected:
-	//! shorthand for the type of data storage of message entries
-	typedef ListMemBuf<entry,MAX_UNREAD,index_t> mq_t;
-	
-	//! the data storage of message entries
-	mq_t mq;
-};
+template<unsigned int MAX_UNREAD, unsigned int MAX_RECEIVERS, unsigned int MAX_SENDERS>
+typename MessageQueue<MAX_UNREAD,MAX_RECEIVERS,MAX_SENDERS>::rcvrs_t::index_t
+MessageQueue<MAX_UNREAD,MAX_RECEIVERS,MAX_SENDERS>::lookupReceiver(SemaphoreManager::semid_t rcvr) const {
+	for(index_t rcvr_id=rcvrs.begin(); rcvr_id!=rcvrs.end(); rcvr_id=rcvrs.next(rcvr_id))
+		if(rcvrs[rcvr_id]==rcvr)
+			return rcvr_id;
+	std::cerr << "WARNING: tried to look up queue receiver " << rcvr << ", which is not registered as a receiver for this queue" << std::endl;
+	return rcvrs.end();
+}
 
 /*! @file
  * @brief Defines MessageQueue, which provides mechanisms for sending shared memory regions between processes
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/MessageQueueStatusThread.cc ./IPC/MessageQueueStatusThread.cc
--- ../Tekkotsu_2.4.1/IPC/MessageQueueStatusThread.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./IPC/MessageQueueStatusThread.cc	2006-08-29 01:56:46.000000000 -0400
@@ -0,0 +1,140 @@
+#ifndef PLATFORM_APERIOS
+#include "MessageQueueStatusThread.h"
+#include "MessageQueue.h"
+#include "Shared/debuget.h"
+#include <algorithm>
+
+using namespace std; 
+
+MessageQueueStatusThread::~MessageQueueStatusThread() {
+	if(isRunning()) {
+		stop();
+		//join(); // join turns out to be a bad idea here -- the thread being stopped may be waiting on a lock we currently hold
+	}
+}
+
+void MessageQueueStatusThread::addStatusListener(StatusListener* l) {
+	if(l==NULL)
+		return;
+	if(find(statusListeners.begin(),statusListeners.end(),l)==statusListeners.end()) {
+		//not already added
+		statusListeners.push_back(l);
+		if(!isRunning()) {
+			if(queue==NULL)
+				return;
+			semid=queue->addReadStatusListener();
+			if(semid==queue->getSemaphoreManager()->invalid()) {
+				std::cerr << "ERROR: could not start MessageQueueStatusThread -- out of semaphore IDs" << std::endl;
+				return;
+			}
+			//cout << "MessageQueueStatusThread added MessageQueue read listener" << endl;
+			numRead=queue->getMessagesRead();
+			start();
+		}
+	}
+}
+
+void MessageQueueStatusThread::removeStatusListener(StatusListener* l) {
+	std::list<StatusListener*>::iterator it=find(statusListeners.begin(),statusListeners.end(),l);
+	if(it!=statusListeners.end())
+		statusListeners.erase(it);
+	if(isRunning() && 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
+	}
+}
+
+void MessageQueueStatusThread::setMessageQueue(MessageQueueBase& mq) {
+	if(running) {
+		stop();
+		//join(); // join turns out to be a bad idea here -- the thread being stopped may be waiting on a lock we currently hold
+	}
+	queue=&mq;
+	if(statusListeners.size()!=0)
+		start();
+	/*
+	MessageQueueBase* oldqueue=queue;
+	SemaphoreManager::semid_t oldsem=semid;
+	queue=&mq;
+	semid=queue->addReadStatusListener();
+	if(semid==queue->getSemaphoreManager()->invalid()) {
+		std::cerr << "ERROR: could not switch MessageQueue -- new queue out of semaphores, stopping thread" << std::endl;
+		queue=oldqueue;
+		semid=oldsem;
+		if(running)
+			stop();
+		return;
+	}
+	numRead=queue->getMessagesRead();
+	if(oldqueue!=NULL && oldsem!=queue->getSemaphoreManager()->invalid()) {
+		if(running)
+			oldqueue->getSemaphoreManager()->raise(oldsem,1); //so run will notice the switchover
+		oldqueue->removeReadStatusListener(oldsem);
+	}*/
+}
+
+MessageQueueBase* MessageQueueStatusThread::getMessageQueue() {
+	return queue;
+}
+
+bool MessageQueueStatusThread::launched() {
+	return Thread::launched();
+}
+
+void * MessageQueueStatusThread::run() {
+	for(;;) {
+		queue->getSemaphoreManager()->lower(semid,1,true);
+		//there might be a few reads, handle them as a group
+		unsigned int more=queue->getSemaphoreManager()->getValue(semid);
+		if(more>0)
+			if(!queue->getSemaphoreManager()->lower(semid,more,false))
+				std::cerr << "WARNING: MessageQueueStatusThread had a message notification disappear (is someone else using the semaphore?  Get your own!)" << std::endl;
+		testCancel();
+#ifdef DEBUG
+		// This part just for sanity checking -- could do away with numRead altogether otherwise
+		unsigned int nowRead=queue->getMessagesRead();
+		unsigned int read=nowRead-numRead;
+		numRead=nowRead;
+		ASSERT(read==more+1,"WARNING: MessageQueueStatusThread's semaphore count does not match queue's read count ("<< (more+1) << " vs " << read<<")");
+#endif
+		//ok, notify the listeners
+		fireMessagesRead(more+1);
+	}
+}
+
+void MessageQueueStatusThread::stop() {
+	Thread::stop();
+	if(semid!=queue->getSemaphoreManager()->invalid()) //if semid is still invalid, probably canceling before the launch got off
+		queue->getSemaphoreManager()->raise(semid,1); //so run will notice the stop request
+}
+
+void MessageQueueStatusThread::cancelled() {
+	if(queue==NULL)
+		return;
+	//cout << "MessageQueueStatusThread removing MessageQueue read listener" << endl;
+	queue->removeReadStatusListener(semid);
+	semid=queue->getSemaphoreManager()->invalid();
+}
+
+void MessageQueueStatusThread::fireMessagesRead(unsigned int howmany) {
+	if(howmany==0)
+		return;
+	std::list<StatusListener*>::iterator it=statusListeners.begin();
+	while(it!=statusListeners.end()) {
+		std::list<StatusListener*>::iterator cur=it++; //increment early in case the listener changes subscription
+		(*cur)->messagesRead(*queue,howmany);
+	}
+}
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/MessageQueueStatusThread.h ./IPC/MessageQueueStatusThread.h
--- ../Tekkotsu_2.4.1/IPC/MessageQueueStatusThread.h	1969-12-31 19:00:00.000000000 -0500
+++ ./IPC/MessageQueueStatusThread.h	2006-06-16 21:15:38.000000000 -0400
@@ -0,0 +1,102 @@
+//-*-c++-*-
+#ifndef INCLUDED_MessageQueueStatusThread_h_
+#define INCLUDED_MessageQueueStatusThread_h_
+
+#ifdef PLATFORM_APERIOS
+#  warning MessageQueueStatusThread is not Aperios compatable, this is not going to compile
+#else
+
+#include "IPC/SemaphoreManager.h"
+#include "IPC/Thread.h"
+#include <list>
+
+class MessageQueueBase;
+
+//! description of MessageQueueStatusThread
+class MessageQueueStatusThread : protected Thread {
+public:
+	//!An interface to allow you to receive callbacks when a message has been read from a MessageQueue, subscribed via an external class which is monitoring the queue's MessageQueueBase::pollStatus() (e.g. LoadFileThread)
+	class StatusListener {
+	public:
+		//! destructor -- does nothing
+		virtual ~StatusListener() {}
+		
+		//! Called after a message has been read by all receivers, and thus has been removed from the queue
+		/*! 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
+		*
+		*  @param which The MessageQueueBase which has had message(s) read
+		*  @param howmany The number of message which have been cleared */
+		virtual void messagesRead(MessageQueueBase& which, unsigned int howmany)=0;
+	};
+	
+	
+	//! constructor
+	MessageQueueStatusThread()
+		: Thread(), statusListeners(), queue(NULL), semid(), numRead()
+	{}
+	//! constructor, automatically starts the thread with the specified queue, and an optional initial listener
+	explicit MessageQueueStatusThread(MessageQueueBase& mq, StatusListener* listener=NULL)
+		: Thread(), statusListeners(), queue(NULL), semid(), numRead()
+	{
+		setMessageQueue(mq);
+		addStatusListener(listener);
+	}
+	//! destructor, remove ourself from queue
+	~MessageQueueStatusThread();
+
+	//! Request updates to StatusListener callbacks
+	virtual void addStatusListener(StatusListener* l);
+	//! Unsubscribes a StatusListener from future updates
+	virtual void removeStatusListener(StatusListener* l);
+	
+	//! (re)sets the message queue being listened to
+	virtual void setMessageQueue(MessageQueueBase& mq);
+	//! returns the current queue
+	virtual MessageQueueBase* getMessageQueue();
+	
+protected:
+	//! start the thread
+	virtual bool launched();
+	//! wait for the queue's message read semaphore to be raised, and notify listeners
+	virtual void* run();
+	//! indicates it's time to stop monitoring the queue (need to raise the semaphore so run() will notice the stop)
+	virtual void stop();
+	//! cleanup
+	virtual void cancelled();
+	
+	//! Notifies statusListeners that a message has been read by all MessageQueue receivers
+	virtual void fireMessagesRead(unsigned int howmany);
+
+	//! MessageQueueBase::StatusListeners currently subscribed from addStatusListener()
+	std::list<StatusListener*> statusListeners;
+	
+	//! The MessageQueue that this thread is monitoring
+	MessageQueueBase* queue;
+	
+	//! 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
+	unsigned int numRead;
+	
+private:
+	MessageQueueStatusThread(const MessageQueueStatusThread&); //!< don't call, shouldn't copy
+	MessageQueueStatusThread& operator=(const MessageQueueStatusThread&); //!< don't call, shouldn't assign
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/MessageReceiver.cc ./IPC/MessageReceiver.cc
--- ../Tekkotsu_2.4.1/IPC/MessageReceiver.cc	2005-07-28 14:22:16.000000000 -0400
+++ ./IPC/MessageReceiver.cc	2006-08-23 17:48:10.000000000 -0400
@@ -1,31 +1,37 @@
 #ifndef PLATFORM_APERIOS
 
 #include "MessageReceiver.h"
+#include "Shared/debuget.h"
 //#include "local/sim/Process.h"
 //#include <iostream>
 //using namespace std;
 
-MessageReceiver::MessageReceiver(MessageQueueBase& mq, bool (*callback) (RCRegion*)/*=NULL*/, bool startThread/*=true*/)
-: Thread(), queue(mq), nextMessage(0), lastProcessedMessage(-1U), process(callback), sleeptime(1000), curit((index_t)-1)
+MessageReceiver::MessageReceiver(MessageQueueBase& mq, bool (*callback) (RCRegion*)/*=NULL*/, bool startThread/*=true*/, bool subscribe/*=true*/)
+: Thread(), queue(mq), semid(mq.getSemaphoreManager()->invalid()),
+nextMessage(0), lastProcessedMessage(-1U), process(callback), curit((index_t)-1)
 {
-	queue.addReceiver();
 	if(startThread)
 		start();
+	else if(subscribe) {
+		ASSERTRET(semid==queue.getSemaphoreManager()->invalid(),"semid is already set?");
+		semid=queue.addReceiver();
+		if(semid==queue.getSemaphoreManager()->invalid())
+			std::cerr << "ERROR: could not start MessageReceiver -- out of semaphore IDs" << std::endl;
+	}
 }
 
 MessageReceiver::~MessageReceiver() {
-	if(isRunning())
-		queue.removeReceiver();
+	if(!isRunning())
+		return;
+	stop();
+	join();
+	queue.removeReceiver(semid);
+	semid=queue.getSemaphoreManager()->invalid();
 }
 
 RCRegion * MessageReceiver::peekNextMessage() {
 	MessageQueueBase::AutoLock autolock(queue.getLock());
-	if(queue.isEnd(curit)) {
-		index_t it=queue.newest(); //start with the newest
-		while(!queue.isEnd(it) && queue.getMessageSN(it)>=nextMessage)
-			it=queue.older(it); //scan back to the first already read by this process
-		curit=it=queue.newer(it); //go to the following one (first unread)
-	}
+	findCurrentMessage();
 	if(queue.isEnd(curit))
 		return NULL;
 	return queue.peekMessage(curit);
@@ -33,95 +39,103 @@
 
 RCRegion * MessageReceiver::getNextMessage() {
 	MessageQueueBase::AutoLock autolock(queue.getLock());
-	index_t it; //will be set to the current message to return; curit will be set to the following message
+	findCurrentMessage();
+	if(queue.isEnd(curit))
+		return NULL;
+	nextMessage=queue.getMessageSN(curit)+1;
+	curit=queue.newer(curit); //next time, start on (or peek at) the one after this
+	return queue.readMessage(curit,semid);
+}
+
+void MessageReceiver::stop() {
+	Thread::stop();
+	queue.getSemaphoreManager()->raise(semid,1); //trigger a check so the thread will notice the stop
+}
+
+void MessageReceiver::findCurrentMessage() {
 	if(queue.isEnd(curit)) {
-		it=queue.newest(); //start with the newest
-		while(!queue.isEnd(it) && queue.getMessageSN(it)>=nextMessage)
-			it=queue.older(it); //scan back to the first already read by this process
-		curit=it=queue.newer(it); //go to the following one (first unread)
+		curit=queue.newest(); //start with the newest
+		while(!queue.isEnd(curit) && queue.getMessageSN(curit)>=nextMessage)
+			curit=queue.older(curit); //scan back to the first already read by this process
+		curit=queue.newer(curit); //go to the following one (first unread)
 	} else {
-		it=curit;
-		while(!queue.isEnd(it) && queue.getMessageSN(it)<nextMessage)
-			it=queue.newer(it); //scan forward to next message not read by this process
-		curit=it;
+		while(!queue.isEnd(curit) && queue.getMessageSN(curit)<nextMessage)
+			curit=queue.newer(curit); //scan forward to next message not read by this process
 	}
-	if(queue.isEnd(it))
-		return NULL;
-	nextMessage=queue.getMessageSN(it)+1;
-	curit=queue.newer(it); //next time, start on (or peek at) the one after this
-	return queue.readMessage(it);
 }
 
-void MessageReceiver::markRead() {
-	if(queue.isEnd(curit))
-		return;
-	nextMessage=queue.getMessageSN(curit)+1;
-	queue.markRead(curit);
-	curit=queue.newer(curit); //next time, start on (or peek at) the one after this
+void MessageReceiver::finish() {
+	if(isRunning()) {
+		stop();
+		join();
+	}
+	if(semid!=queue.getSemaphoreManager()->invalid()) {
+		//cout << Process::getName() << " finish" << endl;
+		while(processNextMessage()) {}
+		queue.removeReceiver(semid);
+		semid=queue.getSemaphoreManager()->invalid();
+	}
 }
 
-void MessageReceiver::waitNextMessage() {
-	for(;;) {
-		RCRegion * ans=peekNextMessage();
-		if(ans!=NULL)
-			return;
-		usleep(sleeptime);
+bool MessageReceiver::launched() {
+	if(semid==queue.getSemaphoreManager()->invalid())
+		semid=queue.addReceiver();
+	if(semid==queue.getSemaphoreManager()->invalid()) {
+		std::cerr << "ERROR: could not start MessageReceiver -- out of semaphore IDs" << std::endl;
+		return false;
 	}
+	return Thread::launched();
 }
 
 unsigned int MessageReceiver::runloop() {
-	RCRegion * msg;
 	//cout << Process::getName() << " runloop" << endl;
-	while((msg=peekNextMessage())!=NULL) {
-		//cout << Process::getName() << " got " << msg->ID().key << ' ' << lastProcessedMessage << ' ' << queue.getMessageSN(curit) << ' ' << curit << endl;
-		bool used=false;
-		if(lastProcessedMessage!=queue.getMessageSN(curit)) {
-			//cout << Process::getName() << " process" << endl;
-			lastProcessedMessage=queue.getMessageSN(curit);
-			used=process(msg);
-			if(used)
-				markRead(); // message was consumed, mark it read so next peek will get the next
-			//cout << used << ' ' << curit;
-			//if(!queue.isEnd(curit))
-			//cout << lastProcessedMessage << ' ' << queue.getMessageSN(curit);
-			//cout << endl;
-		}
-		msg->RemoveReference();
-		if(!used) //have to break out of the loop to sleep & check interrupts -- otherwise we'll busyloop peeking at the same message
-			break;
+	pushNoCancel();
+	waitNextMessage();
+	while(processNextMessage()) { //get everything else in the queue
+		queue.getSemaphoreManager()->lower(semid,1,false);
 	}
-	return sleeptime;
+	popNoCancel();
+	return 0;
 }
 
-void MessageReceiver::finish() {
-	if(!isRunning())
-		return;
-	stop();
-	join();
-	RCRegion * msg;
-	//cout << Process::getName() << " finish" << endl;
-	while((msg=peekNextMessage())!=NULL) {
-		//cout << Process::getName() << " got " << msg->ID().key << ' ' << lastProcessedMessage << ' ' << queue.getMessageSN(curit) << ' ' << curit << endl;
-		bool used=false;
-		if(lastProcessedMessage!=queue.getMessageSN(curit)) {
-			//cout << Process::getName() << " process" << endl;
-			lastProcessedMessage=queue.getMessageSN(curit);
-			used=process(msg);
-			if(used)
-				markRead(); // message was consumed, mark it read so next peek will get the next
-			//cout << used << ' ' << curit;
-			//if(!queue.isEnd(curit))
-			//cout << lastProcessedMessage << ' ' << queue.getMessageSN(curit);
-			//cout << endl;
-		}
-		msg->RemoveReference();
-		if(!used) // if the consumer can't process immediately, we're not waiting around -- drop the rest
-			break;
+bool MessageReceiver::waitNextMessage() {
+	return queue.getSemaphoreManager()->lower(semid,1,true);
+}
+
+bool MessageReceiver::processNextMessage() {
+	RCRegion * msg=peekNextMessage();
+	if(msg==NULL)
+		return false;
+	//cout << Process::getName() << " got " << msg->ID().key << ' ' << lastProcessedMessage << ' ' << queue.getMessageSN(curit) << ' ' << curit << endl;
+	bool used=false;
+	if(lastProcessedMessage!=queue.getMessageSN(curit)) {
+		lastProcessedMessage=queue.getMessageSN(curit);
+		//cout << Process::getName() << " process received " << lastProcessedMessage << " at " << TimeET() << endl;
+		used=process(msg);
+		if(used)
+			markRead(false); // message was consumed, mark it read
+		//cout << used << ' ' << curit;
+		//if(!queue.isEnd(curit))
+		//cout << lastProcessedMessage << ' ' << queue.getMessageSN(curit);
+		//cout << endl;
 	}
-	queue.removeReceiver();
+	msg->RemoveReference();
+	return used;
+}
+
+void MessageReceiver::markRead(bool checkNext) {
+	findCurrentMessage();
+	if(queue.isEnd(curit))
+		return;
+	nextMessage=queue.getMessageSN(curit)+1;
+	queue.markRead(curit,semid);
+	curit=queue.newer(curit); //next time, start on (or peek at) the one after this
+	if(checkNext && !queue.isEnd(curit))
+		queue.getSemaphoreManager()->raise(semid,1); //trigger a check if there are more waiting in the queue
 }
 
 
+
 /*! @file
  * @brief 
  * @author Ethan Tira-Thompson (ejt) (Creator)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/MessageReceiver.h ./IPC/MessageReceiver.h
--- ../Tekkotsu_2.4.1/IPC/MessageReceiver.h	2005-07-28 14:22:16.000000000 -0400
+++ ./IPC/MessageReceiver.h	2006-08-23 16:16:03.000000000 -0400
@@ -9,29 +9,56 @@
 #include "MessageQueue.h"
 #include "Thread.h"
 
-//! description of MessageReceiver
+//! Spawns a thread for monitoring a MessageQueue, calls a specified function when new messages are available
+/*! Uses a semaphore which is raised by the MessageQueue itself when a new message is posted.
+ *  This should have almost no overhead, and fairly low latency (at least, much lower latency
+ *  than you would get by running multiple busy loops polling for new messages)
+ *
+ *  Keep in mind that the monitor runs in a separate thread, so you will need to consider mutex issues
+ *  when the callback is executing. */
 class MessageReceiver : public Thread {
 public:
-	explicit MessageReceiver(MessageQueueBase& mq, bool (*callback) (RCRegion*)=NULL, bool startThread=true);
-	~MessageReceiver();
+	//! constructor, indicate the message queue, and optional callback function and whether to start the monitor right away
+	/*! @param mq is the message queue that the receiver will register with
+	 *  @param callback is the function to call when messages are received
+	 *  @param startThread controls whether the thread will be launched by the constructor
+	 *  @param subscribe only applies if @a startThread is false, indicates whether the receiver should register as a listener even though the thread isn't checking (yet)
+	 *  This last parameter allows you to avoid missing messages that come in before you're ready to process them */
+	explicit MessageReceiver(MessageQueueBase& mq, bool (*callback) (RCRegion*)=NULL, bool startThread=true, bool subscribe=true);
+	//! destructor, stops and joins thread
+	virtual ~MessageReceiver();
 	
-	RCRegion * peekNextMessage();
-	RCRegion * getNextMessage();
-	void markRead();
-	void waitNextMessage();
-	unsigned int runloop();
-	void finish();
+	//! returns the next unread message without marking it read, or NULL if there are currently no more messages.  MessageReceiver retains reference.
+	virtual RCRegion * peekNextMessage();
+	//! returns the next unread message, marking it as read.  Caller inherits reference, and should call RemoveReference when done.
+	virtual RCRegion * getNextMessage();
+	//! marks the current message as read, and allows MessageQueue to process next unread message
+	void markRead() { markRead(true); }
 	
-	void setCallback(bool (*callback) (RCRegion*)) { process=callback; }
+	//! thread control -- stop monitoring (can call start() later to resume)
+	virtual void stop();
+	//! thread control -- stop(), join(), and process any final messages in the queue; unsubscribes as a listener of the MessageQueue
+	virtual void finish();
+	
+	//! allows you to change the callback function -- should be set before the thread is started (otherwise, why bother starting it?)
+	virtual void setCallback(bool (*callback) (RCRegion*)) { process=callback; }
 	
 protected:
-	typedef MessageQueueBase::index_t index_t;
-	MessageQueueBase& queue;
-	unsigned int nextMessage;
-	unsigned int lastProcessedMessage;
-	bool (*process) (RCRegion*);
-	unsigned int sleeptime;
-	index_t curit;
+	typedef MessageQueueBase::index_t index_t; //!< shorthand for the message id type
+
+	virtual void findCurrentMessage(); //!< sets #curit to the oldest message which hasn't been marked read
+	virtual bool launched(); //!< register as a listener with the queue, if we haven't already (retains listener status between stop/start)
+	virtual unsigned int runloop(); //!< wait for a new message, and then process it
+	virtual bool waitNextMessage(); //!< wait for #semid to be raised to indicate a new message is in the queue (or at least, that it needs to be checked); returns false if interrupted
+	virtual bool processNextMessage(); //!< gets the next message and processes it
+	virtual void markRead(bool checkNext); //!< if @a checksNext is set, raises #semid so that if additional messages came in while we were processing the current one, they will be picked up
+	
+	MessageQueueBase& queue; //!< the MessageQueue being monitored
+	SemaphoreManager::semid_t semid; //!< the semaphore raised when the queue should be checked for new messages
+	unsigned int nextMessage; //!< the expected serial number of the next message to be sent
+	unsigned int lastProcessedMessage; //!< the serial number of the last received message
+	bool (*process) (RCRegion*); //!< the client callback function
+	index_t curit; //!< the message id of the last received message (currently being processed)
 	
 private:
 	MessageReceiver(const MessageReceiver& r); //!< don't call
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/MutexLock.cc ./IPC/MutexLock.cc
--- ../Tekkotsu_2.4.1/IPC/MutexLock.cc	2005-06-01 01:47:46.000000000 -0400
+++ ./IPC/MutexLock.cc	2006-05-08 18:07:54.000000000 -0400
@@ -5,6 +5,7 @@
 #ifndef PLATFORM_APERIOS
 SemaphoreManager MutexLockBase::preallocated;
 SemaphoreManager* MutexLockBase::semgr=&preallocated;
+ThreadNS::Lock MutexLockBase::thdLocks[SemaphoreManager::MAX_SEM];
 #endif
 
 /*! @file 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/MutexLock.h ./IPC/MutexLock.h
--- ../Tekkotsu_2.4.1/IPC/MutexLock.h	2005-07-25 23:22:02.000000000 -0400
+++ ./IPC/MutexLock.h	2006-08-11 17:51:40.000000000 -0400
@@ -2,12 +2,16 @@
 #ifndef __MUTEX_LOCK_ET__
 #define __MUTEX_LOCK_ET__
 
+#include "Shared/Resource.h"
+#include "ProcessID.h"
 #include <iostream>
+#include <exception>
+#include <typeinfo>
+
 #ifndef PLATFORM_APERIOS
 #  include <unistd.h>
 #  include "SemaphoreManager.h"
-#else
-#  include <exception>
+#  include "Thread.h"
 #endif
 
 // If you want to use the same software-only lock on both
@@ -25,7 +29,7 @@
  *  created via fork to handle virtual calls properly, and I don't
  *  want to put that overhead on the otherwise lightweight SoundPlay
  *  process under Aperios. */
-class MutexLockBase {
+class MutexLockBase : public Resource {
 public:
 	virtual ~MutexLockBase() {} //!< basic destructor
 	
@@ -57,6 +61,7 @@
 	static void aboutToFork() {
 		preallocated.aboutToFork();
 	}
+	
 protected:
 	//! the global semaphore manager object for all locks, may point to preallocated during process initialization or destruction
 	static SemaphoreManager* semgr;
@@ -74,6 +79,9 @@
 	 *  it's the only thing that's going to need an ID before the
 	 *  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];
 #endif
 };
 
@@ -130,22 +138,27 @@
 	
 	//! 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)) {
 			//have to wait and then claim lock
-			if(semgr!=NULL && !semgr->hadFault())
+			if(semgr!=NULL && !semgr->hadFault()) {
 				semgr->testZero_add(sem,1);
-			else
+			} else
 				std::cerr << "Warning: MutexLock assuming lock of " << sem << " because SemaphoreManager is NULL" << std::endl;
 			owner_index=id;
 		} else {
@@ -161,6 +174,8 @@
 	/*! 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;
@@ -174,8 +189,10 @@
 			if(semgr->testZero_add(sem,1,false)) {
 				owner_index=id;
 				return true;
-			} else
+			} else {
+				thdLocks[sem].unlock();
 				return false;
+			}
 		}
 	}
 	
@@ -184,17 +201,20 @@
 		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
@@ -205,6 +225,8 @@
 			return;
 		}
 		semgr->setValue(sem,0);
+		while(thdLocks[sem].getLockLevel()>0)
+			thdLocks[sem].unlock();
 	}
 	
 	//! returns the lockcount
@@ -216,9 +238,17 @@
 	}
 	
 	//! returns the current owner's id
-	inline int owner() { return owner_index; }
+	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();
+	}
+	
 	SemaphoreManager::semid_t sem; //!< the SysV semaphore number
 	unsigned int owner_index; //!< holds the tekkotsu process id of the current lock owner
 };
@@ -229,9 +259,15 @@
 #else //SOFTWARE ONLY mutual exclusion, used on Aperios, or if MUTEX_LOCK_ET_USE_SOFTWARE_ONLY is defined
 
 
+//#define MUTEX_LOCK_ET_USE_SPINCOUNT
 
+// if DEBUG_MUTEX_LOCK is defined, we'll display information about each lock
+// access while the left front paw button is pressed
+//#define DEBUG_MUTEX_LOCK
 
-//#define MUTEX_LOCK_ET_USE_SPINCOUNT
+#ifdef DEBUG_MUTEX_LOCK
+#  include "Shared/WorldState.h"
+#endif
 
 //! A software only mutual exclusion lock. (does not depend on processor or OS support)
 /*! Use this to prevent more than one process from accessing a data structure
@@ -268,6 +304,16 @@
 	//! constructor, just calls the init() function.
 	MutexLock() : doors_used(0), owner_index(NO_OWNER), lockcount(0) { init();	}
 
+#ifndef PLATFORM_APERIOS
+	//! destructor, re-enables thread cancelability if lock was held (non-aperios only)
+	~MutexLock() {
+		if(owner_index!=NO_OWNER) {
+			owner_index=NO_OWNER;
+			thdLock[sem].unlock();
+		}
+	}
+#endif
+
 	//! blocks (by busy looping on do_try_lock()) until a lock is achieved
 	/*! You should pass some process-specific ID number as the input - just
 	 *  make sure no other process will be using the same value.
@@ -289,7 +335,7 @@
 	unsigned int get_lock_level() const { return lockcount;	}
 
 	//! returns the current owner's id
-	inline int owner() { return owner_index==NO_OWNER ? NO_OWNER : doors[owner_index].id; }
+	inline int owner() const { return owner_index==NO_OWNER ? NO_OWNER : doors[owner_index].id; }
 
 	//! allows you to reset one of the possible owners, so another process can take its place.  This is not tested
 	void forget(int id);
@@ -300,6 +346,14 @@
 #endif
 	
  protected:
+	friend class MarkScope;
+	virtual void useResource(Resource::Data&) {
+		lock(ProcessID::getID());
+	}
+	virtual void releaseResource(Resource::Data&) {
+		unlock();
+	}
+	
 	//! Does the work of trying to get a lock
 	/*! Pass @c true for @a block if you want it to use FCFS blocking
 	 *  instead of just returning right away if another process has the lock */
@@ -349,11 +403,20 @@
 template<unsigned int num_doors>
 void
 MutexLock<num_doors>::lock(int id) {
-	if(owner()!=id)
+#ifndef PLATFORM_APERIOS
+	thdLock[sem].lock();
+#endif
+	if(owner()!=id) {
 		if(!do_try_lock(lookup(id),true)) {
 			//spin(); //note the block argument above -- should never spin if that is actually working
 			std::cout << "Warning: lock() failed to achieve lock" << std::endl;
 		}
+	} else {
+#ifdef DEBUG_MUTEX_LOCK
+		if(state==NULL || state->buttons[LFrPawOffset])
+			std::cerr << id << " re-locked " << this << " level " << lockcount+1 << std::endl;
+#endif
+	}
 	lockcount++;
 }
 
@@ -361,15 +424,27 @@
 template<unsigned int num_doors>
 bool
 MutexLock<num_doors>::try_lock(int id) {
+#ifndef PLATFORM_APERIOS
+	if(!thdLock[sem].trylock())
+		return false;
+#endif
 	if(owner()==id) {
+#ifdef DEBUG_MUTEX_LOCK
+		if(state==NULL || state->buttons[LFrPawOffset])
+			std::cerr << id << " re-locked " << this << " level " << lockcount+1 << std::endl;
+#endif
 		lockcount++;
 		return true;
 	} else {
 		if(do_try_lock(lookup(id),false)) {
 			lockcount++;
 			return true;
-		} else
+		} else {
+#ifndef PLATFORM_APERIOS
+			thdLock[sem].unlock())
+#endif
 			return false;
+		}
 	}
 }
 
@@ -377,21 +452,32 @@
 template<unsigned int num_doors>
 void
 MutexLock<num_doors>::unlock() {
-	if(lockcount==0)
+	if(lockcount==0) {
 		std::cerr << "Warning: MutexLock::unlock caused underflow" << std::endl;
-	else if(--lockcount==0)
+		return;
+	}
+#ifdef DEBUG_MUTEX_LOCK
+	if(state==NULL || state->buttons[LFrPawOffset])
+		std::cerr << doors[owner_index].id << " unlock " << this << " level "<< lockcount << std::endl;
+#endif
+	if(--lockcount==0) {
 		if(owner_index!=NO_OWNER) {
 			unsigned int tmp = owner_index;
 			owner_index=NO_OWNER;
 			doors[tmp].BL_in_use=false;
 			doors[tmp].BL_ready=false;
 			// *** Lock has been released *** //
+#ifndef PLATFORM_APERIOS
+			if(owner_index==id) {
+				thdLock[sem].unlock();
+			}
+#endif
 		}
+	}
 }
 
 
 //! If you define this to do something more interesting, can use it to see what's going on in the locking process
-#define mutexdebugout(i,c) {}
 //#define mutexdebugout(i,c) { std::cout << ((char)(i==0?c:((i==1?'M':'a')+(c-'A')))) << std::flush; }
 
 
@@ -402,10 +488,12 @@
 		std::cerr << "WARNING: new process attempted to lock beyond num_doors ("<<num_doors<<")" << std::endl;
 		return false;
 	}
+#ifdef DEBUG_MUTEX_LOCK
+	if(state==NULL || state->buttons[LFrPawOffset])
+		std::cerr << doors[i].id << " attempting lock " << this << " held by " << owner_index << " at " << get_time() << std::endl;
+#endif	
 	unsigned char S[num_doors]; // a local copy of everyone's doors
 	// *** Entering FCFS doorway *** //
-//	pprintf(TextOutputStream,"**%d**\n",i);
-mutexdebugout(i,'A');
 	doors[i].FCFS_in_use=true;
 	for(unsigned int j=0; j<num_doors; j++)
 		S[j]=doors[j].turn;
@@ -414,20 +502,20 @@
 	doors[i].BL_ready=true;
 	doors[i].FCFS_in_use=false;
 	// *** Leaving FCFS doorway *** //
-mutexdebugout(i,'B');
 	for(unsigned int j=0; j<num_doors; j++) {
-mutexdebugout(i,'C');
 		while(doors[j].FCFS_in_use || (doors[j].BL_ready && S[j]==doors[j].turn))
 			if(block)
 				spin();
 			else {
 				doors[i].BL_ready=false;
+#ifdef DEBUG_MUTEX_LOCK
+				if(state==NULL || state->buttons[LFrPawOffset])
+					std::cerr << doors[i].id << " giving up on lock " << this << " held by " << owner_index << " at " << get_time() << std::endl;
+#endif	
 				return false;
 			}
-mutexdebugout(i,'D');
 	}
 	// *** Entering Burns-Lamport *** //
-mutexdebugout(i,'E');
 	do {
 		doors[i].BL_in_use=true;
 		for(unsigned int t=0; t<i; t++)
@@ -435,12 +523,14 @@
 				doors[i].BL_in_use=false;
 				if(!block) {
 					doors[i].BL_ready=false;
+#ifdef DEBUG_MUTEX_LOCK
+					if(state==NULL || state->buttons[LFrPawOffset])
+						std::cerr << doors[i].id << " giving up on lock " << this << " held by " << owner_index << " at " << get_time() << std::endl;
+#endif	
 					return false;
 				}
-mutexdebugout(i,'F');
 				while(doors[t].BL_in_use)
 					spin();
-mutexdebugout(i,'G');
 				break;
 			}
 	} while(!doors[i].BL_in_use);
@@ -449,8 +539,11 @@
 			spin();
 	// *** Leaving Burns-Lamport ***//
 	// *** Lock has been given *** //
-mutexdebugout(i,'H');
 	owner_index=i;
+#ifdef DEBUG_MUTEX_LOCK
+	if(state==NULL || state->buttons[LFrPawOffset])
+		std::cerr << doors[i].id << " received lock " << this << " at " << get_time() << std::endl;
+#endif	
 	return true;
 }
 
@@ -481,7 +574,7 @@
 	do_try_lock(i,true);
 	doors[i].id=doors[--doors_used].id;
 	doors[doors_used].id=NO_OWNER;
-	release();
+	releaseAll();
 }
 
 #endif //MUTEX_LOCK_ET_USE_SOFTWARE_ONLY
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/PollThread.cc ./IPC/PollThread.cc
--- ../Tekkotsu_2.4.1/IPC/PollThread.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./IPC/PollThread.cc	2006-08-07 17:55:27.000000000 -0400
@@ -0,0 +1,150 @@
+#ifndef PLATFORM_APERIOS
+#include "PollThread.h"
+#include <errno.h>
+#include <signal.h>
+
+//better to put this here instead of the header
+using namespace std; 
+
+void PollThread::start() {
+	launching=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)
+		return false;
+	period.Set(static_cast<long>(sleeptime));
+	return true;
+}
+
+void PollThread::interrupted() {
+	if(!initialPoll) {
+		if(period-startTime.Age()<1L) {
+			delay=0L;
+		} else {
+			while(!(period-startTime.Age()<1L))
+				startTime-=period;
+			startTime+=period;
+			delay=period;
+		}
+	}
+}
+
+void * PollThread::run() {
+	launching=false;
+	timespec sleepSpec,remainSpec;
+	if(startTime.Age()<delay) {
+		sleepSpec=delay-startTime.Age();
+		while(nanosleep(&sleepSpec,&remainSpec)) {
+			if(errno!=EINTR) {
+				perror("PollThread::run(): initial nanosleep");
+				break;
+			}
+			//interrupted() may have changed delay to indicate remaining sleep time
+			if(delay<1L || delay<startTime.Age())
+				break;
+			sleepSpec=delay-startTime.Age();
+		}
+	}
+	testCancel();
+	if(!poll())
+		return returnValue;
+	initialPoll=false;
+	bool wasInterrupted=true; // need to add delay instead of period for the first time, same as if an interrupt occurred
+	for(;;) {
+		bool noSleep=false;
+		if(TimeET(0,0)<period) {
+			if(trackPollTime) {
+				if(wasInterrupted) {
+					if(delay<0L || startTime.Age()<delay) {}
+					else
+						startTime+=delay;
+				} else {
+					if(startTime.Age()<period) {}
+					else
+						startTime+=period;
+				}
+				//the idea with this part is that if we get behind, (because of poll() taking longer than period)
+				// then we want to quick poll again as fast as we can to catch up, but we don't want to backlog
+				// such that we'll be quick-calling multiple times once we do catch up
+				if(period<startTime.Age()) {
+					noSleep=true;
+					while(period<startTime.Age())
+						startTime+=period;
+					startTime-=period; //back off one -- the amount we've overshot counts towards the next period
+				}
+				sleepSpec=period-startTime.Age();
+			} else {
+				sleepSpec=period;
+				startTime.Set();
+			}
+			wasInterrupted=false;
+			while(!noSleep && nanosleep(&sleepSpec,&remainSpec)) {
+				wasInterrupted=true;
+				if(errno!=EINTR) {
+					perror("PollThread::run(): periodic nanosleep");
+					break;
+				}
+				//interrupted() should have changed delay and/or period to indicate remaining sleep time
+				if(delay<1L || delay<startTime.Age())
+					break;
+				sleepSpec=delay-startTime.Age();
+			}
+		} else {
+			startTime.Set();
+		}
+		testCancel();
+		if(!poll())
+			return returnValue;
+	}
+	// this return is just to satisfy warnings with silly compiler
+	return returnValue; //never happens -- cancel or bad poll would exit
+}
+
+//void PollThread::cancelled() {
+	//signal handlers are global, not per-thread, so if we reset the handler, then the next interrupt will cause the program to end :(
+	//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
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/PollThread.h ./IPC/PollThread.h
--- ../Tekkotsu_2.4.1/IPC/PollThread.h	1969-12-31 19:00:00.000000000 -0500
+++ ./IPC/PollThread.h	2006-09-16 13:32:39.000000000 -0400
@@ -0,0 +1,86 @@
+//-*-c++-*-
+#ifndef INCLUDED_PollThread_h_
+#define INCLUDED_PollThread_h_
+
+#ifdef PLATFORM_APERIOS
+#  warning PollThread class is not Aperios compatable
+#else
+
+#include "Thread.h"
+#include "Shared/TimeET.h"
+
+//! description of PollThread
+class PollThread : public Thread {
+public:
+	//! constructor
+	PollThread() : Thread(), delay(0L), period(0L), startTime(0L), trackPollTime(false), launching(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)
+	{
+		if(autostart)
+			start();
+	}
+	//! destructor
+	~PollThread() {
+		if(isRunning()) {
+			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
+	
+protected:
+	//! this is the function which will be called at the specified frequency, override it with your own functionality
+	/*! @return true if run() should continue, false to stop the thread.
+	 *  The default implementation calls runloop() and sets #period to its return value if that value is not -1U.
+	 *  If the value is -1U, it returns false.  Feel free to override this directly, instead of runloop(),
+	 *  particularly if you don't intend to change period dynamically. */
+	virtual bool poll();
+	
+	//! called if a signal is sent while sleeping, should reset #delay to indicate remaining sleep time, relative to startTime
+	/*! On return, #delay should be set such that #delay-startTime.Age() is remaining sleep time.  In other words,
+	 *  simply set #delay to the #period to maintain previously requested timing.
+	 *  
+	 *  This default implementation will set #delay to the remaining time needed to maintain current period setting.
+	 *  Feel free to override and reset #period (or other member variables) if you need to change timing dynamically.
+	 *  If the period is shortened such that poll() should have already occurred based on time of previous
+	 *  call and the new period (plus any delay value), then poll() will be called immediately upon return. */
+	virtual void interrupted();
+	
+	virtual void * run();
+	//virtual void cancelled();
+	
+	//! called if a SIGALRM is sent (generally, by a call to interrupt())
+	static void handleInterrupt(int signal);
+	
+	TimeET delay; //!< amount of time to delay between call to start() and first call to poll(), or if interrupt occurs after first poll(), amount of time to re-sleep
+	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
+};
+
+#endif //Aperios check
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/ProcessID.cc ./IPC/ProcessID.cc
--- ../Tekkotsu_2.4.1/IPC/ProcessID.cc	2005-06-01 01:47:46.000000000 -0400
+++ ./IPC/ProcessID.cc	2006-09-16 02:01:40.000000000 -0400
@@ -1,6 +1,78 @@
 #include "ProcessID.h"
 
-ProcessID::ProcessID_t ProcessID::ID=ProcessID::NumProcesses;
+#include "Shared/WorldState.h"
+
+#ifdef PLATFORM_APERIOS
+#  include <iostream>
+using namespace stacktrace;
+#endif
+
+using namespace std;
+
+namespace ProcessID {
+	ProcessID_t ID=NumProcesses; //!< holds ID number
+	
+#ifndef PLATFORM_APERIOS
+	// on "normal" platforms we can trust the id specified by the process to stay consistent
+	ProcessID_t getID() { return ID; }
+
+#else
+	// but on the Aibo, we have to unroll the stack to see which thread it is
+
+	//! array of StackFrame structures, one per #NumProcesses, set by setMap()
+	StackFrame* frames=NULL;
+	
+	//! 
+	void setMap(stacktrace::StackFrame idmap[]) {
+		frames=idmap;
+	}
+	
+	stacktrace::StackFrame* getMapFrame() {
+		if(frames==NULL) //setMap hasn't been called yet
+			return NULL;
+		if(ID==NumProcesses) // ID hasn't been set
+			return NULL;
+		return &frames[ID];
+	}
+
+
+	ProcessID_t getID() {
+		if(frames==NULL) { //setMap hasn't been called yet
+			//cerr << "getID() called before setMap() id==" << ID << endl;
+			//displayCurrentStackTrace();
+			return ID;
+		}
+		StackFrame f;
+#ifdef DEBUG_STACKTRACE
+		f.debug=(state!=NULL)?(state->buttons[LFrPawOffset]>.1):1;
+		if(f.debug)
+			fprintf(stderr,"getID() for %d: ",ID);
+#endif
+		getCurrentStackFrame(&f);
+		while(unrollStackFrame(&f,&f)) {}
+		for(unsigned int i=0; i<NumProcesses; i++) {
+			if(frames[i].gp==f.gp) {
+#ifdef DEBUG_STACKTRACE
+				if(i!=(unsigned int)ID || f.debug)
+					cout << "getID() from " << ID << " is " << i << endl;
+#endif
+				return static_cast<ProcessID_t>(i);
+			}
+		}
+		cerr << "ERROR: Unknown entry point (sp=" << f.sp << ",ra=" << (void*)f.ra << ",gp=" << (void*)f.gp << "), implied process " << ID << endl;
+		displayCurrentStackTrace();
+		cerr << "Map:" << endl;
+		for(unsigned int i=0; i<NumProcesses; i++)
+			cerr << "  " << i << " (sp=" << frames[i].sp << ",ra=" << (void*)frames[i].ra << ",gp=" << (void*)frames[i].gp << ")" << endl;
+		return ID;
+	}
+
+#endif
+
+	void setID(ProcessID_t id) { ID=id; }
+}
+
+
 
 /*! @file
  * @brief Declares the static ProcessID::ID, that's all
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/ProcessID.h ./IPC/ProcessID.h
--- ../Tekkotsu_2.4.1/IPC/ProcessID.h	2005-06-01 01:47:46.000000000 -0400
+++ ./IPC/ProcessID.h	2006-08-22 18:23:03.000000000 -0400
@@ -2,7 +2,11 @@
 #ifndef INCLUDED_ProcessID_h_
 #define INCLUDED_ProcessID_h_
 
-//! this is a class instead of a namespace so i can limit write access of the ID value to the OObjects
+#ifdef PLATFORM_APERIOS
+#  include "Shared/StackTrace.h"
+#endif
+
+//! holds information to identify currently running process
 /*!
  * Although the ProcessID_t enum specifies the maximum number of processes
  * in its NumProcesses value, this doesn't have to correspond to the actual
@@ -12,10 +16,9 @@
  * memory regions for things like attachment pointers or other per-process
  * data.
  *
- * Not all processes *need* to have a named id, they just need a unique id.
+ * Not all processes need to have a *named* id, they just need a unique id.
  */
-class ProcessID {
-public:
+namespace ProcessID {
 	//! Holds ID number for each process
 	enum ProcessID_t {
 		MainProcess,   //!< MainObj process
@@ -27,12 +30,33 @@
 		NumProcesses   //!< maximum number of 'friendly' processes -- see class docs
 	};
 	
-	static ProcessID_t getID() { return ID; }  //!< returns process's ID number, or if within a virtual function on a shared object, the process which created it (annoying)
-	static void setID(ProcessID_t id) { ID=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
+	void setID(ProcessID_t id); //!< sets the ID during init (be careful you know what you're doing if you call this)
+
+	//! returns a string version of the name of the process
+	inline const char* getIDStr() {
+		switch(getID()) {
+			case MainProcess: return "Main";
+			case MotionProcess: return "Motion";
+			case SoundProcess: return "Sound";
+#ifndef PLATFORM_APERIOS
+			case SimulatorProcess: return "Simulator";
+#endif
+			default: return "Invalid Process";
+		}
+	}
 	
-private:
-	static ProcessID_t ID; //!< holds ID number
-};
+#ifdef PLATFORM_APERIOS
+	//! sets location of shared memory map from IDs to current entry point, this is required to be set up before any entry()'s
+	/*! @param idmap array of StackFrame structures, one per #NumProcesses
+	 *  the idea is to have idmap stored in a shared memory region, so functions can tell which one they belong to */
+	void setMap(stacktrace::StackFrame idmap[]);
+	
+	//! returns the stack frame which should be set to the entry point of the current function
+	/*! this is only valid if it is called before any shared object processing is done */
+	stacktrace::StackFrame* getMapFrame();
+#endif
+}
 
 /*! @file
  * @brief Defines ProcessID - simple little global for checking which process is currently running, kind of. (see ProcessID::getID() )
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/RCRegion.cc ./IPC/RCRegion.cc
--- ../Tekkotsu_2.4.1/IPC/RCRegion.cc	2005-06-23 16:17:54.000000000 -0400
+++ ./IPC/RCRegion.cc	2006-08-15 17:45:36.000000000 -0400
@@ -1,7 +1,8 @@
 #ifndef PLATFORM_APERIOS
 #include "RCRegion.h"
-#include "LockScope.h"
+#include "Shared/MarkScope.h"
 #include "Shared/debuget.h"
+#include "Thread.h"
 #include <unistd.h>
 #include <sstream>
 #include <sys/stat.h>
@@ -28,11 +29,18 @@
 
 using namespace std;
 
-typedef LockScope<ProcessID::NumProcesses> AutoLock;
+typedef MarkScope AutoLock;
 
+#if TEKKOTSU_SHM_STYLE==SYSV_SHM
 key_t RCRegion::nextKey=1024;
+#elif TEKKOTSU_SHM_STYLE==POSIX_SHM
+key_t RCRegion::nextKey=0;
+#endif
+
 RCRegion::attachedRegions_t RCRegion::attachedRegions;
 bool RCRegion::isFaultShutdown=false;
+ThreadNS::Lock* RCRegion::staticLock=NULL;
+
 
 #if TEKKOTSU_SHM_STYLE==SYSV_SHM
 //under SYSV shared memory, the keys are just numbers, and it's just as likely that the conflicted
@@ -50,6 +58,7 @@
 #endif
 
 RCRegion * RCRegion::attach(const Identifier& rid) {
+	MarkScope l(getStaticLock());
 	attachedRegions_t::iterator it=attachedRegions.find(rid.key);
 	if(it==attachedRegions.end())
 		return new RCRegion(rid); // the constructor will add entry to attachedRegions
@@ -61,7 +70,7 @@
 }
 
 void RCRegion::AddReference() {
-	AutoLock autolock(*lock,ProcessID::getID());
+	AutoLock autolock(*lock);
 	//cout << "AddReference " << id.shmid << ' ' << ProcessID::getID();
 	references[ProcessID::getID()]++;
 	references[ProcessID::NumProcesses]++;
@@ -73,6 +82,8 @@
 
 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++)
@@ -80,21 +91,27 @@
 		cerr << endl;
 		return;
 	}
-	//if(MutexLockBase::getSemaphoreManager()!=NULL) //check in case this region contained the mutexman and SharedObject just destructed it
-	lock->lock(ProcessID::getID());
 	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)
-	lock->unlock();
-	if(isFaultShutdown) {
+	/*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) {
+	}*/
+	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");
@@ -120,7 +137,7 @@
 					// 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 (shm_unlink) of region " << id.key << " returned " << strerror(err);
+					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;
@@ -133,12 +150,18 @@
 #  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 old;
 	//cout << endl;
 }
 
 void RCRegion::AddSharedReference() {
-	AutoLock autolock(*lock,ProcessID::getID());
+	AutoLock autolock(*lock);
 	//cout << "AddSharedReference " << id.shmid << ' ' << ProcessID::getID();
 	references[ProcessID::NumProcesses]++;
 	//cout << " counts are now:";
@@ -148,7 +171,7 @@
 }
 
 void RCRegion::RemoveSharedReference() {
-	AutoLock autolock(*lock,ProcessID::getID());
+	AutoLock autolock(*lock);
 	//cout << "RemoveSharedReference " << id.shmid << ' ' << ProcessID::getID();
 	if(references[ProcessID::NumProcesses]==0) {
 		cerr << "Warning: RCRegion shared reference count underflow on " << id.key << " by " << ProcessID::getID() << "!  ";
@@ -158,6 +181,7 @@
 		return;
 	}
 	references[ProcessID::NumProcesses]--;
+	ASSERT(references[ProcessID::NumProcesses]>0,"removal of shared reference was last reference -- should have local reference as well");
 	//cout << " counts are now:";
 	//for(unsigned int i=0; i<ProcessID::NumProcesses+1; i++)
 	//	cout << ' ' << references[i];
@@ -167,19 +191,27 @@
 
 void RCRegion::aboutToFork(ProcessID::ProcessID_t newID) {
 	//cout << "RCRegion aboutToFork to " << newID << endl;
-	attachedRegions_t::const_iterator it=attachedRegions.begin();
-	for(; it!=attachedRegions.end(); ++it) {
-		//cout << "Duplicating attachments for " << (*it).first;
-		(*it).second->references[newID]=(*it).second->references[ProcessID::getID()];
-		(*it).second->references[ProcessID::NumProcesses]+=(*it).second->references[newID];
-		//cout << " counts are now:";
-		//for(unsigned int i=0; i<ProcessID::NumProcesses+1; i++)
-		//	cout << ' ' << (*it).second->references[i];
-		//cout << endl;
+	ThreadNS::Lock* old;
+	{
+		MarkScope l(getStaticLock());
+		attachedRegions_t::const_iterator it=attachedRegions.begin();
+		for(; it!=attachedRegions.end(); ++it) {
+			//cout << "Duplicating attachments for " << (*it).first;
+			(*it).second->references[newID]=(*it).second->references[ProcessID::getID()];
+			(*it).second->references[ProcessID::NumProcesses]+=(*it).second->references[newID];
+			//cout << " counts are now:";
+			//for(unsigned int i=0; i<ProcessID::NumProcesses+1; i++)
+			//	cout << ' ' << (*it).second->references[i];
+			//cout << endl;
+		}
+		old=staticLock;
+		staticLock=NULL;
 	}
+	delete old;
 }
 
 void RCRegion::faultShutdown() {
+	MarkScope l(getStaticLock());
 	if(isFaultShutdown) {
 		cerr << "WARNING: RCRegion::faultShutdown() called again... ignoring" << endl;
 		return;
@@ -216,7 +248,28 @@
 	}
 }
 
+RCRegion::attachedRegions_t::const_iterator RCRegion::attachedBegin(bool threadSafe) {
+	if(threadSafe) {
+		MarkScope l(getStaticLock());
+		attachedRegions.begin()->second->AddReference();
+		return attachedRegions.begin();
+	} else
+		return attachedRegions.begin();
+}
+RCRegion::attachedRegions_t::const_iterator RCRegion::attachedEnd() {
+	return attachedRegions.end();
+}
+void RCRegion::attachedAdvance(RCRegion::attachedRegions_t::const_iterator& it, int x/*=1*/) {
+	MarkScope l(getStaticLock());
+	if(it!=attachedRegions.end())
+		it->second->RemoveReference();
+	std::advance(it,x);
+	if(it!=attachedRegions.end())
+		it->second->AddReference();
+}
+
 RCRegion::~RCRegion() {
+	MarkScope l(getStaticLock());
 	attachedRegions.erase(id.key);
 	ASSERT(base==NULL,"destructed with attachment!");
 	ASSERT(references==NULL,"destructed with local references!");
@@ -231,9 +284,17 @@
 	return pages*pagesize; //round up to the nearest page
 }
 
+
+ThreadNS::Lock& RCRegion::getStaticLock() {
+	if(staticLock==NULL)
+		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());
 	id.size=sz;
 	sz=calcRealSize(sz);
 	if(create) {
@@ -344,6 +405,7 @@
 #endif
 }
 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
 #ifndef USE_UNBACKED_SHM
@@ -412,7 +474,7 @@
 				     << "         (may have been leftover from a previous crash)" << endl;
 #endif
 				if(!unlinkRegion())
-					perror("Warning: Shared memory unlink (shm_unlink)");
+					perror("Warning: Shared memory unlink");
 			}
 			//note fall-through from REPLACE into EXIT - only try delete once, and then recreate and exit if it fails again
 			case EXIT: {
@@ -421,7 +483,9 @@
 					cerr << "ERROR: Opening new region " << id.key << ": " << strerror(err) << " (shm_open)" << endl;
 					if(err==EEXIST)
 						cerr << "This error suggests a leaked memory region, perhaps from a bad crash on a previous run.\n"
+#ifdef USE_UNBACKED_SHM
 							<< "You may either be able to use shm_unlink to remove the region, or reboot.\n"
+#endif
 							<< "Also make sure that no other copies of the simulator are already running." << endl;
 					exit(EXIT_FAILURE);
 				}
@@ -433,7 +497,7 @@
 			if(close(fd)<0)
 				perror("Warning: Closing temporary file descriptor from shm_open");
 			if(!unlinkRegion())
-				perror("Warning: Shared memory unlink (shm_unlink)");
+				perror("Warning: Shared memory unlink");
 			exit(EXIT_FAILURE);
 		}
 	} else {
@@ -445,12 +509,12 @@
 	}
 	base=static_cast<char*>(mmap(NULL,sz,PROT_READ|PROT_WRITE,MAP_SHARED,fd,(off_t)0));	
 	int err=errno;
-	if (base == reinterpret_cast<char*>(-1)) {
+	if (base == MAP_FAILED) { /* MAP_FAILED generally defined as ((void*)-1) */
 		cerr << "ERROR: Attaching region " << id.key << " of size " << sz << ": " << strerror(err) << " (mmap)" << endl;
 		if(close(fd)<0)
 			perror("Warning: Closing temporary file descriptor from shm_open");
 		if(!unlinkRegion())
-			perror("Warning: Shared memory unlink (shm_unlink)");
+			perror("Warning: Shared memory unlink");
 		exit(EXIT_FAILURE);
 	}
 	if(close(fd)<0) {
@@ -460,7 +524,7 @@
 	references=reinterpret_cast<unsigned int*>(base+sz-extra);
 	if(create) {
 		new (lock) MutexLock<ProcessID::NumProcesses>;
-		AutoLock autolock(*lock,ProcessID::getID());
+		AutoLock autolock(*lock);
 		for(unsigned int i=0; i<ProcessID::NumProcesses+1; i++)
 			references[i]=0;
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/RCRegion.h ./IPC/RCRegion.h
--- ../Tekkotsu_2.4.1/IPC/RCRegion.h	2005-06-01 01:47:46.000000000 -0400
+++ ./IPC/RCRegion.h	2006-08-23 15:24:20.000000000 -0400
@@ -30,47 +30,66 @@
 #  error Unknown TEKKOTSU_SHM_STYLE setting
 #endif
 
+namespace ThreadNS {
+	class Lock;
+}
 
 //! provides compatability with the OPEN-R type of the same name
 class RCRegion {
 public:
+
+	// The type of region Identifier depends on the style of shared memory being used
+
 #if TEKKOTSU_SHM_STYLE==SYSV_SHM
 	//! contains all information needed to attach this region from a different process
 	struct Identifier {
 		Identifier() : key(), shmid(), size(0) {}
-		key_t key;
-		int shmid;
-		size_t size;
+		key_t key; //!< key_t is defined by system headers, contains system region info
+		int shmid; //!< an integer key value which identifies the region
+		size_t size; //!< the size of the region
 	};
+
+#elif TEKKOTSU_SHM_STYLE==POSIX_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) {}
+		char key[MAX_NAME_LEN]; //!< a string name for the key
+		size_t size; //!< size of the region
+	};
+
+#  ifndef USE_UNBACKED_SHM
+	static plist::Primitive<std::string> shmRoot; //!< determines location of the file backing within file system
+#  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
+
+
+	// The constructors, offering either an Aperios-compatable version,
+	// or a linux-specific version offering explicit control over the
+	// key value, aids better debugging
+
+#if TEKKOTSU_SHM_STYLE==SYSV_SHM
 	//! constructor (OPEN-R compatability)
 	explicit RCRegion(size_t sz)
 		: id(), base(NULL), references(NULL), lock(NULL)
 	{ init(sz,nextKey,true); }
-	//! constructor, name isn't used for sysv
+	//! 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)
 	{ init(sz,nextKey,true); }
+
 #elif TEKKOTSU_SHM_STYLE==POSIX_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;
-#  ifndef USE_UNBACKED_SHM
-	static plist::Primitive<std::string> shmRoot;
-#  endif
-	static plist::Primitive<bool> useUniqueMemoryRegions;
-	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
-	struct Identifier {
-		Identifier() : size(0) {}
-		char key[MAX_NAME_LEN];
-		size_t size;
-	};
 	//! constructor (OPEN-R compatability, name is autogenerated)
 	explicit RCRegion(size_t sz)
 		: id(), base(NULL), references(NULL), lock(NULL)
 	{
 		char name[RCRegion::MAX_NAME_LEN];
-		static unsigned int sn=0;
-		snprintf(name,RCRegion::MAX_NAME_LEN,"Rgn.%d.%d",ProcessID::getID(),++sn);
+		snprintf(name,RCRegion::MAX_NAME_LEN,"Rgn.%d.%u",ProcessID::getID(),static_cast<unsigned int>(++nextKey));
 		name[RCRegion::MAX_NAME_LEN-1]='\0';
 		init(sz,name,true);
 	}
@@ -80,23 +99,51 @@
 	{ init(sz,name,true); }
 #endif
 
+	//! requests that a specified RCRegion be loaded into the current process's memory space
 	static RCRegion * attach(const Identifier& rid);
 	
-	char * Base() const { return base; }
-	size_t Size() const { return id.size; }
-	static void setNextKey(key_t k) { nextKey=k; }
-	const Identifier& ID() const { return id; }
+	char * Base() const { return base; } //!< the pointer to the shared memory region
+	size_t Size() const { return id.size; } //!< the size of the shared memory region
+	static void setNextKey(key_t k) { nextKey=k; } //!< sets the next key to be used for automatic assignment to new regions
+	static key_t getNextKey() { return nextKey+1; } //!< return the next region serial number -- doesn't actually increment it though, repeated calls will return the same value until the value is actually used
+	const Identifier& ID() const { return id; } //!< returns the identifier of this region
 	
-	int NumberOfReference() const { return references[ProcessID::NumProcesses]; }
-	int NumberOfLocalReference() const { return references[ProcessID::getID()]; }
-	void AddReference();
-	void RemoveReference();
-	void AddSharedReference();
-	void RemoveSharedReference();
+	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
+	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
+	void RemoveSharedReference(); //!< removes a reference which is held by another shared memory region
 	
-	static void aboutToFork(ProcessID::ProcessID_t newID);
-	static void faultShutdown();
-	static unsigned int NumberOfAttach() { return attachedRegions.size(); }
+	static void aboutToFork(ProcessID::ProcessID_t newID); //!< does housekeeping to mark the region as attached and the same number of references in the new process as well
+	static void faultShutdown(); //!< try to unload all regions in a clean manner
+
+#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
+	//! a map from the shared memory key type to the actual region structure
+	typedef std::map<std::string,RCRegion*> attachedRegions_t;
+#endif
+	static unsigned int NumberOfAttach() { return attachedRegions.size(); } //!< returns the number of regions which are currently attached in the process
+	
+	//! Returns an iterator to the beginning of the attached regions mapping -- it->first is the key, it->second is the RCRegion*
+	/*! If you need thread-safety (i.e. another thread may attach/detach while you are iterating), pass true, and be sure to use attachedAdvance() to increment the iterator!
+	 *  This doesn't prevent other threads from attaching/detaching regions, it only prevents detaching the one you're on.
+	 *  When you're done with a thread-safe iterator, either attachedAdvance() it off the end, or manually call RemoveReference() on the iterator's final region */
+	static attachedRegions_t::const_iterator attachedBegin(bool threadSafe);
+	//! Returns an iterator to the end of the attached regions -- it->first is the key, it->second is the RCRegion*
+	/*! If you need thread-safety (i.e. another thread may attach/detach while you are iterating), be sure to use attachedAdvance() to decrement the iterator!
+	 *  This doesn't prevent other threads from attaching/detaching regions, it only prevents detaching the one you're on. */
+	static attachedRegions_t::const_iterator attachedEnd();
+	//! Increments the attached region iterator in a thread-safe way -- only use this if you previously passed 'true' to begin(), or are decrementing from end()
+	/*! If you are using an iterator obtained without thread-safety, just increment it normally -- don't switch to this or it will screw up reference counting.
+	 *  If you insist on switching back and forth between thread-safe advance (this function) and normal iterator advancing, you will need to add a reference to the current iterator's region before calling this.
+	 *  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 {
@@ -105,46 +152,59 @@
 		EXIT //!< go home and cry about it
 	};
 	
-	static void setConflictResolution(ConflictResolutionStrategy crs) { conflictStrategy=crs; }
-	static ConflictResolutionStrategy getConflictResolution() { return conflictStrategy; }
+	static void setConflictResolution(ConflictResolutionStrategy crs) { conflictStrategy=crs; } //!< sets #conflictStrategy
+	static ConflictResolutionStrategy getConflictResolution() { return conflictStrategy; } //!< returns #conflictStrategy
+
 	
 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)
 	{ init(rid.size,rid.key,false); }
 
-	~RCRegion();
+	~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>);
+	//! returns the size of the region to be allocated, given the size requested by the client
 	static unsigned int calcRealSize(unsigned int size);
 
+	//! intializes and returns #staticLock
+	static ThreadNS::Lock& getStaticLock();
+
 #if TEKKOTSU_SHM_STYLE==SYSV_SHM
+	//! 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, key_t sug_key, bool create);
 #elif TEKKOTSU_SHM_STYLE==POSIX_SHM
+	//! returns the qualified version of this region's key (see getQualifiedName(const std::string& key) )
 	std::string getQualifiedName() const { return getQualifiedName(id.key); }
+	//! wraps the region's key with a root path prefix and optionally a PID suffix (see #useUniqueMemoryRegions and #shmRoot)
 	static std::string getQualifiedName(const std::string& key);
+	//! opens a region either in "pure" shared memory, or in file-backed shared memory, based on whether USE_UNBACKED_SHM is defined
 	int openRegion(int mode) const;
+	//! unlinks a region either in "pure" shared memory, or in file-backed shared memory, based on whether USE_UNBACKED_SHM is defined
 	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);
 #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;
 									  
-	static key_t nextKey;
-#if TEKKOTSU_SHM_STYLE==SYSV_SHM
-	typedef std::map<key_t,RCRegion*> attachedRegions_t;
-#elif TEKKOTSU_SHM_STYLE==POSIX_SHM
-	typedef std::map<std::string,RCRegion*> attachedRegions_t;
-#endif
-	static attachedRegions_t attachedRegions;
+	static ThreadNS::Lock* staticLock; //!< a lock over all static RCRegion members for the current process
+
+	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
 	
-	Identifier id;
-	char * base;
-	unsigned int * references;
-	MutexLock<ProcessID::NumProcesses> * lock;
+	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_2.4.1/IPC/RegionRegistry.h ./IPC/RegionRegistry.h
--- ../Tekkotsu_2.4.1/IPC/RegionRegistry.h	2005-06-01 01:47:46.000000000 -0400
+++ ./IPC/RegionRegistry.h	2006-06-16 17:49:23.000000000 -0400
@@ -8,7 +8,7 @@
 
 #include "ListMemBuf.h"
 #include "RCRegion.h"
-#include "LockScope.h"
+#include "Shared/MarkScope.h"
 #include "ProcessID.h"
 
 //! Keeps track of currently available shared memory regions
@@ -16,7 +16,7 @@
 class RegionRegistry {
 protected:
 	mutable MutexLock<ProcessID::NumProcesses> lock;
-	typedef LockScope<ProcessID::NumProcesses> AutoLock;
+	typedef MarkScope AutoLock;
 	
 	//! Holds information regarding a shared memory region available for listening
 	struct entry {
@@ -40,12 +40,12 @@
 	RegionRegistry() : lock(), avail() {}
 	
 	~RegionRegistry() {
-		AutoLock autolock(lock,ProcessID::getID());
+		AutoLock autolock(lock);
 		avail.clear();
 	}
 	
 	index_t findRegion(const std::string& name) const {
-		AutoLock autolock(lock,ProcessID::getID());
+		AutoLock 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))
@@ -67,7 +67,7 @@
 	}
 	
 	RCRegion * registerRegion(const std::string& name, size_t size) {
-		AutoLock autolock(lock,ProcessID::getID());
+		AutoLock autolock(lock);
 		index_t it=findRegion(name);
 		if(it!=end()) {
 			//found, already registered
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/SemaphoreManager.cc ./IPC/SemaphoreManager.cc
--- ../Tekkotsu_2.4.1/IPC/SemaphoreManager.cc	2005-06-23 16:18:56.000000000 -0400
+++ ./IPC/SemaphoreManager.cc	2006-08-11 14:44:16.000000000 -0400
@@ -6,6 +6,7 @@
 #include <errno.h>
 #include <stdio.h>
 #include <exception>
+#include <stdexcept>
 #include <iostream>
 
 //this is for linux compatability -- apparently you're *supposed* to
@@ -24,7 +25,19 @@
 
 SemaphoreManager::SemaphoreManager()
 : sems(), nsem(sems_t::MAX_ENTRIES), semid(-1), mysem(sems.end()), refc(sems.end())
-{
+{init();}
+
+SemaphoreManager::SemaphoreManager(unsigned int numRequest)
+: sems(), nsem(numRequest+2), semid(-1), mysem(sems.end()), refc(sems.end())
+{init();}
+
+void SemaphoreManager::init() {
+	if(nsem>sems_t::MAX_ENTRIES) {
+		cout << "SemaphoreManager created with request for " << nsem << " semaphores, but sems_t::MAX_ENTRIES is " << sems_t::MAX_ENTRIES << endl;
+		nsem=sems_t::MAX_ENTRIES;
+	}
+	unsigned int req=nsem;
+
 	//the seminfo structure is kernel-private and I can't find a portable way to access
 	//SEMMSL without it.
 	/*semun params; 
@@ -42,6 +55,7 @@
 	//So instead we'll do a binary search for the size:
 	unsigned int lowbound=0; //inclusive
 	unsigned int highbound=nsem; //inclusive
+	//note that first pass asks for highbound - if it succeeds there's no search
 	while(lowbound!=highbound) {
 		semid=semget(IPC_PRIVATE,nsem,IPC_CREAT | IPC_EXCL | 0666);
 		if(semid<0) {
@@ -61,16 +75,15 @@
 		}
 		nsem=(lowbound+highbound+1)/2;
 	}
-	if(nsem!=sems_t::MAX_ENTRIES)
-		cerr << "WARNING: System can only allocate " << nsem << " semaphores per set (SEMMSL). " << sems_t::MAX_ENTRIES << " were suggested." << endl;
-	
 	//get the semaphore set
 	semid=semget(IPC_PRIVATE,nsem,IPC_CREAT | IPC_EXCL | 0666);
 	if(semid<0) {
 		perror("ERROR: SemaphoreManager construction (semget)");
 				exit(EXIT_FAILURE);
 	}
-	
+	if(nsem!=req)
+		cerr << "WARNING: System can only allocate " << nsem << " semaphores per set for id=" << semid << " (SEMMSL or SEMMNS max reached). " << req << " were requested." << endl;
+		
 	//initialize to 0 (unlocked)
 	unsigned short int semvals[sems_t::MAX_ENTRIES];
 	for(unsigned int i=0; i<nsem; i++)
@@ -146,7 +159,8 @@
 				sems.erase(refc);
 				sems.erase(mysem);
 				for(semid_t it=sems.begin(); it!=sems.end(); it=sems.next(it))
-					cerr << "Warning: semaphore id " << it << " from set " << semid << " was still active when the set was dereferenced" << endl;
+					if(it<nsem)
+						cerr << "Warning: semaphore id " << it << " from set " << semid << " was still active when the set was dereferenced" << endl;
 				if(semctl(semid,-1,IPC_RMID)<0) {
 					perror("ERROR: SemaphoreManager deletion from operator= (semctl)");
 					exit(EXIT_FAILURE);
@@ -207,6 +221,9 @@
 	lower(mysem,1);
 	semid_t id=sems.new_front();
 	raise(mysem,1);
+	if(id!=sems.end())
+		setValue(id,0);
+	intrPolicy[id]=INTR_RETRY;
 	return id;
 }
 void SemaphoreManager::releaseSemaphore(semid_t id) {
@@ -220,10 +237,30 @@
 	while(semop(semid,&sb,1)<0) {
 		if(errno==EAGAIN)
 			return false;
-		perror("ERROR: SemaphoreManager unable to lower semaphore (semop)");
 		if(errno==EINTR) {
-			cerr << "       I was interrupted.  Trying again...";
+			switch(intrPolicy[id]) {
+				case INTR_CANCEL_VERBOSE:
+					perror("ERROR: SemaphoreManager unable to lower semaphore (semop)");
+					cerr << "       semop was interrupted by signal, cancelling lower()";
+				case INTR_CANCEL:
+					return false;
+				case INTR_RETRY_VERBOSE:
+					perror("ERROR: SemaphoreManager unable to lower semaphore (semop)");
+					cerr << "       semop was interrupted by signal.  Trying again...";
+				case INTR_RETRY:
+					break; //while loop will retry
+				case INTR_THROW_VERBOSE:
+					perror("ERROR: SemaphoreManager unable to lower semaphore (semop)");
+					cerr << "       semop was interrupted by signal.  Throwing exception...";
+				case INTR_THROW:
+					throw std::runtime_error("EINTR returned by lower semop");
+				case INTR_EXIT:
+					perror("ERROR: SemaphoreManager unable to lower semaphore (semop)");
+					cerr << "       semop was interrupted by signal.  Exiting...";
+					exit(EXIT_FAILURE);
+			}
 		} else {
+			perror("ERROR: SemaphoreManager unable to lower semaphore (semop)");
 			cerr << "       ";
 			if(errno==EIDRM) {
 				cerr << "Semaphore set has been removed.  " << endl;
@@ -276,7 +313,29 @@
 			}
 			cerr << "Goodbye" << endl;
 			exit(EXIT_FAILURE);
-		} //else cerr << "       I was interrupted.  Trying again...";
+		} else {
+			switch(intrPolicy[id]) {
+				case INTR_CANCEL_VERBOSE:
+					perror("ERROR: SemaphoreManager unable to testZero (semop)");
+					cerr << "       semop was interrupted by signal, cancelling testZero()";
+				case INTR_CANCEL:
+					return false;
+				case INTR_RETRY_VERBOSE:
+					perror("ERROR: SemaphoreManager unable to testZero (semop)");
+					cerr << "       semop was interrupted by signal.  Trying again...";
+				case INTR_RETRY:
+					break; //while loop will retry
+				case INTR_THROW_VERBOSE:
+					perror("ERROR: SemaphoreManager unable to testZero (semop)");
+					cerr << "       semop was interrupted by signal.  Throwing exception...";
+				case INTR_THROW:
+					throw std::runtime_error("EINTR returned by testZero semop");
+				case INTR_EXIT:
+					perror("ERROR: SemaphoreManager unable to testZero (semop)");
+					cerr << "       semop was interrupted by signal.  Exiting...";
+					exit(EXIT_FAILURE);
+			}
+		}
 	}
 	return true;
 }
@@ -302,7 +361,29 @@
 			}
 			cerr << "Goodbye" << endl;
 			exit(EXIT_FAILURE);
-		} //else cerr << "       I was interrupted.  Trying again...";
+		} else {
+			switch(intrPolicy[id]) {
+				case INTR_CANCEL_VERBOSE:
+					perror("ERROR: SemaphoreManager unable to testZero_add (semop)");
+					cerr << "       semop was interrupted by signal, cancelling testZero_add()";
+				case INTR_CANCEL:
+					return false;
+				case INTR_RETRY_VERBOSE:
+					perror("ERROR: SemaphoreManager unable to testZero_add (semop)");
+					cerr << "       semop was interrupted by signal.  Trying again...";
+				case INTR_RETRY:
+					break; //while loop will retry
+				case INTR_THROW_VERBOSE:
+					perror("ERROR: SemaphoreManager unable to testZero_add (semop)");
+					cerr << "       semop was interrupted by signal.  Throwing exception...";
+				case INTR_THROW:
+					throw std::runtime_error("EINTR returned by testZero_add semop");
+				case INTR_EXIT:
+					perror("ERROR: SemaphoreManager unable to testZero_add (semop)");
+					cerr << "       semop was interrupted by signal.  Exiting...";
+					exit(EXIT_FAILURE);
+			}
+		}
 	}
 	return true;
 }
@@ -327,7 +408,29 @@
 			}
 			cerr << "Goodbye" << endl;
 			exit(EXIT_FAILURE);
-		} //else cerr << "       I was interrupted.  Trying again...";
+		} else {
+			switch(intrPolicy[id]) {
+				case INTR_CANCEL_VERBOSE:
+					perror("ERROR: SemaphoreManager unable to add_testZero (semop)");
+					cerr << "       semop was interrupted by signal, cancelling add_testZero()";
+				case INTR_CANCEL:
+					return false;
+				case INTR_RETRY_VERBOSE:
+					perror("ERROR: SemaphoreManager unable to add_testZero (semop)");
+					cerr << "       semop was interrupted by signal.  Trying again...";
+				case INTR_RETRY:
+					break; //while loop will retry
+				case INTR_THROW_VERBOSE:
+					perror("ERROR: SemaphoreManager unable to add_testZero (semop)");
+					cerr << "       semop was interrupted by signal.  Throwing exception...";
+				case INTR_THROW:
+					throw std::runtime_error("EINTR returned by add_testZero semop");
+				case INTR_EXIT:
+					perror("ERROR: SemaphoreManager unable to add_testZero (semop)");
+					cerr << "       semop was interrupted by signal.  Exiting...";
+					exit(EXIT_FAILURE);
+			}
+		}
 	}
 	return true;
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/SemaphoreManager.h ./IPC/SemaphoreManager.h
--- ../Tekkotsu_2.4.1/IPC/SemaphoreManager.h	2005-06-14 23:40:05.000000000 -0400
+++ ./IPC/SemaphoreManager.h	2006-05-08 18:06:35.000000000 -0400
@@ -7,10 +7,14 @@
 #else
 
 #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
+/*! If you can't increase your system's SEMMSL (and possibly SEMMNS), you
+ *  may want to consider decreasing this. */
 #define SYSTEM_MAX_SEM 250
 #endif
 
@@ -18,42 +22,102 @@
 /*! Should be initialized pre-fork into a shared region */
 class SemaphoreManager {
 protected:
-	static const unsigned int MAX_SEM=SYSTEM_MAX_SEM; //!wouldn't want to claim the entire system's worth, even if we could
-	typedef ListMemBuf<bool,MAX_SEM> sems_t;
-	sems_t sems;
+	typedef ListMemBuf<bool,SYSTEM_MAX_SEM> sems_t; //!< shorthand for the type of #sems
 	
 public:
+	//! wouldn't want to claim the entire system's worth, even if we could
+	static const unsigned int MAX_SEM=SYSTEM_MAX_SEM;
+
+	//! shorthand for the semaphore indexing type
 	typedef sems_t::index_t semid_t;
+	//! specify options for how to handle EINTR (signal occurred) error condition during a semaphore operation, see setInterruptPolicy()
+	enum IntrPolicy_t {
+		INTR_CANCEL_VERBOSE, //!< give up, return failure, display error message on console
+		INTR_CANCEL, //!< give up, return failure
+		INTR_RETRY_VERBOSE, //!< just repeat semaphore operation, display error message on console
+		INTR_RETRY, //!< just repeat semaphore operation
+		INTR_THROW_VERBOSE, //!< throw a std::runtime_error exception, display error message on console
+		INTR_THROW, //!< throw a std::runtime_error exception
+		INTR_EXIT, //!< kill process, with error message
+	};
 	
+	//! Creates a SemaphoreManager with room for sems_t::MAX_ENTRIES entries
+	/*! 2 of these entries are reserved for internal use, so user code
+	 *  will actually only have access to sems_t::MAX_ENTRIES-2 entries.
+	 *  Use available() to determine this value at runtime. */
 	SemaphoreManager();
-	SemaphoreManager(const SemaphoreManager& mm);
-	SemaphoreManager& operator=(const SemaphoreManager& mm);
-	~SemaphoreManager();
 	
+	//! Creates a SemaphoreManager with room for @a numRequest entries
+	/*! adds 2 for SemaphoreManager's own reference count and mutex lock,
+	 *  so you'll actually have @a numRequest semaphores available */
+	explicit SemaphoreManager(unsigned int numRequest);
+	
+	SemaphoreManager(const SemaphoreManager& mm); //!< copy supported
+	SemaphoreManager& operator=(const SemaphoreManager& mm); //!< assignment supported
+	~SemaphoreManager(); //!< destructor
+	
+	//! call this on semaphores in shared memory regions if a fork is about to occur so reference counts can be updated for the other process
 	void aboutToFork();
+	//! call this if semaphores need to be released during an emergency shutdown (otherwise semaphore sets can leak past process shutdown -- bad system design IMHO!)
 	void faultShutdown();
+	//! returns true if #semid is invalid, indicating further semaphore operations are bogus
 	bool hadFault() const { return semid==-1; }
 
-	semid_t getSemaphore();
-	void releaseSemaphore(semid_t id);
+	//! returns a new semaphore id, or invalid() if none are available
+	semid_t getSemaphore() ATTR_must_check;
+	//! marks a semaphore as available for reassignment
+	void releaseSemaphore(semid_t id); 
 
+	//! return the semaphore's interrupt policy (doesn't check @a id validity)
+	IntrPolicy_t getInterruptPolicy(semid_t id) const { return intrPolicy[id]; }
+	//! set the semaphore's interrupt policy (doesn't check @a id validity)
+	void setInterruptPolicy(semid_t id, IntrPolicy_t p) { intrPolicy[id]=p; }
+	
+	//! lowers a semaphore's value by @a x, optionally blocking if the value would go negative until it is raised enough to succeed
+	/*! returns true if the semaphore was successfully lowered.*/
 	bool lower(semid_t id, unsigned int x, bool block=true) const;
+	//! raises a semaphore's value by @a x
 	void raise(semid_t id, unsigned int x) const;
-	int getValue(semid_t id) const;
-	void setValue(semid_t id, int x) const;
+
+	int getValue(semid_t id) const; //!< returns the semaphore's value
+	void setValue(semid_t id, int x) const; //!< sets the semaphore's value
+	
+	//! tests if the semaphore's value is zero, optionally blocking until it is
+	/*! returns true if the semaphore's value is zero.
+	 *  @see testZero_add(), add_testZero() */
 	bool testZero(semid_t id, bool block=true) const;
+	//! tests if the semaphore's value is zero, optionally blocking until it is, and then adding @a x
+	/*! If @a x is negative, then @a addblock will cause it to block
+	 *  again until someone else raises the semaphore.  Otherwise, the
+	 *  add should be performed as an atomic unit with the test.  If @a
+	 *  x is non-negative, then the add should never block.
+	 *  @see add_testZero(), testZero() */
 	bool testZero_add(semid_t id, unsigned int x, bool testblock=true, bool addblock=true) const;
+	//! adds @a x to the semaphore's value, optionally blocking in the case that @a x is negative and larger than the semaphore's value.  After adding, test whether the semaphore is zero, optionally blocking again until it is.
+	/*! If no blocking is required (e.g. @a x is positive) then the add
+	 *  and test should be an atomic pair.
+	 *  @see testZero_add(), testZero() */
 	bool add_testZero(semid_t id, unsigned int x, bool addblock=true, bool testblock=true) const;
 	
+	//! returns the number of semaphores currently available in the set
 	unsigned int available() const { return sems_t::MAX_ENTRIES-sems.size(); }
+	//! returns the number of semaphores which have been used
+	/*! the SemaphoreManager requires 2 semaphores from the set, one for
+	 *  reference counting and one for mutual exclusion during function
+	 *  calls */
 	unsigned int used() const { return sems.size()-(sems_t::MAX_ENTRIES-nsem); }
+	//! returns the "invalid" id value, for testing against getSemaphore
 	semid_t invalid() const { return sems.end(); }
 
 protected:
-	unsigned int nsem;
-	int semid;
-	semid_t mysem;
-	semid_t refc;
+	void init(); //!< basic initialization called by the constructor -- don't call twice
+
+	sems_t sems; //!< tracks which semaphores have been handed out; the bool value isn't actually used
+	unsigned int nsem; //!< number of real semaphores in the set obtained from the system
+	int semid; //!< the system's identifier for the set
+	semid_t mysem; //!< a lock semaphore for management operations on the set (handing out or taking back semaphores from clients)
+	semid_t refc; //!< a reference count of this semaphore set -- when it goes back to 0, the set is released from the system
+	IntrPolicy_t intrPolicy[sems_t::MAX_ENTRIES]; //!< interrupt policy for each semaphore
 };
 
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/SharedObject.h ./IPC/SharedObject.h
--- ../Tekkotsu_2.4.1/IPC/SharedObject.h	2005-06-13 16:29:48.000000000 -0400
+++ ./IPC/SharedObject.h	2006-09-16 16:11:52.000000000 -0400
@@ -11,6 +11,13 @@
 public:
 	void* data() const { return rcr->Base(); } //!< returns a pointer to the data region
 	RCRegion * getRegion() const { return rcr; } //!< returns the OPEN-R memory region, should you need it
+	
+	virtual ~SharedObjectBase() {} //!< destructor
+	
+#ifndef PLATFORM_APERIOS
+	//! return the next region serial number -- doesn't actually increment it though, repeated calls will return the same value until the value is actually used
+	static unsigned int getNextKey() { return serialNumber+1; }
+#endif
 
 protected:
 	//! constructor, protected because you shouldn't need to create this directly, just a common interface to all templates of SharedObject
@@ -27,8 +34,6 @@
 		rcr=sob.rcr;
 		rcr->AddReference();
 	}
-	//< destructor
-	virtual ~SharedObjectBase() {} 
 
 	//!removes a reference from #rcr, and if necessary, destructs its data
 	virtual void removeRef()=0;
@@ -98,7 +103,7 @@
 	}
 	//@}
 	
-	//< destructor
+	//! destructor, removes reference to shared region
 	virtual ~SharedObject() { removeRef(); }
 	
 	MC* operator->() const { return dataCasted(); } //!< smart pointer to the underlying class
@@ -128,7 +133,10 @@
 		RCRegion * r = new RCRegion(calcsize());
 #else
 		char name[RCRegion::MAX_NAME_LEN];
-		snprintf(name,RCRegion::MAX_NAME_LEN,"ShdObj.%d.%d",ProcessID::getID(),++serialNumber);
+		unsigned int suffixlen=snprintf(name,RCRegion::MAX_NAME_LEN,".%d.%d",ProcessID::getID(),++serialNumber);
+		if(suffixlen>RCRegion::MAX_NAME_LEN)
+			suffixlen=RCRegion::MAX_NAME_LEN;
+		snprintf(name,RCRegion::MAX_NAME_LEN,"Sh.%.*s.%d.%d",RCRegion::MAX_NAME_LEN-suffixlen-3,typeid(MC).name(),ProcessID::getID(),++serialNumber);
 		name[RCRegion::MAX_NAME_LEN-1]='\0';
 		RCRegion * r = new RCRegion(name,calcsize());
 #endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/Thread.cc ./IPC/Thread.cc
--- ../Tekkotsu_2.4.1/IPC/Thread.cc	2005-08-01 19:17:59.000000000 -0400
+++ ./IPC/Thread.cc	2006-08-15 17:45:57.000000000 -0400
@@ -1,14 +1,19 @@
 #ifndef PLATFORM_APERIOS
 #include "Thread.h"
+#include "Shared/ReferenceCounter.h"
+#include "ProcessID.h"
 
 #include <pthread.h>
 #include <string.h>
 #include <iostream>
 #include <signal.h>
 #include <unistd.h>
+#include <cassert>
 
 using namespace std;
 
+#define THREADCANCEL_SANITY_CHECKS
+
 struct Threadstorage_t {
 	Threadstorage_t() : threadInfo(), threadAttr() {
 		if(int err=pthread_attr_init(&threadAttr))
@@ -20,12 +25,17 @@
 	}
 	pthread_t threadInfo;
 	pthread_attr_t threadAttr;
+	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;
 
-Thread::Thread() : pt(new Threadstorage_t), running(false), returnValue(NULL) {}
+Thread::Thread()
+	: pt(new Threadstorage_t), running(false), returnValue(NULL),
+	noCancelDepth(0), cancelOrig(PTHREAD_CANCEL_ENABLE)
+{}
 
 Thread::~Thread() {
 	//can only happen externally
@@ -33,10 +43,11 @@
 		stop();
 		join();
 	}
-	if(pt==NULL) {
+	/*if(pt==NULL) {
 		std::cerr << "Thread storage already deleted!?!?!" << std::endl;
 		*(int*)NULL=0xDEADDEAD;
-	}
+	}*/
+	assert(pt!=NULL);
 	delete pt;
 	pt=NULL;
 }
@@ -57,30 +68,41 @@
 		unsigned int sleeptime=runloop();
 		if(sleeptime==-1U)
 			return returnValue;
-		usleep(sleeptime);
+		if(sleeptime>0)
+			usleep(sleeptime);
 		testCancel();
 	}
-	return NULL; //never happens
+	// this return is just to satisfy warnings with silly compiler
+	return returnValue; //never happens -- cancel or max sleep time would exit
 }
 
 void Thread::stop() {
+	if(!running) {
+		std::cerr << "Thread::stop() -- thread is already stopped!" << std::endl;
+		return;
+	}
 	if(int err=pthread_cancel(pt->threadInfo))
-		cerr << "Thread cancel(), pthread_cancel: " << strerror(err) << endl;
+		cerr << "Thread cancel(), pthread_cancel("<<pt->threadInfo<<"): " << strerror(err) << endl;
 }
 
 void Thread::kill() {
-	if(int err=pthread_kill(pt->threadInfo,SIGALRM))
-		cerr << "Thread stop(), pthread_kill(SIGALRM): " << strerror(err) << endl;
+	sendSignal(SIGUSR1);
 }
 
 void Thread::murder() {
 	if(int err=pthread_detach(pt->threadInfo))
 		cerr << "Thread kill(), thread_detach: " << strerror(err) << endl;
-	if(int err=pthread_kill(pt->threadInfo,SIGSTOP))
-		cerr << "Thread kill(), pthread_kill(SIGSTOP): " << strerror(err) << endl;
+	sendSignal(SIGSTOP);
 	running=false;
 }
 
+void Thread::sendSignal(int sig) {
+	if(!isRunning())
+		return;
+	if(int err=pthread_kill(pt->threadInfo,sig))
+		cerr << "Thread kill(), pthread_kill("<<sig<<"): " << strerror(err) << endl;
+}
+
 void * Thread::join() {
 	void * ans=NULL;
 	if(int err=pthread_join(pt->threadInfo, &ans))
@@ -88,25 +110,89 @@
 	return ans;
 }
 
+Thread* Thread::getCurrent() {
+	if(Threadstorage_t::selfKey==0) {
+		static bool gaveError=false;
+		if(!gaveError) {
+			cerr << "ERROR: In Thread::getCurrent(), selfKey uninitialized; Thread::initMainThread was not called." << endl;
+			cerr << "       (This error will only be displayed once)" << endl;
+			gaveError=true;
+		}
+		return NULL;
+	}
+	return static_cast< Thread* >(pthread_getspecific(Threadstorage_t::selfKey));
+}
+
+void Thread::initMainThread() {
+	if(int err=pthread_key_create(&Threadstorage_t::selfKey,warnSelfUndestructed))
+		cerr << "WARNING: In Thread::initMainThread(), pthread_key_create(selfKey) returned " << strerror(err) << endl;
+	if(int err=pthread_setspecific(Threadstorage_t::selfKey,NULL))
+		cerr << "WARNING: In Thread::initMainThread(), pthread_setspecific(selfKey) returned " << strerror(err) << endl;
+}
+
+void Thread::releaseMainThread() {
+	//handle_exit(NULL);
+	if(int err=pthread_key_delete(Threadstorage_t::selfKey))
+		cerr << "WARNING: In Thread::releaseMainThread, pthread_key_delete(selfKey) returned " << strerror(err) << endl;
+}
+
 void Thread::testCancel() {
+#ifdef DEBUG
+	if(noCancelDepth!=0) {
+		cerr << "WARNING: Thread::testCancel called with noCancelDepth=="<<noCancelDepth<<" (process="<<ProcessID::getID()<<", thread="<<pthread_self()<<")"<<endl;
+	}
+#endif
 	pthread_testcancel();
 }
 
 void * Thread::launch(void * msg) {
-	if(int err=pthread_setcancelstate(PTHREAD_CANCEL_ENABLE,NULL))
-		cerr << "Thread launch(), pthread_setcanceltype: " << strerror(err) << endl;
-	if(int err=pthread_setcanceltype(PTHREAD_CANCEL_DEFERRED,NULL))
+	//cout << "Spawn thread " << pthread_self() << " from process " << ProcessID::getID() << endl;
+	Thread* cur=static_cast<Thread*>(msg);
+	if(cur==NULL) {
+		cerr << "ERROR: Thread::launch with NULL msg" << endl;
+		return NULL;
+	}
+
+	if(int err=pthread_setspecific(Threadstorage_t::selfKey,msg))
+		cerr << "WARNING: In ThreadNS::launch(), pthread_setspecific(selfKey) returned " << strerror(err) << endl;
+	
+	//disable cancel while calling launch()
+	if(int err=pthread_setcancelstate(PTHREAD_CANCEL_DISABLE,NULL))
 		cerr << "Thread launch(), pthread_setcanceltype: " << strerror(err) << endl;
-	signal(SIGALRM,Thread::handle_signal);
-	void * ans=NULL;
-	{
-		//These pthread functions actually define a scope between them
-		//I've added braces of my own to make this explicitly clear
-		pthread_cleanup_push(Thread::handle_exit,msg);
-		static_cast<Thread*>(msg)->run();
-		pthread_cleanup_pop(true);
+	++(cur->noCancelDepth);
+	if(signal(SIGUSR1,Thread::handle_launch_signal)==SIG_ERR)
+		perror("Thread launch(), signal(SIGUSR1,handle_launch_signal)");
+	if(!cur->launched()) {
+		//subclass's launch cancelled launch
+		--(cur->noCancelDepth);
+		handle_exit(NULL);
+		return cur->returnValue;
 	}
-	return ans;
+	--(cur->noCancelDepth);
+	
+	//These pthread functions actually define a scope between them (ugh)
+	//I've added braces of my own to make this explicitly clear
+	pthread_cleanup_push(Thread::handle_exit,msg); {
+		
+		if(signal(SIGUSR1,Thread::handle_signal)==SIG_ERR)
+			perror("Thread launch(), signal(SIGUSR1,handle_signal)");
+		
+		if(cur->noCancelDepth==0) {
+			//reset cancelability before run
+			if(int err=pthread_setcancelstate(cur->cancelOrig,NULL))
+				cerr << "Thread launch(), pthread_setcanceltype: " << strerror(err) << endl;
+			if(int err=pthread_setcanceltype(PTHREAD_CANCEL_DEFERRED,NULL))
+				cerr << "Thread launch(), pthread_setcanceltype: " << strerror(err) << endl;
+		}
+		cur->returnValue=cur->run();
+		
+	} pthread_cleanup_pop(true);
+	return cur->returnValue;
+}
+
+void Thread::handle_launch_signal(int /*sig*/) {
+	handle_exit(NULL);
+	pthread_exit(NULL);
 }
 
 void Thread::handle_signal(int /*sig*/) {
@@ -114,13 +200,99 @@
 }
 
 void Thread::handle_exit(void * th) {
-	static_cast<Thread*>(th)->running=false;
+	//cout << "Cull thread " << pthread_self() << endl;
+	Thread* cur=getCurrent();
+	if(cur==NULL) {
+		cerr << "ERROR: handle_exit called for a NULL thread" << endl;
+		if(th!=NULL) {
+			static_cast<Thread*>(th)->cancelled();
+			static_cast<Thread*>(th)->running=false;
+		}
+		return;
+	}
+	
+	if(th!=NULL && th!=cur)
+		cerr << "WARNING: handle_exit argument does not match selfKey" << endl;
+	if(cur->noCancelDepth!=0) {
+		cerr << "WARNING: thread " << pthread_self() << " of ProcessID_t " << ProcessID::getID() << " exited while noCancelDepth>0 (was " << cur->noCancelDepth << ")" << endl;
+		cerr << "         This may indicate a mutex was left locked." << endl;
+	}
+	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;
 }
 
+void Thread::pushNoCancel() {
+	Thread * cur=getCurrent();
+	if(cur==NULL) {
+		//cerr << "ERROR: Thread::pushNoCancel was given NULL thread by getCurrent, thread=" << pthread_self() << endl;
+		//not so bad, indicates already canceled -- don't test cancel again, don't want to cancel-recurse
+		if(int err=pthread_setcancelstate(PTHREAD_CANCEL_DISABLE,NULL))
+			cerr << "ERROR: Thread pushNoCancel(), pthread_setcanceltype: " << strerror(err) << endl;
+	} else {
+		++(cur->noCancelDepth);
+		int previous=-1;
+		if(int err=pthread_setcancelstate(PTHREAD_CANCEL_DISABLE,&previous))
+			cerr << "ERROR: Thread pushNoCancel(), pthread_setcanceltype: " << strerror(err) << endl;
+#ifdef THREADCANCEL_SANITY_CHECKS
+		if(cur->noCancelDepth==1 && previous!=cur->cancelOrig)
+			cerr << "WARNING: In Thread::pushNoCancel, cancel state was wrong (was " << previous << ", expected " << cur->cancelOrig << ")" << endl;
+		else if(cur->noCancelDepth!=1 && previous!=PTHREAD_CANCEL_DISABLE)
+			cerr << "WARNING: In Thread::pushNoCancel, cancel state was somehow re-enabled" << endl;
+#endif
+	}
+}
+void Thread::popNoCancel() {
+	Thread * cur=getCurrent();
+	if(cur==NULL) {
+		//cerr << "ERROR: Thread::popNoCancel was given NULL thread by getCurrent, thread=" << pthread_self() << endl;
+		//not so bad, indicates already canceled -- don't test cancel again, don't want to cancel-recurse
+		return; //no point in continuing
+	} else if(cur->noCancelDepth==0) {
+		cerr << "ERROR: Thread::popNoCancel underflow" << endl;
+	} else
+		--(cur->noCancelDepth);
+	int previous=-1;
+	if(cur->noCancelDepth==0) {
+		if(int err=pthread_setcancelstate(cur->cancelOrig,&previous))
+			cerr << "ERROR: Thread popNoCancel(), pthread_setcanceltype: " << strerror(err) << endl;
+	}
+#ifdef THREADCANCEL_SANITY_CHECKS
+	else { //still disabled, double check it
+		if(int err=pthread_setcancelstate(PTHREAD_CANCEL_DISABLE,&previous))
+			cerr << "ERROR: Thread popNoCancel(), pthread_setcanceltype: " << strerror(err) << endl;
+	}
+	if(previous!=PTHREAD_CANCEL_DISABLE)
+		cerr << "WARNING: In Thread::popNoCancel, cancel state was somehow re-enabled" << endl;
+#endif
+}
+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(msg==NULL) {
+		cerr << "       Message is null, warnCancelDepthUndestructed shouldn't have been called." << endl;
+	} else {
+		pthread_setspecific(Threadstorage_t::selfKey,NULL);
+	}
+	assert(cur==msg);
+}
+
+
 namespace ThreadNS {
 		
-	struct LockStorage {
-		LockStorage() : mutex(), attr() {
+	//!This private class handles the actual lock implementation, which allows Lock to provide an abstract interface
+	class Lock::LockStorage : public ReferenceCounter {
+	public:
+		LockStorage() : ReferenceCounter(), locklevel(0), mutex(), attr(), threadkey() {
+			AddReference();
 			pthread_mutexattr_init(&attr);
 			pthread_mutexattr_settype(&attr,PTHREAD_MUTEX_RECURSIVE);
 			pthread_mutex_init(&mutex,&attr);
@@ -128,62 +300,119 @@
 		~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)
+				cerr << "WARNING: lockstorage destructed with " << locklevel << " locks still in effect" << endl;
+				while(locklevel>0) {
+					locklevel--;
+					Thread::popNoCancel();
+				}
+			}
 		}
-		LockStorage(const LockStorage& ls) : mutex(ls.mutex), attr(ls.attr) {}
-		LockStorage& operator=(const LockStorage& ls) { mutex=ls.mutex; attr=ls.attr; return *this; }
+		LockStorage(const LockStorage& ls) : ReferenceCounter(ls), locklevel(ls.locklevel), mutex(ls.mutex), attr(ls.attr), threadkey(ls.threadkey) {}
+		LockStorage& operator=(const LockStorage& ls) { ReferenceCounter::operator=(ls); locklevel=ls.locklevel; mutex=ls.mutex; attr=ls.attr; threadkey=ls.threadkey; return *this; }
 		void lock() {
-			pthread_mutex_lock(&mutex);
+			Thread::pushNoCancel();
+			if(int err=pthread_mutex_lock(&mutex)) {
+				cerr << "ERROR: ThreadNS::Lock::lock() failed: " << strerror(err) << endl;
+				Thread::popNoCancel();
+			} else
+				locklevel++;
 		}
 		bool trylock() {
-			return !pthread_mutex_trylock(&mutex);
+			Thread::pushNoCancel();
+			if(!pthread_mutex_trylock(&mutex)) {
+				locklevel++;
+				return true;
+			} else {
+				Thread::popNoCancel();
+				return false;
+			}
 		}
 		void unlock() {
-			pthread_mutex_unlock(&mutex);
+			if(locklevel==0)
+				cerr << "ERROR: ThreadNS::Lock::unlock() underflow" << endl;
+			locklevel--;
+			if(int err=pthread_mutex_unlock(&mutex))
+				cerr << "ERROR: ThreadNS::Lock::unlock() failed: " << strerror(err) << endl;
+			Thread::popNoCancel();
 		}
+		unsigned int getLockLevel() { return locklevel; }
+	protected:
+				 
+		unsigned int locklevel;
 		pthread_mutex_t mutex;
 		pthread_mutexattr_t attr;
+		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
 	};
 
-	map<int,struct LockStorage*> Lock::ids;
-	bool Lock::issetup=false;
+	Lock::LockStorage* Lock::glock=NULL;
 
-	Lock::Lock() : my_id() {
-		if(!issetup)
+	Lock::Lock() : mylock(new LockStorage), locklevel(0) {
+		if(glock==NULL)
 			setup();
-		ids[-1]->lock();
-		my_id=(--ids.end())->first+1;
-		ids[my_id]=new LockStorage;
-		ids[-1]->unlock();
 	}
-	/*
-	Lock::Lock(int ident, bool autolock/ *=true* /) : my_id(ident) {
-		if(!issetup)
-			setup();
-		if(ids.find(my_id)==ids.end()) {
-			ids[-1]->lock();
-			ids[my_id]=new LockStorage;
-			ids[-1]->unlock();
-		}
+	/*Lock::Lock(const Lock& l)
+		: mylock(l.mylock), locklevel(0)
+	{
+		glock->lock();
+		mylock->AddReference();
+		glock->unlock();
+		lock();
+	}
+	Lock::Lock(const Lock& l, bool autolock)
+		: mylock(l.mylock), locklevel(0)
+	{
+		glock->lock();
+		mylock->AddReference();
+		glock->unlock();
 		if(autolock)
-			ids[my_id]->lock();
+			lock();
 	}
-	*/
+	Lock& Lock::operator=(const Lock& l) {
+		glock->lock();
+		lock();
+		if(locklevel>2)
+			cerr << "WARNING: ThreadNS::Lock overwritten with "<<locklevel<<" locks still in effect" << endl;
+		if(!mylock->RemoveReference())
+			while(locklevel>0)
+				unlock();
+		mylock=l.mylock;
+		locklevel=0;
+		glock->unlock();
+		return *this;
+	}*/
 	Lock::~Lock() {
-		ids[my_id]->unlock();
+		glock->lock();
+		if(locklevel>1)
+			cerr << "WARNING: ThreadNS::Lock destructed with "<<locklevel<<" locks still in effect" << endl;
+		if(!mylock->RemoveReference())
+			while(locklevel>0)
+				unlock();
+		glock->unlock();
 	}
 
 	void Lock::lock() {
-		ids[my_id]->lock();
+		mylock->lock();
+		locklevel++;
 	}
 	bool Lock::trylock() {
-		return ids[my_id]->trylock();
+		if(mylock->trylock()) {
+			locklevel++;
+			return true;
+		} else {
+			return false;
+		}
 	}
 	void Lock::unlock() {
-		ids[my_id]->unlock();
+		locklevel--;
+		mylock->unlock();
+	}
+	unsigned int Lock::getLockLevel() const {
+		return mylock->getLockLevel();
 	}
 	void Lock::setup() {
-		issetup=true;
-		ids[-1]=new LockStorage;
+		if(glock==NULL)
+			glock=new LockStorage;
 	}
 
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/IPC/Thread.h ./IPC/Thread.h
--- ../Tekkotsu_2.4.1/IPC/Thread.h	2005-08-01 19:17:59.000000000 -0400
+++ ./IPC/Thread.h	2006-06-16 17:49:23.000000000 -0400
@@ -6,57 +6,132 @@
 #  warning Thread class is not Aperios compatable
 #else
 
+#include "Shared/Resource.h"
 #include <stddef.h>
-#include <map>
 
+//! provides Thread related data structures
 namespace ThreadNS {
-	class Lock {
+	//! an inter-thread lock -- doesn't work across processes, only threads within a process.  (see MutexLock for inter-process locks)
+	class Lock : public Resource {
 	public:
-		Lock();
-		explicit Lock(const Lock& l, bool autolock=true) : my_id(l.my_id) { if(autolock) lock(); }
-		//explicit Lock(int ident, bool autolock=true);
-		~Lock();
-		void lock();
-		bool trylock();
-		void unlock();
-		int getID() const { return my_id; }
+		Lock(); //!< constructor
+		//explicit Lock(const Lock& l); //!< copy constructor -- shallow copy, share a lock, is handy for locking over a scope!!! (lock is automatically obtained on copy -- to avoid autolock, pass false to the two-argument constructor: Lock(const Lock& l, bool autolock) )
+		//Lock(const Lock& l, bool autolock); //!< copy constructor -- shallow copy, share a lock, is handy for locking over a scope!!!
+		//Lock& operator=(const Lock& l); //!< assignment -- dereference (and release) any previous lock, take on the new storage (shallow copy!)
+		~Lock(); //!< destructor -- dereference and release (if any references remain)
+		void lock(); //!< block until lock is obtained
+		bool trylock(); //!< see if lock is available
+		void unlock(); //!< release lock, if held
+		unsigned int getInstanceLockLevel() const { return locklevel; } //!< returns the lock level of the local instance of Lock (as opposed to the lock storage structure, which might be shared with other Lock instances)
+		unsigned int getLockLevel() const; //!< returns the lock level of the lock storage itself, the sum of all instance's lock levels
 	protected:
-		static std::map<int,struct LockStorage*> ids;
-		static bool issetup;
-		static void setup();
-		int my_id;
+		friend class MarkScope;
+		virtual void useResource(Resource::Data&) { lock(); }
+		virtual void releaseResource(Resource::Data&) { unlock(); }
+		
+		class LockStorage; //!< this internal class will hold the system-dependent lock information
+		static LockStorage* glock; //!< The global lock to protect Locks sharing #mylock's
+		LockStorage* mylock; //!< This lock's implementation
+		static void setup(); //!< creates a new #glock if it is currently NULL (should be called by the Lock() constructor)
+		unsigned int locklevel; //!< the current lock level from this Lock, may differ from #mylock's lock level if several Locks are sharing a storage!
+	private:
+		Lock(const Lock& l); //!< don't call
+		Lock& operator=(const Lock& l); //!< don't call
 	};	
 }	
 
-//! description of Thread
+//! Provides a nice wrapping of pthreads library
+/*! If you need to provide cleanup functions on stop(), cancelled(), etc., you
+ *  should override the destructor to stop and join so that you can be assured
+ *  that your cleanup will be called if the thread is auto-destructed by going out of scope */
 class Thread {
 public:
-	typedef ThreadNS::Lock Lock;
-	Thread();
-	virtual ~Thread()=0;
+	typedef ThreadNS::Lock Lock; //!< shorthand for pthread lock wrapper
+
+	Thread(); //!< constructor, does not start thread by itself (although subclasses may)
+	virtual ~Thread()=0; //!< destructor, will stop and join the thread, but you should override it to do the same if you provide any cleanup functions
 	
+	//! 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();
-	virtual void * run();
-	virtual unsigned int runloop() { return -1U; }
+	
+	//! 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.
+	 *  @see pushNoCancel(), popNoCancel() */
 	virtual void stop();
+	
+	//! sends a SIGUSR1 to the thread, breaking its execution, but still allowing handle_exit (and thus cancelled()) to be called.
+	/*! Beware if your thread uses mutual exclusion locks, this can cause the thread to terminate while still holding locks */
 	virtual void kill();
+	
+	//! detaches thread and sends SIGSTOP, which immediately halts the thread without any chance for cleanup
+	/*! Beware if your thread uses mutual exclusion locks, this @b will cause the thread to terminate while still holding locks. */
 	virtual void murder();
+	
+	//! sends a signal to the thread
+	virtual void sendSignal(int sig);
+	
+	//! 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
 	virtual bool isRunning() const { return running; }
 	
+	//! returns the Thread object for the current thread (or NULL for the main thread)
+	static Thread* getCurrent() ;
+	
+	//! should be called before any threads are created to allow some global thread-specific data to be set up
+	static void initMainThread();
+	//! should be called if you no longer expect to have any threads in use
+	static void releaseMainThread();
+
+	//! should be called whenever a critical section has been entered (i.e. mutex obtained) -- prevents cancel from occurring until popNoCancel() is called
+	static void pushNoCancel();
+	//! 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();
+	
 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; }
+	//! called by launch() once the thread has been set up; when this returns, the thread ends, see runloop()
+	/*! Default implementation repeatedly calls runloop(), usleep(), and testCancel().
+	 *  If you override, you should also be sure to call testCancel occasionally in order to support stop()
+	 *  If function returns a value, that value overrides #returnValue.  If cancel occurs, #returnValue is used. */
+	virtual void * run();
+	//! override this as a convenient way to define your thread -- return the number of *micro*seconds to sleep before the next call; return -1U to indicate end of processing
+	virtual unsigned int runloop() { return -1U; }
+	//! called when handle_exit() is triggered, either by the thread being cancelled, or when run() has returned voluntarily
+	virtual void cancelled() {}
+	
+	//! checks to see if stop() has been called, and if so, will exit the thread (passing through handle_exit() first)
 	virtual void testCancel();
+	//! thread entry point -- calls launched() on the thread (as indicated by @a msg), and then run()
 	static void * launch(void * msg);
+	//! indicates kill() has been called (or SIGUSR1 was sent from some other source) while launch() was still running
+	static void handle_launch_signal(int sig);
+	//! indicates kill() has been called (or SIGUSR1 was sent from some other source)
 	static void handle_signal(int sig);
+	//! 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);
-	
+
+	//! 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
 	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;
+	//! depth of the pushNoCancel() stack
+	unsigned int noCancelDepth;
+	//! cancel status at root of no-cancel stack (may be no-cancel through and through)
+	int cancelOrig;
 
 private:
-	Thread(const Thread& r); //!< don't call
-	Thread& operator=(const Thread& r); //!< don't call
+	Thread(const Thread& r); //!< don't call, not a well defined operation
+	Thread& operator=(const Thread& r); //!< don't call, not a well defined operation
 };
 
 #endif //Aperios check
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Makefile ./Makefile
--- ../Tekkotsu_2.4.1/Makefile	2005-08-07 00:11:02.000000000 -0400
+++ ./Makefile	2006-09-26 17:53:57.000000000 -0400
@@ -15,7 +15,7 @@
 # defined this variable for us to use its configuration.
 TEKKOTSU_ROOT:=$(shell pwd | sed 's/ /\\ /g')
 TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEKKOTSU_ROOT)/project/Environment.conf
-include $(TEKKOTSU_ENVIRONMENT_CONFIGURATION)
+include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
 
 
 #############  MAKEFILE VARIABLES  ################
@@ -36,19 +36,18 @@
 	  $(if $(TEKKOTSU_DEBUG),-DOPENR_DEBUG,) \
 	  `aperios/bin/xml2-config --cflags`
 else
-  PLATFORM_FLAGS=`xml2-config --cflags`
+  PLATFORM_FLAGS=`xml2-config --cflags` -isystem /usr/include/libpng12
 endif
 
-CXXFLAGS= \
-	$(if $(TEKKOTSU_DEBUG),-g -fno-inline -DDEBUG,) \
-	$(if $(TEKKOTSU_DEBUG),,-O2 -frename-registers -fomit-frame-pointer) \
+CXXFLAGS:= \
+	$(if $(TEKKOTSU_DEBUG),$(TEKKOTSU_DEBUG),$(TEKKOTSU_OPTIMIZE)) \
 	-pipe -ffast-math -fno-common \
 	-Wall -W -Wshadow -Wlarger-than-8192 -Wpointer-arith -Wcast-qual \
 	-Woverloaded-virtual -Weffc++ -Wdeprecated -Wnon-virtual-dtor \
 	-I$(TEKKOTSU_ROOT) -I$(TEKKOTSU_ROOT)/Motion/roboop \
 	-I$(TEKKOTSU_ROOT)/Shared/newmat \
 	-D$(TEKKOTSU_TARGET_PLATFORM)  -D$(TEKKOTSU_TARGET_MODEL) \
-	$(PLATFORM_FLAGS)
+	$(PLATFORM_FLAGS) $(CXXFLAGS)
 
 INCLUDE_PCH=$(if $(TEKKOTSU_PCH),-include $(TK_BD)/$(TEKKOTSU_PCH))
 
@@ -61,8 +60,8 @@
 # You shouldn't need to change anything here unless you want to add
 # external libraries or new directories for the search
 SRCSUFFIX:=.cc
-SRC_DIRS:=Behaviors Events IPC Motion Shared Sound Vision Wireless
-SRCS:=$(shell find $(SRC_DIRS) -name "*$(SRCSUFFIX)")
+SRC_DIRS:=Behaviors DualCoding Events IPC Motion Shared Sound Vision Wireless
+SRCS:=$(shell find $(SRC_DIRS) -name "*$(SRCSUFFIX)" | xargs ls -t)
 
 # We should also make sure these libraries are ready to go
 # Note we've been lucky that these libraries happen to use a different
@@ -76,7 +75,10 @@
 ###################################################
 # Hopefully, you shouldn't have to change anything down here...
 
-.PHONY: all compile clean cleanDeps reportTarget docs dox doc alldocs cleanDoc updateLibs $(USERLIBS) tools platformBuild update install
+#delete automatic suffix list
+.SUFFIXES:
+
+.PHONY: all compile clean cleanDeps reportTarget testEnv docs dox doc alldocs cleanDoc updateTools updateLibs $(USERLIBS) platformBuild update install
 
 all:
 	@echo "Running $(MAKE) from the root directory will first build the"
@@ -90,18 +92,19 @@
 	@echo "You will want to run make from your project directory in order"
 	@echo "to produce executables..."
 	@echo ""
-	export TEKKOTSU_TARGET_PLATFORM=PLATFORM_APERIOS; \
-	$(MAKE) compile
-	export TEKKOTSU_TARGET_PLATFORM=PLATFORM_LOCAL; \
-	$(MAKE) compile
+	$(MAKE) TEKKOTSU_TARGET_PLATFORM=PLATFORM_APERIOS compile
+	$(MAKE) TEKKOTSU_TARGET_PLATFORM=PLATFORM_LOCAL compile
 	@echo "Build successful."
 
-update install:
+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 "be linked against by the projects and tools."
-	@echo "However, only a project can install or update to memory stick."
+	@echo ""
+	@echo "However, you can only install or update to memory stick from within a project."
 	@echo "You can use the template project directory if you want to build a stick"
 	@echo "with the standard demo behaviors."
 
@@ -119,6 +122,8 @@
 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
@@ -134,12 +139,12 @@
         cat $*.log | $(FILTERSYSWARN) | $(COLORFILT) | $(TEKKOTSU_LOGVIEW); \
         test $$retval -eq 0;
 
-%.d:
+$(TK_BD)/%.d: %.cc
 	@mkdir -p $(dir $@)
 	@src=$(patsubst %.d,%.cc,$(patsubst $(TK_BD)%,$(TEKKOTSU_ROOT)%,$@)); \
 	if [ ! -f "$$src" ] ; then \
-		echo "Generating source file '$$src'"; \
-		$(MAKE) "$$src" ; \
+		echo "ERROR: Missing source file '$$src'... you shouldn't be seeing this"; \
+		exit 1; \
 	fi; \
 	echo "$@..." | sed 's@.*$(TK_BD)/@Generating @'; \
 	$(CXX) $(CXXFLAGS) -MP -MG -MT "$@" -MT "$(@:.d=.o)" -MM "$$src" > $@
@@ -150,8 +155,13 @@
 	echo "$@..." | sed 's@.*$(TK_BD)/@Generating @'; \
 	$(CXX) $(CXXFLAGS) -MP -MG -MT "$@" -MT "$(@:.d=.gch)" -MM "$$src" > $@
 
+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)
+endif
+
 ifneq ($(MAKECMDGOALS),)
-ifeq ($(filter clean% docs dox doc alldocs,$(MAKECMDGOALS)),)
+ifeq ($(filter clean% docs dox doc alldocs newstick,$(MAKECMDGOALS)),)
 -include $(DEPENDS)
 ifeq ($(TEKKOTSU_TARGET_PLATFORM),PLATFORM_APERIOS)
 -include $(TK_BD)/aperios/aperios.d
@@ -159,24 +169,46 @@
 endif
 endif
 
-compile: tools reportTarget updateLibs platformBuild
+compile: reportTarget updateTools updateLibs platformBuild
 
-tools:
-	@$(MAKE) -C tools
+$(TOOLS_BUILT_FLAG):
+	@$(MAKE) TOOLS_BUILT_FLAG="$(TOOLS_BUILT_FLAG)" -C tools
 
 dox docs doc:
-	docs/builddocs --update --tree --search --detailed
+	docs/builddocs --update --tree --search
 
 alldocs:
-	docs/builddocs --update --all --tree --search --detailed
+	docs/builddocs --update --all --tree --search
 
-reportTarget:
+ifeq ($(MAKELEVEL),0)
+reportTarget: testEnv
 	@echo " ** Targeting $(TEKKOTSU_TARGET_MODEL) for build on $(TEKKOTSU_TARGET_PLATFORM) ** ";
-	@echo " ** TEKKOTSU_DEBUG is $(if $(TEKKOTSU_DEBUG),ON ,OFF) ** ";
+	@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;
+
+updateTools: | $(TOOLS_BUILT_FLAG) 
+	$(MAKE) -C tools
 
 updateLibs: $(USERLIBS)
 
-$(USERLIBS):
+$(USERLIBS): | $(TOOLS_BUILT_FLAG)
 	@echo "$@:"; \
 	export TEKKOTSU_ENVIRONMENT_CONFIGURATION="$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)"; \
 	$(MAKE) -C "$@"
@@ -189,23 +221,24 @@
 	@$(AR2) $@
 
 %.h :
+	@echo "ERROR: Seems to be a missing header file '$@'...";
 	@if [ "$(notdir $@)" = "def.h" -o "$(notdir $@)" = "entry.h" ] ; then \
 		echo "WARNING: You shouldn't be seeing this message.  Report that you did." ; \
 		echo "         Try a clean recompile." ; \
+		exit 1; \
 	fi;
-	@echo "ERROR: Seems to be a missing header file '$@'...";
 	@echo "       Someone probably forgot to check a file into CVS.";
 	@echo "       I'll try to find where it's being included from:";
+	@echo "       if this was a file you recently deleted, just make again after this completes. (will update dependency files)";
 	@find . -name "*.h" -exec grep -H "$(notdir $@)" \{\} \; ;
 	@find . -name "*.cc" -exec grep -H "$(notdir $@)" \{\} \; ;
-	@echo "";
-	@echo "You might need to rebuild the dependancy files ('make cleanDeps') to get rid of this error.";
+	@find $(TK_BD) -name "*.d" -exec grep -qH "$(notdir $@)" \{\} \; -exec rm \{\} \; ;
 	@exit 1
 
 #don't try to make random files via this implicit chain
 %:: %.o ;
 
-%.o: $(if $(TEKKOTSU_PCH),$(TK_BD)/$(TEKKOTSU_PCH).gch)
+%.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..."; \
@@ -219,7 +252,7 @@
 	@rm -f $(addsuffix ~,$(SRCS)) $(SRCS:$(SRCSUFFIX)=.h~)
 	@printf "done.\n"
 	rm -rf $(TEKKOTSU_BUILDDIR)
-	(cd $(TEKKOTSU_ROOT)/tools && $(MAKE) clean);
+	$(MAKE) TOOLS_BUILT_FLAG="$(TOOLS_BUILT_FLAG)" -C tools clean;
 	for dir in `ls aperios` ; do \
 		if [ "$$dir" = "CVS" ] ; then continue; fi; \
 		if [ -f "aperios/$$dir" ] ; then continue; fi; \
@@ -228,7 +261,7 @@
 
 cleanDeps:
 	@printf "Cleaning all .d files from build directory..."
-	@find "$(TK_BD)/../.." -name "*.d" -exec rm \{\} \;
+	@find "$(TEKKOTSU_BUILDDIR)" -name "*.d" -exec rm \{\} \;
 	@printf "done.\n"
 
 cleanDoc:
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/DynamicMotionSequence.h ./Motion/DynamicMotionSequence.h
--- ../Tekkotsu_2.4.1/Motion/DynamicMotionSequence.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Motion/DynamicMotionSequence.h	2006-09-09 00:32:52.000000000 -0400
@@ -1,6 +1,6 @@
 //-*-c++-*-
-#ifndef INCLUDED_DynamicMotionSequenceMC_h_
-#define INCLUDED_DynamicMotionSequenceMC_h_
+#ifndef INCLUDED_DynamicMotionSequence_h_
+#define INCLUDED_DynamicMotionSequence_h_
 
 #include "MotionSequenceEngine.h"
 #include "MotionCommand.h"
@@ -15,7 +15,7 @@
 	//!constructor
 	DynamicMotionSequence() : MotionCommand(), MotionSequenceEngine(), moves(), erased() {clear();}
 	//!constructor, loads from a file and then resets the playtime to beginning and begins to play
-	explicit DynamicMotionSequence(const char* filename) : MotionCommand(), MotionSequenceEngine(), moves(), erased() {clear();LoadFile(filename);setTime(1);}
+	explicit DynamicMotionSequence(const char* filename) : MotionCommand(), MotionSequenceEngine(), moves(), erased() {clear();loadFile(filename);setTime(1);}
 	//!destructor
 	virtual ~DynamicMotionSequence() {}
 
@@ -100,18 +100,22 @@
 	//! marks keyframe @a x unused
 	virtual void eraseKeyFrame(Move_idx_t x) { erased.push_back(x); }
 	//! advances (or rewinds) @a prev and @a next so that @a t falls between them
-	void setRange(unsigned int t,Move_idx_t& prev, Move_idx_t& next) const {
+	bool setRange(unsigned int t,Move_idx_t& prev, Move_idx_t& next) const {
+		bool moved=false;
 		if(next!=invalid_move && moves[next].starttime<=t) {
+			moved=true;
 			do {
 				prev=next;
 				next=moves[prev].next;
 			} while(next!=invalid_move && moves[next].starttime<=t);
-		} else if(t<moves[prev].starttime) {
-			do {
+		} else {
+			while(moves[prev].prev!=invalid_move && t<moves[prev].starttime) {
 				next=prev;
 				prev=moves[next].prev;
-			} while(t<moves[prev].starttime);
+				moved=true;
+			}
 		}
+		return moved;
 	}
 };
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/EmergencyStopMC.cc ./Motion/EmergencyStopMC.cc
--- ../Tekkotsu_2.4.1/Motion/EmergencyStopMC.cc	2005-06-06 14:30:19.000000000 -0400
+++ ./Motion/EmergencyStopMC.cc	2006-09-18 14:08:01.000000000 -0400
@@ -12,7 +12,7 @@
 
 EmergencyStopMC::EmergencyStopMC()
 	: PostureMC(), paused(false), stilldown(false), active(true), period(2000),
-		timeoflastbtn(0), timeofthisbtn(0), timeoflastfreeze(0), duration(600),
+		timeoflastbtn(0), timeofthisbtn(0), timeoflastfreeze(0), timeoflastrelease(0), duration(600),
 		pidcutoff(0.2), ledengine()
 {
 	for(unsigned int i=0; i<NumPIDJoints; i++)
@@ -53,27 +53,41 @@
 		if((get_time()-timeoflastbtn)<duration)
 			setStopped(!paused);
 	}
-	if(!paused)
-		return 0;
-	//immediately following a pause, just hold current position at first to prevent twitching if we were in motion
-	if(get_time()-timeoflastfreeze>FrameTime*NumFrames*5) { 
-		//once joints have come to rest, respond to outside forces
-		for(unsigned int i=0; i<NumPIDJoints; i++) {
-			//exponential average of duty cycles to filter out noise
-			piddutyavgs[i]=piddutyavgs[i]*.9f+state->pidduties[i]*.1f;
-			//reset if there's something significantly out of place (perhaps we're being overridden)
-			if(fabsf(state->outputs[PIDJointOffset+i]-cmds[PIDJointOffset+i].value)>.15f) {
-				//if(PIDJointOffset+i==LFrLegOffset+RotatorOffset)
-				//cout << "resetting from " << cmds[PIDJointOffset+i].value << " to " << state->outputs[PIDJointOffset+i] << endl;
-				curPositions[PIDJointOffset+i]=cmds[PIDJointOffset+i].value=state->outputs[PIDJointOffset+i];
-				dirty=true;
-				targetReached=false;
-			}
-			//give if there's a force...
-			if(fabsf(piddutyavgs[i])>pidcutoff) {
-				cmds[PIDJointOffset+i].value-=piddutyavgs[PIDJointOffset+i]; //move in the direction of the force
-				dirty=true;
-				targetReached=false;
+	unsigned int curt=get_time();
+	dirty=dirty || (curt<timeoflastrelease);
+	if(!paused) {
+		if(!dirty)
+			return 0;
+		if(curt>=timeoflastrelease) {
+			for(unsigned int i=LEDOffset; i<LEDOffset+NumLEDs; i++)
+				motman->setOutput(this,i,0.f); //blank out LEDs to avoid residual background display
+			dirty=false;
+			return 0;
+		}
+		float w = (curt>=timeoflastrelease) ? 0 : (static_cast<float>(timeoflastrelease-curt)/FADE_OUT_TIME);
+		for(unsigned int i=0; i<NumOutputs; i++)
+			cmds[i].weight=w;
+	} else {
+		//immediately following a pause, just hold current position at first to prevent twitching if we were in motion
+		if(curt-timeoflastfreeze>FrameTime*NumFrames*5) { 
+			//once joints have come to rest, respond to outside forces
+			for(unsigned int i=0; i<NumPIDJoints; i++) {
+				//exponential average of duty cycles to filter out noise
+				piddutyavgs[i]=piddutyavgs[i]*.9f+state->pidduties[i]*.1f;
+				//reset if there's something significantly out of place (perhaps we're being overridden)
+				if(fabsf(state->outputs[PIDJointOffset+i]-cmds[PIDJointOffset+i].value)>.15f) {
+					//if(PIDJointOffset+i==LFrLegOffset+RotatorOffset)
+					//cout << "resetting from " << cmds[PIDJointOffset+i].value << " to " << state->outputs[PIDJointOffset+i] << endl;
+					curPositions[PIDJointOffset+i]=cmds[PIDJointOffset+i].value=state->outputs[PIDJointOffset+i];
+					dirty=true;
+					targetReached=false;
+				}
+				//give if there's a force...
+				if(fabsf(piddutyavgs[i])>pidcutoff) {
+					cmds[PIDJointOffset+i].value-=piddutyavgs[PIDJointOffset+i]; //move in the direction of the force
+					dirty=true;
+					targetReached=false;
+				}
 			}
 		}
 	}
@@ -81,13 +95,13 @@
 	if(state->robotDesign&WorldState::ERS7Mask) {
 		//a special Battlestar Galactica inspired effect for the ERS-7
 		static float acts[5];
-		static bool first=true;
-		if(first) {
+		static bool wasPaused=false;
+		if(!wasPaused && paused) {
 			for(int i=0; i<5; i++)
 				acts[i]=0;
-			first=false;
+			wasPaused=paused;
 		}
-		float t=get_time();
+		float t=curt;
 		t/=period;
 		t=(((int)t)&1)?(int)t+1-t:(t-(int)t);
 		t*=8;
@@ -95,18 +109,22 @@
 		const float gamma=.83;
 		const float amp=.5;
 		float imp[5];
+		// 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));
+			imp[i]=exp(invsigma*(t-i-2)*(t-i-2))*w;
 			acts[i]+=amp*imp[i];
-			acts[i]*=gamma;
+			acts[i]*=gamma*w;
 		}
-		cmds[ERS7Info::FaceLEDPanelOffset+6].value=acts[0]/2+imp[0];
-		cmds[ERS7Info::FaceLEDPanelOffset+7].value=acts[4]/2+imp[4];
-		cmds[ERS7Info::FaceLEDPanelOffset+8].value=acts[1]/2+imp[1];
-		cmds[ERS7Info::FaceLEDPanelOffset+9].value=acts[3]/2+imp[3];
+		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];
 	}
-	return PostureMC::updateOutputs();
+	int changed=PostureMC::updateOutputs();
+	dirty=(curt<timeoflastrelease);
+	return changed;
 }
 
 void EmergencyStopMC::setActive(bool a) {
@@ -127,12 +145,12 @@
 			if(paused) {
 				freezeJoints();
 				if(sound)
-					sndman->PlayFile(config->motion.estop_on_snd);
+					sndman->playFile(config->motion.estop_on_snd);
 				cout << "*** PAUSED ***" << endl;
 			} else {
 				releaseJoints();
 				if(sound)
-					sndman->PlayFile(config->motion.estop_off_snd);
+					sndman->playFile(config->motion.estop_off_snd);
 				cout << "*** UNPAUSED ***" << endl;
 			}
 		}
@@ -142,8 +160,10 @@
 void EmergencyStopMC::freezeJoints() {
 	dirty=true;
 	targetReached=false;
-	for(unsigned int i=0; i<NumOutputs; i++)
-		curPositions[i]=cmds[i].value=motman->getOutputCmd(i).value;
+	for(unsigned int i=0; i<NumOutputs; i++) {
+		OutputCmd c=motman->getOutputCmd(i);
+		curPositions[i]=cmds[i].value = (c.weight==0) ? state->outputs[i] : c.value;
+	}
 	for(unsigned int i=0; i<NumPIDJoints; i++)
 		piddutyavgs[i]=0; //or: state->pidduties[i];
 	for(unsigned int i=0; i<LEDOffset; i++)
@@ -174,34 +194,19 @@
 void EmergencyStopMC::releaseJoints() {
 	dirty=true;
 	targetReached=false;
-	for(unsigned int i=0; i<NumOutputs; i++)
-		cmds[i].unset();
-	//these lines prevent residual display
-	if(state->robotDesign&WorldState::ERS210Mask) {
-		motman->setOutput(this,ERS210Info::TlRedLEDOffset,0.f);
-		motman->setOutput(this,ERS210Info::TlBluLEDOffset,0.f);
-	} else if(state->robotDesign&WorldState::ERS220Mask) {
-		for(unsigned int i = 0; i < NumLEDs; i++)
-			if((ERS220Info::TailLEDMask|ERS220Info::BackLEDMask) & (1 << i))
-				motman->setOutput(this,LEDOffset + i,0.f);
-	} else if(state->robotDesign&WorldState::ERS7Mask) {
-		cmds[ERS7Info::MdBackColorLEDOffset].set(0,0.f);
-		for(int i=6; i<6+5; i++)
-			cmds[ERS7Info::FaceLEDPanelOffset+i].set(0,0.f);
-	} else {
-		cmds[LEDOffset+NumLEDs-1].set(0,0.f);
-		cmds[LEDOffset+NumLEDs-2].set(0,0.f);
-	}
-	postEvent(EventBase(EventBase::estopEGID,getID(),EventBase::deactivateETID,get_time()-timeoflastfreeze));
+	unsigned int curt=get_time();
+	timeoflastrelease=curt+FADE_OUT_TIME;
+	postEvent(EventBase(EventBase::estopEGID,getID(),EventBase::deactivateETID,curt-timeoflastfreeze));
 }
 
 bool EmergencyStopMC::trigger() {
-	if(state->robotDesign&WorldState::ERS210Mask)
-		return state->button_times[ERS210Info::BackButOffset];
-	if(state->robotDesign&WorldState::ERS220Mask)
-		return state->button_times[ERS220Info::BackButOffset];
-	if(state->robotDesign&WorldState::ERS7Mask)
-		return state->button_times[ERS7Info::FrontBackButOffset]+state->button_times[ERS7Info::MiddleBackButOffset]+state->button_times[ERS7Info::RearBackButOffset];
+	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)
+		return st->button_times[ERS7Info::FrontBackButOffset]+st->button_times[ERS7Info::MiddleBackButOffset]+st->button_times[ERS7Info::RearBackButOffset];
 	serr->printf("EmergencyStopMC: unsupported model!\n");
 	return false;
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/EmergencyStopMC.h ./Motion/EmergencyStopMC.h
--- ../Tekkotsu_2.4.1/Motion/EmergencyStopMC.h	2005-01-07 14:36:38.000000000 -0500
+++ ./Motion/EmergencyStopMC.h	2006-09-16 02:28:07.000000000 -0400
@@ -40,6 +40,8 @@
 	void freezeJoints(); //!< code to execute when locking joints
 	void releaseJoints(); //!< code to execute when releasing joints
 	static bool trigger(); //!< true when the trigger condition is active
+	
+	static const unsigned int FADE_OUT_TIME=400; //!< number of milliseconds to fade out lock on joints
 
 	bool paused; //!< true if the joints are current locked up
 	bool stilldown; //!< true if the back button was down on last updateJointCmds
@@ -48,6 +50,7 @@
 	unsigned int timeoflastbtn; //!< time of the last button press
 	unsigned int timeofthisbtn; //!< time of the current button press
 	unsigned int timeoflastfreeze; //!< the time estop was last turned on
+	unsigned int timeoflastrelease; //!< the time estop was last turned off (may be in the future if still fading out control of joints!)
 	unsigned int duration; //!<the maximum time (in milliseconds) of consecutive button-down's to count as a double tap
 	float piddutyavgs[NumPIDJoints]; //!< a running average of PID feedback ("duty"), so one bad reading doesn't cause a movement, need a consistent pressure
 	float pidcutoff; //!<abs pid duty cycle above which we just reset joint to current
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/HeadPointerMC.cc ./Motion/HeadPointerMC.cc
--- ../Tekkotsu_2.4.1/Motion/HeadPointerMC.cc	2005-01-25 15:06:42.000000000 -0500
+++ ./Motion/HeadPointerMC.cc	2006-08-31 17:42:02.000000000 -0400
@@ -1,20 +1,33 @@
+#include <math.h>
+
 #include "HeadPointerMC.h"
+#include "Kinematics.h"
 #include "Shared/debuget.h"
 #include "Shared/WorldState.h"
 #include "MotionManager.h"
-#include <math.h>
 #include "Shared/Config.h"
 #include "Wireless/Socket.h"
 
 HeadPointerMC::HeadPointerMC()
-	: MotionCommand(), dirty(true), hold(true), tolerance(.035),
-		targetReached(false), targetTimestamp(0), timeout(2000), 
+	: MotionCommand(), dirty(true), hold(true), tolerance(.05),
+		targetReached(true), targetTimestamp(0), timeout(2000), 
 	  headkin(::config->motion.makePath(::config->motion.kinematics),"Camera")
 {
 	setWeight(1);
 	defaultMaxSpeed();
+	takeSnapshot();
+}
+
+void HeadPointerMC::freezeMotion() {
+	for(unsigned int i=0; i<NumHeadJoints; i++)
+		headTargets[i]=headCmds[i].value;
+	dirty=false;
+}
+
+void HeadPointerMC::takeSnapshot() {
 	for(unsigned int i=0; i<NumHeadJoints; i++)
 		headTargets[i]=headCmds[i].value=state->outputs[HeadOffset+i];
+	dirty=true;
 }
 
 void HeadPointerMC::defaultMaxSpeed(float x/*=1*/) {
@@ -45,6 +58,8 @@
 
 	NEWMAT::ColumnVector poE=headkin.convertLink(0,headkin.get_dof())*Pobj;
 	poE=poE.SubMatrix(1,3,1,1);
+	//	float theta = acos(poE(3)/sqrt(poE(1)*poE(1)+poE(2)*poE(2)+poE(3)*poE(3)));
+	//	cout << "Computed:\n theta1: " << mathutils::rad2deg(theta) << " degrees\n";
 	NEWMAT::ColumnVector plE=Plink.SubMatrix(1,3,1,1);
 	float plE2=plE.SumSquare();
 	float plE_len=sqrt(plE2);
@@ -60,7 +75,11 @@
 
 	for(unsigned int i=0; i<NumHeadJoints; i++)
 		setJointValue(i,headkin.get_q(2+i));
-	return conv;
+
+	//	NEWMAT::ColumnVector poE2=headkin.convertLink(0,headkin.get_dof())*Pobj;
+	//	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);
 }
 	
 bool HeadPointerMC::lookAtPoint(float x, float y, float z, float d) {
@@ -71,7 +90,8 @@
 	NEWMAT::ColumnVector q=headkin.inv_kin_pos(Pobj,0,headkin.get_dof(),Plink,conv);
 	for(unsigned int i=0; i<NumHeadJoints; i++)
 		setJointValue(i,headkin.get_q(2+i));
-	return conv;
+	//	return conv;
+	return isReachable(Pobj);
 }
 	
 bool HeadPointerMC::lookInDirection(float x, float y, float z) {
@@ -82,9 +102,11 @@
 	NEWMAT::ColumnVector q=headkin.inv_kin_pos(Pobj,0,headkin.get_dof(),Plink,conv);
 	for(unsigned int i=0; i<NumHeadJoints; i++)
 		setJointValue(i,headkin.get_q(2+i));
-	return conv;
+	//	return conv;
+	return isReachable(Pobj);
 }
 
+
 int HeadPointerMC::updateOutputs() {
 	int tmp=isDirty();
 	if(tmp || hold) {
@@ -125,9 +147,9 @@
 int HeadPointerMC::isAlive() {
 	if(dirty || !targetReached)
 		return true;
-	if(targetReached && get_time()-targetTimestamp>timeout) { //prevents a conflicted HeadPointerMC's from fighting forever
-		if(getAutoPrune())
-			serr->printf("WARNING: HeadPointerMC timed out - possible joint conflict or out-of-range target\n");
+	if(targetReached && (!hold || get_time()-targetTimestamp>timeout)) { //prevents a conflicted HeadPointerMC's from fighting forever
+		if(get_time()-targetTimestamp>timeout && getAutoPrune())
+			serr->printf("WARNING: HeadPointerMC (mcid %d) timed out - possible joint conflict or out-of-range target\n",getID());
 		return false;
 	}
 	float maxdiff=0;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/HeadPointerMC.h ./Motion/HeadPointerMC.h
--- ../Tekkotsu_2.4.1/Motion/HeadPointerMC.h	2005-01-07 16:13:31.000000000 -0500
+++ ./Motion/HeadPointerMC.h	2006-09-26 15:29:40.000000000 -0400
@@ -1,16 +1,16 @@
 //-*-c++-*-
 #ifndef INCLUDED_HeadPointerMC_h
 #define INCLUDED_HeadPointerMC_h
-
 #include "MotionCommand.h"
 #include "OutputCmd.h"
 #include "Shared/RobotInfo.h"
+#include "Shared/mathutils.h"
 #include "roboop/robot.h"
 
 //! This class gives some quick and easy functions to point the head at things
 class HeadPointerMC : public MotionCommand {
 public:
-	//! Constructor, defaults to all joints to current value in ::state
+	//! Constructor, defaults to all joints to current value in ::state (i.e. calls takeSnapshot() automatically)
 	HeadPointerMC();
 	
 	//! Destructor
@@ -24,6 +24,17 @@
 	virtual float getTolerance() { return tolerance; } //!< returns #tolerance
 	virtual void setTimeout(unsigned int delay) { timeout=delay; } //!< sets #timeout
 	virtual unsigned int getTimeout() { return timeout; } //!< returns #timeout
+	
+	//! sets the target to last sent commands, and dirty to false; essentially freezes motion in place
+	/*! This is very similar to takeSnapshot(), but will do the "right thing" (retain current position) when motion blending is involved.
+	 *  A status event will be generated if/when the joints reach the currently commanded position.
+	 *  Probably should use freezeMotion() if you want to stop a motion underway, but takeSnapshot() if you want to reset/intialize to the current joint positions. */
+	virtual void freezeMotion();
+	//! sets the target joint positions to current sensor values
+	/*! Similar to freezeMotion() when a motion is underway, but only if no other MotionCommands are using neck joints.
+	  *  A status event will @e not be generated unless a motion was already underway.
+	  *  Probably should use freezeMotion() if you want to stop a motion underway, but takeSnapshot() if you want to reset/intialize to the current joint positions. */
+	virtual void takeSnapshot();
 
 	//!@name Speed Control
 	
@@ -77,7 +88,7 @@
 	}
 	
 	//! Centers the camera on a point in space, attempting to keep the camera as far away from the point as possible
-	/*! Point should be relative to the body reference frame (see ::BaseFrameOffset)
+	/*! Point should be relative to the body reference frame (see ::BaseFrameOffset).  Returns true if the target is reachable.
 	 *  @param x location in millimeters
 	 *  @param y location in millimeters
 	 *  @param z location in millimeters
@@ -86,7 +97,7 @@
 	bool lookAtPoint(float x, float y, float z);
 	
 	//! Centers the camera on a point in space, attempting to move the camera @a d millimeters away from the point
-	/*! Point should be relative to the body reference frame (see ::BaseFrameOffset)
+	/*! Point should be relative to the body reference frame (see ::BaseFrameOffset).  Returns true if the target is reachable.
 	 *  @param x location in millimeters
 	 *  @param y location in millimeters
 	 *  @param z location in millimeters
@@ -94,15 +105,17 @@
 	bool lookAtPoint(float x, float y, float z, float d);
 	
 	//! Points the camera in a given direction
-	/*! Vector should be relative to the body reference frame (see ::BaseFrameOffset)
+	/*! Vector should be relative to the body reference frame (see ::BaseFrameOffset).  Returns true if the target is reachable.
 	 *  @param x component of the direction vector
 	 *  @param y component of the direction vector
 	 *  @param z component of the direction vector */
 	bool lookInDirection(float x, float y, float z);
+
+
 	
 	//@}
 	
-	
+public:	
 	//!@name Inherited:
 	virtual int updateOutputs(); //!< Updates where the head is looking
 	virtual int isDirty() { return (dirty || !targetReached)?3:0; } //!< true if a change has been made since the last updateJointCmds() and we're active
@@ -111,6 +124,14 @@
 	//@}
 
  protected:
+         //! checks if target point or direction is actually reachable
+        bool isReachable(const NEWMAT::ColumnVector& Pobj) {
+	  NEWMAT::ColumnVector poE=headkin.convertLink(0,headkin.get_dof())*Pobj;
+	  const float theta = mathutils::rad2deg(acos(poE(3)/sqrt(poE(1)*poE(1)+poE(2)*poE(2)+poE(3)*poE(3))));
+	  //	  cout << "theta: " << theta << " degrees\n";
+	  return theta < 5.0;
+	}
+
 	//! puts x in the range (-pi,pi)
 	static float normalizeAngle(float x) { return x-rint(x/(2*M_PI))*(2*M_PI); }
 	
@@ -152,10 +173,10 @@
 	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
-  float headTargets[NumHeadJoints];    //!< stores the target value of each joint
+	float headTargets[NumHeadJoints];    //!< stores the target value of each joint
 	OutputCmd headCmds[NumHeadJoints];   //!< stores the last values we sent from updateOutputs
 	float maxSpeed[NumHeadJoints];       //!< initialized from Config::motion_config, but can be overridden by setMaxSpeed(); rad per frame
-	ROBOOP::Robot headkin;               //!< provides kinematics computations
+	ROBOOP::Robot headkin;               //!< provides kinematics computations, there's a small leak and safety issue here because ROBOOP::Robot contains pointers, and those pointers typically aren't freed because MotionCommand destructor isn't called when detaching shared region
 };
 
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/Kinematics.cc ./Motion/Kinematics.cc
--- ../Tekkotsu_2.4.1/Motion/Kinematics.cc	2005-06-01 01:47:47.000000000 -0400
+++ ./Motion/Kinematics.cc	2006-09-09 00:32:53.000000000 -0400
@@ -4,90 +4,80 @@
 #include "roboop/config.h"
 #include "Shared/WorldState.h"
 #include <sstream>
-#include "local/sim/Process.h"
+#include <float.h>
+#include <iostream>
 
 using namespace std;
 
 Kinematics * kine = NULL;
 ROBOOP::Config * Kinematics::roconfig = NULL;
 Kinematics::InterestPointMap * Kinematics::ips = NULL;
+std::vector< std::vector<unsigned int> > Kinematics::chainMaps;
+Kinematics::JointMap Kinematics::jointMaps[NumReferenceFrames];
+bool Kinematics::staticsInited=false;
+#ifndef THREADSAFE_KINEMATICS
+std::vector<ROBOOP::Robot*> Kinematics::chains;
+#endif
 
 void
 Kinematics::init() {
+#ifdef THREADSAFE_KINEMATICS
 	unsigned int nchains=::config->motion.kinematic_chains.size();
-	if(nchains==0) {
-		serr->printf("ERROR Kinematics::init(): no kinematic chains were selected\n");
-		return;
-	}
-	jointMaps[BaseFrameOffset]=JointMap(0,0);
 	chains.resize(nchains);
-	chainMaps.resize(nchains);
-	if(roconfig==NULL)
-		roconfig=new ROBOOP::Config(::config->motion.makePath(::config->motion.kinematics),true);
 	for(unsigned int i=0; i<nchains; i++) {
-		string section=::config->motion.kinematic_chains[i];
-		chains[i]=new ROBOOP::Robot(*roconfig,section);
-		int dof=0;
-		if(roconfig->select_int(section,"dof",dof)!=0) {
-			serr->printf("ERROR Kinematics::init(): unable to find 'dof' in chain %d (%s)\n",i,section.c_str());
+		chains[i]=newChain(i);
+		//cout << "Created " << chains[i] << " for " << this << endl;
+	}
+#endif
+	checkStatics();
+}
+
+void Kinematics::initStatics() {
+	if(!staticsInited) {
+		unsigned int nchains=::config->motion.kinematic_chains.size();
+		if(nchains==0) {
+			serr->printf("ERROR Kinematics::init(): no kinematic chains were selected\n");
 			return;
 		}
-		chainMaps[i].resize(dof+1);
-		for(int l=0; l<=dof; l++)
-			chainMaps[i][l]=-1U;
-		for(int l=1; l<=dof; l++) {
-			ostringstream ostr;
-			ostr << section << "_LINK" << l;
-			string link = ostr.str();
-			if(roconfig->parameter_exists(link,"tekkotsu_output")) {
-				int tkout=-1U;
-				roconfig->select_int(link,"tekkotsu_output",tkout);
-				if((unsigned int)tkout>=NumOutputs) {
-					serr->printf("WARNING Kinematics::init(): invalid tekkotsu_output %d on chain %d (%s), link %d (%s)\n",tkout,i,section.c_str(),l,link.c_str());
-				} else {
-					jointMaps[tkout]=JointMap(i,l);
-					chainMaps[i][l]=tkout;
-				}
-			}
-			if(roconfig->parameter_exists(link,"tekkotsu_frame")) {
-				int tkout=-1U;
-				roconfig->select_int(link,"tekkotsu_frame",tkout);
-				tkout+=NumOutputs;
-				if((unsigned int)tkout>=NumReferenceFrames)
-					serr->printf("WARNING Kinematics::init(): invalid tekkotsu_frame %d on chain %d (%s), link %d (%s)\n",tkout,i,section.c_str(),l,link.c_str());
-				else {
-					jointMaps[tkout]=JointMap(i,l);
-					chainMaps[i][l]=tkout;
-				}
-			}
+		jointMaps[BaseFrameOffset]=JointMap(0,0);
+		
+#ifndef THREADSAFE_KINEMATICS
+		chains.resize(nchains);
+		for(unsigned int i=0; i<nchains; i++) {
+			chains[i]=newChain(i);
+			//cout << "Created " << chains[i] << " for " << this << endl;
 		}
-	}
-
-	if(ips==NULL) {
-		int numIP=0;
-		roconfig->select_int("InterestPoints","Length",numIP);
-		ips=new InterestPointMap(numIP);
-		pair<string,InterestPoint> ip;
-		string chain;
-		for(int i=1; i<=numIP; i++) {
-			char section[100];
-			snprintf(section,100,"InterestPoint%d",i);
-			roconfig->select_float(section,"x",ip.second.x);
-			roconfig->select_float(section,"y",ip.second.y);
-			roconfig->select_float(section,"z",ip.second.z);
-			roconfig->select_string(section,"chain",chain);
-			roconfig->select_int(section,"link",ip.second.link);
-			roconfig->select_string(section,"name",ip.first);
-			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;
-			if(ip.second.chain==::config->motion.kinematic_chains.size())
-				serr->printf("WARNING: Chain %s is not recognized for interest point %d\n",chain.c_str(),i);
-			else
-				ips->insert(ip);
+#endif
+		
+		if(ips==NULL) {
+			int numIP=0;
+			roconfig->select_int("InterestPoints","Length",numIP);
+			ips=new InterestPointMap(numIP);
+			pair<string,InterestPoint> ip;
+			string chain;
+			for(int i=1; i<=numIP; i++) {
+				char section[100];
+				snprintf(section,100,"InterestPoint%d",i);
+				roconfig->select_float(section,"x",ip.second.x);
+				roconfig->select_float(section,"y",ip.second.y);
+				roconfig->select_float(section,"z",ip.second.z);
+				roconfig->select_string(section,"chain",chain);
+				roconfig->select_int(section,"link",ip.second.link);
+				roconfig->select_string(section,"name",ip.first);
+				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;
+				if(ip.second.chain==::config->motion.kinematic_chains.size())
+					serr->printf("WARNING: Chain %s is not recognized for interest point %d\n",chain.c_str(),i);
+				else
+					ips->insert(ip);
+			}
 		}
+		staticsInited=true;
+#ifndef THREADSAFE_KINEMATICS
+		delete roconfig; // static chains are initialized, don't need to keep this around...
+#endif
 	}
-
 	/*cout << "Joint Maps" << endl;
 	for(unsigned int i=0; i<NumOutputs; i++)
 		cout << outputNames[i] << ": " << jointMaps[i].chain << ' ' << jointMaps[i].link << endl;
@@ -99,8 +89,71 @@
 		cout << "chainMaps["<<i<<"]["<<j<<"] == " << chainMaps[i][j] << endl;*/
 }
 
+ROBOOP::Robot* Kinematics::newChain(unsigned int chainIdx) {
+	if(roconfig==NULL) {
+		unsigned int nchains=::config->motion.kinematic_chains.size();
+		chainMaps.resize(nchains);
+		roconfig=new ROBOOP::Config(::config->motion.makePath(::config->motion.kinematics),true);
+		for(unsigned int i=0; i<nchains; i++) {
+			string section=::config->motion.kinematic_chains[i];
+			int dof=0;
+			if(roconfig->select_int(section,"dof",dof)!=0) {
+				serr->printf("ERROR Kinematics::init(): unable to find 'dof' in chain %d (%s)\n",i,section.c_str());
+				chainMaps[i].resize(0);
+				continue;
+			}
+			chainMaps[i].resize(dof+1);
+			for(int l=0; l<=dof; l++)
+				chainMaps[i][l]=-1U;
+			for(int l=1; l<=dof; l++) {
+				ostringstream ostr;
+				ostr << section << "_LINK" << l;
+				string link = ostr.str();
+				if(roconfig->parameter_exists(link,"tekkotsu_output")) {
+					int tkout=-1U;
+					roconfig->select_int(link,"tekkotsu_output",tkout);
+					if((unsigned int)tkout>=NumOutputs) {
+						serr->printf("WARNING Kinematics::init(): invalid tekkotsu_output %d on chain %d (%s), link %d (%s)\n",tkout,i,section.c_str(),l,link.c_str());
+					} else {
+						jointMaps[tkout]=JointMap(i,l);
+						chainMaps[i][l]=tkout;
+					}
+				}
+				if(roconfig->parameter_exists(link,"tekkotsu_frame")) {
+					int tkout=-1U;
+					roconfig->select_int(link,"tekkotsu_frame",tkout);
+					tkout+=NumOutputs;
+					if((unsigned int)tkout>=NumReferenceFrames)
+						serr->printf("WARNING Kinematics::init(): invalid tekkotsu_frame %d on chain %d (%s), link %d (%s)\n",tkout,i,section.c_str(),l,link.c_str());
+					else {
+						jointMaps[tkout]=JointMap(i,l);
+						chainMaps[i][l]=tkout;
+					}
+				}
+			}
+		}
+	}
+	if(chainMaps[chainIdx].size()==0)
+		return NULL;
+	return new ROBOOP::Robot(*roconfig,::config->motion.kinematic_chains[chainIdx]);
+}
+
+Kinematics::~Kinematics() {
+#ifdef THREADSAFE_KINEMATICS
+	for(unsigned int i=0; i<chains.size(); i++) {
+		if(chains[i]==NULL)
+			cerr << "Warning: Kinematics chains appear to already be deleted! (multiple free?)" << endl;
+		delete chains[i];
+		chains[i]=NULL;
+	}
+#endif
+}
+
 NEWMAT::ReturnMatrix
 Kinematics::jointToBase(unsigned int j) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
 	unsigned int c=-1U,l=-1U;
 	if(!lookup(j,c,l)) {
 		NEWMAT::Matrix A(4,4);
@@ -113,6 +166,9 @@
 
 NEWMAT::ReturnMatrix
 Kinematics::linkToBase(unsigned int j) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
 	unsigned int c=-1U,l=-1U;
 	if(!lookup(j,c,l)) {
 		NEWMAT::Matrix A(4,4);
@@ -125,6 +181,9 @@
 
 NEWMAT::ReturnMatrix
 Kinematics::baseToJoint(unsigned int j) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
 	unsigned int c=-1U,l=-1U;
 	if(!lookup(j,c,l)) {
 		NEWMAT::Matrix A(4,4);
@@ -137,6 +196,9 @@
 
 NEWMAT::ReturnMatrix
 Kinematics::baseToLink(unsigned int j) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
 	unsigned int c=-1U,l=-1U;
 	if(!lookup(j,c,l)) {
 		NEWMAT::Matrix A(4,4);
@@ -149,6 +211,9 @@
 
 NEWMAT::ReturnMatrix
 Kinematics::jointToJoint(unsigned int ij, unsigned int oj) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
 	unsigned int ci=-1U,li=-1U,co=-1U,lo=-1U;
 	if(ij==oj || !lookup(ij,ci,li) || !lookup(oj,co,lo)) {
 		NEWMAT::Matrix A(4,4);
@@ -174,6 +239,9 @@
 
 NEWMAT::ReturnMatrix
 Kinematics::jointToLink(unsigned int ij, unsigned int oj) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
 	unsigned int ci=-1U,li=-1U,co=-1U,lo=-1U;
 	if(!lookup(ij,ci,li) || !lookup(oj,co,lo)) {
 		NEWMAT::Matrix A(4,4);
@@ -199,6 +267,9 @@
 
 NEWMAT::ReturnMatrix
 Kinematics::linkToJoint(unsigned int ij, unsigned int oj) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
 	unsigned int ci=-1U,li=-1U,co=-1U,lo=-1U;
 	if(!lookup(ij,ci,li) || !lookup(oj,co,lo)) {
 		NEWMAT::Matrix A(4,4);
@@ -224,6 +295,9 @@
 
 NEWMAT::ReturnMatrix
 Kinematics::linkToLink(unsigned int ij, unsigned int oj) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
 	unsigned int ci=-1U,li=-1U,co=-1U,lo=-1U;
 	if(ij==oj || !lookup(ij,ci,li) || !lookup(oj,co,lo)) {
 		NEWMAT::Matrix A(4,4);
@@ -249,6 +323,9 @@
 
 void
 Kinematics::getInterestPoint(const std::string& name, unsigned int& j, NEWMAT::Matrix& ip) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
 	unsigned int c=-1U,l=-1U;
 	getInterestPoint(name,c,l,ip);
 	j=chainMaps[c][l];
@@ -256,6 +333,9 @@
 
 void
 Kinematics::getInterestPoint(const std::string& name, unsigned int& c, unsigned int& l, NEWMAT::Matrix& ip) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
 	InterestPointMap::iterator it=ips->find(name);
 	ip=NEWMAT::ColumnVector(4);
 	if(it==ips->end()) {
@@ -271,13 +351,16 @@
 
 NEWMAT::ReturnMatrix
 Kinematics::getJointInterestPoint(unsigned int joint, const std::string& name) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
 	NEWMAT::ColumnVector ans(4);
 	ans=0;
 	unsigned int co=-1U,lo=-1U;
 	if(!lookup(joint,co,lo)) {
 		ans.Release(); return ans;
 	}
-	for(unsigned int pos=0,len=0; pos<name.size(); pos+=len+1) {
+	for(std::string::size_type pos=0,len=0; pos<name.size(); pos+=len+1) {
 		len=name.find(',',pos);
 		if(len==string::npos)
 			len=name.size();
@@ -307,18 +390,53 @@
 	ans.Release(); return ans;
 }
 
-LegOrder_t
-Kinematics::findUnusedLeg(const NEWMAT::ColumnVector& down) {
-	float height[NumLegs]; //not actually the real height, but proportional to it, which is all we need
+void
+Kinematics::calcLegHeights(const NEWMAT::ColumnVector& down, float heights[NumLegs]) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
+	//initialize to the height of the ball of the foot
 	for(unsigned int i=0; i<NumLegs; i++) {
-		height[i]=NEWMAT::DotProduct(jointToBase(PawFrameOffset+i).SubMatrix(1,3,4,4),down.SubMatrix(1,3,1,1));
-		//cout << "height["<<i<<"]=="<<height[i]<<endl;
+		NEWMAT::ColumnVector ip_b=jointToBase(PawFrameOffset+i).SubMatrix(1,3,4,4);
+		float h=-ip_b(1)*down(1) - ip_b(2)*down(2) - ip_b(3)*down(3);
+		h-=BallOfFootRadius; //add the ball's radius
+		heights[i]=h;
 	}
-	
+	//see if any interest points are lower
+	for(InterestPointMap::const_iterator it=ips->begin(); it!=ips->end(); ++it) {
+		unsigned int c=(*it).second.chain;
+		LegOrder_t leg;
+		if(config->motion.kinematic_chains[c]=="LFr")
+			leg=LFrLegOrder;
+		else if(config->motion.kinematic_chains[c]=="RFr")
+			leg=RFrLegOrder;
+		else if(config->motion.kinematic_chains[c]=="LBk")
+			leg=LBkLegOrder;
+		else if(config->motion.kinematic_chains[c]=="RBk")
+			leg=RBkLegOrder;
+		else
+			continue;
+		unsigned int l=(*it).second.link;
+		NEWMAT::Matrix ip=pack((*it).second.x,(*it).second.y,(*it).second.z);
+		update(c,l);
+		NEWMAT::ColumnVector ip_b=chains[c]->convertLinkToFrame(l,0)*ip;
+		float h=-ip_b(1)*down(1) - ip_b(2)*down(2) - ip_b(3)*down(3);
+		if(h<heights[leg])
+			heights[leg]=h;
+	}
+}
+
+LegOrder_t
+Kinematics::findUnusedLeg(const NEWMAT::ColumnVector& down) {
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
+	float heights[NumLegs];
+	calcLegHeights(down,heights);
 	//Find the highest foot
 	unsigned int highleg=0;
 	for(unsigned int i=1; i<NumLegs; i++)
-		if(height[highleg]>height[i])
+		if(heights[i]>heights[highleg])
 			highleg=i;
 	//cout << "High: " << highleg << endl;
 	return static_cast<LegOrder_t>(highleg);
@@ -326,24 +444,155 @@
 
 NEWMAT::ReturnMatrix
 Kinematics::calculateGroundPlane() {
-  return calculateGroundPlane(pack(state->sensors[BAccelOffset],state->sensors[LAccelOffset],state->sensors[DAccelOffset]));
+	NEWMAT::ColumnVector down=pack(state->sensors[BAccelOffset],-state->sensors[LAccelOffset],state->sensors[DAccelOffset]);
+	if(down.SumSquare()<1.01) //1 because homogenous coord is 1
+		down=pack(0,0,-1); //default to a down vector if sensors don't give a significant indication of gravity
+	return calculateGroundPlane(down);
 }
 
+// TODO comment out name tracking (and this following #include) once we're sure it's working
+#include "PostureEngine.h"
 NEWMAT::ReturnMatrix
 Kinematics::calculateGroundPlane(const NEWMAT::ColumnVector& down) {
-	//Find the unused foot
-	unsigned int highleg=findUnusedLeg(down);
+#ifndef THREADSAFE_KINEMATICS
+	checkStatics();
+#endif
+	NEWMAT::Matrix lowip(3,3); //3 points define a plane
+	float heights[3];
+	unsigned int legs[3];
+	std::string names[3];
+	//initialize to max float
+	for(unsigned int i=0; i<3; i++) {
+		heights[i]=FLT_MAX;
+		legs[i]=-1U;
+	}
+	//Check the balls of the foot
+	for(unsigned int i=0; i<NumLegs; i++) {
+		NEWMAT::ColumnVector ip_b=jointToBase(PawFrameOffset+i).SubMatrix(1,3,4,4);
+		float h=-ip_b(1)*down(1) - ip_b(2)*down(2) - ip_b(3)*down(3);
+		h-=BallOfFootRadius; //add the ball's radius
+		if(h<heights[0]) {
+			if(h<heights[1]) {
+				heights[0]=heights[1];
+				lowip.SubMatrix(1,3,1,1)=lowip.SubMatrix(1,3,2,2);
+				legs[0]=legs[1];
+				names[0]=names[1];
+				if(h<heights[2]) {
+					heights[1]=heights[2];
+					lowip.SubMatrix(1,3,2,2)=lowip.SubMatrix(1,3,3,3);
+					legs[1]=legs[2];
+					names[1]=names[2];
+					
+					heights[2]=h;
+					lowip.SubMatrix(1,3,3,3)=ip_b;
+					legs[2]=i;
+					names[2]="paw"; names[2]+=(char)('0'+i);
+				} else {
+					heights[1]=h;
+					lowip.SubMatrix(1,3,2,2)=ip_b;
+					legs[1]=i;
+					names[1]="paw"; names[1]+=(char)('0'+i);
+				}
+			} else {
+				heights[0]=h;
+				lowip.SubMatrix(1,3,1,1)=ip_b;
+				legs[0]=i;
+				names[0]="paw"; names[0]+=(char)('0'+i);
+			}
+		}
+	}
+	//cout << "Ground plane initial: " << names[0] <<" ("<<heights[0]<<") " << names[1] << " ("<<heights[1]<<") " << names[2] << " ("<<heights[2]<<")"<< endl;
+	
+	//now check interest points
+	for(InterestPointMap::const_iterator it=ips->begin(); it!=ips->end(); ++it) {
+		if((*it).first.substr(0,3)=="Toe")
+			continue;
+		unsigned int c=(*it).second.chain;
+		unsigned int l=(*it).second.link;
+		NEWMAT::Matrix ip=pack((*it).second.x,(*it).second.y,(*it).second.z);
+		update(c,l);
+		NEWMAT::ColumnVector ip_b=chains[c]->convertLinkToFrame(l,0)*ip;
+		float h=-ip_b(1)*down(1) - ip_b(2)*down(2) - ip_b(3)*down(3);
+		if(h<heights[0]) {
+			unsigned int leg;
+			if(config->motion.kinematic_chains[c]=="LFr")
+				leg=LFrLegOrder;
+			else if(config->motion.kinematic_chains[c]=="RFr")
+				leg=RFrLegOrder;
+			else if(config->motion.kinematic_chains[c]=="LBk")
+				leg=LBkLegOrder;
+			else if(config->motion.kinematic_chains[c]=="RBk")
+				leg=RBkLegOrder;
+			else
+				leg=-1U;
+			
+			if(h<heights[1]) {
+				if(h<heights[2]) {
+					if(leg==-1U || legs[1]!=leg && legs[2]!=leg) {
+						heights[0]=heights[1];
+						lowip.SubMatrix(1,3,1,1)=lowip.SubMatrix(1,3,2,2);
+						legs[0]=legs[1];
+						names[0]=names[1];
+					}
+					if(leg==-1U || legs[2]!=leg) {
+						heights[1]=heights[2];
+						lowip.SubMatrix(1,3,2,2)=lowip.SubMatrix(1,3,3,3);
+						if(legs[2]!=leg)
+							legs[1]=legs[2];
+						names[1]=names[2];
+					}
+					
+					heights[2]=h;
+					lowip.SubMatrix(1,3,3,3)=ip_b.SubMatrix(1,3,1,1);
+					legs[2]=leg;
+					names[2]=(*it).first;
+				} else {
+					if(leg!=-1U && legs[2]==leg)
+						continue;
+					if(leg==-1U || legs[1]!=leg) {
+						heights[0]=heights[1];
+						lowip.SubMatrix(1,3,1,1)=lowip.SubMatrix(1,3,2,2);
+						legs[0]=legs[1];
+						names[0]=names[1];
+					}
+					heights[1]=h;
+					lowip.SubMatrix(1,3,2,2)=ip_b.SubMatrix(1,3,1,1);
+					legs[1]=leg;
+					names[1]=(*it).first;
+				}
+			} else {
+				if(leg!=-1U && (legs[1]==leg || legs[2]==leg))
+					continue;
+				heights[0]=h;
+				lowip.SubMatrix(1,3,1,1)=ip_b.SubMatrix(1,3,1,1);
+				legs[0]=leg;
+				names[0]=(*it).first;
+			}
+		}
+	}
 	
 	//Fit a plane to the remaining 3 feet
-	NEWMAT::Matrix legs(3,3);
-	for(unsigned int i=0; i<highleg; i++)
-		legs.Column(i+1)=jointToBase(PawFrameOffset+i).SubMatrix(1,3,4,4);
-	for(unsigned int i=highleg+1; i<NumLegs; i++)
-		legs.Column(i)=jointToBase(PawFrameOffset+i).SubMatrix(1,3,4,4);
-	//cout << legs;
 	NEWMAT::ColumnVector ones(3); ones=1;
 	NEWMAT::ColumnVector p(4);
-	p.SubMatrix(1,3,1,1) = legs.t().i()*ones;
+	try {
+		p.SubMatrix(1,3,1,1) = lowip.t().i()*ones;
+	} catch(...) {
+		std::cout << "Exception during ground plane processing, saving current posture..." << std::flush;
+		if(PostureEngine * tpose=dynamic_cast<PostureEngine*>(this)) {
+			tpose->setSaveFormat(true,state);
+			tpose->saveFile("/error.pos");
+		} else {
+			PostureEngine pose;
+			pose.takeSnapshot();
+			pose.setWeights(1);
+			pose.setSaveFormat(true,state);
+			pose.saveFile("/error.pos");
+		}
+		std::cout << "Wrote current sensor info \"error.pos\" on memstick" << std::endl;
+		cout << "Ground plane was using " << names[0] <<" ("<<heights[0]<<") " << names[1] << " ("<<heights[1]<<") " << names[2] << " ("<<heights[2]<<")"<< endl;
+		cout << lowip;
+		throw;
+	}
 	p(4)=1;
 	p.Release(); return p;
 }
@@ -353,7 +602,7 @@
                            unsigned int b, const NEWMAT::ColumnVector& p_b,
                            unsigned int f)
 {
-	/*! Mathematcal implementation:
+	/*! Mathematical implementation:
 	 *  
 	 *  Need to convert @a p_b to @a p_j
 	 *  
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/Kinematics.h ./Motion/Kinematics.h
--- ../Tekkotsu_2.4.1/Motion/Kinematics.h	2005-01-14 16:20:05.000000000 -0500
+++ ./Motion/Kinematics.h	2006-09-16 13:32:39.000000000 -0400
@@ -115,12 +115,26 @@
 class Kinematics {
 public:
 	//!Constructor, pass the full path to the kinematics configuration file
-	Kinematics() : chains(), chainMaps() {
+	Kinematics()
+#ifdef THREADSAFE_KINEMATICS
+	: chains()
+#endif
+	{
 		init();
 	}
+	//!Copy constructor, everything is either update-before-use or static, copy is normal init
+	Kinematics(const Kinematics&)
+#ifdef THREADSAFE_KINEMATICS
+	: chains()
+#endif
+	{
+		init();
+	}
+	//!Assignment operator, everything is either update-before-use or static, assignment is no-op
+	Kinematics& operator=(const Kinematics&) { return *this; }
 
 	//!Destructor
-	virtual ~Kinematics() {}
+	virtual ~Kinematics();
 
 
 
@@ -189,21 +203,29 @@
 
 
 
-	//! Find the leg which is in least contact with ground (as best we can anyway)
-	/*! This can be either based on gravity vector from accelerometer readings,
-	 *  or if that may be unreliable due to being in motion, we could do some basic
-	 *  balance modeling.
+	//! 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
+	 *  balance modeling and pass a predicted vector.  This uses the interest point database
+	 *  to find the lowest interest point for each leg
+	 *  @note on Aibo platforms, if packing accelerometer readings, don't forget to negate the "left" accelerometer! */
+	void calcLegHeights(const NEWMAT::ColumnVector& down, float heights[NumLegs]);
+	
+	//! Find the leg which is in least contact with ground
+	/*! @see calcLegHeights()
+	 *  @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);
 
-	//! Find the ground plane (by fitting plane to legs other the one specified by findUnusedLeg(down))
+	//! 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
 	 *  gravity vector as the "down" vector.
 	 *  @return vector of the form @f$p_1x + p_2y + p_3z = p_4@f$, relative to the base frame */
 	NEWMAT::ReturnMatrix calculateGroundPlane();
 
-	//! Find the ground plane (by fitting plane to legs other the one specified by findUnusedLeg(down))
-	/*! @return vector of the form @f$p_1x + p_2y + p_3z = p_4@f$, relative to the base frame */
+	//! Find the ground plane by fitting a plane to the lowest 3 interest points
+	/*! @note on Aibo platforms, if packing accelerometer readings, don't forget to negate the "left" accelerometer!
+	 *  @return vector of the form @f$p_1x + p_2y + p_3z = p_4@f$, relative to the base frame */
 	NEWMAT::ReturnMatrix calculateGroundPlane(const NEWMAT::ColumnVector& down);
 
 	//! Find the point of intersection between a ray and a plane
@@ -256,6 +278,15 @@
 	//! Called by constructors to do basic setup - first call will read Config::motion_config::kinematics from disk, future initializes reuse static roconfig
 	void init();
 	
+	//! initializes static variables -- only call if not #staticsInited
+	static void initStatics();
+	
+	//! checks that statics have been initialized, and calls initStatics if they are missing
+	static void checkStatics() { if(!staticsInited) initStatics(); }
+	
+	//! called by init to allocate/initialize each of #chains
+	static ROBOOP::Robot* newChain(unsigned int chainIdx);
+	
 	//! Returns the location of a named point, relative to the link it is attached to
 	/*! @param[in]  name   the name of the interest point; varies by model, <a href="http://www.tekkotsu.org/Kinematics.html">see the diagrams</a> for your model.
 	 *  @param[out] c      on exit, chain index the IP is on
@@ -293,11 +324,20 @@
 		return true;
 	}
 
+	//! initially false, set to true after first Kinematics is initialized
+	static bool staticsInited;
+
+#ifdef THREADSAFE_KINEMATICS
 	//! A separate ROBOOP::Robot instantiation for each chain since ROBOOP package doesn't support branching chains (which would be rather difficult to implement well)
 	std::vector<ROBOOP::Robot*> chains;
+#else
+	//! A separate ROBOOP::Robot instantiation for each chain since ROBOOP package doesn't support branching chains (which would be rather difficult to implement well)
+	/*! static allocation solves problems with shared memory regions, but becomes thread-UNsafe... */
+	static std::vector<ROBOOP::Robot*> chains;
+#endif
 
 	//! holds mapping for each chain's links back to the tekkotsu outputs and reference frames they represent
-	std::vector< std::vector<unsigned int> > chainMaps;
+	static std::vector< std::vector<unsigned int> > chainMaps;
 	
 	//! Allows mapping from tekkotsu output index to chain and link indicies
 	struct JointMap {
@@ -319,7 +359,7 @@
 	};
 
 	//! holds mapping from tekkotsu output index to chain and link indicies
-	JointMap jointMaps[NumReferenceFrames];
+	static JointMap jointMaps[NumReferenceFrames];
 	
 	//! cache of the configuration of the robot for rapid initialization (so we don't have to re-read from disk)
 	static ROBOOP::Config * roconfig;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/LedEngine.cc ./Motion/LedEngine.cc
--- ../Tekkotsu_2.4.1/Motion/LedEngine.cc	2004-09-12 00:22:37.000000000 -0400
+++ ./Motion/LedEngine.cc	2006-08-22 18:23:04.000000000 -0400
@@ -270,19 +270,30 @@
 void LedEngine::clear() {
 	for(unsigned int i=0; i<NumLEDs; i++) {
 		infos[i].value=0;
+		infos[i].flashtime=0;
 		infos[i].isCycling=false;
 	}
 	numCycling=0;
 	dirty=true;
 }
 
+void LedEngine::extendFlash(unsigned int ms) {
+	for(unsigned int i=0; i<NumLEDs; i++)
+		if(infos[i].flashtime!=0)
+			infos[i].flashtime+=ms;
+	if(nextFlashEnd!=0)
+		nextFlashEnd+=ms;
+	dirty=true;
+}
+
 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
-		if(state->robotDesign & WorldState::ERS220Mask)
+		WorldState * st=WorldState::getCurrent();
+		if(st->robotDesign & WorldState::ERS220Mask)
 			numMasks=ERS220numMasks;
-		if(state->robotDesign & WorldState::ERS7Mask)
+		if(st->robotDesign & WorldState::ERS7Mask)
 			numMasks=ERS7numMasks;
 		if(x>9 || x<-9) {
 			ccycle(FaceLEDMask&~TopBrLEDMask,333,10,-5);
@@ -317,6 +328,8 @@
 		return;
 	float bg = ((x-1)/3)/3.0;
 	float fg = bg+.333333333;
+	if(WorldState::getCurrent()->robotDesign & WorldState::ERS7Mask)
+		bg*=bg; // dim the background a bit more on ERS7
 	switch(x%3) {
 	case 1:
 		infos[high].value=bg;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/LedEngine.h ./Motion/LedEngine.h
--- ../Tekkotsu_2.4.1/Motion/LedEngine.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Motion/LedEngine.h	2006-10-03 18:30:36.000000000 -0400
@@ -10,17 +10,26 @@
 
 // LEDBitMask_t and associated constants are defined in RobotInfo.h
 
-//! Provides basic LED effects to anything that inherits from (recommended method for MotionCommands) or instantiates it (just in case you have reason to)
-/*! Provides a collection of special effects so that the code can be
+//! Provides basic LED effects via subclassing (e.g. LedMC) or embedding (e.g. EmergencyStopMC)
+/*! This implements a collection of LED special effects so that the code can be
  *  reused various places as feedback to to the user.
  *
- * Cycling ("pulsing") and single-value setting are mutually exclusive;
- * one will cut off the other
+ * The basic effects provided are:
+ * - static brightness (set(), cset(), invert(), clear())
+ * - temporary setting (flash(), cflash())
+ * - pulsing/blinking (cycle(), ccycle())
+ * - numeric display (displayNumber(), displayPercent())
  *
- * A flash will invert and override the current setting, so that it
+ * The 'c' prefix on a function (cset(), cflash(), ccycle()) means it will call clear() before doing its own setting.  This is
+ * a quick way to replace whatever is currently displayed with whatever you are about to display.
+ * 
+ * A flash() will invert and override the current setting, so that it
  * will "reset" after the flash.  Flashes change mid-range values to
  * extremes to make the flash visible (ie not just (1-current)) Normal
- * invert will do simple inverses (just (1-current))
+ * invert() will do simple inverses (just (1-current)), and doesn't change back automatically.
+ *
+ * Cycling ("pulsing") and single-value setting are mutually exclusive;
+ * one will cut off the other
  *
  * getSetting() returns value of last set();
  * getValue() returns what's actually being returned to Motion at the moment
@@ -33,6 +42,28 @@
  * the lights" style of display instead of this pseudo-arabic display.
  * (look close to see that green bar LED at the top of the 210, which 
  * doesn't show up well in the camera image for some reason. )
+ * <img src="NumberLEDs-ERS7.jpg">
+ *
+ * The ERS-7 also has a "mode" which controls how certain face LEDs are
+ * interpreted.  By setting ERS7Info::LEDABModeOffset /
+ * ERS7Info::LEDABModeMask, you can switch between the modes -- a value
+ * of 0 is mode "A", and a value of 1 is mode "B".
+ * <img src="ERS7-LED-Modes.png">
+ *
+ * Things to note for the ERS-7:
+ * - There are many fewer LEDs than there are holes in the "grill" (the holes you see on the face are not the positions of the LEDs.
+ * - Each LED covers several holes.
+ * - Not all holes have LEDs behind them -- some areas of the face panel are always dark.
+ * - Some LEDs (12 and 13) control two symmetrical physical LEDs.
+ * - Some LEDs change color based on mode (0-1), some don't change at all (2-11), and some change position and color (12-13)
+ * - We don't have individual names for all of the LEDs on the panel.  Instead you base off of FaceLEDPanelOffset or FaceLEDPanelMask to address the LEDs, e.g., to set the <i>n</i>th led to <i>x</i>:
+ *   @code
+ *   LedEngine::set(FaceLEDPanelMask << n, x)
+ *   @endcode
+ *   or (if using other classes, e.g. PostureEngine)
+ *   @code
+ *   PostureEngine::setOutputCmd(FaceLEDPanelOffset + n, x)
+ *   @endcode
  */
 
 class LedEngine {
@@ -79,6 +110,9 @@
 	void cycle(LEDBitMask_t leds, unsigned int period, float amp, float offset=0, int phase=0);
 	//!sets all leds to 0.
 	void clear();
+	
+	//!adds @a ms to all flash times (may resurrect previously completed flashes)
+	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; }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/LedMC.h ./Motion/LedMC.h
--- ../Tekkotsu_2.4.1/Motion/LedMC.h	2004-12-17 00:52:36.000000000 -0500
+++ ./Motion/LedMC.h	2006-09-19 01:40:08.000000000 -0400
@@ -9,7 +9,7 @@
 #include "OutputCmd.h"
 #include "MotionManager.h"
 
-//! This is just a simple wrapper - you probably want to be looking at LedEngine.h
+//! This is just a simple wrapper - you probably want to be looking at LedEngine
 /*! This is handy if all you want to do is control the LED's, but since other
  *  MotionCommands will probably also want to make use of the LEDs, they can
  *  just use the engine component to do all the work. */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/MMAccessor.h ./Motion/MMAccessor.h
--- ../Tekkotsu_2.4.1/Motion/MMAccessor.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Motion/MMAccessor.h	2006-10-03 17:40:59.000000000 -0400
@@ -39,11 +39,30 @@
  *  MMAccessor when it's actually a member of YourMotionCommand, this is because MMAccessor behaves as a
  *  'smart pointer', which overloads operator->() so it is fairly transparent to use.
  *
- *  See also the templated checkin(Ret_t ret) function for more examples of streamlined usage.
+ *  In some cases, you may wish to access a prunable motion, but may be unsure of whether the
+ *  motion is still alive.  If it has been pruned, the MC_ID is no longer valid, and will not provide
+ *  access to the motion.  Worse, however, is that enough new motions have been created that the
+ *  ID has been recycled and now refers to another, different, motion.
+ *
+ *  The solution to this requires two steps.  First, you must retain the SharedObject you used to
+ *  initially create the motion.  This is required because if the MotionManager prunes the motion,
+ *  it will dereference the memory region, and if there are no other references to the region, it
+ *  will be deallocated, destroying the data.  Second, you pass this SharedObject to the MMAccessor
+ *  constructor as shown:
+ *  @code
+ *  SharedObject<YourMC> yourmc;
+ *  // ... stuff ... if yourmc was added to MotionManager, it may or may not still be active
+ *  MMAccessor<YourMC> your_acc(*yourmc); // doesn't matter!
+ *  // your_acc now provides no-op access if not in MotionManager, checks it out if it is
+ *  @endcode
+ *  This guarantees safe access regardless to the current status of the motion.  (Note that you can
+ *  also just listen for the (EventBase::motmanEGID, MC_ID, EventBase::deactivateETID) event
+ *  to be notified when a motion is pruned... however, unless you still have a reference to
+ *  the SharedObject, you won't be able to access/reuse the motion after it was pruned)
  *
  *  MMAccessor is a small class, you may consider passing it around instead of a MotionManager::MC_ID
  *  if appropriate.  (Would be appropriate to avoid multiple checkin/outs in a row from different
- *  functions, but not as appropriate for storage and reuse of the same MMAccessor.
+ *  functions, but not as appropriate for storage and reuse of the same MMAccessor.)
  */
 template<class MC_t>
 class MMAccessor {
@@ -60,9 +79,14 @@
 	}
 
 	//! constructor, allows objects to provide uniform access to MotionCommands, regardless of whether they are currently in the MotionManager
-	MMAccessor(MotionCommand * ptr) : mc_id(MotionManager::invalid_MC_ID), checkOutCnt(0), mcptr(ptr) {}
+	/*! if ckout is true (default parameter), will attempt to check out the motion if the motion reports it has a valid ID */
+	MMAccessor(MC_t & ptr, bool ckout=true) : mc_id(ptr.getID()), checkOutCnt(0), mcptr(&ptr) {
+		if(ckout && mc_id!=MotionManager::invalid_MC_ID)
+			checkout();
+	}
 
-	//! copy constructor - will reference the same mc_id - checkin/checkouts are independent between this and @a a; however, if @a a is checkout out, @c this will check itself out as well
+	//! copy constructor - will reference the same mc_id - checkin/checkouts are independent between this and @a a; however, if @a a is checked out, @c this will check itself out as well
+	/*! If the original was checked out, this will checkout as well (so #checkOutCnt will be 1) */
 	MMAccessor(const MMAccessor& a) : mc_id(a.mc_id), checkOutCnt(0), mcptr(a.mcptr) {
 		if(a.checkOutCnt>0)
 			checkout();
@@ -75,18 +99,22 @@
 	}
 
 	//! allows assignment of MMAccessor's, similar to the copy constructor - the two MMAccessor's will control the same MotionCommand
+	/*! If the original was checked out, this will checkout as well (so #checkOutCnt will be 1) */
 	MMAccessor<MC_t> operator=(const MMAccessor<MC_t>& a) {
 		mc_id=a.mc_id;
 		mcptr=a.mcptr;
-		if(motman->isOwner(mc_id))
+		checkOutCnt=0;
+		if(a.checkOutCnt>0)
 			checkout();
 		return *this;
 	}
 	
 	//! So you can check out if not done by default (or you checked in already)
-	inline MC_t* checkout() {
-		if(mc_id!=MotionManager::invalid_MC_ID)
-			mcptr=static_cast<MC_t*>(motman->checkoutMotion(mc_id));
+	/*! @param throwOnNULL if true, indicates an exception should be thrown if the checked out motion is NULL (indicates #mc_id does not reference an active MC) */
+	inline MC_t* checkout(bool throwOnNULL=true) {
+		mcptr=static_cast<MC_t*>(motman->checkoutMotion(mc_id));
+		if(throwOnNULL && mcptr==NULL)
+			throw std::runtime_error("MMAccessor attempted to checkout an invalid MC_ID");
 		checkOutCnt++;
 		return mcptr;
 	}
@@ -98,7 +126,8 @@
 	/*! Don't forget, you can also just limit the scope using extra { }'s */
 	inline void checkin() {
 		if(checkOutCnt>0) {
-			motman->checkinMotion(mc_id);
+			if(mc_id!=MotionManager::invalid_MC_ID)
+				motman->checkinMotion(mc_id);
 			checkOutCnt--;
 		}
 		if(checkOutCnt==0)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/MotionCommand.cc ./Motion/MotionCommand.cc
--- ../Tekkotsu_2.4.1/Motion/MotionCommand.cc	2005-06-29 18:04:51.000000000 -0400
+++ ./Motion/MotionCommand.cc	2006-09-11 19:05:11.000000000 -0400
@@ -7,7 +7,7 @@
 
 void MotionCommand::postEvent(const EventBase& event) {
 	if(queue==NULL) {
-		erouter->postEvent(event.clone());
+		erouter->postEvent(event);
 	} else {
 		queue->encodeEvent(event);
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/MotionCommand.h ./Motion/MotionCommand.h
--- ../Tekkotsu_2.4.1/Motion/MotionCommand.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Motion/MotionCommand.h	2006-10-03 23:14:56.000000000 -0400
@@ -4,6 +4,7 @@
 
 #include "Shared/RobotInfo.h"
 #include "MotionManagerMsg.h"
+#include "Shared/WorldState.h"
 #include "OutputCmd.h"
 #include <stddef.h>
 
@@ -12,13 +13,17 @@
 
 //! The abstract base class for motions, provides common interface.  All motions should inherit from this
 /*! For instructions on how to create:
- * - <b>a new subclass</b> of MotionCommand, read on.  Also see the step-by-step
- *   <a href="../FirstMotionCommand.html">guide</a>
- * - <b>an instantiation</b> of a MotionCommand subclass, see MotionManager
+ * - <b>an instantiation</b> of an existing MotionCommand, see MotionManager
+ * - <b>a new subclass</b> of MotionCommand, read on.  Also see the step-by-step tutorials:
+ *   - <a href="../FirstMotionCommand.html">Tekkotsu's "First MotionCommand" Tutorial</a>
+ *   - <a href="http://www.cs.cmu.edu/~dst/Tekkotsu/Tutorial/motion.shtml">David Touretzky's Motion Commands chaper</a>
+ *   - <a href="http://www.cs.cmu.edu/afs/cs/academic/class/15494-s06/www/lectures/motion_commands.pdf">CMU's Cognitive Robotics slides</a>
  * 
  * To create a new type of motion, you'll want to subclass this.  You
  * don't need to do anything fancy, but just be sure to override the 3
- * abstract functions.
+ * abstract functions, updateOutputs(), isAlive(), and isDirty().
+ *
+ * There is a quick-start boilerplate included in the distribution: <a href="http://cvs.tekkotsu.org/cgi/viewcvs.cgi/Tekkotsu/project/templates/motioncommand.h?rev=HEAD&content-type=text/vnd.viewcvs-markup"><i>project</i><tt>/templates/motioncommand.h</tt></a>:
  *
  * When an output is set to a value, that output is held at that value
  * until it is set to a new value, even if the MotionCommand that set
@@ -41,21 +46,21 @@
  *
  * Here is the cycle of calls made by MotionManager to your command:
  * -# shouldPrune() (by default, this will return !isAlive() iff #autoprune==true)
- * -# updateJointCmds() (assuming the MC wasn't pruned after the previous step)
+ * -# updateOutputs() (assuming the MC wasn't pruned after the previous step)
  * 
  * So, if you want to hold a joint at a value, each time your
- * updateJointCmds() function is called, you should tell the
+ * updateOutputs function is called, you should tell the
  * MotionManager to keep the joint there (using one of
  * MotionManager::setOutput()'s).  If you do not set a joint after a
- * call to updateJointCmds, the MotionManager will assume you are no
+ * call to updateOutputs, the MotionManager will assume you are no
  * longer using that joint and a lower priority MotionCommand may
  * inherit it.
  *
  * MotionCommands which generate events should use the inherited
- * postEvent() instead of trying to access a global ::erouter - the
+ * MotionCommand::postEvent() instead of trying to access a global ::erouter - the
  * inherited version will properly handle sending the events
- * regardless of the current context, but trying to access a
- * non-shared global like ::erouter could cause problems.
+ * regardless of the current process context, but trying to access a
+ * non-shared global like ::erouter could cause problems otherwise.
  *
  * @warning <b>Be careful what you call in MotionManager</b> \n
  * Some functions are marked MotionCommand-safe - this is another
@@ -116,7 +121,11 @@
 	//        ******************
 
 	//! Constructor: Defaults to kStdPriority and autoprune==true
-	MotionCommand() : MotionManagerMsg(), queue(NULL), autoprune(true), started(false) {}
+	MotionCommand() : MotionManagerMsg(), queue(NULL), autoprune(true), started(false)
+#ifdef PLATFORM_APERIOS
+		, state()
+#endif
+	{ }
 	//! Destructor
 	virtual ~MotionCommand() {}
 	
@@ -141,6 +150,11 @@
 	
 	//! only called from MMCombo during process setup, allows MotionCommands to send events
 	void setTranslator(EventTranslator * q) { queue=q; }
+	
+#ifdef PLATFORM_APERIOS
+	//! called by MotionManager each time a process checks out the motion, makes sure #state is set for the calling process
+	void setWorldState(WorldState* s) { state.cur=s; }
+#endif
 
 protected:
 	//! this utility function will probably be of use to a lot of MotionCommand's
@@ -181,7 +195,14 @@
 
 	int autoprune; //!< default true, autoprune setting, if this is true and isAlive() returns false, MotionManager will attempt to remove the MC automatically
 	bool started; //!< true if the MotionCommand is currently running (although it may be overridden by a higher priority MotionCommand)
-
+#ifdef PLATFORM_APERIOS
+	//! purposely shadows global ::state as a member of MotionCommand, so subclasses will be guaranteed to use the current process's instance instead of that of the process they were created in
+	struct StateRedirect {
+		WorldState * operator->() const { return cur==NULL ? WorldState::getCurrent() : cur; }
+		WorldState * cur;
+	} state; 
+#endif
+	
 private:
 	MotionCommand(const MotionCommand&); //!< don't call
 	MotionCommand& operator=(const MotionCommand&); //!< don't call
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/MotionManager.cc ./Motion/MotionManager.cc
--- ../Tekkotsu_2.4.1/Motion/MotionManager.cc	2005-06-29 18:04:51.000000000 -0400
+++ ./Motion/MotionManager.cc	2006-09-25 19:30:16.000000000 -0400
@@ -2,6 +2,14 @@
 #include "Shared/debuget.h"
 #include "Shared/WorldState.h"
 #include "Events/EventRouter.h"
+#include "Shared/StackTrace.h"
+#include "Shared/ProjectInterface.h"
+
+#ifndef PLATFORM_APERIOS
+#  include "IPC/MessageQueue.h"
+#  include "IPC/MessageReceiver.h"
+#  include "Shared/ProjectInterface.h"
+#endif
 
 #include "Shared/ERS210Info.h"
 #include "Shared/ERS220Info.h"
@@ -55,7 +63,7 @@
 #else //now PLATFORM_LOCAL
 
 void
-MotionManager::InitAccess(MessageQueueBase& mcbufq) {
+MotionManager::InitAccess(MessageQueueBase& mcbufq, Resource& behaviorLock) {
 	if(numAcc==MAX_ACCESS) {
 		printf("*** ERROR *** attempted to register more accessors with MotionManager than allowed by MAX_ACCESS\n");
 		return;
@@ -66,38 +74,58 @@
 	//	cout << "numAcc is " << &numAcc << " from " << this << endl;
 	MMlock.lock(_MMaccID);
 	subjs[_MMaccID]=&mcbufq;
+	mcrecvs[_MMaccID]=new MessageReceiver(*subjs[_MMaccID],receivedMsg);
+	procLocks[_MMaccID]=&behaviorLock;
 	if(cmdlist.size()>0) //Shouldn't happen - busy wait in doAddMotion
 		cout << "*** WARNING *** MOTIONS ADDED BEFORE ALL INITACCESSED" << endl;
 	MMlock.unlock();
 }
 
+#endif //PLATFORM-specific initialization
+
 void
 MotionManager::RemoveAccess() {
+#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;
+#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) {
-			checkoutMotion(mc_id,true);
-			cmdlist[mc_id].rcr[_MMaccID]->RemoveReference();
-			cmdlist[mc_id].rcr[_MMaccID]=NULL;
-			bool found=false;
-			for(unsigned int i=0; i<numAcc; i++)
+			MotionCommand* mc=checkoutMotion(mc_id,true);
+			int found=0;
+			for(unsigned int i=0; i<numAcc; i++) {
 				if(cmdlist[mc_id].rcr[i]!=NULL) {
-					found=true;
-					break;
+					found++;
 				}
-			if(!found) {
-				cout << "Warning: dropping motion command " << mc_id << ", was active at shutdown (leaked?)" << endl;
-				push_free(mc_id);
-				//should we check in?  The lock isn't technically valid anymore...
-				//checkinMotion(mc_id);
-			} else
+			}
+			cout << "Warning: " << ProcessID::getIDStr() << " dropping motion command " << mc_id << ", was active at shutdown " << (mc->getAutoPrune()?"(was set for autoprune)":"(leaked?)") << endl;
+#ifdef PLATFORM_APERIOS
+			int refs=1;
+#else
+			int refs=cmdlist[mc_id].rcr[_MMaccID]->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;
+			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
+				mc_id=p;
+			} else {
 				checkinMotion(mc_id);
+			}
 		}
 	}
 	func_end();
 }
 
-#endif //PLATFORM-specific initialization
 
 MotionManager::~MotionManager() {
 	if(!cmdlist.empty()) {
@@ -269,7 +297,7 @@
  *  or a big massive function which doesn't pollute the namespace?  This is the latter, for
  *  better or worse. */
 void
-MotionManager::getOutputs(float outputs[NumFrames][NumOutputs]) {
+MotionManager::getOutputs(float outputs[][NumOutputs]) {
 	//	if(begin(id)!=end())
 	//if(state && state->buttons[LFrPawOffset]) cout << "getAngles..." << flush;
 	if(state==NULL) {
@@ -287,7 +315,7 @@
 	func_begin();
 	//	if(begin(id)!=end())
 	//	cout << id << "..." << flush;
-	//	cout << "CHECKOUT..." << flush;
+	//cout << "CHECKOUT..." << flush;
 	for(uint output=0; output<NumOutputs; output++)
 		cmdstates[output].clear();
 
@@ -306,10 +334,11 @@
 		if(state->pids[output][0]==0 && state->pids[output][1]==0 && state->pids[output][2]==0)
 			cmdSums[output]=state->outputs[output];
 
-	//	std::cout << "UPDATE..." << std::flush;
+	//std::cout << "UPDATE..." << std::flush;
 	std::list<MC_ID> unlocked;
 	for(MC_ID it=begin(); it!=end(); it=next(it)) // check out all the MotionCommands (only one at a time tho)
-		unlocked.push_back(it);
+		if(cmdlist[it].lastAccessor!=(accID_t)-1)
+			unlocked.push_back(it);
 	unsigned int lastProcessed=get_time();
 	while(unlocked.size()>0) { // keep cycling through all the locks we didn't get
 		for(std::list<MC_ID>::iterator it=unlocked.begin(); it!=unlocked.end(); ) {
@@ -319,13 +348,32 @@
 			else {
 				// we got a lock
 				cur_cmd=*it;
-				if(mc->shouldPrune()) {
+				bool prune=true;
+				try {
+					prune=mc->shouldPrune();
+				} catch(const std::exception& ex) {
+					ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionCommand prune test, will prune",&ex);
+				} catch(...) {
+					ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionCommand prune test, will prune",NULL);
+				}
+				if(prune) {
 					cout << "Removing expired " << *it << " (autoprune)" << endl;
+					checkinMotion(*it); // release lock, done with motion (don't need to (and shouldn't) keep lock through the removeMotion())
+					//only the last process to receive the remove notification actually does the remove, and
+					//wouldn't be able to undo the thread portion of the lock made in this process
+					//so we have to take off our own lock here first.
 					removeMotion(*it);
-				} else
-					mc->updateOutputs(); // the MotionCommand should make calls to setOutput from within here
+				} else {
+					try {
+						mc->updateOutputs(); // the MotionCommand should make calls to setOutput from within here
+					} catch(const std::exception& ex) {
+						ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionCommand updateOutputs",&ex);
+					} catch(...) {
+						ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionCommand updateOutputs",NULL);
+					}
+					checkinMotion(*it); // release lock, done with motion
+				}
 				cur_cmd=invalid_MC_ID;
-				checkinMotion(*it); // release lock, done with motion
 				// remove id from list of unprocessed motioncommands
 				std::list<MC_ID>::iterator rem=it++;
 				unlocked.erase(rem);
@@ -378,15 +426,13 @@
 			while(ent!=curstatelist.end() && alpha>0) {
 				OutputCmd curcmd;
 				float curp=curstatelist[ent].priority;
-				float curalpha=1; // curalpha is multiplicative sum of leftovers (weights between 0 and 1)
-				for(;curstatelist[ent].priority==curp; ent=curstatelist.next(ent)) {
+				float curalpha=1; // curalpha is cumulative product of leftovers (weights between 0 and 1)
+				for(;ent!=curstatelist.end() && curstatelist[ent].priority==curp; ent=curstatelist.next(ent)) {
 					//weighted average within priority level
 					float curweight=curstatelist[ent].frames[frame].weight;
-					ASSERT(curweight>=0,"negative output weights are illegal");
-					if(curweight<0) { //negative weights are illegal
-						cout << "weight=" << curweight << endl;
+					ASSERT(curweight>=0,"negative output weights are illegal, MC_ID="<<curstatelist[ent].mcid<<" joint="<<outputNames[output]<<" frame="<<frame<<" weight="<<curweight);
+					if(curweight<0) //negative weights are illegal
 						curweight=0;
-					}
 					curcmd.value+=curstatelist[ent].frames[frame].value*curweight;
 					curcmd.weight+=curweight;
 					if(curweight<1)
@@ -396,14 +442,15 @@
 				}
 				if(curcmd.weight>0) {
 					//weighted average of priority levels
-					sumcmd.value+=curcmd.value/curcmd.weight*(1-curalpha);
-					sumcmd.weight+=(1-curalpha);
+					sumcmd.value+=curcmd.value/curcmd.weight*alpha*(1-curalpha);
+					sumcmd.weight+=alpha*(1-curalpha);
 					alpha*=curalpha;
 				}
 			}
-			if(sumcmd.weight>0) 
-				outputs[frame][output]=sumcmd.value/sumcmd.weight;
-			else //if zero weight, hold last value
+			if(sumcmd.weight>0) {
+				sumcmd.value/=sumcmd.weight;
+				outputs[frame][output]=sumcmd.value;
+			} else //if zero weight, hold last value
 				sumcmd.value=outputs[frame][output]=cmdSums[output];
 			if(frame==NumFrames-1)
 				cmds[output]=sumcmd;
@@ -428,7 +475,7 @@
 			float tmpweight=0;
 			float curp=curstatelist[ent].priority;
 			float curalpha=1; // curalpha is multiplicative sum of leftovers (weights between 0 and 1)
-			for(;curstatelist[ent].priority==curp; ent=curstatelist.next(ent)) {
+			for(;ent!=curstatelist.end() && curstatelist[ent].priority==curp; ent=curstatelist.next(ent)) {
 				//weighted average within priority level
 				float curweight=curstatelist[ent].pid.weight;
 				ASSERT(curweight>=0,"negative PID weights are illegal")
@@ -489,8 +536,6 @@
 		cout << "MotionManager::updateWorldState() - could not detect model" << endl;
 }
 
-#ifdef PLATFORM_APERIOS
-
 /*! 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
@@ -518,10 +563,15 @@
  *  setting PIDs at too high a frequency.
  */
 bool
+#ifdef PLATFORM_APERIOS
 MotionManager::updatePIDs(OPrimitiveID primIDs[NumOutputs]) {
+#else
+MotionManager::updatePIDs() {
+#endif
 	//cout << "updatePIDs " << endl;
 	bool dirty=!pidchanges.empty();
 	while(!pidchanges.empty()) {
+#ifdef PLATFORM_APERIOS
 		float gain[3];
 		word shift[3];
 
@@ -557,6 +607,7 @@
 		//cout << gain[0] << ' ' << shift[0] << "   " << gain[1] << ' ' << shift[1] << "   " << gain[2] << ' ' << shift[2] << endl;
 
 		OPENR::SetJointGain(primIDs[pidchanges.front().joint],(word)gain[0],(word)gain[1],(word)gain[2],shift[0],shift[1],shift[2]);
+#endif //PLATFORM_APERIOS or PLATFORM_LOCAL
 		for(uint i=0; i<3; i++)
 			state->pids[pidchanges.front().joint][i]=pidchanges.front().pids[i];
 		pidchanges.pop_front();
@@ -564,6 +615,7 @@
 	return dirty;
 }
 
+#ifdef PLATFORM_APERIOS
 void
 MotionManager::receivedMsg(const ONotifyEvent& event) {
 	//	cout << "receivedMsg..." << flush;
@@ -575,7 +627,24 @@
 	//	cout << "receivedMsg-done" << endl;
 	func_end();
 }
-
+#else //PLATFORM_LOCAL
+bool
+MotionManager::receivedMsg(RCRegion* msg) {
+	try {
+		MarkScope l(*motman->procLocks[_MMaccID]);
+		/*MotionManagerMsg * mminfo = reinterpret_cast<MotionManagerMsg*>(msg->Base());
+		if(mminfo->creatorPID==ProcessID::getID())
+			return true; //don't process echos*/
+		motman->processMsg(msg);
+	} catch(const std::exception& ex) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionManagerMsg processing (MotionManager::receivedMsg)",&ex))
+			throw;
+	} catch(...) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionManagerMsg processing (MotionManager::receivedMsg)",NULL))
+			throw;
+	}
+	return true;
+}
 #endif //PLATFORM_APERIOS or PLATFORM_LOCAL
 
 void
@@ -586,46 +655,94 @@
 		return;
 	}
 	func_begin();
-	//	cout << id << "..." << flush;
+	//cout << ProcessID::getID() << "..." << flush;
 	MotionManagerMsg * mminfo = reinterpret_cast<MotionManagerMsg*>(rcr->Base());
 	MC_ID mc_id=mminfo->mc_id;
+	if(mc_id==invalid_MC_ID) {
+		//cout << "add message for already-deleted motion" << endl;
+		func_end();
+		return;
+	}
 	switch(mminfo->type) {
 		case MotionManagerMsg::addMotion: {
-			//cout << "receiveMotion(): rcr->NumberOfReference()==" << rcr->NumberOfReference() << endl;
-			rcr->AddReference();
-			//cout << "receiveMotion()NOW: rcr->NumberOfReference()==" << rcr->NumberOfReference() << endl;
-			cmdlist[mc_id].rcr[_MMaccID]=rcr;
-			//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[_MMaccID]->DoStart();
-			erouter->postEvent(new EventBase(EventBase::motmanEGID,mc_id,EventBase::activateETID,0));
+			if(cmdlist[mc_id].rcr[_MMaccID]==NULL) {
+				//cout << "receiveMotion()NOW: rcr->NumberOfReference()==" << rcr->NumberOfReference() << endl;
+				cmdlist[mc_id].rcr[_MMaccID]=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);
+			} 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!");
+#endif
+			}
+			if(ProcessID::getID()==ProcessID::MotionProcess && cmdlist[mc_id].lastAccessor!=(accID_t)-1) {
+				checkoutMotion(mc_id,true);
+				try {
+					cmdlist[mc_id].baseaddrs[_MMaccID]->DoStart();
+				} catch(const std::exception& ex) {
+					ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionCommand DoStart()",&ex);
+				} catch(...) {
+					ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionCommand DoStart()",NULL);
+				}
+				checkinMotion(mc_id);
+			}
 		} break;
 		case MotionManagerMsg::deleteMotion: {
 			//cout << "deleteMotion(): cmdlist[mc_id].rcr[_MMaccID]->NumberOfReference()==" << cmdlist[mc_id].rcr[_MMaccID]->NumberOfReference() << endl;
-			//cout << "deleting mc_id=="<<mc_id << endl;
-			if(cmdlist[mc_id].rcr[_MMaccID]==NULL)
-				cout << "WARNING: MotionManager attempted to delete a NULL motion! mc_id="<<mc_id<<" _MMaccID=" << _MMaccID << endl;
-			else {
-				checkoutMotion(mc_id,true);
-				cmdlist[mc_id].baseaddrs[_MMaccID]->DoStop();
-				erouter->postEvent(new EventBase(EventBase::motmanEGID,mc_id,EventBase::deactivateETID,0));
-				cmdlist[mc_id].rcr[_MMaccID]->RemoveReference();
-				cmdlist[mc_id].rcr[_MMaccID]=NULL;
-				bool found=false;
-				for(unsigned int i=0; i<numAcc; i++)
+			//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) {
+#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()) {
+#endif
+					cout << "WARNING: MotionManager attempted to delete a NULL motion! mc_id="<<mc_id<<" process=" << ProcessID::getIDStr() << endl;
+					stacktrace::displayCurrentStackTrace();
+#ifndef PLATFORM_APERIOS
+				}
+#endif
+			} else {
+				cmdlist[mc_id].lock.lock(_MMaccID);
+				int found=0;
+				for(unsigned int i=0; i<numAcc; i++) {
 					if(cmdlist[mc_id].rcr[i]!=NULL) {
-						found=true;
-						break;
+						found++;
 					}
-				if(!found) {
-					push_free(mc_id);
-					//should we check in?  The lock isn't technically valid anymore...
-					//checkinMotion(mc_id);
+				}
+				if(ProcessID::getID()==ProcessID::MotionProcess) {
+					// no need to check out, motion should already be marked inaccessible from original call to removeMotion (as asserted at beginning of deleteMotion case)
+					try {
+						convertMotion(mc_id)->DoStop();
+					} catch(const std::exception& ex) {
+						ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionCommand DoStop()",&ex);
+					} catch(...) {
+						ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionCommand DoStop()",NULL);
+					}
+					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;
+				if(found==1) {
+					push_free(mc_id); //don't unlock -- lock destructor will release the lock as the entry is destructed
 				} else {
-					cout << "Warning: motion command " << mc_id << " still has attachments after delete message received" << endl;
-					checkinMotion(mc_id);
+					cmdlist[mc_id].lock.unlock();
+				}
+				if(ProcessID::getID()==ProcessID::MainProcess) {
+					try {
+						erouter->postEvent(EventBase::motmanEGID,mc_id,EventBase::deactivateETID,0);
+					} catch(const std::exception& ex) {
+						ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during event posting",&ex);
+					} catch(...) {
+						ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during event posting",NULL);
+					}
 				}
 			}
 			//cout << "deleteMotion()NOW: cmdlist[mc_id].rcr[_MMaccID]->NumberOfReference()==" << cmdlist[mc_id].rcr[_MMaccID]->NumberOfReference() << endl;
@@ -633,7 +750,7 @@
 		default:
 			printf("*** WARNING *** unknown MotionManager msg type received\n");
 	}
-	//	cout << "processMsg-done" << endl;
+	//cout << "processMsg-done" << endl;
 	func_end();
 }
 
@@ -657,15 +774,18 @@
 	//	cout << id << "..." << flush;
 	for(MC_ID it=cmdlist.begin(); it!=cmdlist.end(); it=cmdlist.next(it)) {
 		if(cmdlist[it].baseaddrs[_MMaccID]==mc) {
-			cerr << "Warning: re-added motion command " << it << endl;
-			return it;
+			cerr << "Warning: adding motion command at " << mc << ", is already running in motion manager as MC_ID " << it << endl;
+			return func_end(it);
 		}
 	}
 	MC_ID mc_id = pop_free();
+	//cout << sm.getRegion()->ID().key << " holds " << mc_id << endl;
 	if(mc_id==cmdlist.end()) {
 		cout << "MotionManager::addMotion() - Out of room, could not add" << endl;
 		return func_end(cmdlist.end());
 	}
+	//cout << "setAdd(" << mc_id << ")" << endl;
+	mc->setAdd(mc_id);
 	cmdlist[mc_id].baseaddrs[_MMaccID]=mc;
 	cmdlist[mc_id].rcr[_MMaccID]=sm.getRegion();
 	//cout << "addMotion(): sm.getRegion()->NumberOfReference()==" << sm.getRegion()->NumberOfReference() << endl;
@@ -673,8 +793,14 @@
 	//cout << "addMotion()NOW: sm.getRegion()->NumberOfReference()==" << sm.getRegion()->NumberOfReference() << endl;
 	cmdlist[mc_id].lastAccessor=_MMaccID;
 	cmdlist[mc_id].priority=priority;
-	//cout << "setAdd(" << mc_id << ")" << endl;
-	mc->setAdd(mc_id);
+	try {
+		erouter->postEvent(EventBase::motmanEGID,mc_id,EventBase::activateETID,0);
+	} catch(const std::exception& ex) {
+		ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during event posting",&ex);
+	} catch(...) {
+		ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during event posting",NULL);
+	}
+	
 #ifdef PLATFORM_APERIOS
 	OStatus err;
 	/*{
@@ -691,7 +817,13 @@
 	err=subjs[_MMaccID]->NotifyObservers();
 	ASSERT(err==oSUCCESS,"*** ERROR MotionManager: NotifyObservers returned " << err);
 #else //PLATFORM_LOCAL
-	subjs[_MMaccID]->sendMessage(sm.getRegion());
+	try {
+		subjs[_MMaccID]->sendMessage(sm.getRegion());
+	} catch(const std::exception& ex) {
+		ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during message sending",&ex);
+	} catch(...) {
+		ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during message sending",NULL);
+	}
 #endif //PLATFORM check for IPC stuff
 	//	cout << "addMotion-done" << endl;
 	//cout << " - " << get_time() << endl;
@@ -701,8 +833,9 @@
 MotionCommand *
 MotionManager::checkoutMotion(MC_ID mcid,bool block) {
 	//cout << "checkout..." << flush;
-	if(mcid>=MAX_MOTIONS) {
-		cout << "*** WARNING *** " << _MMaccID << " tried to access invalid mcid " << mcid << endl;
+	if(mcid>=MAX_MOTIONS || mcid==invalid_MC_ID) {
+		cout << "*** WARNING *** " << ProcessID::getIDStr() << " tried to access invalid mcid " << mcid << endl;
+		stacktrace::displayCurrentStackTrace();
 		return NULL;
 	}
 	if(block)
@@ -711,37 +844,91 @@
 		if(!cmdlist[mcid].lock.try_lock(_MMaccID))
 			return NULL;
 	if(cmdlist[mcid].lastAccessor==(accID_t)-1) {
-		cout << "*** WARNING *** " << _MMaccID << " tried to access dead mcid " << mcid << endl;
+		cout << "*** WARNING *** " << ProcessID::getIDStr() << " tried to access dead mcid " << mcid << endl;
+		stacktrace::displayCurrentStackTrace();
 		cmdlist[mcid].lock.unlock();
 		return NULL;
 	}
 	//cout << "locked..." << endl;
-	MotionCommand * base = cmdlist[mcid].baseaddrs[_MMaccID];
+	//cout << "checkout-done..." << flush;
+	return convertMotion(mcid);
+}
+
+MotionCommand *
+MotionManager::convertMotion(MC_ID mc) {
+	MotionCommand * base = cmdlist[mc].baseaddrs[_MMaccID];
 	//	cout << "base=" << base << "..." << flush;
-	if(cmdlist[mcid].lastAccessor!=_MMaccID) {
+	if(cmdlist[mc].lastAccessor!=_MMaccID) {
 		//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[mcid].lastAccessor=_MMaccID;
+		cmdlist[mc].lastAccessor=_MMaccID;
 	}
 	base->setTranslator(etrans);
-	//cout << "checkout-done..." << flush;
+#ifdef PLATFORM_APERIOS
+	base->setWorldState(state);
+#endif
 	return base;
 }
 
 void
 MotionManager::checkinMotion(MC_ID mcid) {
-	cmdlist[mcid].baseaddrs[_MMaccID]->setTranslator(NULL);
-	if(mcid!=invalid_MC_ID)
-		cmdlist[mcid].lock.unlock();
+	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];
+		base->setTranslator(NULL);
+#ifdef PLATFORM_APERIOS
+		base->setWorldState(NULL);
+#endif
+	}
+	cmdlist[mcid].lock.unlock();
 }
 
 void
 MotionManager::removeMotion(MC_ID mcid) {
-	if(mcid==invalid_MC_ID)
+	if(mcid>=MAX_MOTIONS || mcid==invalid_MC_ID)
 		return;
 	func_begin();
+	if(cmdlist[mcid].lastAccessor==(accID_t)-1) {
+		cout << "WARNING: removeMotion called for a motion which has already been removed mc_id="<<mcid<<" process=" << ProcessID::getIDStr() << endl;
+		stacktrace::displayCurrentStackTrace();
+		func_end();
+		return;
+	}
+	if(cmdlist[mcid].rcr[_MMaccID]==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);
+	if(ProcessID::getID()==ProcessID::MotionProcess) {
+		MotionCommand * mc=checkoutMotion(mcid,true);
+		try {
+			mc->DoStop();
+		} catch(const std::exception& ex) {
+			ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionCommand DoStop()",&ex);
+		} catch(...) {
+			ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionCommand DoStop()",NULL);
+		}
+		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].lock.unlock();
+	if(ProcessID::getID()==ProcessID::MainProcess) {
+		try {
+			erouter->postEvent(EventBase::motmanEGID,mcid,EventBase::deactivateETID,0);
+		} catch(const std::exception& ex) {
+			ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during event posting",&ex);
+		} catch(...) {
+			ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during event posting",NULL);
+		}
+	}
 #ifdef PLATFORM_APERIOS
 	MotionManagerMsg dmsg;
 	dmsg.setDelete(mcid);
@@ -749,18 +936,18 @@
 	subjs[_MMaccID]->SetData(&dmsg,sizeof(dmsg));
 	subjs[_MMaccID]->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;
-	subjs[_MMaccID]->sendMessage(dmsg.getRegion());
-#endif //PLATFORM check for IPC stuff
-	 //cout << " - " << get_time() << endl;
-	 //cout << "removeMotion(): cmdlist[mcid].rcr[_MMaccID]->NumberOfReference()==" << cmdlist[mcid].rcr[_MMaccID]->NumberOfReference() << endl;
-	if(cmdlist[mcid].rcr[_MMaccID]!=NULL) {
-		cmdlist[mcid].rcr[_MMaccID]->RemoveReference();
-		cmdlist[mcid].rcr[_MMaccID]=NULL;
+	try {
+		subjs[_MMaccID]->sendMessage(dmsg.getRegion());
+	} catch(const std::exception& ex) {
+		ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during message sending",&ex);
+	} catch(...) {
+		ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during message sending",NULL);
 	}
-	//cout << "removeMotion()NOW: cmdlist[mcid].rcr[_MMaccID]->NumberOfReference()==" << cmdlist[mcid].rcr[_MMaccID]->NumberOfReference() << endl;
+#endif //PLATFORM check for IPC stuff
 	func_end();
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/MotionManager.h ./Motion/MotionManager.h
--- ../Tekkotsu_2.4.1/Motion/MotionManager.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Motion/MotionManager.h	2006-10-03 18:28:15.000000000 -0400
@@ -18,51 +18,62 @@
 #  include <OPENR/ObjcommEvent.h>
 #  include <OPENR/OObject.h>
 #else //PLATFORM_LOCAL
-#  include "IPC/MessageQueue.h"
+class MessageQueueBase;
+class MessageReceiver;
 #endif
 
 class EventTranslator;
 
-//! The purpose of this class is to provide mutually exclusive access to the MotionCommands and simplify their sharing between memory spaces
-/*! Since MotionObject and MainObject run as separate processes, they
+//! The purpose of this class is to repeatedly compute the final set of joint angles for the robot, managing a set of (possibly conflicting) MotionCommands
+/*! Since Main and Motion run as separate processes, they
  *  could potentially try to access the same motion command at the
  *  same time, leading to unpredictable behavior.  The MotionManager
- *  enforces a set of locks to solve this.
+ *  enforces a set of locks to serialize access to the MotionCommands.
+ *  Although you could call checkoutMotion() and checkinMotion() directly,
+ *  it is instead recommended to use MMAccessor to automatically handle
+ *  casting and checkin for you.
  *
- *  The other problem is that we are sharing between processes.
- *  MotionManager will do what's necessary to distribute new
- *  MotionCommand's to all the processes (currently just MainObj and
- *  MotoObj)\n You should be able to create and add a new motion in
- *  one line:
+ *  The other problem is that we are sharing the memory holding MotionCommands between processes.
+ *  MotionManager will do the necessary magic behind the scenes to distribute new
+ *  MotionCommands to all the involved processes (currently just Main and
+ *  Motion)\n You can create and add a new motion in one line:
  *
  *  @code
- *  motman->addMotion( SharedObject<YourMC>([arg1,...]) , autoprune [, priority ]);
+ *  // type A: prunable motions are automatically removed when completed:
+ *  motman->addPrunableMotion( SharedObject<YourMC>([arg1,...]) [, priority ] );
+ *
+ *  // type B: persistent motions are removed only when you explicitly request it:
+ *  MC_ID id = motman->addPersistentMotion( SharedObject<YourMC>([arg1,...]) [, priority ] );
+ *  // then later: motman->removeMotion(id);
  *  @endcode
  *  
- *  But if you want to do some more initializations not handled by the
+ *  If you want to do some more initializations not handled by the MotionCommand's
  *  constructor (the @p arg1, @p arg2, ...  params) then you would
  *  want to do something like the following:
  *  
  *  @code
- *  SharedObject<YourMC> tmpvar([arg1,[arg2,...]]);
- *  tmpvar->cmd1();
- *  tmpvar->cmd2();
+ *  SharedObject<YourMC> yourmc([arg1,[arg2,...]]);
+ *  yourmc->cmd1();
+ *  yourmc->cmd2();
  *  //...
- *  motman->addPrunableMotion(tmpvar [, ...]); //or addPersistentMotion(...)
+ *  motman->addPrunableMotion(yourmc [, ...]); //or addPersistentMotion(...)
  *  @endcode
  *
- *  Notice that tmpvar is of type SharedObject, but you're calling @c
- *  YourMC functions on it...  SharedObject is a "smart pointer" which
+ *  Notice that @c yourmc is actually of type SharedObject, but you're calling @c
+ *  YourMC's functions on it through the '->' operator...  SharedObject is a "smart pointer" which
  *  will pass your function calls on to the underlying templated type.
  *  Isn't C++ great? :)
  *
- *  @warning Once the MotionCommand has been added you must check it
- *  out to modify it or risk concurrent access problems.
- *
- *  @see MotionCommand for information on creating new motion primitives.
+ *  @warning Once the MotionCommand has been added, you must check it
+ *  out to make any future modifications it or risk concurrent access problems.
+ *  In other words, you should @e not keep the SharedObject and continue
+ *  to access the motion through that unless you know the motion is not active
+ *  in the MotionManager.  Instead, always use a MMAccessor.
  *
  *  @see MMAccessor for information on accessing motions after you've
- *  added them to MotionManager.
+ *  added them to MotionManager, or if it @e may be active in the MotionManager.
+ *
+ *  @see MotionCommand for information on creating new motion primitives.
  */
 class MotionManager {
 public:
@@ -92,9 +103,10 @@
 	void InitAccess(OSubject* subj);            //!< @b LOCKS @b MotionManager Everyone who is planning to use the MotionManager needs to call this before they access it or suffer a horrible fate
 	void receivedMsg(const ONotifyEvent& event); //!< @b LOCKS @b MotionManager This gets called by an OObject when it receives a message from one of the other OObject's MotionManagerComm Subject
 #else
-	void InitAccess(MessageQueueBase& mcbufq); //!< @b LOCKS @b MotionManager Everyone who is planning to use the MotionManager needs to call this before they access it or suffer a horrible fate
-	void RemoveAccess(); //!< needed in order to dereference shared memory regions before shutting down
+	void InitAccess(MessageQueueBase& mcbufq, Resource& behaviorLock); //!< @b LOCKS @b MotionManager Everyone who is planning to use the MotionManager needs to call this before they access it or suffer a horrible fate
+	static bool receivedMsg(RCRegion* msg); //!< called with incoming messages, will pass non-echos to processMsg()
 #endif
+	void RemoveAccess(); //!< needed in order to dereference shared memory regions before shutting down
 	static void setTranslator(EventTranslator* et) {etrans=et;} //!< sets #etrans, should be called before any events can be sent
 	void processMsg(RCRegion* region); //!< @b LOCKS @b MotionManager This gets called by receivedMsg when under Aperios, or directly if you already have an RCRegion
 	~MotionManager(); //!<destructor
@@ -143,10 +155,12 @@
 	//@}
 
 	//@{
-	void getOutputs(float outputs[NumFrames][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 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
+	bool updatePIDs();      //!< 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
 #endif
 	//@}
 
@@ -172,6 +186,8 @@
 protected:
 	//!does the actual work of adding a motion
 	MC_ID doAddMotion(const SharedObjectBase& sm, bool autoprune, float priority);
+	//! sets up a motion command to be accessed by the current process
+	MotionCommand* convertMotion(MC_ID mc);
 	
 	//! used to request pids for a given joint
 	struct PIDUpdate {
@@ -234,6 +250,8 @@
 #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];
 #endif
 
 	static int _MMaccID;          //!<Stores the accessor for the current process
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/MotionManagerMsg.h ./Motion/MotionManagerMsg.h
--- ../Tekkotsu_2.4.1/Motion/MotionManagerMsg.h	2003-09-02 16:58:49.000000000 -0400
+++ ./Motion/MotionManagerMsg.h	2006-09-16 13:32:39.000000000 -0400
@@ -2,7 +2,17 @@
 #ifndef INCLUDED_MotionManagerMsg_h
 #define INCLUDED_MotionManagerMsg_h
 
-//! A small header that preceeds data sent by MotionManager between processes
+#include "IPC/ProcessID.h"
+
+//! A small header that precedes data sent by MotionManager between processes
+/*! Typically this is broadcast to all processes using the MotionManager so
+ *  each process has to update its own fields of MotionManager.
+ *
+ *  One tricky aspect is that with the IPC mechanisms on PLATFORM_LOCAL
+ *  the originating process will get an "echo" of the message, whereas
+ *  on PLATFORM_APERIOS it's set up so the sender doesn't get an echo
+ *  of its own message.  However, this complexity is handled by
+ *  MotionManager, not here. */
 struct MotionManagerMsg {
 	//! the type to use when referring to MotionCommand ID's
 	typedef unsigned short MC_ID;
@@ -11,7 +21,7 @@
 	static const MC_ID invalid_MC_ID=static_cast<MC_ID>(-1); 
 
 	//! constructor
-	MotionManagerMsg() : type(unknown), mc_id(invalid_MC_ID) {}
+	MotionManagerMsg() : type(unknown), creatorPID(ProcessID::getID()), mc_id(invalid_MC_ID) {}
 
 	//! virtual destructor
 	/*! doesn't do anything, but don't remove it, otherwise this would no longer be a virtual base class */
@@ -27,8 +37,15 @@
 private:
 	friend class MotionManager;
 
-	//! Denotes what type of message this is
-	enum MsgType { addMotion, deleteMotion, unknown } type;
+	//! Denotes what type of message this is (see #type)
+	enum MsgType {
+		addMotion,     //!< indicates the msg is actually MotionCommand to be added to the MotionManager
+		deleteMotion,  //!< indicates the msg's #mc_id references a MotionCommand to be removed from the MotionManager
+		unknown        //!< failsafe default until one of the others is set
+	} type; //!< indicates what processing this message requires
+	
+	//! holds the process that this message was created/sent from
+	ProcessID::ProcessID_t creatorPID;
 	
 	//! The id of the MotionCommand this is in reference to
 	MC_ID mc_id;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/MotionSequenceEngine.cc ./Motion/MotionSequenceEngine.cc
--- ../Tekkotsu_2.4.1/Motion/MotionSequenceEngine.cc	2005-07-14 13:09:03.000000000 -0400
+++ ./Motion/MotionSequenceEngine.cc	2006-09-23 15:51:11.000000000 -0400
@@ -1,4 +1,5 @@
-#include "MotionSequenceMC.h"
+#include "MotionSequenceEngine.h"
+#include "DynamicMotionSequence.h"
 #include "Shared/get_time.h"
 #include "Shared/WorldState.h"
 #include "Shared/Config.h"
@@ -83,12 +84,12 @@
 	return used+1;
 }
 
-unsigned int MotionSequenceEngine::LoadBuffer(const char buf[], unsigned int len) {
+unsigned int MotionSequenceEngine::loadBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
 	if(strncmp("#POS",buf,4)==0) {
 		// allow inlined loading of posture files
 		PostureEngine pose;
-		unsigned int used=pose.LoadBuffer(buf,len);
+		unsigned int used=pose.loadBuffer(buf,len);
 		if(used!=0)
 			setPose(pose);
 		return used;
@@ -139,13 +140,13 @@
 		char arg1[arglen];
 		char arg2[arglen];
 		written=readWord(buf,&buf[len],command,cmdlen);
-		if(!ChkAdvance(written,&buf,&len,"*** ERROR MotionSequenceEngine load corrupted - line %d\n",linenum)) return 0;
+		if(!checkInc(written,buf,len,"*** ERROR MotionSequenceEngine load corrupted - line %d\n",linenum)) return 0;
 		written=readWord(buf,&buf[len],arg1,arglen);
 		if(written>0)
-			if(!ChkAdvance(written,&buf,&len,"*** ERROR MotionSequenceEngine load corrupted - line %d\n",linenum)) return 0;
+			if(!checkInc(written,buf,len,"*** ERROR MotionSequenceEngine load corrupted - line %d\n",linenum)) return 0;
 		written=readWord(buf,&buf[len],arg2,arglen);
 		if(written!=0)
-			if(!ChkAdvance(written,&buf,&len,"*** ERROR MotionSequenceEngine load corrupted - line %d\n",linenum)) return 0;
+			if(!checkInc(written,buf,len,"*** ERROR MotionSequenceEngine load corrupted - line %d\n",linenum)) return 0;
 		for(;len>0 && *buf!='\n' && *buf!='\r';buf++,len--) {}
 		if(*buf=='\n') { //in case of \r\n
 			buf++;
@@ -168,27 +169,47 @@
 			} else {
 				setTime(newtime);
 			}
-		} else if(strcasecmp(command,"load")==0) {
+		} else if(strcasecmp(command,"load")==0 || strcasecmp(command,"overlay")==0) {
 			PostureEngine pose;
-			if(pose.LoadFile(arg1)!=0) {
+			if(pose.loadFile(arg1)!=0) {
+				// it's a posture file
 				setPose(pose);
-			} else
-				cout << "*** WARNING could not read file " << arg1 << " for load - line " << linenum << endl;
-		} else if(strcasecmp(command,"overlay")==0) {
-			PostureEngine pose;
-			if(pose.LoadFile(arg1)!=0)
-				overlayPose(pose);
-			else
+			} else if(overlayMotion(arg1)!=0) {
+				// it's a motionsequence file (conditional test did the overlay)
+			} else {
+				// unknown file, give warning
 				cout << "*** WARNING could not read file " << arg1 << " for overlay - line " << linenum << endl;
+			}
+		} else if(strcasecmp(command,"loadExplicit")==0) {
+			PostureEngine pose;
+			if(pose.loadFile(arg1)!=0) {
+				setExplicitPose(pose);
+			} 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();
 		} else if(strcasecmp(command,"radians")==0) {
 			setSaveRadians();
 		} else {
 			lastOutputIdx=getOutputIndex(command,lastOutputIdx+1);
-			if(lastOutputIdx==NumOutputs)
+			bool found = (lastOutputIdx!=NumOutputs);
+			unsigned int lidx=lastOutputIdx,ridx=NumOutputs;
+			if(!found) { // base name not found
+				// try symmetric left/right versions
+				char tname[cmdlen+1];
+				strncpy(tname+1,command,cmdlen);
+				tname[0]='L';
+				lidx=getOutputIndex(tname,lastOutputIdx+1);
+				if(lidx!=NumOutputs) {
+					tname[0]='R';
+					ridx=getOutputIndex(tname,lidx+1);
+					if(ridx!=NumOutputs)
+						found=true;
+				}
+			}
+			if (!found) {
 				cout << "*** WARNING " << command << " is not a valid joint on this model." << endl;
-			else {
+			} else {
 				char* used;
 				double value=strtod(arg1,&used), weight=1;
 				if(*used!='\0')
@@ -197,11 +218,19 @@
 					if(arg2[0]!='\0') {
 						weight=strtod(arg2,&used);
 						if(*used!='\0') {
-							cout << "*** WARNING illegal weight argument: " << arg2 << " - line " << linenum << endl;
-							weight=1;
+							 cout << "*** WARNING illegal weight argument: " << arg2 << " - line " << linenum << endl;
+							 weight=1;
 						}
 					}
-					setOutputCmd(lastOutputIdx,OutputCmd(value*loadSaveMode,weight));
+					if(lastOutputIdx!=NumOutputs) {
+						// found exact match earlier
+						setOutputCmd(lastOutputIdx,OutputCmd(value*loadSaveMode,weight));
+					} else {
+						// found symmetric matches earlier
+						setOutputCmd(lidx,OutputCmd(value*loadSaveMode,weight));
+						setOutputCmd(ridx,OutputCmd(value*loadSaveMode,weight));
+						lastOutputIdx=ridx;
+					}
 				}
 			}
 		}
@@ -213,16 +242,16 @@
 	return origlen-len;
 }
 
-unsigned int MotionSequenceEngine::SaveBuffer(char buf[], unsigned int len) const {
+unsigned int MotionSequenceEngine::saveBuffer(char buf[], unsigned int len) const {
 	//std::cout << "SAVEBUFFER..." << std::flush;
 	unsigned int origlen=len;
 	int written=snprintf(buf,len,"#MSq\n");
-	if(!ChkAdvance(written,(const char**)&buf,&len,"*** ERROR MotionSequenceEngine save failed on header\n")) return 0;	if(len==0 || len>origlen) {
+	if(!checkInc(written,buf,len,"*** ERROR MotionSequenceEngine save failed on header\n")) return 0;	if(len==0 || len>origlen) {
 		cout << "*** ERROR MotionSequenceEngine save overflow on header" << endl;
 		return 0;
 	}
 	written=snprintf(buf,len,isSaveRadians()?"radians\n":"degrees\n");
-	if(!ChkAdvance(written,(const char**)&buf,&len,"*** ERROR MotionSequenceEngine save failed on mode\n")) return 0;	if(len==0 || len>origlen) {
+	if(!checkInc(written,buf,len,"*** ERROR MotionSequenceEngine save failed on mode\n")) return 0;	if(len==0 || len>origlen) {
 		cout << "*** ERROR MotionSequenceEngine save overflow" << endl;
 		return 0;
 	}
@@ -237,7 +266,7 @@
 	}
 	if(hasInitialFrame) {
 		written=snprintf(buf,len,"setTime\t0\n");
-		if(!ChkAdvance(written,(const char**)&buf,&len,"*** ERROR MotionSequenceEngine save failed on initial frame spec\n")) return 0;
+		if(!checkInc(written,buf,len,"*** ERROR MotionSequenceEngine save failed on initial frame spec\n")) return 0;
 	}
 	while(t!=-1U) {
 		//std::cout << "t="<<t<<"..."<<std::endl;
@@ -247,10 +276,10 @@
 			if((t!=0 || getKeyFrame(tprevs[i]).cmd.weight!=0) && getKeyFrame(tprevs[i]).starttime==t) {
 				if(getKeyFrame(tprevs[i]).cmd.weight==1) {
 					written=snprintf(buf,len,"%s\t%g\n",outputNames[i],getKeyFrame(tprevs[i]).cmd.value/loadSaveMode);
-					if(!ChkAdvance(written,(const char**)&buf,&len,"*** ERROR MotionSequenceEngine save failed\n")) return 0;
+					if(!checkInc(written,buf,len,"*** ERROR MotionSequenceEngine save failed\n")) return 0;
 				} else {
 					written=snprintf(buf,len,"%s\t%g\t%g\n",outputNames[i],getKeyFrame(tprevs[i]).cmd.value/loadSaveMode,getKeyFrame(tprevs[i]).cmd.weight);
-					if(!ChkAdvance(written,(const char**)&buf,&len,"*** ERROR MotionSequenceEngine save failed\n")) return 0;
+					if(!checkInc(written,buf,len,"*** ERROR MotionSequenceEngine save failed\n")) return 0;
 				}
 				if(len==0 || len>origlen) {
 					cout << "*** ERROR MotionSequenceEngine save overflow" << endl;
@@ -262,7 +291,7 @@
 		t=setNextFrameTime(tprevs,tnexts);
 		if(t!=-1U) {
 			written=snprintf(buf,len,"delay\t%d\n",t-last);
-			if(!ChkAdvance(written,(const char**)&buf,&len,"*** ERROR MotionSequenceEngine save failed\n")) return 0;
+			if(!checkInc(written,buf,len,"*** ERROR MotionSequenceEngine save failed\n")) return 0;
 			if(len==0 || len>origlen) {
 				cout << "*** ERROR MotionSequenceEngine save overflow" << endl;
 				return 0;
@@ -270,7 +299,7 @@
 		}
 	}
 	written=snprintf(buf,len,"#END\n");
-	if(!ChkAdvance(written,(const char**)&buf,&len,"*** ERROR MotionSequenceEngine save failed on #END\n")) return 0;
+	if(!checkInc(written,buf,len,"*** ERROR MotionSequenceEngine save failed on #END\n")) return 0;
 	if(len==0 || len>origlen) {
 		cout << "*** ERROR MotionSequenceEngine save overflow on #END" << endl;
 		return 0;
@@ -279,17 +308,23 @@
 	cout << "SAVE-done!" << endl;
 }
 
-unsigned int MotionSequenceEngine::LoadFile(const char filename[]) {
-	return LoadSave::LoadFile(config->motion.makePath(filename).c_str());
+unsigned int MotionSequenceEngine::loadFile(const char filename[]) {
+	return LoadSave::loadFile(config->motion.makePath(filename).c_str());
 }
-unsigned int MotionSequenceEngine::SaveFile(const char filename[]) const {
-	return LoadSave::SaveFile(config->motion.makePath(filename).c_str());
+unsigned int MotionSequenceEngine::saveFile(const char filename[]) const {
+	return LoadSave::saveFile(config->motion.makePath(filename).c_str());
 }
 
 void MotionSequenceEngine::setTime(unsigned int x) {
 	playtime=x;
-	for(unsigned int i=0; i<NumOutputs; i++)
-		setRange(x,prevs[i],nexts[i]);
+	WorldState * st=WorldState::getCurrent();
+	for(unsigned int i=0; i<NumOutputs; i++) {
+		if(setRange(x,prevs[i],nexts[i])) {
+			OutputCmd& cmd=getKeyFrame((playspeed<0)?nexts[i]:prevs[i]).cmd;
+			if(cmd.weight<=0)
+				cmd.value=st->outputs[i];
+		}
+	}
 }
 
 void MotionSequenceEngine::setOutputCmd(unsigned int i, const OutputCmd& cmd) {
@@ -316,13 +351,24 @@
 		prevs[i]=x;
 //		cout << "set " << i << ' ' << outputNames[i] << ' ' << cur.cmd.value << ' ' << cur.cmd.weight << ' ' << cur.starttime << " state: " << starts[i] <<' '<< prevs[i] <<' '<< prev_m.next <<' '<< nexts[i] << " new: " << cur.prev << ' ' << x << ' ' << cur.next << endl;
 	}
+	curstamps[i]=-1U;
 }
 
 void MotionSequenceEngine::setPose(const PostureEngine& pose) {
 	for(unsigned int i=0; i<NumOutputs; i++)
+		if(pose.getOutputCmd(i).weight>0)
+			setOutputCmd(i,pose.getOutputCmd(i));
+}
+
+void MotionSequenceEngine::setExplicitPose(const PostureEngine& pose) {
+	for(unsigned int i=0; i<NumOutputs; i++)
 		setOutputCmd(i,pose.getOutputCmd(i));
 }
 
+void MotionSequenceEngine::overlayPose(const PostureEngine& pose) {
+	setPose(pose);
+}
+
 PostureEngine MotionSequenceEngine::getPose() {
 	PostureEngine pose;
 	getPose(pose);
@@ -334,22 +380,84 @@
 		pose.setOutputCmd(i,getOutputCmd(i));
 }
 
-void MotionSequenceEngine::overlayPose(const PostureEngine& pose) {
-	for(unsigned int i=0; i<NumOutputs; i++)
-		if(pose.getOutputCmd(i).weight>0)
-			setOutputCmd(i,pose.getOutputCmd(i));
+unsigned int MotionSequenceEngine::overlayMotion(const std::string& msFile) {
+	DynamicMotionSequence ms;
+	if(ms.loadFile(msFile.c_str())==0)
+		return 0;
+	overlayMotion(ms);
+	return ms.getEndTime();
+}
+
+/*! @todo should better handle conflicts with keyframes in original motion
+ *  
+ *  This is not a particularly well implemented function -- it will interleave
+ *  @a ms's keyframes with any pre-existing ones, but will clobber frames which
+ *  coincide with @a ms's own.  Probably will not give the desired effect when
+ *  the motion is actually overlaying something, but it will work for basic
+ *  usage cases. */
+void MotionSequenceEngine::overlayMotion(const MotionSequenceEngine& ms) {
+	//merge keyframes for each output, advance playhead by ms.endtime at the end
+	for(unsigned int i=0; i<NumOutputs; i++) {
+		//cout << "Processing " << outputNames[i] << ":" << endl;
+		Move_idx_t myPrevIdx=prevs[i];
+		unsigned int myPrevTime=getKeyFrame(prevs[i]).starttime;
+		Move_idx_t myNextIdx=getKeyFrame(myPrevIdx).next;
+		unsigned int myNextTime=-1U;
+		if(myNextIdx!=invalid_move)
+			myNextTime=getKeyFrame(myNextIdx).starttime;
+		for(Move_idx_t curOtherIdx=ms.starts[i]; curOtherIdx!=invalid_move; curOtherIdx=ms.getKeyFrame(curOtherIdx).next) {
+			const Move& curOther=ms.getKeyFrame(curOtherIdx);
+			while(myNextTime <= curOther.starttime+getTime()) {
+				//cout << "Advancing to " << myNextTime << endl;
+				myPrevIdx=myNextIdx;
+				myPrevTime=myNextTime;
+				myNextIdx=getKeyFrame(myPrevIdx).next;
+				myNextTime= (myNextIdx==invalid_move ? -1U : getKeyFrame(myNextIdx).starttime);
+			}
+			if(curOther.cmd.weight > 0) {
+				if(curOther.starttime+getTime() == myPrevTime) {
+					//replace current 'prev'
+					//cout << "replacing frame " << myPrevIdx << " at " << myPrevTime << endl;
+					getKeyFrame(myPrevIdx).cmd=curOther.cmd;
+				} else {
+					//insert new keyframe between 'prev' and 'next'
+					Move_idx_t insIdx=newKeyFrame();
+					//cout << "adding new frame at " << curOther.starttime+getTime() << " with index " << insIdx << endl;
+					if(insIdx==invalid_move)
+						return; //newKeyFrame should have reported error, we can silently return
+					Move& ins=getKeyFrame(insIdx);
+					ins.prev=myPrevIdx;
+					ins.next=myNextIdx;
+					ins.cmd=curOther.cmd;
+					ins.starttime=curOther.starttime+getTime();
+					getKeyFrame(myPrevIdx).next=insIdx;
+					if(myNextIdx!=invalid_move)
+						getKeyFrame(myNextIdx).prev=insIdx;
+					if(myPrevIdx==prevs[i]) {
+						nexts[i]=insIdx;
+						curstamps[i]=-1U;
+					}
+					myPrevIdx=insIdx; //inserted frame is now 'prev'
+					myPrevTime=ins.starttime;
+					if(myPrevTime>endtime)
+						endtime=myPrevTime;
+				}
+			}
+		}
+	}
+	advanceTime(ms.getEndTime());
 }
 
 void MotionSequenceEngine::compress() {
 	for(unsigned int i=0; i<NumOutputs; i++) {
 		Move_idx_t prev=getKeyFrame(starts[i]).next;
-		if(prev==(Move_idx_t)-1)
+		if(prev==invalid_move)
 			break;
 		Move_idx_t cur=getKeyFrame(prev).next;
-		if(cur==(Move_idx_t)-1)
+		if(cur==invalid_move)
 			break;
 		Move_idx_t next=getKeyFrame(cur).next;
-		while(next!=(Move_idx_t)-1) {
+		while(next!=invalid_move) {
 			OutputCmd tmp;
 			Move& prev_m=getKeyFrame(prev);
 			Move& cur_m=getKeyFrame(cur);
@@ -374,18 +482,20 @@
 	unsigned int t=0;
 	Move_idx_t tprevs[NumOutputs];
 	Move_idx_t tnexts[NumOutputs];
-	for(unsigned int i=0;i<NumOutputs;i++)
+	for(unsigned int i=0;i<NumOutputs;i++) {
 		tnexts[i]=getKeyFrame(tprevs[i]=starts[i]).next;
+		curstamps[i]=-1U;
+	}
 	while(t!=-1U) {
 		for(unsigned int i=0; i<NumOutputs; i++) {
 			//second and third conditionals are to skip transitions between 0 weighted frames
-			if(tnexts[i]!=(Move_idx_t)-1 && (getKeyFrame(tprevs[i]).cmd.weight!=0 || getKeyFrame(tnexts[i]).cmd.weight!=0) && getKeyFrame(tprevs[i]).starttime==t) {
+			if(tnexts[i]!=invalid_move && (getKeyFrame(tprevs[i]).cmd.weight!=0 || getKeyFrame(tnexts[i]).cmd.weight!=0) && getKeyFrame(tprevs[i]).starttime==t) {
 				float dv=fabs(getKeyFrame(tprevs[i]).cmd.value-getKeyFrame(tnexts[i]).cmd.value);
 				unsigned int dt=getKeyFrame(tnexts[i]).starttime-getKeyFrame(tprevs[i]).starttime;
 				if(dv/dt>comps[i]) {
 					unsigned int delay=(unsigned int)(dv/comps[i])-dt;
 					for(unsigned int j=0; j<NumOutputs; j++)
-						for(Move_idx_t c=tnexts[j]; c!=(Move_idx_t)-1; c=getKeyFrame(c).next)
+						for(Move_idx_t c=tnexts[j]; c!=invalid_move; c=getKeyFrame(c).next)
 							getKeyFrame(c).starttime+=delay;
 				}
 			}
@@ -411,11 +521,12 @@
 void MotionSequenceEngine::resume() {
 	playing=true;
 	lasttime=get_time();
+	WorldState * st=WorldState::getCurrent();
 	for(unsigned int i=0; i<NumOutputs; i++) {
 		Move_idx_t cur=starts[i];
-		while(cur!=(Move_idx_t)-1) {
+		while(cur!=invalid_move) {
 			if(getKeyFrame(cur).cmd.weight!=0) {
-				getKeyFrame(starts[i]).cmd.value=state->outputs[i];
+				getKeyFrame(starts[i]).cmd.value=st->outputs[i];
 				break;
 			}
 			cur=getKeyFrame(cur).next;
@@ -428,9 +539,16 @@
 	for(unsigned int i=0; i<NumOutputs; i++)
 		if(n[i]!=invalid_move && getKeyFrame(n[i]).starttime<ans)
 			ans=getKeyFrame(n[i]).starttime;
-	if(ans!=-1U)
-		for(unsigned int i=0; i<NumOutputs; i++)
-			setRange(ans,p[i],n[i]);
+	if(ans!=-1U) {
+		WorldState * st=WorldState::getCurrent();
+		for(unsigned int i=0; i<NumOutputs; i++) {
+			if(setRange(ans,p[i],n[i])) {
+				const OutputCmd& cmd=getKeyFrame((playspeed<0)?n[i]:p[i]).cmd;
+				if(cmd.weight<=0)
+					const_cast<OutputCmd&>(cmd).value=st->outputs[i]; //it's ok to assign the value when weight is '0', still "const"... kinda
+			}
+		}
+	}
 	return ans;
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/MotionSequenceEngine.h ./Motion/MotionSequenceEngine.h
--- ../Tekkotsu_2.4.1/Motion/MotionSequenceEngine.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Motion/MotionSequenceEngine.h	2006-10-03 19:01:28.000000000 -0400
@@ -6,18 +6,18 @@
 #include "IPC/ListMemBuf.h"
 #include "PostureEngine.h"
 
-//! A handy little (or not so little) class for switching between a sequence of postures
-/*! Outputs are handled independently.  It's easy to add keyframes
+//! A handy class for storing a sequence of keyframed movements
+/*! Each outputs is handled independently.  It's easy to add keyframes
  *  which modify all of the outputs, but since each output is tracked
  *  individually, OutputCmd's with 0 weight can be used to not affect
- *  other motions.  For instance, pan the head left to right while
+ *  other motions.  For instance, if you want to pan the head left to right while
  *  moving the right leg up and down several times, you won't have to
- *  specify the position of the head in its motion at each of the leg
+ *  specify the intermediary position of the head in its motion at each of the leg
  *  motion keyframes.
  *
  *  Be aware that the 0 time frame will be replaced on a call to
- *  play() with the current body posture.  However, this only applies
- *  to  outputs which have a non-zero weighted frame defined at some
+ *  play() with the current body posture from ::state.  However, this only applies
+ *  to outputs which have a non-zero weighted frame defined at some
  *  point.  The weights, of the 0 time frame will remain unchanged.  
  *  These weights are initially set to 0, so that it's
  *  possible to 'fade in' the first frame of the motion sequence from
@@ -25,8 +25,9 @@
  *
  *  To fade out at the end, set a frame with 0 weight for everything.
  *  Otherwise it will simply die suddenly.  When a joint reaches its
- *  last keyframe, it will be set to 0 weight for all future
- *  updateOutputs() (unless of course the playhead is reset)
+ *  last keyframe, if #hold is set (the default) it will hold its last value
+ *  until the MotionSequence is reset or stopped.  If #hold is false,
+ *  then the joint is treated as 0 weight once it reaches its last frame.
  *
  *  Currently, MotionSequenceEngine is intended mainly for building, 
  *  not editing.  It's easy to add keyframes, but hard/impossible to
@@ -46,15 +47,93 @@
  *    - '<tt>delay </tt><i>time-delta</i>' - moves playhead forward, in milliseconds (synonym for <tt>advanceTime</tt>)
  *    - '<tt>setTime </tt><i>time</i>' - sets play time to specified value, in ms
  *    - '<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 is a posture, sets position
- *    - '<tt>overlay </tt><i>filename</i>' - file can be a posture or another motion sequence
- *    - '<tt>degrees</tt>' - following <i>value</i>s will be interpreted as degrees [default]
- *    - '<tt>radians</tt>' - following <i>value</i>s will be interpreted as radians
+ *    - '<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>'
  *  
  *  Lines beginning with '#' are ignored as comments.  Be aware if you
  *  load the file and then save it again, these comments will be lost.
+ *
+ *  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:nod       0 
+
+<i>\# Pan right</i>
+advanceTime  850 
+NECK:pan~       -45 
+
+<i>\# Pan left</i>
+advanceTime  900 
+NECK:pan~       45 
+NECK:tilt       15 
+NECK:nod       0 
+
+\#END
+</pre></td></tr></table>
+ *  
+ *  This graph illustrates the motion of the tilt and pan joints in example 1:
+ *  <img src="MotionSequenceGraph1.png">
+ *  Notice how the joint will move from wherever it is initally to the first
+ *  keyframe <i>for that joint</i>.  Specifying the tilt joint a second time
+ *  at the end of the motion forces the tilt joint to be held at that position
+ *  throughout the motion, regardless of the #hold setting at the time
+ *  the sequence is run.
+ *  
+ *  Example 2: This example will straighten the head and the tail, pan the
+ *  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
+NECK:pan~ 0
+NECK:tilt 0
+TAIL:pan~ 0
+TAIL:tilt 0
+
+<i>\# Pan left</i>
+advanceTime 1000
+NECK:pan~ 90
+<i>\# Pan right</i>
+advanceTime 1000
+NECK:pan~ -90
+
+<i>\# Center head</i>
+<i>\# Update tail time index</i>
+advanceTime 500
+NECK:pan~ 0
+<i>\# Note this respecification of TAIL:pan~ at 0 -- see graph below</i>
+TAIL:pan~ 0
+
+<i>\# Wag left</i>
+advanceTime 500
+TAIL:pan~ 90
+<i>\# Wag right</i>
+advanceTime 500
+TAIL:pan~ -90
+
+\#END 
+</pre></td></tr></table>
+ *  
+ *  These graphs illustrate the motion of the pan joint for the head and the tail:
+ *  <img src="MotionSequenceGraph2-head.png">
+ *  <img src="MotionSequenceGraph2-tail.png">
+ *  The head's motion should be straightforward.  The thing to note in the tail's
+ *  graph is why the second <code>TAIL:pan~ 0</code> is necessary at time
+ *  2550.  If it were not specified, the tail would slowly move to the left over the
+ *  course of the head's movement.  We want it to stay still until the head is done,
+ *  so it must be respecified at the same position to hold it at that value in the
+ *  intervening time.
  *  
  *  After loading a motion sequence, the playtime is left at the end.
  *  This is to make it easy to append/overlay motion sequences.
@@ -71,7 +150,8 @@
  *
  *  //Over the course of the first 700 milliseconds, go to standing posture:
  *  standSit->setTime(700);
- *  standSit->setPose(PostureEngine("stand.pos")); // can also use LoadFile("stand.pos")
+ *  standSit->setPose(PostureEngine("stand.pos"));
+ *  // could also use standSit->loadFile("stand.pos")
  *
  *  //Then take another 700 milliseconds to straighten out the head:
  *  standSit->advanceTime(700);
@@ -96,8 +176,11 @@
  *  However, you can either call MotionManager::addPersistentMotion()
  *  to add it, or call setAutoPrune(false), if you want to retain the
  *  same instantiation between executions.
- *  
+ *
  *  @see PostureEngine for information on the posture files
+ *  @see <a href="http://www.cs.cmu.edu/~dst/Tekkotsu/Tutorial/postures.shtml">David Touretzky's "Postures and Motion Sequences" Chapter</a>
+ *  @see <a href="http://www.cs.cmu.edu/afs/cs/academic/class/15494-s06/www/lectures/postures.pdf">CMU's Cognitive Robotics posture slides</a>
+ *  @todo We should also have an insertMotion()
  */
 class MotionSequenceEngine : public LoadSave {
 public:
@@ -111,10 +194,10 @@
 	
 	//!@name LoadSave related
 	virtual unsigned int getBinSize() const; //!< inherited, returns the size used to save the sequence
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len); //!< 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 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
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len); //!< 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 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
 	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
@@ -127,10 +210,13 @@
 	unsigned int advanceTime(unsigned int x) {setTime(playtime+x); return playtime; } //!< advance the play/edit index by @a x milliseconds, and then returns the new getTime()
 	void setOutputCmd(unsigned int i, const OutputCmd& cmd); //!< will insert a keyframe for the given output, or change an existing one
 	const OutputCmd& getOutputCmd(unsigned int i); //!< gets the value of output @a i at the playhead
-	void setPose(const PostureEngine& pose); //!< calls setOutputCmd on each of the OutputCmds in @a pose
+	void setPose(const PostureEngine& pose); //!< calls setOutputCmd for all non-zero weighted OutputCmds in @a pose (if you wish to set from a file, use loadFile)
+	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); //!< calls setOutputCmd on non-zero weighted OutputCmds in @a pose
+	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
 	virtual unsigned int getMaxFrames() const=0; //!< returns the maximum number of key frames (Move's) which can be stored, determined by the instantiating MotionSequenceMC's template parameter
 	virtual unsigned int getUsedFrames() const=0; //!< returns the number of used key frames (Move's) which have been stored by the instantiation MotionSequenceEngine subclass
@@ -193,8 +279,8 @@
 		ans.set(prev.cmd,next.cmd,prevweight);
 	}
 	
-	//!Sets prev and next to the appropriate values for the given time and output index
-	virtual void setRange(unsigned int t,Move_idx_t& prev, Move_idx_t& next) const=0;
+	//!Sets prev and next to the appropriate values for the given time and output index, return true if there was a change
+	virtual bool setRange(unsigned int t,Move_idx_t& prev, Move_idx_t& next) const=0;
 
 	//!sets playtime to next time for which any output has a keyframe, -1 if none exists
 	unsigned int setNextFrameTime(Move_idx_t p[NumOutputs], Move_idx_t n[NumOutputs]) const;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/MotionSequenceMC.h ./Motion/MotionSequenceMC.h
--- ../Tekkotsu_2.4.1/Motion/MotionSequenceMC.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Motion/MotionSequenceMC.h	2006-09-09 00:32:54.000000000 -0400
@@ -5,6 +5,7 @@
 #include "MotionSequenceEngine.h"
 #include "MotionCommand.h"
 #include "MotionManager.h"
+#include "Events/EventBase.h"
 
 //! Instantiates MotionSequenceEngines - when you want to run a motion sequence, make one of these
 /*! Allows a compile-time variable amount of data storage through its template parameter.
@@ -18,16 +19,16 @@
 
 	//!constructor
 	MotionSequenceMC()
-		: MotionCommand(), MotionSequenceEngine(), moves()
+		: MotionCommand(), MotionSequenceEngine(), moves(), lastDirty(false)
 	{
 		clear();
 	}
 	//!constructor, loads from a file and then resets the playtime to beginning and begins to play
 	explicit MotionSequenceMC(const std::string& filename)
-		: MotionCommand(), MotionSequenceEngine(), moves()
+		: MotionCommand(), MotionSequenceEngine(), moves(), lastDirty(false)
 	{
 		clear();
-		LoadFile(filename.c_str());
+		loadFile(filename.c_str());
 		setTime(1);
 	}
 	//!destructor
@@ -40,9 +41,13 @@
 	virtual int updateOutputs() {
 		MotionSequenceEngine::updateOutputs();
 		if(!isPlaying()) {
+			if(lastDirty)
+				postEvent(EventBase(EventBase::motmanEGID,getID(),EventBase::statusETID));
+			lastDirty=false;
 			for(unsigned int i=0; i<NumOutputs; i++) //just copies getOutputCmd(i) across frames
 				motman->setOutput(this,i,getOutputCmd(i));
 		} else {
+			lastDirty=true;
 			//cout << getTime() << ": ";
 			for(unsigned int i=0; i<NumOutputs; i++) { //fill out the buffer of commands for smoother movement
 				Move_idx_t prev=prevs[i],next=nexts[i];
@@ -89,6 +94,7 @@
 
 	// MEMBERS:
 	list_t moves; //!< stores all of the movement keyframes
+	bool lastDirty; //!< true if last updateOutputs was dirty, so we know when to post status event
 
 	virtual Move& getKeyFrame(Move_idx_t x) { return moves[x]; } //!< returns #moves[@a x]
 	virtual const Move& getKeyFrame(Move_idx_t x) const { return moves[x]; } //!< returns #moves[@a x]
@@ -101,8 +107,10 @@
 	//! marks keyframe @a x unused
 	virtual void eraseKeyFrame(Move_idx_t x) { moves.erase(x); }
 	//! advances (or rewinds) @a prev and @a next so that @a t falls between them
-	void setRange(unsigned int t,Move_idx_t& prev, Move_idx_t& next) const {
+	bool setRange(unsigned int t,Move_idx_t& prev, Move_idx_t& next) const {
+		bool moved=false;
 		if(next!=invalid_move && moves[next].starttime<=t) {
+			moved=true;
 			do {
 				prev=next;
 				next=moves[prev].next;
@@ -111,8 +119,10 @@
 			while(moves[prev].prev!=invalid_move && t<moves[prev].starttime) {
 				next=prev;
 				prev=moves[next].prev;
+				moved=true;
 			} 
 		}
+		return moved;
 	}
 };
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/OldKinematics.cc ./Motion/OldKinematics.cc
--- ../Tekkotsu_2.4.1/Motion/OldKinematics.cc	2004-08-05 16:29:04.000000000 -0400
+++ ./Motion/OldKinematics.cc	2006-10-03 22:41:52.000000000 -0400
@@ -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][ERS7Info::MinRange] || 
-		 angles[1]>ERS7Info::outputRanges[ERS7Info::HeadOffset+PanOffset][ERS7Info::MaxRange]
+	if(angles[1]<ERS7Info::outputRanges[ERS7Info::HeadOffset+PanOffset][MinRange] || 
+		 angles[1]>ERS7Info::outputRanges[ERS7Info::HeadOffset+PanOffset][MaxRange]
 		 ) {
 		double elv=-atan2(target.x,target.z);
-		elv=bound(elv,ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][ERS7Info::MinRange],ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][ERS7Info::MaxRange]);
+		elv=bound(elv,ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][MinRange],ERS7Info::outputRanges[ERS7Info::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][ERS7Info::MinRange] || 
-		 angles[2]>ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][ERS7Info::MaxRange]
+	if(angles[2]<ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][MinRange] || 
+		 angles[2]>ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][MaxRange]
 		 ) {
 		double nod;
-		if(angles[2]<ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][ERS7Info::MinRange])
-			nod=ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][ERS7Info::MinRange];
+		if(angles[2]<ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][MinRange])
+			nod=ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][MinRange];
 		else
-			nod=ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][ERS7Info::MaxRange];
+			nod=ERS7Info::outputRanges[ERS7Info::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][ERS7Info::MinRange])
+		if(angles[2]<ERS7Info::outputRanges[ERS7Info::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][ERS7Info::MinRange])
-			angles[0]=ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][ERS7Info::MinRange];
-		else if(angles[0]>ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][ERS7Info::MaxRange])
-			angles[0]=ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][ERS7Info::MaxRange];
+		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];
 		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_2.4.1/Motion/OutputPID.h ./Motion/OutputPID.h
--- ../Tekkotsu_2.4.1/Motion/OutputPID.h	2003-12-13 00:01:40.000000000 -0500
+++ ./Motion/OutputPID.h	2006-09-16 13:32:39.000000000 -0400
@@ -27,12 +27,14 @@
 	float weight; //!< weight to be used in averaging, 0 to "fall through"
 
 protected:
-	inline void set_pid(const float p[3]) { //!< handy utility function
+	 //! handy utility function, sets #pid[0:2] to @a p[0:2]
+	inline void set_pid(const float p[3]) {
 		pid[0]=p[0];
 		pid[1]=p[1];
 		pid[2]=p[2];
 	}
-	inline void set_pid(const float p, const float i, const float d) { //!< handy utility function
+	 //! handy utility function, sets #pid[0:2] to [@a p,@a i,@a d]
+	inline void set_pid(const float p, const float i, const float d) {
 		pid[0]=p;
 		pid[1]=i;
 		pid[2]=d;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/PostureEngine.cc ./Motion/PostureEngine.cc
--- ../Tekkotsu_2.4.1/Motion/PostureEngine.cc	2005-01-07 14:36:38.000000000 -0500
+++ ./Motion/PostureEngine.cc	2006-09-09 00:32:55.000000000 -0400
@@ -3,17 +3,17 @@
 #include "Motion/roboop/robot.h"
 #include "Shared/Config.h"
 #include <stdio.h>
+#include <iostream>
 
 PostureEngine::~PostureEngine() {}
 
 void PostureEngine::takeSnapshot() {
-	for(unsigned int i=0; i<NumOutputs; i++)
-		cmds[i].value=state->outputs[i];
+	takeSnapshot(*WorldState::getCurrent());
 }
 
-void PostureEngine::takeSnapshot(const WorldState* st) {
+void PostureEngine::takeSnapshot(const WorldState& st) {
 	for(unsigned int i=0; i<NumOutputs; i++)
-		cmds[i].value=st->outputs[i];
+		cmds[i].value=st.outputs[i];
 }
 
 void PostureEngine::setWeights(float w, unsigned int lowjoint, unsigned int highjoint) {
@@ -127,129 +127,490 @@
 	return max;
 }
 
-unsigned int PostureEngine::getBinSize() const {
-	unsigned int len=11;
-	char buf[255];
-	for(unsigned int i=0; i<NumOutputs; i++)
-		if(cmds[i].weight>0)
-			len+=snprintf(buf,len,"%s\t% .4f\t% .4f\n",outputNames[i],cmds[i].value,cmds[i].weight);
-	return len;
+void PostureEngine::setSaveFormat(bool condensed, WorldState* ws) {
+	saveFormatCondensed=condensed;
+	loadSaveSensors=ws;
 }
 
-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;
-	}
-	char formatstring[64];
-	snprintf(formatstring,64,"%%%dc %%f %%f%%n",outputNameLen); //std::cout << "Format: " << formatstring << std::endl;
-	unsigned int idx=0;
-	unsigned int linenum=1;
-	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--;
+unsigned int PostureEngine::getBinSize() const {
+	unsigned int written=11; //accounts for initial #POS\n and final #END\n, plus 1
+	const unsigned int len=0;
+	char buf[len];
+	if(saveFormatCondensed) {
+		written+=snprintf(buf,len,"condensed %s\n",RobotName);
+		if(loadSaveSensors!=NULL)
+			written+=snprintf(buf,len,"meta-info = %u %u\n",loadSaveSensors->lastSensorUpdateTime,loadSaveSensors->frameNumber);
+		bool weightsAllEqual=true;
+		float weightsVal=cmds[0].weight;
+		for(unsigned int i=1; i<NumOutputs && weightsAllEqual; i++)
+			weightsAllEqual=(cmds[i].weight==weightsVal);
+		if(!weightsAllEqual || weightsVal!=0) { //if they're all 0, skip outputs and weights
+			written+=snprintf(buf,len,"outputs =");
+			for(unsigned int i=0; i<NumOutputs; i++) {
+				written+=snprintf(buf,len," %g",cmds[i].value);
 			}
-			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--;
+			if(!weightsAllEqual || weightsVal!=1) { //if they're all 1, skip weights
+				written+=snprintf(buf,len,"\nweights =");
+				for(unsigned int i=0; i<NumOutputs; i++) {
+					written+=snprintf(buf,len," %g",cmds[i].weight);
 				}
-				linenum++;
-				continue;
 			}
+			written+=snprintf(buf,len,"\n");
 		}
-		written=-1;
-		jname[0]='\0';
-		sscanf(buf,formatstring,jname,&fval,&fwht,&written);
-		if(!ChkAdvance(written,&buf,&len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0;
-		while(*buf!='\n' && *buf!='\r')
-			buf++;
-		if(buf[0]=='\r' && buf[1]=='\n')
-			buf+=2;
-		else
-			buf++;
-		linenum++;
-		//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(strcmp(jname,outputNames[idx])==0) {
-				cmds[idx].set(fval,fwht);
-				break;
+		if(loadSaveSensors!=NULL) {
+			written+=snprintf(buf,len,"buttons =");
+			for(unsigned int i=0; i<NumButtons; i++) {
+				written+=snprintf(buf,len," %g",loadSaveSensors->buttons[i]);
 			}
-		if(idx==NumOutputs) { //not found following startidx, look from beginning
-			for(idx=0;idx<startidx;idx++)
-				if(strcmp(jname,outputNames[idx])==0) {
-					cmds[idx].set(fval,fwht);
-					break;
+			written+=snprintf(buf,len,"\nsensors =");
+			for(unsigned int i=0; i<NumSensors; i++) {
+				written+=snprintf(buf,len," %g",loadSaveSensors->sensors[i]);
 			}
-			if(idx==startidx && strcmp(jname,outputNames[idx])!=0) //not found at all
-				std::cout << "*** WARNING '" << jname << "' is not a valid joint on this model." << std::endl;
+			written+=snprintf(buf,len,"\npidduties =");
+			for(unsigned int i=0; i<NumPIDJoints; i++) {
+				written+=snprintf(buf,len," %g",loadSaveSensors->pidduties[i]);
+			}
+			written+=snprintf(buf,len,"\n");
+		}		
+	} 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);
+		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(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,"</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,"</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,"</pidduties>\n");
 		}
 	}
-	std::cout << "*** WARNING PostureEngine load missing #END" << std::endl;
-	return origlen-len;
+	return written;
+}
+
+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--;
+	}
+	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);
+	}
+      } 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;
+		}
+	      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;
+		}
+	      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;
+		}
+	      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(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;
+					}
+				}
+				tname[0]='R';
+				for(idx=0;idx<NumOutputs;idx++) {
+					if(strncmp(tname,outputNames[idx],outputNameLen+1)==0) {
+						ridx=idx;
+						break;
+					}
+				}
+				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;
 }
 
 //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 PostureEngine::saveBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
 	int written=snprintf(buf,len,"#POS\n");
-	if(!ChkAdvance(written,(const char**)&buf,&len,"*** ERROR PostureEngine save failed on header\n")) return 0;
-	if(len==0 || len>origlen) {
-		std::cout << "*** ERROR PostureEngine save overflow on header" << std::endl;
-		return 0;
-	}
-	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(!ChkAdvance(written,(const char**)&buf,&len,"*** ERROR PostureEngine save failed\n")) return 0;
-			if(len==0 || len>origlen) {
-				std::cout << "*** ERROR PostureEngine save overflow" << std::endl;
-				return 0;
+	if(!checkInc(written,buf,len,"*** ERROR PostureEngine save failed on header\n")) return 0;
+	if(saveFormatCondensed) {
+		written=snprintf(buf,len,"condensed %s\n",RobotName);
+		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);
+			if(!checkInc(written,buf,len,"*** ERROR PostureEngine save pidduty failed\n")) return 0;
+		}
+		bool weightsAllEqual=true;
+		float weightsVal=cmds[0].weight;
+		for(unsigned int i=1; i<NumOutputs && weightsAllEqual; i++)
+			weightsAllEqual=(cmds[i].weight==weightsVal);
+		if(!weightsAllEqual || weightsVal!=0) { //if they're all 0, skip outputs and weights
+			written=snprintf(buf,len,"outputs =");
+			if(!checkInc(written,buf,len,"*** ERROR PostureEngine save outputs header failed\n")) return 0;
+			for(unsigned int i=0; i<NumOutputs; i++) {
+				written=snprintf(buf,len," %g",cmds[i].value);
+				if(!checkInc(written,buf,len,"*** ERROR PostureEngine save output failed\n")) return 0;
+			}
+			if(!weightsAllEqual || weightsVal!=1) { //if they're all 1, skip weights
+				written=snprintf(buf,len,"\nweights =");
+				if(!checkInc(written,buf,len,"*** ERROR PostureEngine save weights header failed\n")) return 0;
+				for(unsigned int i=0; i<NumOutputs; i++) {
+					written=snprintf(buf,len," %g",cmds[i].weight);
+					if(!checkInc(written,buf,len,"*** ERROR PostureEngine save weight failed\n")) return 0;
+				}
 			}
+			written=snprintf(buf,len,"\n");
+			if(!checkInc(written,buf,len,"*** ERROR PostureEngine save final newline failed\n")) return 0;
+		}
+		if(loadSaveSensors!=NULL) {
+			written=snprintf(buf,len,"buttons =");
+			if(!checkInc(written,buf,len,"*** ERROR PostureEngine save buttons header failed\n")) return 0;
+			for(unsigned int i=0; i<NumButtons; i++) {
+				written=snprintf(buf,len," %g",loadSaveSensors->buttons[i]);
+				if(!checkInc(written,buf,len,"*** ERROR PostureEngine save button failed\n")) return 0;
+			}
+			written=snprintf(buf,len,"\nsensors =");
+			if(!checkInc(written,buf,len,"*** ERROR PostureEngine save sensors header failed\n")) return 0;
+			for(unsigned int i=0; i<NumSensors; i++) {
+				written=snprintf(buf,len," %g",loadSaveSensors->sensors[i]);
+				if(!checkInc(written,buf,len,"*** ERROR PostureEngine save sensor failed\n")) return 0;
+			}
+			written=snprintf(buf,len,"\npidduties =");
+			if(!checkInc(written,buf,len,"*** ERROR PostureEngine save pidduties header failed\n")) return 0;
+			for(unsigned int i=0; i<NumPIDJoints; i++) {
+				written=snprintf(buf,len," %g",loadSaveSensors->pidduties[i]);
+				if(!checkInc(written,buf,len,"*** ERROR PostureEngine save pidduty failed\n")) return 0;
+			}
+			written=snprintf(buf,len,"\n");
+			if(!checkInc(written,buf,len,"*** ERROR PostureEngine save final newline failed\n")) return 0;
+		}		
+	} 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);
+			if(!checkInc(written,buf,len,"*** ERROR PostureEngine sensor begin save failed\n")) return 0;
+		}
+		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(!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]);
+				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]);
+				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]);
+				if(!checkInc(written,buf,len,"*** ERROR PostureEngine save pidduties failed\n")) return 0;
+			}
+			written=snprintf(buf,len,"</pidduties>\n");
+			if(!checkInc(written,buf,len,"*** ERROR PostureEngine sensor end save failed\n")) return 0;
 		}
-	written=snprintf(buf,len,"#END\n");
-	if(!ChkAdvance(written,(const char**)&buf,&len,"*** ERROR PostureEngine save failed on #END\n")) return 0;
-	if(len==0 || len>origlen) {
-		std::cout << "*** ERROR PostureEngine save overflow on #END" << std::endl;
-		return 0;
 	}
+	written=snprintf(buf,len,"#END\n");
+	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());
+unsigned int PostureEngine::loadFile(const char filename[]) {
+	return LoadSave::loadFile(config->motion.makePath(filename).c_str());
 }
-unsigned int PostureEngine::SaveFile(const char filename[]) const {
-	return LoadSave::SaveFile(config->motion.makePath(filename).c_str());
+unsigned int PostureEngine::saveFile(const char filename[]) const {
+	return LoadSave::saveFile(config->motion.makePath(filename).c_str());
 }
 
 /*
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/PostureEngine.h ./Motion/PostureEngine.h
--- ../Tekkotsu_2.4.1/Motion/PostureEngine.h	2005-01-07 14:36:38.000000000 -0500
+++ ./Motion/PostureEngine.h	2006-10-03 22:57:12.000000000 -0400
@@ -11,18 +11,45 @@
 
 //! 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
- *  @see PostureMC */
+ *  @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>
+ *  @see <a href="http://www.cs.cmu.edu/~dst/Tekkotsu/Tutorial/forwardkin.shtml">David Touretzky's "Forward Kinematics" Chapter</a>
+ *  @see <a href="http://www.cs.cmu.edu/afs/cs/academic/class/15494-s06/www/lectures/postures.pdf">CMU's Cognitive Robotics posture slides</a>
+ *  @see <a href="http://www.cs.cmu.edu/afs/cs/academic/class/15494-s06/www/lectures/kinematics.pdf">CMU's Cognitive Robotics kinematics slides</a>
+ */
 class PostureEngine : public LoadSave, public Kinematics {
 public:
 
 	//!@name Constructors
+	
 	//!constructor
-	PostureEngine() : LoadSave(), Kinematics(*kine) {}
+	PostureEngine() : LoadSave(), Kinematics(*kine), saveFormatCondensed(false), loadSaveSensors(NULL) {}
 	//!constructor, loads a position from a file
-	/*! @todo might want to make a library of common positions so they don't have to be loaded repeatedly from memstick */
-	PostureEngine(const std::string& filename) : LoadSave(), Kinematics(*kine) { LoadFile(filename.c_str()); }
+	/*! @todo might want to make a library stored in memory of common positions so they don't have to be loaded repeatedly from memstick */
+	PostureEngine(const std::string& filename) : LoadSave(), Kinematics(*kine), saveFormatCondensed(false), loadSaveSensors(NULL) { loadFile(filename.c_str()); }
 	//!constructor, initializes joint positions to the current state of the outputs as defined by @a state
-	PostureEngine(const WorldState* st) : LoadSave(), Kinematics(*kine) { takeSnapshot(st); }
+	PostureEngine(const WorldState* st) : LoadSave(), Kinematics(*kine), saveFormatCondensed(false), loadSaveSensors(NULL) { if(st!=NULL) takeSnapshot(*st); }
+
+	//! copy constructor
+	PostureEngine(const PostureEngine& pe)
+		: LoadSave(pe), Kinematics(pe), saveFormatCondensed(pe.saveFormatCondensed), loadSaveSensors(pe.loadSaveSensors)
+	{
+		for(unsigned int i=0; i<NumOutputs; i++)
+			cmds[i]=pe.cmds[i];
+	}
+		
+	//! assignment operator
+	PostureEngine& operator=(const PostureEngine& pe) {
+		LoadSave::operator=(pe);
+		Kinematics::operator=(pe);
+		saveFormatCondensed=pe.saveFormatCondensed;
+		loadSaveSensors=pe.loadSaveSensors;
+		for(unsigned int i=0; i<NumOutputs; i++)
+			cmds[i]=pe.cmds[i];
+		return *this;
+	}
+
 	//! destructor
 	virtual ~PostureEngine();
 	//@}
@@ -32,7 +59,7 @@
 	//! You should be able to call the non-virtual functions without checking out, just a MotionManager::peekMotion().  Theoretically.
 	//!@name Output Value Access/Control
 	virtual void takeSnapshot(); //!< sets the values of #cmds to the current state of the outputs (doesn't change the weights)
-	virtual void takeSnapshot(const WorldState* st); //!< sets the values of #cmds to the current state of the outputs as defined by @a state (doesn't change the weights)
+	virtual void takeSnapshot(const WorldState& st); //!< sets the values of #cmds to the current state of the outputs as defined by @a state (doesn't change the weights)
 	virtual void setWeights(float w) { setWeights(w,0,NumOutputs); } //!< set the weights of all #cmds
 	virtual void setWeights(float w, unsigned int lowjoint, unsigned int highjoint); //!< the the weights of a range of #cmds
 	virtual void clear(); //!< sets all joints to unused
@@ -47,41 +74,65 @@
 
 	//!Uses LoadSave interface so you can load/save to files, uses a human-readable storage format
 	//!@name LoadSave
+	virtual void setSaveFormat(bool condensed, WorldState* ws); //!< sets #saveFormatCondensed and #loadSaveSensors (pass ::state for @a ws if you want to use current sensor values)
+	virtual void setLoadedSensors(WorldState* ws) { loadSaveSensors=ws; } //!< if @a ws is non-NULL, any sensor values in loaded postures will be stored there (otherwise they are ignored)
+	virtual WorldState* getLoadedSensors() const { return loadSaveSensors; } //!< returns value previously stored by setLoadSensors()
 	virtual unsigned int getBinSize() const;
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
-	virtual unsigned int LoadFile(const char filename[]);
-	virtual unsigned int SaveFile(const char filename[]) const;
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
+	virtual unsigned int loadFile(const char filename[]);
+	virtual unsigned int saveFile(const char filename[]) const;
 	//@}
 
 
 
 	//!@name Kinematics
 
-	//! Performs inverse kinematics to solve for positioning @a Peff on link @a j to @a Ptgt (expects homogenous form); if solution found, stores result in this posture and returns true
+	//! Performs inverse kinematics to solve for positioning @a Peff on link @a j as close as possible to @a Ptgt (base coordinates in homogenous form); if solution found, stores result in this posture and returns true
 	/*! @param Ptgt the target point, in base coordinates
 	 *  @param link the output offset of the joint to move
-	 *  @param Peff the point (relative to @a link) which you desire to have moved to @a Ptgt (it's the desired "effector") */
+	 *  @param Peff the point (relative to @a link) which you desire to have moved to @a Ptgt (it's the desired "effector")
+	 *
+	 *  The difference between solveLinkPosition() and solveLinkVector() is typically small,
+	 *  but critical when you're trying to look at something -- the solution obtained by
+	 *  simplying trying to solve for the position may not align the vector with the target --
+	 *  solveLinkVector() tries to ensure the vector is aligned with the target, even if that
+	 *  isn't the closest solution position-wise.
+	 */
 	virtual bool solveLinkPosition(const NEWMAT::ColumnVector& Ptgt, unsigned int link, const NEWMAT::ColumnVector& Peff);
 
-	//! Performs inverse kinematics to solve for positioning Peff on link @a j to @a Ptgt; if solution found, stores result in this posture and returns true
+	//! Performs inverse kinematics to solve for positioning Peff on link @a j as close as possible to @a Ptgt (base coordinates); if solution found, stores result in this posture and returns true
 	/*! @param Ptgt_x the target x position (relative to base frame)
 	 *  @param Ptgt_y the target y position (relative to base frame)
 	 *  @param Ptgt_z the target z position (relative to base frame)
 	 *  @param link the output offset of the joint to move
 	 *  @param Peff_x the x position (relative to @a link) which you desire to have moved to @a Ptgt (it's the desired "effector")
 	 *  @param Peff_y the y position (relative to @a link) which you desire to have moved to @a Ptgt (it's the desired "effector")
-	 *  @param Peff_z the z position (relative to @a link) which you desire to have moved to @a Ptgt (it's the desired "effector") */
+	 *  @param Peff_z the z position (relative to @a link) which you desire to have moved to @a Ptgt (it's the desired "effector")
+	 *
+	 *  The difference between solveLinkPosition() and solveLinkVector() is typically small,
+	 *  but critical when you're trying to look at something -- the solution obtained by
+	 *  simplying trying to solve for the position may not align the vector with the target --
+	 *  solveLinkVector() tries to ensure the vector is aligned with the target, even if that
+	 *  isn't the closest solution position-wise.
+	 */
 	virtual bool solveLinkPosition(float Ptgt_x, float Ptgt_y, float Ptgt_z, unsigned int link, float Peff_x, float Peff_y, float Peff_z)
 	{ return solveLinkPosition(pack(Ptgt_x,Ptgt_y,Ptgt_z),link,pack(Peff_x,Peff_y,Peff_z)); }
 
-	//! Performs inverse kinematics to solve for positioning Peff on link @a j to point at Ptgt (expects homogenous form); if solution found, stores result in this posture and returns true
+	//! Performs inverse kinematics to solve for aligning the vector through Peff on link @a j and the link's origin to point at @a Ptgt (base coordinates in homogenous form); if solution found, stores result in this posture and returns true
 	/*! @param Ptgt the target point, in base coordinates
 	 *  @param link the output offset of the joint to move
-	 *  @param Peff the point (relative to @a link) which you desire to have moved to @a Ptgt (it's the desired "effector") */
+	 *  @param Peff the point (relative to @a link) which you desire to have moved to @a Ptgt (it's the desired "effector")
+	 *
+	 *  The difference between solveLinkPosition() and solveLinkVector() is typically small,
+	 *  but critical when you're trying to look at something -- the solution obtained by
+	 *  simplying trying to solve for the position may not align the vector with the target --
+	 *  solveLinkVector() tries to ensure the vector is aligned with the target, even if that
+	 *  isn't the closest solution position-wise.
+	 */
 	virtual bool solveLinkVector(const NEWMAT::ColumnVector& Ptgt, unsigned int link, const NEWMAT::ColumnVector& Peff);
 
-	//! Performs inverse kinematics to solve for positioning @a Peff on link @a j to point at @a Ptgt; if solution found, stores result in this posture and returns true
+	//! Performs inverse kinematics to solve for aligning the vector through Peff on link @a j and the link's origin to point at @a Ptgt (base coordinates); if solution found, stores result in this posture and returns true
 	/*! @param Ptgt_x the target x position (relative to base frame)
 	 *  @param Ptgt_y the target y position (relative to base frame)
 	 *  @param Ptgt_z the target z position (relative to base frame)
@@ -90,7 +141,14 @@
 	 *  @param Peff_y the y position (relative to @a link) which you desire to have moved to @a Ptgt (it's the desired "effector")
 	 *  @param Peff_z the z position (relative to @a link) which you desire to have moved to @a Ptgt (it's the desired "effector")
 	 *
-	 *  @todo this method is an approximation, could be more precise, and perhaps faster, although this is pretty good. */
+	 *  @todo this method is an approximation, could be more precise, and perhaps faster, although this is pretty good.
+	 *
+	 *  The difference between solveLinkPosition() and solveLinkVector() is typically small,
+	 *  but critical when you're trying to look at something -- the solution obtained by
+	 *  simplying trying to solve for the position may not align the vector with the target --
+	 *  solveLinkVector() tries to ensure the vector is aligned with the target, even if that
+	 *  isn't the closest solution position-wise.
+	 */
 	virtual bool solveLinkVector(float Ptgt_x, float Ptgt_y, float Ptgt_z, unsigned int link, float Peff_x, float Peff_y, float Peff_z)
 	{ return solveLinkVector(pack(Ptgt_x,Ptgt_y,Ptgt_z),link,pack(Peff_x,Peff_y,Peff_z)); }
 
@@ -140,11 +198,13 @@
 
 	//!the table of outputs' values and weights, can be accessed through setOutputCmd() and getOutputCmd()
 	OutputCmd cmds[NumOutputs];
+
+	bool saveFormatCondensed;      //!< requests a condensed file format, smaller but less readable
+	WorldState* loadSaveSensors;   //!< If non-null, saves will include sensor readings from here, and loads will store any read sensors into here
 };
 
 /*! @file
  * @brief Describes PostureEngine, a base class for managing the values and weights of all the outputs
- * @todo write a binary version of Load/Save commands for faster access
  * @author ejt (Creator)
  *
  * $Author: ejt $
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/PostureMC.cc ./Motion/PostureMC.cc
--- ../Tekkotsu_2.4.1/Motion/PostureMC.cc	2005-01-07 16:12:35.000000000 -0500
+++ ./Motion/PostureMC.cc	2006-08-31 17:48:00.000000000 -0400
@@ -1,6 +1,5 @@
 #include "PostureMC.h"
 #include "Shared/Config.h"
-#include "MotionManager.h"
 #include "Shared/WorldState.h"
 
 PostureMC& PostureMC::setDirty(bool d/*=true*/) {
@@ -60,14 +59,19 @@
 int PostureMC::isAlive() {
 	if(dirty || !targetReached)
 		return true;
-	if(targetReached && get_time()-targetTimestamp>timeout) { //prevents a conflicted PostureMC's from fighting forever
-		if(getAutoPrune())
+	if(targetReached && (!hold || get_time()-targetTimestamp>timeout)) { //prevents a conflicted PostureMC's from fighting forever
+		if(get_time()-targetTimestamp>timeout && getAutoPrune())
 			serr->printf("WARNING: posture timed out - possible joint conflict or out-of-range target\n");
 		return false;
 	}
-	PostureEngine tmp; 
-	tmp.takeSnapshot(); 
-	return (maxdiff(tmp)>tolerance);
+	float max=0;
+	for(unsigned int i=0; i<NumOutputs; i++)
+		if(cmds[i].weight>0) {
+			float dif=cmds[i].value-state->outputs[i];
+			if(dif>max)
+				max=dif;
+		}
+	return (max>tolerance);
 }
 
 void PostureMC::init() {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/PostureMC.h ./Motion/PostureMC.h
--- ../Tekkotsu_2.4.1/Motion/PostureMC.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Motion/PostureMC.h	2006-09-09 00:32:56.000000000 -0400
@@ -4,6 +4,7 @@
 
 #include "MotionCommand.h"
 #include "PostureEngine.h"
+#include "MotionManager.h"
 
 class WorldState;
 
@@ -120,7 +121,7 @@
 	//!These functions merely set the dirty flag and then call the PostureEngine version of the function
 	//!@name PostureEngine Stuff
 	inline virtual void takeSnapshot() { setDirty(); PostureEngine::takeSnapshot(); }
-	inline virtual void takeSnapshot(const WorldState* st) { setDirty(); PostureEngine::takeSnapshot(st); }
+	inline virtual void takeSnapshot(const WorldState& st) { setDirty(); PostureEngine::takeSnapshot(st); }
 	inline virtual void setWeights(float w) { setWeights(w,0,NumOutputs); }
 	inline virtual void setWeights(float w, unsigned int lowjoint, unsigned int highjoint) { setDirty(); PostureEngine::setWeights(w,lowjoint,highjoint); }
 	inline virtual void clear() { setDirty(); PostureEngine::clear(); }
@@ -128,8 +129,8 @@
 	inline virtual PostureEngine& setUnderlay(const PostureEngine& pe) { setDirty(); PostureEngine::setUnderlay(pe); return *this; }
 	inline virtual PostureEngine& setAverage(const PostureEngine& pe,float w=0.5) { setDirty(); PostureEngine::setAverage(pe,w); return *this; }
 	inline virtual PostureEngine& setCombine(const PostureEngine& pe) { setDirty(); PostureEngine::setCombine(pe); return *this; }
-	inline PostureEngine& setOutputCmd(unsigned int i, const OutputCmd& c) { setDirty(); PostureEngine::setOutputCmd(i,c); return *this; }
-	inline virtual unsigned int LoadBuffer(const char buf[], unsigned int len) { setDirty(); return PostureEngine::LoadBuffer(buf,len); }
+	inline PostureEngine& setOutputCmd(unsigned int i, const OutputCmd& c) { dirty=true; targetReached=false; curPositions[i]=motman->getOutputCmd(i).value; PostureEngine::setOutputCmd(i,c); return *this; }
+	inline virtual unsigned int loadBuffer(const char buf[], unsigned int len) { setDirty(); return PostureEngine::loadBuffer(buf,len); }
 	inline virtual bool solveLinkPosition(const NEWMAT::ColumnVector& Ptgt, unsigned int link, const NEWMAT::ColumnVector& Peff) { setDirty(); return PostureEngine::solveLinkPosition(Ptgt,link,Peff); }
 	inline virtual bool solveLinkPosition(float Ptgt_x, float Ptgt_y, float Ptgt_z, unsigned int link, float Peff_x, float Peff_y, float Peff_z) { setDirty(); return PostureEngine::solveLinkPosition(Ptgt_x,Ptgt_y,Ptgt_z,link,Peff_x,Peff_y,Peff_z); }
 	inline virtual bool solveLinkVector(const NEWMAT::ColumnVector& Ptgt, unsigned int link, const NEWMAT::ColumnVector& Peff) { setDirty(); return PostureEngine::solveLinkVector(Ptgt,link,Peff); }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/TailWagMC.h ./Motion/TailWagMC.h
--- ../Tekkotsu_2.4.1/Motion/TailWagMC.h	2005-04-06 16:36:00.000000000 -0400
+++ ./Motion/TailWagMC.h	2006-02-15 14:14:13.000000000 -0500
@@ -12,48 +12,86 @@
 
 //! A simple motion command for wagging the tail - you can specify period, magnitude, and tilt
 class TailWagMC : public MotionCommand {
- public:
+public:
+
 	//!constructor
-	TailWagMC() : period(500), magnitude(22*M_PI/180), active(true), tilt() { }
+	TailWagMC() :
+		MotionCommand(), period(500), magnitude(22*M_PI/180), 
+		offset(0), active(true), last_pan(0.0), last_sign(0), tilt() { }
+
 	//!constructor
-	TailWagMC(unsigned int cyc_period, float cyc_magnitude) : period(cyc_period), magnitude(cyc_magnitude), active(true), tilt() { }
+	TailWagMC(unsigned int cyc_period, float cyc_magnitude) :
+		MotionCommand(), period(cyc_period), magnitude(cyc_magnitude), 
+		offset(0), active(true), last_pan(0.0), last_sign(0), tilt() { }
+
 	//!destructor
 	virtual ~TailWagMC() {}
+
 	virtual int updateOutputs() {
 		if(!active)
 			return 0;
-		if(state->robotDesign&WorldState::ERS210Mask) {
-			for(unsigned int i=0; i<NumFrames; i++)
-				pans[i].set(sin((2*M_PI*(get_time()+i*FrameTime))/period)*magnitude); //bug fix thanks L.A.Olsson AT herts ac uk
-			motman->setOutput(this,ERS210Info::TailOffset+PanOffset,pans);
-			motman->setOutput(this,ERS210Info::TailOffset+TiltOffset,tilt);
-			return tilt.weight>0?2:1;
-		} else if(state->robotDesign&WorldState::ERS7Mask) {
-			for(unsigned int i=0; i<NumFrames; i++)
-				pans[i].set(sin((2*M_PI*(get_time()+i*FrameTime))/period)*magnitude); //bug fix thanks L.A.Olsson AT herts ac uk
-			motman->setOutput(this,ERS7Info::TailOffset+PanOffset,pans);
-			motman->setOutput(this,ERS7Info::TailOffset+TiltOffset,tilt);
-			return tilt.weight>0?2:1;
-		} else
-			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;
+		}
+		else if(state->robotDesign & WorldState::ERS7Mask) {
+			tail_pan_offset = ERS7Info::TailOffset+PanOffset;
+			tail_tilt_offset = ERS7Info::TailOffset+TiltOffset;
+		}
+		else 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
+			pans[i].set(new_pan);
+			if ( (new_pan-last_pan >= 0 && last_sign == -1) ||
+			     (new_pan-last_pan < 0 && last_sign == +1) )
+				postEvent(EventBase(EventBase::motmanEGID,getID(),EventBase::statusETID));
+			last_sign = new_pan-last_pan >= 0 ? 1 : -1;
+			last_pan = new_pan;
+		}
+		motman->setOutput(this,tail_pan_offset,pans);
+		motman->setOutput(this,tail_tilt_offset,tilt);
+		return tilt.weight>0?2:1;
 	}
+
 	virtual int isDirty() { return active; }
+
 	virtual int isAlive() { return true; }
 
-	void setPeriod(unsigned int p) { period=p; } //!< sets the period of time between swings, in milliseconds
+	//! sets the period of time between swings, in milliseconds
+	/*! a bit complicated in order to avoid jerking around when the period changes */
+	void setPeriod(unsigned int p) {
+		float prevPos=((get_time()+offset)%period)/(float)period;
+		period=p;
+		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
 	void setMagnitude(double mag) { magnitude=mag; } //!< sets the magnitude of swings, in radians
 	double getMagnitude() { 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
-	void setActive(bool a) { active=a; } //!< turns the tail wagger on or off
+
 	bool getActive() { return active; } //!< returns true if this is currently trying to wag the tail
-	
- protected:
+
+	//! turns the tail wagger on or off
+	void setActive(bool a) {
+		if ( active != a )
+			last_sign = 0;
+		active=a;
+	}
+  
+protected:
 	unsigned int period; //!< period of time between swings, in milliseconds
 	double magnitude; //!< magnitude of swings, in radians
+	unsigned int offset; //!< offset in the period, only used if period is changed to avoid twitching
 	bool active; //!< true if this is currently trying to wag the tail
+	float last_pan; //!< last tail position
+	int last_sign; //!< sign of tail movement direction
 	OutputCmd tilt; //!< holds current setting for the tilt joint
 	OutputCmd pans[NumFrames]; //!< holds commands for planning ahead the wagging
 };
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/UPennWalkMC.cc ./Motion/UPennWalkMC.cc
--- ../Tekkotsu_2.4.1/Motion/UPennWalkMC.cc	2005-04-12 17:33:31.000000000 -0400
+++ ./Motion/UPennWalkMC.cc	2006-08-31 17:37:10.000000000 -0400
@@ -389,7 +389,7 @@
   // Check to see if legs should stand rather than walk
   if ((walk_phase == 0) &&
       (xWalk == 0.0) && (yWalk == 0.0) && (aWalk == 0.0)) {
-    StandLegs(0, 0, 0);
+    //StandLegs(0, 0, 0);
     return;
   }
   
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/WalkMC.cc ./Motion/WalkMC.cc
--- ../Tekkotsu_2.4.1/Motion/WalkMC.cc	2005-06-29 18:01:55.000000000 -0400
+++ ./Motion/WalkMC.cc	2006-09-10 14:48:46.000000000 -0400
@@ -111,9 +111,9 @@
     legw[i].air = false;
 
 	if(pfile!=NULL)
-		LoadFile(pfile);
+		loadFile(pfile);
 	else
-		LoadFile(config->motion.walk.c_str());
+		loadFile(config->motion.walk.c_str());
 
 	double zeros[JointsPerLeg];
 	for(unsigned int i=0; i<JointsPerLeg; i++)
@@ -147,106 +147,111 @@
 	return used;	
 }
 
-unsigned int WalkMC::LoadBuffer(const char buf[], unsigned int len) {
+unsigned int WalkMC::loadBuffer(const char buf[], unsigned int len) {
+	enum {
+		VER1, // original CMPack version
+		VER2, // added calibration parameters
+		VER3 // added diff drive and sag parameter
+	} version;
+	
 	unsigned int origlen=len;
-	unsigned int used=0;
-	if((used=checkCreator("WalkMC-2.2",buf,len,false))!=0) {
-		len-=used; buf+=used;
-		if(len>=sizeof(WalkParam))
-			memcpy(&wp,buf,used=sizeof(WalkParam));
-		else
-			return 0;
-		len-=used; buf+=used;
-		if(len>=sizeof(CalibrationParam))
-			memcpy(&cp,buf,used=sizeof(CalibrationParam));
-		else
-			memcpy(&cp,buf,used=len);
-		//return 0;
-		len-=used; buf+=used;
-		//sout->printf("Loaded WalkMC Parameters n=%ud checksum=0x%X\n",origlen-len,checksum(reinterpret_cast<const char*>(&wp),sizeof(wp)+sizeof(cp)));
-		return origlen-len;	
-	} else if((used=checkCreator("WalkMC",buf,len,false))!=0) {
-		sout->printf("Pre-version 2.2 walk parameter file\n");
-		len-=used; buf+=used;
-		for(unsigned int i=0; i<4; i++) {
-			if(len>=sizeof(LegParam))
-				memcpy(&wp.leg[i],buf,used=sizeof(LegParam));
-			else
-				return 0;
-			len-=used; buf+=used;
-		}
-		if(0==(used=decode(wp.body_height,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=decode(wp.body_angle,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=decode(wp.hop,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=decode(wp.sway,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=decode(wp.period,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=decode(wp.useDiffDrive,buf,len))) return 0;
-		len-=used; buf+=used;
-		wp.sag=0;
-		if(len>=sizeof(CalibrationParam))
-			memcpy(&cp,buf,used=sizeof(CalibrationParam));
-		else
-			return 0;
-		len-=used; buf+=used;
-		//sout->printf("Loaded WalkMC Parameters n=%ud checksum=0x%X\n",origlen-len,checksum(reinterpret_cast<const char*>(&wp),sizeof(wp)+sizeof(cp)));
-		return origlen-len;	
+	if(checkCreatorInc("WalkMC-2.2",buf,len,false)) {
+		version=VER3;
+	} else if(checkCreatorInc("WalkMC",buf,len,false)) {
+		sout->printf("Pre-2.2 release walk parameter file\n");
+		version=VER2;
 	} else {
 		// backwards compatability - if there's no creator code, just assume it's a straight WalkParam
-		sout->printf("Assuming old-format walk parameter file\n");
-		for(unsigned int i=0; i<4; i++) {
-			if(len>=sizeof(LegParam))
-				memcpy(&wp.leg[i],buf,used=sizeof(LegParam));
-			else
-				return 0;
-			len-=used; buf+=used;
-		}
-		if(0==(used=decode(wp.body_height,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=decode(wp.body_angle,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=decode(wp.hop,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=decode(wp.sway,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=decode(wp.period,buf,len))) return 0;
-		len-=used; buf+=used;
-		wp.useDiffDrive=0;
-		wp.sag=0;
+		sout->printf("Assuming CMPack format walk parameter file\n");
+		version=VER1;
+	}
+	
+	// Leg parameters
+	for(unsigned int i=0; i<NumLegs; ++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;
+		if(!decodeInc(wp.leg[i].lift_vel.x,buf,len)) return 0;
+		if(!decodeInc(wp.leg[i].lift_vel.y,buf,len)) return 0;
+		if(!decodeInc(wp.leg[i].lift_vel.z,buf,len)) return 0;
+		if(!decodeInc(wp.leg[i].down_vel.x,buf,len)) return 0;
+		if(!decodeInc(wp.leg[i].down_vel.y,buf,len)) return 0;
+		if(!decodeInc(wp.leg[i].down_vel.z,buf,len)) return 0;
+		if(!decodeInc(wp.leg[i].lift_time,buf,len)) return 0;
+		if(!decodeInc(wp.leg[i].down_time,buf,len)) return 0;
+	}
+	// Body parameters
+	if(!decodeInc(wp.body_height,buf,len)) return 0;
+	if(!decodeInc(wp.body_angle,buf,len)) return 0;
+	if(!decodeInc(wp.hop,buf,len)) return 0;
+	if(!decodeInc(wp.sway,buf,len)) return 0;
+	if(!decodeInc(wp.period,buf,len)) return 0;
+	if(version<VER3) wp.useDiffDrive=0; else if(!decodeInc(wp.useDiffDrive,buf,len)) return 0;
+	if(version<VER3) wp.sag=0; else if(!decodeInc(wp.sag,buf,len)) return 0;
+	if(!decodeInc(wp.reserved,buf,len)) return 0;
+	// Calibration parameters
+	if(version<VER2) {
 		cp=CalibrationParam();
-		//sout->printf("Loaded WalkMC Parameters n=%ud checksum=0x%X\n",origlen-len,checksum(reinterpret_cast<const char*>(&wp),sizeof(wp)));
-		return origlen-len;	
+	} else {
+		for(unsigned int i=0; i<3; ++i)
+			for(unsigned int j=0; j<11; ++j)
+				if(!decodeInc(cp.f_calibration[i][j],buf,len)) return 0;
+		for(unsigned int i=0; i<3; ++i)
+			for(unsigned int j=0; j<11; ++j)
+				if(!decodeInc(cp.b_calibration[i][j],buf,len)) return 0;
+		for(unsigned int i=0; i<CalibrationParam::NUM_DIM; ++i)
+			if(!decodeInc(cp.max_accel[i],buf,len)) return 0;
+		for(unsigned int i=0; i<CalibrationParam::NUM_DIM; ++i)
+			if(!decodeInc(cp.max_vel[i],buf,len)) return 0;
 	}
+	return origlen-len;	
 }
 
-unsigned int WalkMC::SaveBuffer(char buf[], unsigned int len) const {
+unsigned int WalkMC::saveBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used=0;
-	if(0==(used=saveCreator("WalkMC-2.2",buf,len))) return 0;
-	len-=used; buf+=used;
-	if(len>=sizeof(WalkParam))
-		memcpy(buf,&wp,used=sizeof(WalkParam));
-	else
-		return 0;
-	len-=used; buf+=used;
-	if(len>=sizeof(CalibrationParam))
-		memcpy(buf,&cp,used=sizeof(CalibrationParam));
-	else
-		return 0;
-	len-=used; buf+=used;
-	//sout->printf("Saved WalkMC Parameters n=%ud checksum=0x%X\n",origlen-len,checksum(reinterpret_cast<const char*>(&wp),sizeof(wp)+sizeof(cp)));
-	return origlen-len;
+	// Leg parameters
+	if(!saveCreatorInc("WalkMC-2.2",buf,len)) return 0;
+	for(unsigned int i=0; i<NumLegs; ++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;
+		if(!encodeInc(wp.leg[i].lift_vel.x,buf,len)) return 0;
+		if(!encodeInc(wp.leg[i].lift_vel.y,buf,len)) return 0;
+		if(!encodeInc(wp.leg[i].lift_vel.z,buf,len)) return 0;
+		if(!encodeInc(wp.leg[i].down_vel.x,buf,len)) return 0;
+		if(!encodeInc(wp.leg[i].down_vel.y,buf,len)) return 0;
+		if(!encodeInc(wp.leg[i].down_vel.z,buf,len)) return 0;
+		if(!encodeInc(wp.leg[i].lift_time,buf,len)) return 0;
+		if(!encodeInc(wp.leg[i].down_time,buf,len)) return 0;
+	}
+	// Body parameters
+	if(!encodeInc(wp.body_height,buf,len)) return 0;
+	if(!encodeInc(wp.body_angle,buf,len)) return 0;
+	if(!encodeInc(wp.hop,buf,len)) return 0;
+	if(!encodeInc(wp.sway,buf,len)) return 0;
+	if(!encodeInc(wp.period,buf,len)) return 0;
+	if(!encodeInc(wp.useDiffDrive,buf,len)) return 0;
+	if(!encodeInc(wp.sag,buf,len)) return 0;
+	if(!encodeInc(wp.reserved,buf,len)) return 0;
+	// Calibration parameters
+	for(unsigned int i=0; i<3; ++i)
+		for(unsigned int j=0; j<11; ++j)
+			if(!encodeInc(cp.f_calibration[i][j],buf,len)) return 0;
+	for(unsigned int i=0; i<3; ++i)
+		for(unsigned int j=0; j<11; ++j)
+			if(!encodeInc(cp.b_calibration[i][j],buf,len)) return 0;
+	for(unsigned int i=0; i<CalibrationParam::NUM_DIM; ++i)
+		if(!encodeInc(cp.max_accel[i],buf,len)) return 0;
+	for(unsigned int i=0; i<CalibrationParam::NUM_DIM; ++i)
+		if(!encodeInc(cp.max_vel[i],buf,len)) return 0;
+	return origlen-len;	
 }
 
-unsigned int WalkMC::LoadFile(const char* filename) {
-	return LoadSave::LoadFile(config->motion.makePath(filename).c_str());
+unsigned int WalkMC::loadFile(const char* filename) {
+	return LoadSave::loadFile(config->motion.makePath(filename).c_str());
 }
-unsigned int WalkMC::SaveFile(const char* filename) const {
-	return LoadSave::SaveFile(config->motion.makePath(filename).c_str());
+unsigned int WalkMC::saveFile(const char* filename) const {
+	return LoadSave::saveFile(config->motion.makePath(filename).c_str());
 }
 
 void WalkMC::setTargetVelocity(double dx,double dy,double da,int n)
@@ -406,6 +411,7 @@
 						e.setXYA(target_vel_xya.x,target_vel_xya.y,target_vel_xya.z);
 						//cout << e.getDescription(true) << endl;
 						postEvent(e);
+						postEvent(EventBase(EventBase::motmanEGID,getID(),EventBase::statusETID,getTravelTime()));
 						//		cout << "WalkMC-done" << endl;
 						return frame==0?0:NumLegs*JointsPerLeg;
 					}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/WalkMC.h ./Motion/WalkMC.h
--- ../Tekkotsu_2.4.1/Motion/WalkMC.h	2005-04-12 15:07:07.000000000 -0400
+++ ./Motion/WalkMC.h	2006-10-03 17:42:50.000000000 -0400
@@ -60,8 +60,7 @@
  *  function to control the direction of the walk.
  *
  *  This class is in some dire need of some cleanup - we (Tekkotsu)
- *  didn't write it, never really bothered to get a deep understanding
- *  of it, but have none the less hacked around and added stuff on top
+ *  didn't write it, have none the less hacked around and added stuff on top
  *  of it.  So pardon the mess, unless you're feeling ambitious to
  *  write your own ;)
  *
@@ -107,15 +106,15 @@
 
 	//! holds information to correct for slippage, non-idealities
 	struct CalibrationParam {
-		CalibrationParam();
+		CalibrationParam(); //!< constructor, sets calibration matricies to identity
 
 		//! symbolic way to refer to each of the directions
 		enum dimension_offset {
-			forward,
-			reverse, 
-			strafe,
-			rotate,
-			NUM_DIM
+			forward, //!< forward (x)
+			reverse, //!< backward (-x)
+			strafe,  //!< sideways (y)
+			rotate,  //!< spin (z/a)
+			NUM_DIM  //!< number of directions we calibrate for
 		};
 
 		float f_calibration[3][11]; //!< matrix of calibration parameters; 3 columns for f,s,r speeds, 2 columns for abs s,r speeds, 1 gabor function, 1 squared planar speed, 3 columns for f*r,s*f,r*s, and 1 column for offset
@@ -136,14 +135,14 @@
 	//! Returns true if we are walking. This modified isDirty allows the AIBO to slow down to a stop rather than stopping immediately.
 	virtual int isDirty();
 	
-	//! always true - never autoprunes
-	virtual int isAlive() { return true; }
+	//! Will prune if we've taken the requested number of steps.
+	virtual int isAlive() { return step_count != 0; }
 
 	virtual unsigned int getBinSize() const;
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
-	virtual	unsigned int LoadFile(const char* filename);
-	virtual unsigned int SaveFile(const char* filename) const;
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
+	virtual	unsigned int loadFile(const char* filename);
+	virtual unsigned int saveFile(const char* filename) const;
 
 	//! set the direction to walk
 	/*! @param dx forward velocity (millimeters per second)
@@ -208,8 +207,8 @@
 	//! returns the current leg position of leg @a i
 	const vector3d& getLegPosition(LegOrder_t i) const { return legpos[i]; }
 
-	WalkParam& getWP() { return wp; }; //!< returns the current walk parameter structure
-	CalibrationParam& getCP() { return cp; }; //!< returns the current walk calibration parameter
+	struct WalkParam& getWP() { return wp; }; //!< returns the current walk parameter structure
+	struct CalibrationParam& getCP() { return cp; }; //!< returns the current walk calibration parameter
 	
 	//! takes current leg positions from WorldState and tries to match the point in the cycle most like it
 	void resetLegPos();
@@ -228,7 +227,7 @@
 	static void applyCalibration(const float mat[3][11], const vector3d& in, vector3d& out);
 
  protected:
-	//! does some setup stuff, calls LoadFile(pfile)
+	//! does some setup stuff, calls loadFile(pfile)
 	void init(const char* pfile);
 
 	bool isPaused; //!< true if we are paused
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/WaypointEngine.h ./Motion/WaypointEngine.h
--- ../Tekkotsu_2.4.1/Motion/WaypointEngine.h	2005-08-09 19:00:50.000000000 -0400
+++ ./Motion/WaypointEngine.h	2006-09-09 00:32:58.000000000 -0400
@@ -91,8 +91,8 @@
  *  <table cellspacing=0 cellpadding=0 width="325" class="figures" align="center" border="0"><tr>
  *  <td class="figure"><img src="Waypoint_Error.png"><div style="padding:10px;">
  *  The effect of the Waypoint::trackPath flag.  When @c true, the robot will attempt to catch up
- *  to its "ideal" location after a perterbation.  When @c false, the robot will ignore the "ideal"
- *  path, and just go straight to the destination from wherever perterbations may push it.
+ *  to its "ideal" location after a perturbation.  When @c false, the robot will ignore the "ideal"
+ *  path, and just go straight to the destination from wherever perturbations may push it.
  *  </div></td></tr></table>
  *
  *  trackPath is a per-waypoint setting, setTracking() sets the
@@ -146,25 +146,25 @@
 
 	//! constructor
 	WaypointEngine()
-		: LoadSave(), waypoints(), isRunning(false), isLooping(true), isTracking(false),
+		: LoadSave(), waypoints(), isRunning(false), isLooping(false), isTracking(false),
 			curWaypoint(waypoints.end()), waypointTime(0), waypointDistance(0), pathLength(0), arcRadius(0),
 			lastUpdateTime(0), Pcorr(.5), turnSpeed(.65)
 	{init();}
 	//! constructor
 	WaypointEngine(char * f)
-		: LoadSave(), waypoints(), isRunning(false), isLooping(true), isTracking(false),
+		: LoadSave(), waypoints(), isRunning(false), isLooping(false), isTracking(false),
 			curWaypoint(waypoints.end()), waypointTime(0), waypointDistance(0), pathLength(0), arcRadius(0),
 			lastUpdateTime(0), Pcorr(.5), turnSpeed(.65)
-	{init(); LoadFile(f); }
+	{init(); loadFile(f); }
 
 	//! returns a rough overestimate of the size needed
 	/*! pretends we need to switch max_turn_speed and track_path on
 		every point, and the longest options are given for every point */
 	virtual unsigned int getBinSize() const;
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
-	virtual unsigned int LoadFile(const char * filename) { return LoadSave::LoadFile(config->motion.makePath(filename).c_str()); }
-	virtual unsigned int SaveFile(const char * filename) const { return LoadSave::SaveFile(config->motion.makePath(filename).c_str()); }
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
+	virtual unsigned int loadFile(const char * filename) { return LoadSave::loadFile(config->motion.makePath(filename).c_str()); }
+	virtual unsigned int saveFile(const char * filename) const { return LoadSave::saveFile(config->motion.makePath(filename).c_str()); }
 
 	virtual void go();      //!< starts walking towards the first waypoint
 	virtual void pause();   //!< halts execution of waypoint list
@@ -316,7 +316,7 @@
 		arcRadius = (radiusRatio==0) ? 0 : (waypointDistance/2)/radiusRatio;
 		pathLength = arcRadius!=0 ? arcRadius*waypoints[iter].arc : waypointDistance;
 
-		cout << "Target is now: ("<<targetPos[0]<<','<<targetPos[1]<<','<<targetPos[2]<<")" << endl;
+		std::cout << "Target is now: ("<<targetPos[0]<<','<<targetPos[1]<<','<<targetPos[2]<<")" << std::endl;
 	}
 
 	//!if @a it follows the current waypoint, applies all the waypoints between #curWaypoint and @a it and returns result as an absolute position (angle field stores heading); otherwise calls the other calcAbsoluteCoords(WaypointListIter_t, float, float, float)
@@ -476,7 +476,7 @@
 }
 
 template<unsigned int MAX_WAY>
-unsigned int WaypointEngine<MAX_WAY>::LoadBuffer(const char buf[], unsigned int len) {
+unsigned int WaypointEngine<MAX_WAY>::loadBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
 	waypoints.clear();
 	if(strncmp("#WyP\n",buf,5)!=0 && strncmp("#WyP\r",buf,5)!=0) {
@@ -527,10 +527,10 @@
 		}
 		int used=-1U;
 		sscanf(buf,"%40s%n",cmd,&used);
-		if(!ChkAdvance(used,&buf,&len,"*** ERROR Waypoint list load corrupted - ran out of room line %d\n",linenum)) return 0;
+		if(!checkInc(used,buf,len,"*** ERROR Waypoint list load corrupted - ran out of room line %d\n",linenum)) return 0;
 		if(strncasecmp(cmd,"add_point",9)==0 || strncasecmp(cmd,"add_arc",7)==0) {
 			sscanf(buf,"%40s %g %g %40s %g %g %g%n",posType,&x_val,&y_val,angType,&angle_val,&speed_val,&arc_val,&used);
-			if(!ChkAdvance(used,&buf,&len,"*** ERROR Waypoint list load corrupted - bad read on add at line %d\n",linenum)) return 0;
+			if(!checkInc(used,buf,len,"*** ERROR Waypoint list load corrupted - bad read on add at line %d\n",linenum)) return 0;
 			if(strncasecmp(angType,"hold",4)==0)
 				ang_val=false;
 			else if(strncasecmp(angType,"follow",6)==0)
@@ -569,10 +569,10 @@
 			int track_tmp;
 			sscanf(buf,"%d%n",&track_tmp,&used);
 			track=track_tmp;
-			if(!ChkAdvance(used,&buf,&len,"*** ERROR Waypoint load corrupted - bad read on track_path line %d\n",linenum)) return 0;
+			if(!checkInc(used,buf,len,"*** ERROR Waypoint load corrupted - bad read on track_path line %d\n",linenum)) return 0;
 		} else if(strncasecmp(cmd,"max_turn_speed",14)==0) {
 			sscanf(buf,"%g%n",&turn,&used);
-			if(!ChkAdvance(used,&buf,&len,"*** ERROR Waypoint load corrupted - bad read on max_turn_speed line %d\n",linenum)) return 0;
+			if(!checkInc(used,buf,len,"*** ERROR Waypoint load corrupted - bad read on max_turn_speed line %d\n",linenum)) return 0;
 		} else {
 			printf("*** ERROR WaypointEngine: Invalid command %s\n",cmd);
 			return 0;
@@ -585,16 +585,16 @@
 }
 
 template<unsigned int MAX_WAY>
-unsigned int WaypointEngine<MAX_WAY>::SaveBuffer(char buf[], unsigned int len) const {
+unsigned int WaypointEngine<MAX_WAY>::saveBuffer(char buf[], unsigned int len) const {
 	unsigned int origLen=len;
 	unsigned int used;
 	unsigned int cnt=0;
 		
 	used=snprintf(buf,len,"#WyP\n");
-	if(!ChkAdvance(used,(const char**)&buf,&len,"*** ERROR Waypoint list save failed on header\n")) return 0;
+	if(!checkInc(used,buf,len,"*** ERROR Waypoint list save failed on header\n")) return 0;
 
 	used=snprintf(buf,len,"#add_{point|arc} {ego|off|abs} x_val y_val {hold|follow} angle_val speed_val arc_val\n");
-	if(!ChkAdvance(used,(const char**)&buf,&len,"*** ERROR Waypoint list save failed on header\n")) return 0;
+	if(!checkInc(used,buf,len,"*** ERROR Waypoint list save failed on header\n")) return 0;
 
 	//set our state variables so we'll be forced to output the first set
 	float turn=waypoints.front().turnSpeed-1;
@@ -604,12 +604,12 @@
 		if(waypoints[it].turnSpeed!=turn) {
 			turn=waypoints[it].turnSpeed;
 			used=snprintf(buf,len,"max_turn_speed %g\n",turn);
-			if(!ChkAdvance(used,(const char**)&buf,&len,"*** ERROR Waypoint list save failed on waypoint %d turnSpeed\n",cnt)) return 0;
+			if(!checkInc(used,buf,len,"*** ERROR Waypoint list save failed on waypoint %d turnSpeed\n",cnt)) return 0;
 		}
 		if(waypoints[it].trackPath!=track) {
 			track=waypoints[it].trackPath;
 			used=snprintf(buf,len,"track_path %d\n",track);
-			if(!ChkAdvance(used,(const char**)&buf,&len,"*** ERROR Waypoint list save failed on waypoint %d\n trackPath",cnt)) return 0;
+			if(!checkInc(used,buf,len,"*** ERROR Waypoint list save failed on waypoint %d\n trackPath",cnt)) return 0;
 		}
 		const char * posType=NULL;
 		switch(waypoints[it].posType) {
@@ -624,12 +624,12 @@
 			used=snprintf(buf,len,"add_point %s %g %g %s %g %g %g\n",posType,waypoints[it].x,waypoints[it].y,(waypoints[it].angleIsRelative?"FOLLOW":"HOLD"),waypoints[it].angle,waypoints[it].speed,waypoints[it].arc);
 		else //todo - store center of circle
 			used=snprintf(buf,len,"add_point %s %g %g %s %g %g %g\n",posType,waypoints[it].x,waypoints[it].y,(waypoints[it].angleIsRelative?"FOLLOW":"HOLD"),waypoints[it].angle,waypoints[it].speed,waypoints[it].arc);
-		if(!ChkAdvance(used,(const char**)&buf,&len,"*** ERROR Waypoint list save failed on waypoint %d\n",cnt)) return 0;
+		if(!checkInc(used,buf,len,"*** ERROR Waypoint list save failed on waypoint %d\n",cnt)) return 0;
 		cnt++;
 	}
 
 	used=snprintf(buf,len,"#END\n");
-	if(!ChkAdvance(used,(const char**)&buf,&len,"*** ERROR Waypoint list save failed on footer\n")) return 0;
+	if(!checkInc(used,buf,len,"*** ERROR Waypoint list save failed on footer\n")) return 0;
 
 	return origLen-len;
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/WaypointWalkMC.h ./Motion/WaypointWalkMC.h
--- ../Tekkotsu_2.4.1/Motion/WaypointWalkMC.h	2005-06-01 01:47:48.000000000 -0400
+++ ./Motion/WaypointWalkMC.h	2006-09-09 00:32:58.000000000 -0400
@@ -35,10 +35,10 @@
 		return WalkMC::updateOutputs();
 	}
 
-	virtual int LoadWaypointFile(const char * f) { return WaypointEngine<MAX_WAYPOINTS>::LoadFile(f); } //!< allows loading a waypoint file
-	virtual int SaveWaypointFile(const char * f) const { return WaypointEngine<MAX_WAYPOINTS>::SaveFile(f); } //!< allows saving a waypoint file
-	virtual int LoadWalkMCFile(const char * f) { return WalkMC::LoadFile(f); } //!< allows loading a WalkMC parameter file
-	virtual int SaveWalkMCFile(const char * f) const { return WalkMC::SaveFile(f); } //!< allows saving a WalkMC parameter file
+	virtual int LoadWaypointFile(const char * f) { return WaypointEngine<MAX_WAYPOINTS>::loadFile(f); } //!< allows loading a waypoint file
+	virtual int SaveWaypointFile(const char * f) const { return WaypointEngine<MAX_WAYPOINTS>::saveFile(f); } //!< allows saving a waypoint file
+	virtual int LoadWalkMCFile(const char * f) { return WalkMC::loadFile(f); } //!< allows loading a WalkMC parameter file
+	virtual int SaveWalkMCFile(const char * f) const { return WalkMC::saveFile(f); } //!< allows saving a WalkMC parameter file
 
 };
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/roboop/Makefile ./Motion/roboop/Makefile
--- ../Tekkotsu_2.4.1/Motion/roboop/Makefile	2005-08-09 22:20:09.000000000 -0400
+++ ./Motion/roboop/Makefile	2006-03-28 12:08:21.000000000 -0500
@@ -6,7 +6,8 @@
 ifndef TEKKOTSU_ENVIRONMENT_CONFIGURATION
 $(error An error has occured, TEKKOTSU_ENVIRONMENT_CONFIGURATION was not defined)
 endif
-include $(TEKKOTSU_ENVIRONMENT_CONFIGURATION)
+TEKKOTSU_ROOT:=../..
+include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
 BUILDDIR=$(TK_LIB_BD)/Motion/roboop
 SRCSUFFIX=.cpp
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Motion/roboop/config.cpp ./Motion/roboop/config.cpp
--- ../Tekkotsu_2.4.1/Motion/roboop/config.cpp	2005-07-25 23:22:08.000000000 -0400
+++ ./Motion/roboop/config.cpp	2006-09-25 19:30:32.000000000 -0400
@@ -130,10 +130,10 @@
       while( !inconffile.eof() )
       {
 	 // Is-it comment line?
-         if(temp.substr(0,1) != "#")
+         if(temp[0] != '#')
          {
 	    // Is-it a section name?
-            if(temp.substr(0,1) == "[") // [section]
+            if(temp[0] == '[') // [section]
             {
 	       // Search for the end of the section name and ignore the rest of the line.
  	       tmpPos = temp.find("]");
@@ -149,10 +149,10 @@
 		   getline(inconffile, temp);
 #endif
 		   // Be sure that is not another section name.
-		   while( (temp.substr(0,1) != "[") &&
+		   while( (temp[0] != '[') &&
 			  (!inconffile.eof()) )
 		     {
-		       if(temp.substr(0,1) != "#") // ignore comments
+		       if(temp[0] != '#') // ignore comments
 			 {
 			   if(temp.find(":") != string::npos)
 			     {
@@ -175,7 +175,7 @@
 			       tmpPos = parameter.find(":");
 			       if (tmpPos != (int)string::npos)
 				 // remove ":" a the end of parameter
-				 parameter = parameter.substr(0, tmpPos);
+				 parameter = parameter.erase(tmpPos);
 			       else
 				 {
 #ifdef __WATCOMC__
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/Buffer.h ./Shared/Buffer.h
--- ../Tekkotsu_2.4.1/Shared/Buffer.h	2004-12-22 20:47:07.000000000 -0500
+++ ./Shared/Buffer.h	2006-09-16 02:28:08.000000000 -0400
@@ -20,6 +20,7 @@
 		Buffer(const Buffer& rhs);
 		//! Makes this buffer a copy of the rhs buffer
 		Buffer& operator=(const Buffer& rhs);
+		//! destructor, deletes #data
 		virtual ~Buffer();
 		
 		//! Gets the pointer to the first element of the underlying array.
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/Cloneable.h ./Shared/Cloneable.h
--- ../Tekkotsu_2.4.1/Shared/Cloneable.h	2005-06-29 18:05:45.000000000 -0400
+++ ./Shared/Cloneable.h	2006-03-16 14:28:03.000000000 -0500
@@ -5,6 +5,7 @@
 //! An interface for cloning objects -- needed for making copies with polymorphism (operator= doesn't work as virtual)
 class Cloneable {
 public:
+	//!destructor
 	virtual ~Cloneable() {}
 
 	//! returns a copy of @c this
@@ -30,7 +31,12 @@
 	 *  gcc version to at least 3.4 and we can switch over to use the
 	 *  "covariant return type".
 	 */
-	virtual Cloneable* clone() const=0;
+
+#if defined(__GNUC__) && (__GNUC__ > 3 || (__GNUC__ == 3 && (__GNUC_MINOR__ > 3)))
+	virtual Cloneable* clone() const __attribute__ ((warn_unused_result)) =0;
+#else
+	virtual Cloneable* clone() const =0;
+#endif
 };
 
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/CommonInfo.h ./Shared/CommonInfo.h
--- ../Tekkotsu_2.4.1/Shared/CommonInfo.h	2003-12-23 01:33:43.000000000 -0500
+++ ./Shared/CommonInfo.h	2006-10-03 22:42:03.000000000 -0400
@@ -27,6 +27,9 @@
 		NodOffset=RollOffset       //!< nod (second tilt)
 	};
 
+	//! 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_2.4.1/Shared/Config.cc ./Shared/Config.cc
--- ../Tekkotsu_2.4.1/Shared/Config.cc	2005-08-05 15:44:22.000000000 -0400
+++ ./Shared/Config.cc	2006-09-27 16:36:06.000000000 -0400
@@ -1,6 +1,8 @@
 #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 <cstring>
@@ -19,6 +21,8 @@
 const OSpeakerVolume ospkvol10dB  = 0xf600;
 #endif
 
+using namespace std;
+
 Config* config=NULL;
 
 void Config::setFileSystemRoot(const std::string& fsr) {
@@ -76,6 +80,9 @@
 				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;
@@ -167,18 +174,24 @@
 			} else if (strncasecmp(key,"rawcam_interval",29)==0) {
 				vision.rawcam_interval=(unsigned int)atoi(value);
 				return &vision.rawcam_interval;
-			} else if (strncasecmp(key,"rle_port",29)==0) {
-				vision.rle_port=atoi(value);
-				return &vision.rle_port;
-			} else if (strncasecmp(key,"rle_transport",29)==0) {
+			} 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.rle_transport=0;
+					vision.segcam_transport=0;
 				else if (strncasecmp(value,"tcp",49)==0)
-					vision.rle_transport=1;
-				return &vision.rle_transport;
-			} else if (strncasecmp(key,"rle_interval",29)==0) {
-				vision.rle_interval=(unsigned int)atoi(value);
-				return &vision.rle_interval;
+					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;
@@ -194,6 +207,9 @@
 			} 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;
@@ -235,6 +251,8 @@
 					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) {
@@ -242,23 +260,37 @@
 				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,"rlecam_skip",29)==0) {
-				vision.rlecam_skip=atoi(value);
-				return &vision.rlecam_skip;
-			} else if (strncasecmp(key,"rlecam_channel",29)==0) {
-				vision.rlecam_channel=atoi(value);
-				return &vision.rlecam_channel;
-			} else if (strncasecmp(key,"rlecam_compression",29)==0) {
+			} 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.rlecam_compression=vision_config::COMPRESS_NONE;
+					vision.segcam_compression=vision_config::COMPRESS_NONE;
 				} else if (strncasecmp(value,"rle",49)==0) {
-					vision.rlecam_compression=vision_config::COMPRESS_RLE;
+					vision.segcam_compression=vision_config::COMPRESS_RLE;
+				} else if (strncasecmp(value,"png",49)==0) {
+					vision.segcam_compression=vision_config::COMPRESS_PNG;
 				}
-				return &vision.rlecam_compression;
+				return &vision.segcam_compression;
 			} else if (strncasecmp(key,"regioncam_skip",29)==0) {
 				vision.regioncam_skip=atoi(value);
 				return &vision.regioncam_skip;
@@ -307,6 +339,15 @@
 			} 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;
@@ -439,7 +480,7 @@
 				else if(strncasecmp(value,"level_3",49)==0)
 					sound.volume=ospkvol10dB;
 				else
-					sound.volume=strtol(value,NULL,0);
+					return NULL;
 				return &sound.volume;
 			} else if (strncasecmp(key,"sample_rate",29)==0) {
 				sound.sample_rate = atoi(value);
@@ -450,13 +491,16 @@
 			} 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_sample_bits",29)==0) {
+			} 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) {
@@ -465,7 +509,7 @@
 			} 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_length",30)==0) {
+			} 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) {
@@ -473,7 +517,7 @@
 				return &sound.streaming.speaker_max_delay;
 			}
 			break;
-		default:
+		case sec_invalid:
 			break;
 	}
 	return NULL;
@@ -500,12 +544,14 @@
 }
 
 void Config::readConfig(const std::string& filename) {
-	FILE* fp = fopen(filename.c_str(), "r");
-	char buf[80], key[30], value[50];
-	section_t section=sec_invalid;
-	if (fp==NULL) return;
+	FILE* fp = fopen(portPath(filename).c_str(), "r");
+	if (fp==NULL)
+		return;
 	
+	char buf[256], key[30], value[50];
+	section_t section=sec_invalid;
 	bool ignoring=false;
+	
 	std::vector<std::string> curmodel;
 #ifdef PLATFORM_APERIOS
 	char rdStr[orobotdesignNAME_MAX + 1];
@@ -532,8 +578,14 @@
 	
 	
 	unsigned int lineno=0;
-	while (fscanf(fp,"%79[^\n]\n", buf)!=EOF) {
+	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) {
@@ -572,10 +624,16 @@
 		} 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) {
+			} else if (sscanf(buf,"%29[^ =] =%49s",key,value)>1) {
 				//printf("setValue(%d,'%s','%s');\n",section,key,value);
-				setValue(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;
 			}
 		}
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/Config.h ./Shared/Config.h
--- ../Tekkotsu_2.4.1/Shared/Config.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Shared/Config.h	2006-09-21 17:26:08.000000000 -0400
@@ -59,13 +59,14 @@
 		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 rle_port;         //!< port to send RLE frames on
-		int rle_transport;    //!< transport protocol: 0 for udp, 1 for tcp
-		unsigned int rle_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)
@@ -83,6 +84,7 @@
 		enum compression_t {
 			COMPRESS_NONE, //!< no compression (other than subsampling)
 			COMPRESS_JPEG, //!< JPEG compression
+			COMPRESS_PNG, //!< PNG compression
 			COMPRESS_RLE   //!< RLE compression
 		};
 		compression_t rawcam_compression;//!< holds whether to send jpeg compression
@@ -90,9 +92,9 @@
 		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 rlecam_skip;       //!< resolution level to transmit segmented images at
-		int rlecam_channel;    //!< channel of RLEGenerator to send
-		compression_t rlecam_compression; //!< what compression to use on the segmented image
+		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 
 
 		//!These values represent a "Plumb Bob" model introduced by Brown in 1966
@@ -128,8 +130,8 @@
 			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*x*y - kc4_tan2*(r2+2*x*x))/radial; //estimating tangential component
-			r_y=(yd - kc3_tan1*(r2+2*y*y) - 2*kc4_tan2*x*y)/radial; //estimating tangential component
+			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;
 		}
       
@@ -161,23 +163,31 @@
 		//!constructor
 		vision_config()
 			: white_balance(3), gain(2), shutter_speed(2), resolution(2),
-				thresh(), colors(), rawcam_port(10011), rawcam_transport(0), rawcam_interval(0),
-				rle_port(10012), rle_transport(0), rle_interval(0), region_port(0), region_transport(0), obj_port(0), restore_image(true), 
+				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), rlecam_skip(1), rlecam_channel(0), rlecam_compression(COMPRESS_RLE), regioncam_skip(1),
+				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
@@ -194,7 +204,7 @@
 		unsigned int worldState_interval; //!< time (in milliseconds) to wait between sending WorldState updates over wireless
 		//!constructor
 		main_config()
-			: seed_rng(true), console_port(10001), stderr_port(10002), error_level(0), debug_level(0),
+			: 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)
@@ -273,6 +283,7 @@
 		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]
 			
 		//!returns an absolute path if @a is relative (to root), otherwise just @a name
 		std::string makePath(const std::string& name) { 
@@ -303,7 +314,7 @@
 		} streaming;
 
 		//!constructor
-		sound_config(Config* c) : thisconfig(c), root(), volume(0xF600), sample_rate(0), sample_bits(0), preload(), streaming() {}
+		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
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/ERS210Info.h ./Shared/ERS210Info.h
--- ../Tekkotsu_2.4.1/Shared/ERS210Info.h	2005-06-01 01:47:48.000000000 -0400
+++ ./Shared/ERS210Info.h	2006-10-03 22:41:51.000000000 -0400
@@ -26,6 +26,7 @@
 	//       ROBOT CONFIGURATION
 	// *******************************
 
+	const char* const RobotName="ERS-210"; //!< 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)
@@ -57,9 +58,14 @@
 	const float CameraFOV=CameraHorizFOV; //!< should be set to maximum of #CameraHorizFOV or #CameraVertFOV
 	const unsigned int CameraResolutionX=176; //!< the number of pixels available in the 'full' layer
 	const unsigned int CameraResolutionY=144; //!< the number of pixels available in the 'full' layer
+	const float BallOfFootRadius=27.922/2; //!< radius of the ball of the foot
+	const float CylinderOfFootRadius=24.606/2; //!< radius of the cylinder of the foot
 
-	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 }; //!< true for joints which can be updated every 32 ms (all but the ears)
+	//! 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 };
 	//@}
 
@@ -135,8 +141,20 @@
 	const LEDBitMask_t TlRedLEDMask= 1<<(TlRedLEDOffset-LEDOffset); //!< red tail light
 	const LEDBitMask_t TlBluLEDMask= 1<<(TlBluLEDOffset-LEDOffset); //!< blue tail light
 
-	const LEDBitMask_t FaceLEDMask = BotLLEDMask|BotRLEDMask|MidLLEDMask|MidRLEDMask|TopLLEDMask|TopRLEDMask|TopBrLEDMask; //!< LEDs for face (all but tail)
-	const LEDBitMask_t HeadLEDMask = BotLLEDMask|BotRLEDMask|MidLLEDMask|MidRLEDMask|TopLLEDMask|TopRLEDMask|TopBrLEDMask; //!< LEDs for face (all but tail)
+	//! LEDs for face (all but tail)
+	const LEDBitMask_t FaceLEDMask
+	= BotLLEDMask	| BotRLEDMask
+	| MidLLEDMask	| MidRLEDMask
+	| TopLLEDMask	| TopRLEDMask
+	| TopBrLEDMask;
+
+	//! LEDs for face (all but tail)
+	const LEDBitMask_t HeadLEDMask
+	= BotLLEDMask | BotRLEDMask
+	| MidLLEDMask | MidRLEDMask
+	| TopLLEDMask | TopRLEDMask
+	| TopBrLEDMask;
+
 	const LEDBitMask_t BackLEDMask = 0; //!< 210 has no back LEDs
 	const LEDBitMask_t TailLEDMask = TlRedLEDMask|TlBluLEDMask; //!< LEDs on tail
 	const LEDBitMask_t AllLEDMask  = (LEDBitMask_t)~0; //!< selects all of the leds
@@ -168,6 +186,7 @@
 		ChinButOffset= 4,
 		BackButOffset,
 		HeadFrButOffset, //!< not in reliable pressure units, but 1.0 is fairly stiff pressure, 0 is none
+		HeadButOffset=HeadFrButOffset,  //!< for ERS-7 compatibility
 		HeadBkButOffset //!< not in reliable pressure units, but 1.0 is fairly stiff pressure, 0 is none
 	};
 	
@@ -395,9 +414,6 @@
 	#define __RI_RAD_FLAG
 	#endif
 	
-	//! Defines the indexes to use to access the min and max entries of ERS210Info::outputRanges and ERS210Info::mechanicalLimits
-	enum MinMaxRange_t { MinRange,MaxRange };
-
 	//! This table holds the software limits of each of the outputs
 	const double outputRanges[NumOutputs][2] =
 		{
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/ERS220Info.h ./Shared/ERS220Info.h
--- ../Tekkotsu_2.4.1/Shared/ERS220Info.h	2005-06-01 01:47:48.000000000 -0400
+++ ./Shared/ERS220Info.h	2006-10-03 22:41:51.000000000 -0400
@@ -29,6 +29,7 @@
 	//       ROBOT CONFIGURATION
 	// *******************************
 
+	const char* const RobotName="ERS-220"; //!< 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)
@@ -60,7 +61,10 @@
 	const float CameraFOV=CameraHorizFOV; //!< should be set to maximum of #CameraHorizFOV or #CameraVertFOV
 	const unsigned int CameraResolutionX=176; //!< the number of pixels available in the 'full' layer
 	const unsigned int CameraResolutionY=144; //!< the number of pixels available in the 'full' layer
+	const float BallOfFootRadius=27.922/2; //!< radius of the ball of the foot
+	const float CylinderOfFootRadius=24.606/2; //!< radius of the cylinder of the foot
 
+	//! true for joints which can be updated every 32 ms (true for all)
 	const bool IsFastOutput[NumOutputs] = {
 		// for PID joints
 		true, true, true,
@@ -78,7 +82,7 @@
 		true, true, true,           // face front LEDs x3
 		true,                       // retractable head light x1
 		// for binary joints (none supported/exist on 220)
-	}; //!< true for joints which can be updated every 32 ms (all but the ears on a 210)
+	};
 
 	//! 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] = {
@@ -98,7 +102,7 @@
 		true, true, true,           // face front LEDs x3
 		true,                       // retractable head light x1
 		// for binary joints (none supported/exist on 220)
-	}; //!< true for joints which can be updated every 32 ms (all but the ears on a 210)
+	};
 
 
 	// *******************************
@@ -201,6 +205,7 @@
 	const LEDBitMask_t TlRedLEDMask= 1<<(TlRedLEDOffset-LEDOffset); //!< red tail light
 	const LEDBitMask_t TlBluLEDMask= 1<<(TlBluLEDOffset-LEDOffset); //!< blue tail light
 
+	//! LEDs for face
 	const LEDBitMask_t FaceLEDMask
 	= FaceFrontLeftLEDMask
 	| FaceFrontRightLEDMask
@@ -211,26 +216,29 @@
 	| FaceFrontALEDMask
 	| FaceFrontBLEDMask
 	| FaceFrontCLEDMask
-	| ModeLEDMask;              //!< LEDs for face
+	| ModeLEDMask;
  
+	//! LEDs on head (face plus retractable light)
 	const LEDBitMask_t HeadLEDMask
-	= FaceLEDMask
-	| RetractableHeadLEDMask;   //!< LEDs on head (face plus retractable light)
+	= FaceLEDMask | RetractableHeadLEDMask;   
  
+	//! LEDs on back
 	const LEDBitMask_t BackLEDMask
 	= BackLeft1LEDMask
 	| BackLeft2LEDMask
 	| BackLeft3LEDMask
 	| BackRight1LEDMask
 	| BackRight2LEDMask
-	| BackRight3LEDMask; //!< LEDs on back
+	| BackRight3LEDMask;
  
+	//! LEDs for tail
 	const LEDBitMask_t TailLEDMask
 	= TailLeftLEDMask
 	| TailCenterLEDMask
-	| TailRightLEDMask;  //!< LEDs for tail
+	| TailRightLEDMask;
  
-	const LEDBitMask_t AllLEDMask  = (LEDBitMask_t)~0; //!< selects all of the leds
+	//! selects all of the leds
+	const LEDBitMask_t AllLEDMask  = (LEDBitMask_t)~0;
 	//@}
 
 
@@ -259,6 +267,7 @@
 		ChinButOffset= 4,
 		BackButOffset,
 		HeadFrButOffset, //!< for the "antenna" - this is <.2 if pushed back all the way
+		HeadButOffset=HeadFrButOffset,  //!< for ERS-7 compatibility
 		HeadBkButOffset, //!< for the "antenna" - this is >.98 if pulled forward, <.2 if pushed back partly
 		TailLeftButOffset,
 		TailCenterButOffset,
@@ -497,9 +506,6 @@
 #define __RI_RAD_FLAG
 #endif
 
-	//! Defines the indexes to use to access the min and max entries of ERSInfo::outputRanges and ERS7Info::mechanicalLimits
-	enum MinMaxRange_t { MinRange,MaxRange };
-
 	//! This table holds the software limits of each of the outputs
 	const double outputRanges[NumOutputs][2] =
 		{
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/ERS2xxInfo.h ./Shared/ERS2xxInfo.h
--- ../Tekkotsu_2.4.1/Shared/ERS2xxInfo.h	2005-06-01 01:47:49.000000000 -0400
+++ ./Shared/ERS2xxInfo.h	2006-10-03 22:41:51.000000000 -0400
@@ -25,6 +25,7 @@
 	//       ROBOT CONFIGURATION
 	// *******************************
 
+	const char* const RobotName="ERS-2xx"; //!< 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)
@@ -56,7 +57,10 @@
 	const float CameraFOV=CameraHorizFOV; //!< should be set to maximum of #CameraHorizFOV or #CameraVertFOV
 	const unsigned int CameraResolutionX=176; //!< the number of pixels available in the 'full' layer
 	const unsigned int CameraResolutionY=144; //!< the number of pixels available in the 'full' layer
+	const float BallOfFootRadius=27.922/2; //!< radius of the ball of the foot
+	const float CylinderOfFootRadius=24.606/2; //!< radius of the cylinder of the foot
 
+	//! true for joints which can be updated every 32 ms (all but the ears on a 210)
 	const bool IsFastOutput[NumOutputs] = {
 		// for PID joints
 		true, true, true, //legs
@@ -78,7 +82,7 @@
 		true, true,                 // tail red/blue from 210
 		// for binary joints
 		false, false
-	}; //!< true for joints which can be updated every 32 ms (all but the ears on a 210)
+	};
 
 	//! we need this so you can tell programmatically which joints are "real" and which are "fake" in compatability mode
 	const bool IsRealERS210[NumOutputs] = {
@@ -102,7 +106,7 @@
 		true, true,                 // tail red/blue from 210
 		// for binary joints
 		true, true
-	}; //!< true for joints which can be updated every 32 ms (all but the ears on a 210)
+	};
 
 	//! we need this so you can tell programmatically which joints are "real" and which are "fake" in compatability mode
 	const bool IsRealERS220[NumOutputs] = {
@@ -126,7 +130,7 @@
 		false, false,               // tail red/blue from 210
 		// for binary joints
 		false, false
-	}; //!< true for joints which can be updated every 32 ms (all but the ears on a 210)
+	};
 
 
 	// *******************************
@@ -234,6 +238,7 @@
 	const LEDBitMask_t TopRLEDMask = 1<<(TopRLEDOffset-LEDOffset); //!< top right (red - angry)
 	const LEDBitMask_t TopBrLEDMask= 1<<(TopBrLEDOffset-LEDOffset); //!< top bar (green)
 
+	//! LEDs for face
 	const LEDBitMask_t FaceLEDMask
 	= FaceFrontLeftLEDMask
 	| FaceFrontRightLEDMask
@@ -244,28 +249,31 @@
 	| FaceFrontALEDMask
 	| FaceFrontBLEDMask
 	| FaceFrontCLEDMask
-	| ModeLEDMask;              //!< LEDs for face
+	| ModeLEDMask;
  
+	//! LEDs on head (face plus retractable light)
 	const LEDBitMask_t HeadLEDMask
-	= FaceLEDMask
-	| RetractableHeadLEDMask;   //!< LEDs on head (face plus retractable light)
+	= FaceLEDMask | RetractableHeadLEDMask;
  
+	//! LEDs on back
 	const LEDBitMask_t BackLEDMask
 	= BackLeft1LEDMask
 	| BackLeft2LEDMask
 	| BackLeft3LEDMask
 	| BackRight1LEDMask
 	| BackRight2LEDMask
-	| BackRight3LEDMask; //!< LEDs on back
+	| BackRight3LEDMask;
  
+	//! LEDs for tail
 	const LEDBitMask_t TailLEDMask
 	= TailLeftLEDMask
 	| TailCenterLEDMask
 	| TailRightLEDMask
 	| TlRedLEDMask
-	| TlBluLEDMask;  //!< LEDs for tail
+	| TlBluLEDMask;
  
-	const LEDBitMask_t AllLEDMask  = (LEDBitMask_t)~0; //!< selects all of the leds
+	//! selects all of the leds
+	const LEDBitMask_t AllLEDMask  = (LEDBitMask_t)~0;
 	//@}
 
 
@@ -294,6 +302,7 @@
 		ChinButOffset= 4,
 		BackButOffset,
 		HeadFrButOffset, //!< see ERS210Info::HeadFrButOffset, ERS220Info::HeadFrButOffset
+		HeadButOffset=HeadFrButOffset,  //!< for ERS-7 compatibility
 		HeadBkButOffset, //!< see ERS210Info::HeadBkButOffset, ERS220Info::HeadBkButOffset
 		TailLeftButOffset,
 		TailCenterButOffset,
@@ -562,9 +571,6 @@
 #define __RI_RAD_FLAG
 #endif
 
-	//! Defines the indexes to use to access the min and max entries of ERS2xxInfo::outputRanges and ERS2xxInfo::mechanicalLimits
-	enum MinMaxRange_t { MinRange,MaxRange };
-
 	//! This table holds the software limits of each of the outputs
 	const double outputRanges[NumOutputs][2] =
 		{
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/ERS7Info.h ./Shared/ERS7Info.h
--- ../Tekkotsu_2.4.1/Shared/ERS7Info.h	2005-06-01 01:47:49.000000000 -0400
+++ ./Shared/ERS7Info.h	2006-10-03 22:41:51.000000000 -0400
@@ -13,12 +13,58 @@
 using namespace RobotInfo;
 
 //! Contains information about the ERS-7 Robot, such as number of joints, PID defaults, timing information, etc.
+/*! 
+You may be particularly interested in the "Output Offsets" section, which, along with the offsets of the common RobotInfo namespace,
+allows you to reference any specific joint or LED on the robot.
+
+The "Input Offsets" section gives the index order of the buttons (#ButtonOffset_t) and sensors (#SensorOffset_t), as well as
+string names for each for easier debugging (#buttonNames, #sensorNames)
+
+"Output Types" section provides "meta-information" regarding the capabilities of the robot, such as the number of head joints, or the number of LEDs, etc.
+
+For more information on your robot's specifications, see also #DefaultPIDs, #MaxOutputSpeed, #outputRanges, and #mechanicalLimits.
+
+"Outputs" (i.e. Joints, LEDs) are often refered to by index ("offset") value within an array.
+These values are formed by specifying a @e section offset, plus a @e specific offset.  Sections are typically general across robot models, whereas the specifics are model-dependent (but can be aliased to provide compatability).
+
+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
+  - + #RotatorOffset: positive moves "out", away from body
+  - + #ElevatorOffset: positive moves up, away from body
+  - + #KneeOffset: positive bends knee (slight negative possible)
+- #HeadOffset - #NumHeadJoints items, add #TPROffset_t:
+  - + #TiltOffset: positive looks up
+  - + #PanOffset: positive looks left
+  - + #NodOffset: positive looks up
+- #TailOffset - #NumTailJoints items, add #TPROffset_t:
+  - + #TiltOffset: positive raises the joint (lowers the tail itself)
+  - + #PanOffset: positive points the tail to the Aibo's right
+- MouthOffset - #NumMouthJoints items (no specific, only 1 joint)
+- LEDs: #NumLEDs items, see #LEDOffset_t; these are all direct offsets, and do not need to be added to anything else
+- #EarOffset - #NumEarJoints items (no specifics, first is left ear, second is right ear)
+
+It happens that these joints can also be grouped by the @e type of joint, so there are additionally a few other offsets that can be used in order to loop across a group of joints:
+- PIDJointOffset - #NumPIDJoints items, servos using PID control
+- LegOffset - #NumLegJoints items, a subset of PID servos corresponding to the leg joints
+- LEDOffset - #NumLEDs items
+- 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
+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>.
+
+@see <a href="../media/TekkotsuQuickReference_ERS7.pdf">ERS-7 Quick Reference Sheet</a>
+*/
 namespace ERS7Info {
 
 	// *******************************
 	//       ROBOT CONFIGURATION
 	// *******************************
 
+	const char* const RobotName="ERS-7"; //!< 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)
@@ -39,6 +85,7 @@
 	const unsigned NumButtons     =  2+4+3+1; //!< the number of buttons that are available, 2 head, 4 paws, 3 back, 1 underbelly see ERS7Info::ButtonOffset_t
 	const unsigned NumSensors     =  3+3+5;  //!< 3 IR (distance), 3 accel (force), 5 from power, see ERS7Info::SensorOffset_t
 	const unsigned NumLEDs        =  27; //!< The number of LEDs which can be controlled
+	const unsigned NumFacePanelLEDs = 14; //!< The number of face panel LEDs
 	
 	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
@@ -50,14 +97,17 @@
 	const float CameraFOV=CameraHorizFOV; //!< should be set to maximum of #CameraHorizFOV or #CameraVertFOV
 	const unsigned int CameraResolutionX=208; //!< the number of pixels available in the 'full' layer
 	const unsigned int CameraResolutionY=160; //!< the number of pixels available in the 'full' layer
+	const float BallOfFootRadius=23.433/2; //!< radius of the ball of the foot
 
-	//! true for joints which can be updated every 32 ms (all ers-7 joints)
+	//! true for joints which can be updated every 32 ms (all joints on ERS-7)
+	/*! @hideinitializer */
 	const bool IsFastOutput[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,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
@@ -74,15 +124,15 @@
 	//!@name Output Offsets
 
 	const unsigned PIDJointOffset = 0; //!< The beginning of the PID Joints
-	const unsigned LegOffset   = PIDJointOffset;           //!< the offset of the beginning of the leg joints
-	const unsigned HeadOffset  = LegOffset+NumLegJoints;   //!< the offset of the beginning of the head joints
-	const unsigned TailOffset  = HeadOffset+NumHeadJoints; //!< the offset of the beginning of the tail joints
-	const unsigned MouthOffset = TailOffset+NumTailJoints; //!< the offset of the beginning of the mouth joint
+	const unsigned LegOffset   = PIDJointOffset;           //!< the offset of the beginning of the leg joints, #NumLegs of #JointsPerLeg each, in #LegOrder_t order; see #LegOffset_t
+	const unsigned HeadOffset  = LegOffset+NumLegJoints;   //!< the offset of the beginning of the head joints, add #TPROffset_t to get specific joint
+	const unsigned TailOffset  = HeadOffset+NumHeadJoints; //!< the offset of the beginning of the tail joints, add #TPROffset_t to get specific joint (except RollOffset not available)
+	const unsigned MouthOffset = TailOffset+NumTailJoints; //!< the offset of the beginning of the mouth joint, is specific joint
 
-	const unsigned LEDOffset   = PIDJointOffset + NumPIDJoints; //!< the offset of LEDs in WorldState::outputs and MotionCommand functions
+	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.  Nor will they be flicked back
+	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 PawFrameOffset    = BaseFrameOffset+1; //!< Use with kinematics to refer to paw reference frames (add appropriate LegOrder_t to specify which paw)
@@ -92,45 +142,46 @@
 	const unsigned ChestIRFrameOffset = FarIRFrameOffset+1; //!< Use with kinematics to refer to chest-mounted infrared (distance) sensor reference frame
 
 
-	//! The offsets of the individual legs
+	//! The offsets of the individual legs, add #REKOffset_t value to access specific joint
+	/*! @hideinitializer */
 	enum LegOffset_t {
-		LFrLegOffset = LegOffset+LFrLegOrder*JointsPerLeg, //!< beginning of left front leg
-		RFrLegOffset = LegOffset+RFrLegOrder*JointsPerLeg, //!< beginning of right front leg
-		LBkLegOffset = LegOffset+LBkLegOrder*JointsPerLeg, //!< beginning of left back leg
-		RBkLegOffset = LegOffset+RBkLegOrder*JointsPerLeg  //!< beginning of right back leg
+		LFrLegOffset = LegOffset+LFrLegOrder*JointsPerLeg, //!< beginning of left front leg's joints
+		RFrLegOffset = LegOffset+RFrLegOrder*JointsPerLeg, //!< beginning of right front leg's joints
+		LBkLegOffset = LegOffset+LBkLegOrder*JointsPerLeg, //!< beginning of left back leg's joints
+		RBkLegOffset = LegOffset+RBkLegOrder*JointsPerLeg  //!< beginning of right back leg's joints
 	};
 	
-	//@}
-	
 	//! 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 {
-		HeadColorLEDOffset = LEDOffset,
-		HeadWhiteLEDOffset,
-		ModeRedLEDOffset,
-		ModeGreenLEDOffset,
-		ModeBlueLEDOffset,
-		WirelessLEDOffset,
-		FaceLEDPanelOffset, //!< the first LED in the panel - add to this to get the other 13 (14 total)
-		FrBackColorLEDOffset = FaceLEDPanelOffset+14, // blue/purple
-		FrBackWhiteLEDOffset,
-		MdBackColorLEDOffset,                    // orange
-		MdBackWhiteLEDOffset,
-		RrBackColorLEDOffset,                    // red
-		RrBackWhiteLEDOffset,
+		HeadColorLEDOffset = LEDOffset, //!< the orange LED immediately above the head button (copositioned with #HeadWhiteLEDOffset)
+		HeadWhiteLEDOffset, //!< the LED immediately above the head button (copositioned with #HeadColorLEDOffset)
+		ModeRedLEDOffset, //!< controls both of the red LEDs above the ears (copositioned with #ModeGreenLEDOffset and #ModeBlueLEDOffset)
+		ModeGreenLEDOffset, //!< controls both of the green LEDs above the ears (copositioned with #ModeRedLEDOffset and #ModeBlueLEDOffset)
+		ModeBlueLEDOffset, //!< controls both of the blue LEDs above the ears (copositioned with #ModeRedLEDOffset and #ModeGreenLEDOffset)
+		WirelessLEDOffset, //!< controls the small rectangular blue LED on the back of the head
+		FaceLEDPanelOffset, //!< the first LED in the panel - add 0 up to (not including) #NumFacePanelLEDs to this to access specific face panel LEDs, see LedEngine for diagram of placement
+		FrBackColorLEDOffset = FaceLEDPanelOffset+NumFacePanelLEDs, //!< @b blue/purple LED on back, closest to head (copositioned with #FrBackWhiteLEDOffset)
+		FrBackWhiteLEDOffset,  //!< white LED on back, closest to head (copositioned with #FrBackColorLEDOffset)
+		MdBackColorLEDOffset, //!< @b orange LED on back, in between FrBackColorLEDOffset and RrBackColorLEDOffset (copositioned with #MdBackWhiteLEDOffset)
+		MdBackWhiteLEDOffset, //!< white LED on back, in between FrBackWhiteLEDOffset and RrBackWhiteLEDOffset (copositioned with #MdBackColorLEDOffset)
+		RrBackColorLEDOffset, //!< @b red LED on back, farthest from head (copositioned with #RrBackWhiteLEDOffset)
+		RrBackWhiteLEDOffset, //!< white LED on back, farthest from head (copositioned with #RrBackColorLEDOffset)
 		LEDABModeOffset, // allows you to control A/B mode setting (this is a "virtual" LED)
 
 		// aliases for 2xx cross-compatibility
-		BotLLEDOffset = FaceLEDPanelOffset+0,//!< aliases for backward compatability (use mode A); bottom left
-		BotRLEDOffset = FaceLEDPanelOffset+1, //!< bottom right
-		MidLLEDOffset = FaceLEDPanelOffset+2, //!< middle left
-		MidRLEDOffset = FaceLEDPanelOffset+3, //!< middle right
-		TopLLEDOffset = FaceLEDPanelOffset+6, //!< top left
-		TopRLEDOffset = FaceLEDPanelOffset+7, //!< top right
-		TopBrLEDOffset= HeadColorLEDOffset,//!< top bar
-		TlRedLEDOffset= RrBackColorLEDOffset,//!< red tail light
-		TlBluLEDOffset= FrBackColorLEDOffset //!< blue tail light
+		BotLLEDOffset = FaceLEDPanelOffset+1,//!< aliases for backward compatability with ERS-210 (use mode A); bottom left of face panel
+		BotRLEDOffset = FaceLEDPanelOffset+0, //!< aliases for backward compatability with ERS-210 (use mode A); bottom right of face panel
+		MidLLEDOffset = FaceLEDPanelOffset+3, //!< aliases for backward compatability with ERS-210 (use mode A); middle left of face panel
+		MidRLEDOffset = FaceLEDPanelOffset+2, //!< aliases for backward compatability with ERS-210 (use mode A); middle right of face panel
+		TopLLEDOffset = FaceLEDPanelOffset+7, //!< aliases for backward compatability with ERS-210 (use mode A); top left of face panel
+		TopRLEDOffset = FaceLEDPanelOffset+6, //!< aliases for backward compatability  with ERS-210(use mode A); top right of face panel
+		TopBrLEDOffset= HeadColorLEDOffset,//!< aliases for backward compatability with ERS-210 (use mode A); top bar (#HeadColorLEDOffset)
+		TlRedLEDOffset= RrBackColorLEDOffset,//!< aliases for backward compatability with ERS-210; red tail light (#RrBackColorLEDOffset)
+		TlBluLEDOffset= FrBackColorLEDOffset //!< aliases for backward compatability with ERS-210; blue tail light (#FrBackColorLEDOffset)
 	};
-	
+	//@}
+		
 	//! Bitmasks for use when specifying combinations of LEDs (see LedEngine ) Note that left/right are robot's point of view
 	//!@name LED Bitmasks
 	typedef unsigned int LEDBitMask_t; //!< So you can be clear when you're refering to a LED bitmask
@@ -160,11 +211,27 @@
 	const LEDBitMask_t TlRedLEDMask= 1<<(TlRedLEDOffset-LEDOffset); //!< red tail light
 	const LEDBitMask_t TlBluLEDMask= 1<<(TlBluLEDOffset-LEDOffset); //!< blue tail light
 
-	const LEDBitMask_t FaceLEDMask = (FaceLEDPanelMask<<0) | (FaceLEDPanelMask<<1) | (FaceLEDPanelMask<<2) | (FaceLEDPanelMask<<3) | (FaceLEDPanelMask<<4) | (FaceLEDPanelMask<<5) | (FaceLEDPanelMask<<6) | (FaceLEDPanelMask<<7) | (FaceLEDPanelMask<<8) | (FaceLEDPanelMask<<9) | (FaceLEDPanelMask<<10) | (FaceLEDPanelMask<<11) | (FaceLEDPanelMask<<12) | (FaceLEDPanelMask<<13); //!< LEDs for the face panel
-	const LEDBitMask_t HeadLEDMask = FaceLEDMask | HeadColorLEDMask | HeadWhiteLEDMask | ModeRedLEDMask | ModeGreenLEDMask | ModeBlueLEDMask | WirelessLEDMask; //!< LEDs for face (all but back lights)
-	const LEDBitMask_t BackLEDMask = FrBackColorLEDMask | FrBackWhiteLEDMask | MdBackColorLEDMask | MdBackWhiteLEDMask | RrBackColorLEDMask | RrBackWhiteLEDMask; //!< LEDS on the back
-	const LEDBitMask_t TailLEDMask = 0; //!< LEDs on tail (ERS-7 has none)
-	const LEDBitMask_t AllLEDMask  = (LEDBitMask_t)~0; //!< selects all of the leds
+	//! LEDs for the face panel (all FaceLEDPanelMask<<(0:NumFacePanelLEDs-1) entries)
+	/*! @hideinitializer */
+	const LEDBitMask_t FaceLEDMask = (FaceLEDPanelMask<<0) | (FaceLEDPanelMask<<1) | (FaceLEDPanelMask<<2) | (FaceLEDPanelMask<<3) | (FaceLEDPanelMask<<4) | (FaceLEDPanelMask<<5) | (FaceLEDPanelMask<<6) | (FaceLEDPanelMask<<7) | (FaceLEDPanelMask<<8) | (FaceLEDPanelMask<<9) | (FaceLEDPanelMask<<10) | (FaceLEDPanelMask<<11) | (FaceLEDPanelMask<<12) | (FaceLEDPanelMask<<13);
+
+	//! LEDs for face (all but back lights)
+	const LEDBitMask_t HeadLEDMask
+	= FaceLEDMask | HeadColorLEDMask | HeadWhiteLEDMask
+	| ModeRedLEDMask | ModeGreenLEDMask | ModeBlueLEDMask
+	| WirelessLEDMask;
+
+	//! LEDS on the back
+	const LEDBitMask_t BackLEDMask
+	= FrBackColorLEDMask | FrBackWhiteLEDMask
+	| MdBackColorLEDMask | MdBackWhiteLEDMask
+	| RrBackColorLEDMask | RrBackWhiteLEDMask;
+
+	//! LEDs on tail (ERS-7 has none)
+	const LEDBitMask_t TailLEDMask = 0;
+
+	//! selects all of the leds
+	const LEDBitMask_t AllLEDMask  = (LEDBitMask_t)~0;
 	//@}
 
 
@@ -184,7 +251,8 @@
 	 *  normal way.  If you want to know when it is pressed (and you are
 	 *  about to shut down) see PowerSourceID::PauseSID.
 	 *
-	 *  @see WorldState::buttons @see ButtonSourceID_t */
+	 *  @see WorldState::buttons @see ButtonSourceID_t
+	 * @hideinitializer */
 	enum ButtonOffset_t {
 		LFrPawOffset = LFrLegOrder,
 		RFrPawOffset = RFrLegOrder,
@@ -238,71 +306,39 @@
 	const unsigned outputNameLen = 9;
 	//! A name of uniform length for referring to joints - handy for posture files, etc.
 	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~~~~",
 		
-		"LED:headC",
-		"LED:headW",
-		"LED:modeR",
-		"LED:modeG",
-		"LED:modeB",
-		"LED:wless",
-		"LED:faceA",
-		"LED:faceB",
-		"LED:faceC",
-		"LED:faceD",
-		"LED:faceE",
-		"LED:faceF",
-		"LED:faceG",
-		"LED:faceH",
-		"LED:faceI",
-		"LED:faceJ",
-		"LED:faceK",
-		"LED:faceL",
-		"LED:faceM",
-		"LED:faceN",
-		"LED:bkFrC",
-		"LED:bkFrW",
-		"LED:bkMdC",
-		"LED:bkMdW",
-		"LED:bkRrC",
-		"LED:bkRrW",
+		"LED:headC","LED:headW",
+		"LED:modeR","LED:modeG",
+		"LED:modeB","LED:wless",
+		"LED:faceA","LED:faceB","LED:faceC","LED:faceD","LED:faceE","LED:faceF","LED:faceG",
+		"LED:faceH","LED:faceI","LED:faceJ","LED:faceK","LED:faceL","LED:faceM","LED:faceN",
+		"LED:bkFrC","LED:bkFrW",
+		"LED:bkMdC","LED:bkMdW",
+		"LED:bkRrC","LED:bkRrW",
 		"LED:ABmod",
 		
-		"EAR:left~",
-		"EAR:right"
+		"EAR:left~","EAR:right"
 	};
 	
 
 	//! 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
-	 *
 	 * The offset consts defined in this file correspond to this table and will make life easier
-	 * if you feel the need to reorder things, but they aren't used perfect @e everywhere \n
+	 * if you feel the need to reorder things, but they can't be arbitrarily reordered... \n
 	 * In particular, assumptions are made that the pid joints will be in slots 0-numPIDJoints
 	 * and that the fast outputs (ie NOT ears) will be in slots 0-NumFastOutputs\n
 	 * There may be other assumptions not noted here!!!
-	 * @note These entries DON'T correspond to the CPC index numbers defined in WorldState (this only lists joints, and in a different order defined by OPEN-R, that one has sensors as well*/
+	 * @note These entries DON'T correspond to the CPC index numbers (this only lists joints for identifying joints to Aperios, CPCs are for identifying sensors from Aperios */
 	const char* const PrimitiveName [NumOutputs] = {
 		"PRM:/r2/c1-Joint2:21",       //!< the left front leg   the rotator
 		"PRM:/r2/c1/c2-Joint2:22",    //!< the left front leg   the elevator 
@@ -439,10 +475,7 @@
 	#define __RI_RAD_FLAG
 	#endif
 	
-	//! Defines the indexes to use to access the min and max entries of ERS7Info::outputRanges and ERS7Info::mechanicalLimits
-	enum MinMaxRange_t { MinRange,MaxRange };
-
-	//! This table holds the software limits of each of the outputs
+	//! 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
@@ -464,7 +497,8 @@
 			{0,1},{0,1} //ears
 		};
 
-	//! This table holds the mechanical limits of each of the outputs @todo same as outputLimits right now, don't know actual values yet
+	//! 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 */
 	const double mechanicalLimits[NumOutputs][2] =
 		{
 			{ RAD(-115),RAD(130) },{ RAD(-10),RAD(88) },{ RAD(-25),RAD(122) }, //left front REK
@@ -478,8 +512,11 @@
 
 			{ RAD(-55),RAD(-3) }, //mouth
 
-			{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1}, //LEDs
-		
+			{0,1},{0,1},{0,1},{0,1},{0,1},{0,1}, //misc head LEDs
+			{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1},{0,1}, //Face LEDs
+			{0,1},{0,1},{0,1},{0,1},{0,1},{0,1}, //back LEDs
+			{0,1}, //virtual mode A/B switcher
+
 			{0,1},{0,1} //ears
 		};
 
@@ -490,7 +527,7 @@
 
 
 	/*! @name CPC IDs
-	 * values defined by OPEN-R, used to interface with lower level OPEN-R code to read sensors - DOESN'T correspond to ERS7Info::PrimitiveName */
+	 * 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                      
@@ -530,7 +567,7 @@
 }
 	
 /*! @file
- * @brief Defines RobotInfo namespace for ERS-210 models, gives some information about the robot's capabilities, such as joint counts, offsets, names and PID values
+ * @brief Defines RobotInfo namespace for ERS-7 models, gives some information about the robot's capabilities, such as joint counts, offsets, names and PID values
  * @author ejt (Creator)
  *
  * $Author: ejt $
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/LoadSave.cc ./Shared/LoadSave.cc
--- ../Tekkotsu_2.4.1/Shared/LoadSave.cc	2004-03-25 12:07:44.000000000 -0500
+++ ./Shared/LoadSave.cc	2006-09-12 16:24:04.000000000 -0400
@@ -1,23 +1,37 @@
 #include "LoadSave.h"
 #include <iostream>
 #include <string.h>
+#include <sys/types.h>
+#include <sys/stat.h>
 
 LoadSave::~LoadSave() {}
 
-unsigned int LoadSave::checkCreator(const char* creator, const char buf[], unsigned int len, bool isLoading) const {
-	unsigned int sz=0,last;
-	char* type=NULL;
-	if(!(last=decode(type,buf+sz,len))) return 0; else sz+=last;
-	if(strncmp(type,creator,strlen(creator))!=0) {
+unsigned int LoadSave::checkCreator(const char* creator, const char buf[], unsigned int len, bool isLoading) const throw() {
+	const char* type=buf+getSerializedSize<unsigned int>();
+	if(strcmp(type,creator)!=0) {
 		if(isLoading)
-			std::cout << "*** WARNING " << creator << "::LoadBuffer - corruption detected" << std::endl;
+			std::cout << "*** WARNING " << creator << "::loadBuffer - corruption detected, got '" << std::string(type) << "'" << std::endl;
 		return 0;
 	}
-	delete [] type;
-	return sz;
+	unsigned int sz;
+	decode(sz,buf,len);
+	return sz+stringpad;
+}
+bool LoadSave::checkCreatorInc(const char* creator, const char*& buf, unsigned int& len, bool isLoading) const throw() {
+	if(unsigned int used=checkCreator(creator,buf,len,isLoading)) { buf+=used; len-=used; return true; }
+	else return false;
+}
+void LoadSave::checkCreatorIncT(const char* creator, const char*& buf, unsigned int& len, bool isLoading) const throw(std::runtime_error) {
+	if(checkCreatorInc(creator,buf,len,isLoading))
+		return;
+	std::string err="incorrect creator code: ";
+	err+=creator;
+	err+=" vs ";
+	err+=std::string(buf,strlen(creator));
+	throw std::runtime_error(err);
 }
 
-unsigned int LoadSave::checkCreator(const char* creator, FILE* f, bool isLoading) const {
+unsigned int LoadSave::checkCreator(const char* creator, FILE* f, bool isLoading) const throw() {
 	unsigned int sz=0,last;
 	unsigned int origpos=ftell(f);
 	char* type=NULL;
@@ -28,23 +42,36 @@
 		sz+=last;
 	if(strncmp(type,creator,strlen(creator))!=0) {
 		if(isLoading)
-			std::cout << "*** WARNING " << creator << "::LoadBuffer - corruption detected" << std::endl;
+			std::cout << "*** WARNING " << creator << "::loadBuffer - corruption detected" << std::endl;
 		fseek(f,origpos,SEEK_SET);
+		delete [] type;	
 		return 0;
 	}
 	delete [] type;	
 	return sz;
 }
 
-unsigned int LoadSave::saveCreator(const char* creator, char buf[], unsigned int len) const {
+unsigned int LoadSave::saveCreator(const char* creator, char buf[], unsigned int len) const throw() {
 	return encode(std::string(creator),buf,len);
 }
+bool LoadSave::saveCreatorInc(const char* creator, char*& buf, unsigned int& len) const throw() {
+	if(unsigned int used=saveCreator(creator,buf,len)) { buf+=used; len-=used; return true; }
+	else return false;
+}
+void LoadSave::saveCreatorIncT(const char* creator, char*& buf, unsigned int& len) const throw(std::runtime_error) {
+	if(saveCreatorInc(creator,buf,len))
+		return;
+	std::string err="unable to save creator code: ";
+	err+=creator;
+	err+=" (ran out of space?)";
+	throw std::runtime_error(err);
+}
 
-unsigned int LoadSave::saveCreator(const char* creator, FILE* f) const {
+unsigned int LoadSave::saveCreator(const char* creator, FILE* f) const throw() {
 	return encode(creator,f);
 }
 
-unsigned int LoadSave::LoadFile(const char* file) {
+unsigned int LoadSave::loadFile(const char* file) {
 	int err;
 	std::cout << "Loading: " << file << std::endl;
 	FILE* f = fopen(file,"r");
@@ -52,7 +79,7 @@
 		std::cout << "*** WARNING could not open file for loading \"" << file << "\"" << std::endl;
 		return 0;
 	}
-	unsigned int sz = LoadFileStream(f);
+	unsigned int sz = loadFileStream(f);
 	if(sz==0)
 		std::cout << "*** WARNING loading of " << file << " failed " << std::endl;
 	err=fclose(f);
@@ -62,7 +89,7 @@
 	}
 	return sz;
 }
-unsigned int LoadSave::SaveFile(const char* file) const {
+unsigned int LoadSave::saveFile(const char* file) const {
 	int err;
 	std::cout << "Saving: " << file << std::endl;
 	FILE* f = fopen(file,"w");
@@ -70,7 +97,7 @@
 		std::cout << "*** WARNING could not open file for saving \"" << file << "\"" << std::endl;
 		return 0;
 	}
-	unsigned int sz = SaveFileStream(f);
+	unsigned int sz = saveFileStream(f);
 	if(sz==0)
 		std::cout << "*** WARNING saving of " << file << " failed " << std::endl;
 	err=fclose(f);
@@ -81,47 +108,44 @@
 	return sz;
 }
 
-unsigned int LoadSave::LoadFileStream(FILE* f) {
-	unsigned int cap=128;
-	unsigned int sz=0;
+unsigned int LoadSave::loadFileStream(FILE* f) {
+	struct stat sb;
+	int err=fstat(fileno(f),&sb);
+	if(err!=0) {
+		perror("fstat failed in LoadSave::loadFileStream()");
+		return 0;
+	}
 	unsigned int origpos=ftell(f);
-	char * buf = new char[cap];
+	unsigned int cap=sb.st_size-origpos;
+	char * buf = NULL;
+	try { buf=new char[cap]; } catch(...) {}
 	if(buf==NULL) {
-		std::cout << "*** WARNING could not allocate " << cap << "+ bytes for LoadFile";
+		std::cout << "*** WARNING could not allocate " << cap << "+ bytes for loadFile";
 		return 0;
 	}
-	unsigned int read=fread(&buf[sz],1,cap-sz,f);
-	while(read==cap-sz) {
-		char * newbuf = new char[cap*2];
-		if(newbuf==NULL) {
-			std::cout << "*** WARNING could not allocate " << cap*2 << "+ bytes for LoadFile";
-			return 0;
-		}
-		memcpy(newbuf,buf,cap);
-		delete [] buf;
-		buf=newbuf;
-		sz=cap;
-		cap*=2;
-		read=fread(&buf[sz],1,cap-sz,f);
+	unsigned int read=fread(buf,1,cap,f);
+	unsigned int pos=0;
+	while(cap!=pos+read) {
+		pos+=read;
+		read=fread(&buf[pos],1,cap-pos,f);
 	}
-	sz+=read;
-	unsigned int resp=LoadBuffer(buf,sz);
+	unsigned int resp=loadBuffer(buf,cap);
 	delete [] buf;
-	if(resp!=sz)
+	if(resp!=cap)
 		fseek(f,origpos+resp,SEEK_SET);
 	return resp;
 }
-unsigned int LoadSave::SaveFileStream(FILE* f) const {
+unsigned int LoadSave::saveFileStream(FILE* f) const {
 	unsigned int sz=getBinSize();
 	char * buf = new char[sz];
 	memset(buf,0xF0,sz);
 	if(buf==NULL) {
-		std::cout << "*** WARNING could not allocate " << sz << " bytes for LoadFile";
+		std::cout << "*** WARNING could not allocate " << sz << " bytes for loadFile";
 		return 0;
 	}
-	unsigned int resp=SaveBuffer(buf,sz);
+	unsigned int resp=saveBuffer(buf,sz);
 	if(resp==0) {
-		std::cout << "*** WARNING SaveBuffer didn't write any data (possibly due to overflow or other error)" << std::endl;
+		std::cout << "*** WARNING saveBuffer didn't write any data (possibly due to overflow or other error)" << std::endl;
 		fwrite(buf,1,sz,f);
 	}	else {
 		unsigned int wrote=fwrite(buf,1,resp,f);
@@ -132,30 +156,17 @@
 	return resp;
 }
 
-bool LoadSave::ChkAdvance(int res, const char** buf, unsigned int* len, const char* msg) {
-	if(res>0) {
-		*buf+=res;
-		*len-=res;
-		return true;
-	} else {
-		printf("%s",msg);
-		return false;
-	}
-}
-
-bool LoadSave::ChkAdvance(int res, const char** buf, unsigned int* len, const char* msg, int arg1) {
-	if(res>0) {
-		*buf+=res;
-		*len-=res;
-		return true;
-	} else {
-		printf(msg,arg1);
-		return false;
-	}
+unsigned int LoadSave::LoadFile(const char* filename) { return loadFile(filename); }
+unsigned int LoadSave::SaveFile(const char* filename) const { return saveFile(filename); }
+bool LoadSave::chkAdvance(int res, const char** buf, unsigned int* len, const char* msg, ...) {
+	va_list al;
+	va_start(al,msg);
+	//todo
+	bool ans=checkInc(res,*buf,*len,msg);
+	va_end(al);
+	return ans;
 }
 
-
-
 /*! @file
  * @brief Implements LoadSave, inherit from this to use a standard interface for loading and saving
  * @author ejt (Creator)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/LoadSave.h ./Shared/LoadSave.h
--- ../Tekkotsu_2.4.1/Shared/LoadSave.h	2005-08-07 00:11:04.000000000 -0400
+++ ./Shared/LoadSave.h	2006-10-03 17:11:51.000000000 -0400
@@ -4,6 +4,14 @@
 
 #include <string>
 #include <sys/param.h>
+#include <stdexcept>
+#include <stdarg.h>
+#include "Shared/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
 
 #ifndef LOADSAVE_SWAPBYTES
 
@@ -30,109 +38,58 @@
 
 #endif
 
-//! Intended as an interface to allow easy and uniform file operations
-/*!
-	
-	Generally, for usage, all you need to know is to call
-	<tt>SaveFile("/path/to/file.ext")</tt> or
-	<tt>SaveBuffer(membuffer)</tt> in order to have the class serialize
-	itself, and the LoadFile() / LoadBuffer() in order to reload the
-	data.
-	
-	So, when SaveFile() is called, it checks that it
-	can open the specified file, and then calls SaveFileStream()
-	with the open file.  This will then check getBinSize(), create a
-	buffer of that size, and call SaveBuffer() to do the actual work of
-	serialization into that buffer.  If SaveBuffer is successful (make
-	sure your getBinSize() doesn't underestimate!) SaveFileStream()
-	copies the buffer out to the file, and then finally, SaveFile() will
-	close the file.
-	
-  This has the nice side effect that if you want to send the data over
-  the network instead of a file, you can call SaveBuffer() directly
-  and reuse the code.  However, if you have a lot of data to save, you
-  can override the SaveFileStream() function as well, and save into
-  the file directly.  So far I've only bothered to do that with
-  only a few classes.
-	
-	The recommended style for using LoadSave in classes with inheritance
-	is to have each subclass first call the superclass's implementation,
-	and then save their own local data.  This compartmentalizes the data
-	access and makes it easy to maintain - the code that serializes is
-	right in with the code that defines the structure.  If you change
-	one, it's easy to see where to change the other.  And protection
-	between levels of inheritance is retained.  (This is why I say it's
-	highly flexible/maintainable, but poor readability since the
-	serialization is all broken up.)
-	
-	I also recommend putting a little string header at the beginning of
-	each class's info.  This will allow polymorphism when loading files
-	(you can look at the string and create the appropriate type) but
-	also is handy for checking field alignment... it's a lot easier to
-	tell how much you're offset within a string than to do the same with
-	a stream of binary values.  Further, you can use the string as
-	version information if you want to be backward compatible in future
-	versions of your code.
+//! Intended as an interface to allow easy and portable serialization operations
+/*! Generally, for triggering serialization of a LoadSave subclass, all you need to know is to call saveFile() /
+    saveBuffer() in order to have the class serialize itself, and loadFile() /
+    loadBuffer() in order to reload the data.
+    
+    When saveFile() is called, it checks that it can open the specified file, and then calls
+    saveFileStream() with the open file.  This will then check getBinSize(), create a buffer of that
+    size, and call saveBuffer() to do the actual work of serialization into that buffer.  If
+    saveBuffer is successful, saveFileStream() copies the buffer out to the file, and then finally,
+    saveFile() will close the file.
+    
+    This means when writing a class which requires serialization, you need only define 3 functions:
+    loadBuffer(), saveBuffer(), and getBinSize().  If you are saving directly into a file and need
+    the highest possible performance, overriding loadFileStream and saveFileStream and
+    reimplementing the serialization operations into the file stream can save a buffer copy.
+    Usually this is not a performance issue, but the interface is there if you need it.
+    
+    The recommended style for using LoadSave in classes with multiple levels of inheritance is to
+    have each subclass first call the superclass's implementation (e.g. of loadBuffer/saveBuffer),
+    and then save their own data afterward.  This compartmentalizes the data access and makes it
+    easy to maintain - the code that serializes is right in with the code that defines the
+    structure.  If you change one, it's easy to see where to change the other.  And protection
+    between levels of inheritance is retained.  (This is why I say it's highly
+    flexible/maintainable, but poor readability since the serialization is all broken up.)
+    
+    I also recommend putting a little string header at the beginning of each class's info via saveCreator() and checkCreator().  This
+    will allow polymorphism when loading files (you can look at the string and create the
+    appropriate type) but also is handy for checking field alignment... it's a lot easier to tell
+    how much you're offset within a string than to do the same with a stream of binary values.
+    Further, you can use the string as version information if you want to be backward compatible in
+    future versions of your code.
 	
-	LoadSave provides a series of encode and decode functions for all
-	the primitive types.  This will handle copying the value into the
-	buffer or file, and can provide platform independence through byte
-	swapping if needed (there's a compiler flag you can set for
-	platforms that have the opposite byte order).  Most of these are
-	pretty straightfoward - an int is just 4 bytes and so on.
+    LoadSave provides a series of encode() and decode() functions for all the primitive types.  This
+    will handle copying the value into the buffer or file, and can provide platform independence
+    through byte swapping if needed (there's a compiler flag you can set for platforms that have the
+    opposite byte order, although this should be autodetected from the system headers).
+    Most of these are pretty straightfoward - an int is just 4 bytes and so on.
 	
-	However, there's one caveat that I want to make sure to point out if
-	you have to write parsing code in say, Java.  Strings are encoded by
-	first storing an int to hold the string's length, then the string
-	itself, and then a null character.  This adds 5 bytes to the length
-	of any string, but makes loading the files much easier/faster - you
-	can call string library functions directly on the buffer if it's
-	already in memory since the string is null terminated, or can
-	allocate memory to hold the string during loading from a file if
-	needed because you'll know the size of the string before you get to
-	it.
+    However, there's one caveat that I want to make sure to point out if you have to write parsing
+    code in say, Java.  Strings are encoded by first storing an int to hold the string's length,
+    then the string itself, and then a null character.  This adds 5 bytes to the length of any
+    string, but makes loading the files much easier/faster - you can call string library functions
+    directly on the buffer if it's already in memory since the string is null terminated, or can
+    allocate memory to hold the string with one pass from a file because you'll know the
+    size of the string before you get to it.
 	
-	Of course, the string stuff is transparent if you just use
-	LoadSave's encode/decode functions to parse it.  But if that's not
-	available (for instance if your receiver is in Java, there's a
-	readLoadSaveString() in VisionListener.java if that will help:
-	http://cvs.tekkotsu.org/cgi-bin/viewcvs.cgi/Tekkotsu/tools/mon/org/tekkotsu/mon/VisionListener.java?rev=1.6&content-type=text/vnd.viewcvs-markup
-	@code
-	public boolean _isConnected;
-
-	public String readLoadSaveString(InputStream in) throws java.io.IOException {
-		int creatorLen=readInt(in);
-		if(!_isConnected) return ""; 
-		String creator=new String(readBytes(in,creatorLen));
-		if(!_isConnected) return "";
-		if(readChar(in)!='\0')
-			System.err.println("Misread LoadSave string? "+creator);
-		return creator;
-	}
-
-	public int readInt(InputStream in) throws IOException {
-		int read=0;
-		int last=0;
-		byte[] buf=new byte[4];
-		while (read<4 && last>=0) { last=in.read(buf,read,4-read); read+=last; }
-		if(last<0)
-			_isConnected=false;
-		return (b2i(buf[3])<<24) | (b2i(buf[2])<<16) |
-					 (b2i(buf[1])<< 8) | b2i(buf[0]);
-	}
-  public byte[] readBytes(InputStream in, int bytes) throws IOException {
-    byte[] ret=new byte[bytes];
-    readBytes(ret, in, bytes);
-    return ret;
-  }
-	public char readChar(InputStream in) throws IOException {
-		return (char)in.read();
-	}
-	@endcode
+    Of course, the string serialization format is transparent if you just stick to using LoadSave's
+    encode/decode functions to parse it.
 */
 class LoadSave {
  public:
-	//! This is the amount of extra space needed to store a string (int for len of string plus 1 for null term
+	//! This is the amount of extra space needed to store a string (int for len of string plus 1 for @code '\0' @endcode termination)
 	static const unsigned int stringpad=sizeof(unsigned int)+1;
 
 	//!@name Constructors/Destructors
@@ -141,71 +98,189 @@
 	virtual ~LoadSave(); //!< destructor
 	//@}
 
-	//! These are useful for sending the data across a network as well as to a file.\n
-	//! These are the only ones that MUST be overridden, as the file
-	//! ops can be based on calling these, tho feel free to override
-	//! the file ops as well if speed or temp. memory is tight.
+	/*! @brief These are useful for sending the data across a network as well as to a file.\n
+	 *  These three functions (getBinSize(), loadBuffer(), saveBuffer() ) are the only ones that MUST be
+	 *  overridden, as the file stream versions can be based on calling these.  However, you can override
+	 *  the file stream versions as well if speed or temp. memory is tight. */
 	//!@name Buffer Operations
-	/*! @brief calculates space needed to save - if you can't precisely add up the size, overestimate and things will still work.
+	
+	//! Calculates space needed to save - if you can't precisely add up the size, just make sure to overestimate and things will still work.
+	/*! getBinSize is used for reserving buffers during serialization, but does not necessarily determine
+	 *  the actual size of what is written -- the return value of saveBuffer() specifies that after the data
+	 *  actually has been written.  If getBinSize overestimates, the extra memory allocation is only
+	 *  temporary, no extra filler bytes are actually stored.
 	 *  @return number of bytes read/written, 0 if error (or empty) */
 	virtual unsigned int getBinSize() const =0;
-	//! Load from a saved buffer
+	//! Load from a saved buffer in memory
 	/*! @param buf pointer to the memory where you should begin loading
-	 *  @param len length of @a buf available (this isn't all yours, might be more stuff saved after yours)
+	 *  @param len length of @a buf available (this isn't necessarily all yours, there might be other things following your data)
 	 *  @return the number of bytes actually used */
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len)=0;
-	//! Save to a given buffer
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len)=0;
+	//! Save to a given buffer in memory
 	/*! @param buf pointer to the memory where you should begin writing
-	 *  @param len length of @a buf available.  (this isn't all yours, constrain yourself to what you returned in getBinSize() )
+	 *  @param len length of @a buf available.  (this isn't necessarily all yours, constrain yourself to what you returned in getBinSize() )
 	 *  @return the number of bytes actually used */
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const =0;
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const =0;
 	//@}
 
 	//!These are called to load and save to files
 	//!@name File Operations
 	/*!@brief initiate opening of the specified file and loading/saving of all appropriate information.
 	 * @param filename the file to load/save @return number of bytes read/written, 0 if error (or empty)*/
-	virtual	unsigned int LoadFile(const char* filename);
-	virtual unsigned int SaveFile(const char* filename) const;
-
+	virtual unsigned int loadFile(const char* filename);
+	virtual unsigned int saveFile(const char* filename) const;
+	
 	//!Used recursively on member objects once a file is already open - DON'T CLOSE the file in your overridden functions
 	/*! @param f a pointer to the file to load
-	 *  @warning could potentially be very inefficient if root-level objects
-	 *  override LoadFile but leaf-level ones use this implementation, but
-	 *  leaf-level ones won't even get this call unless you override the ones
-	 *  above them - hence, this is all or nothing
 	 *	@return number of bytes read, 0 if error (or empty) */
-	virtual unsigned int LoadFileStream(FILE* f);
+	virtual unsigned int loadFileStream(FILE* f);
 	//!Used recursively on member objects once a file is already open - DON'T CLOSE the file in your overridden functions
 	/*! @param f a pointer to the file to save
-	 *  @warning could potentially be very inefficient if root-level objects
-	 *  override SaveFile but leaf-level ones use this implementation, but
-	 *  leaf-level ones won't even get this call unless you override the ones
-	 *  above them - hence, this is all or nothing
 	 *	@return number of bytes written, 0 if error (or empty) */
-	virtual unsigned int SaveFileStream(FILE* f) const;
+	virtual unsigned int saveFileStream(FILE* f) const;
+
+	//! deprecated, use loadFile() instead (refactored to standardize capitalization style)
+	virtual unsigned int LoadFile(const char* filename) ATTR_deprecated;
+	//! deprecated, use saveFile() instead (refactored to standardize capitalization style)
+	virtual unsigned int SaveFile(const char* filename) const ATTR_deprecated;
 	//@}
 
-	//! Handy for checking results from functions which manipulate the buffer
-	/*! @param res number of bytes used
-	 *  @param buf pointer to address of current place in buffer, will be incremented by @a res bytes
+	//! Handy for checking results from functions which manipulate a buffer (see also encodeInc()/decodeInc() )  If res is 0, returns false
+	/*! Doesn't have to be used with encode/decode, also handy with snprintf, sscanf type operations using %n
+	 *  @param res number of bytes used, or 0 if error
+	 *  @param buf pointer to current position in buffer, will be incremented by @a res bytes
+	 *  @param len number of bytes remain between current place and end of buffer, will be decremented by @a res bytes
+	 *  @return true if everything worked, false otherwise */
+	static inline bool checkInc(int res, const char*& buf, unsigned int& len) throw();
+	
+	//! Handy for checking results from functions which manipulate a buffer (see also encodeInc()/decodeInc() )  If res is 0, displays the specified message on stderr and returns false.
+	/*! Doesn't have to be used with encode/decode, also handy with snprintf, sscanf type operations using %n
+	 *  @param res number of bytes used, or 0 if error
+	 *  @param buf pointer to current position in buffer, will be incremented by @a res bytes
 	 *  @param len number of bytes remain between current place and end of buffer, will be decremented by @a res bytes
 	 *  @param msg Error to display if res is less than or equal to zero
 	 *  @return true if everything worked, false otherwise */
-	static bool ChkAdvance(int res, const char** buf, unsigned int* len, const char* msg);
-
-	//! Handy for checking results from functions which manipulate the buffer
-	/*! This really should be rewritten to use variable number of arguments which can be passed
-	 *  directly on to printf...
-	 *  @param res number of bytes used
-	 *  @param buf pointer to address of current place in buffer, will be incremented by @a res bytes
+	static inline bool checkInc(int res, const char*& buf, unsigned int& len, const char* msg, ...) throw() __attribute__((format(printf,4,5)));
+	
+	//! Handy for checking results from functions which manipulate a buffer (see also encodeInc()/decodeInc() ).  If res is 0, returns false
+	/*! Doesn't have to be used with encode/decode, also handy with snprintf, sscanf type operations using %n
+	 *  @param res number of bytes used, or 0 if error
+	 *  @param buf pointer to current position in buffer, will be incremented by @a res bytes
+	 *  @param len number of bytes remain between current place and end of buffer, will be decremented by @a res bytes
+	 *  @return true if everything worked, false otherwise */
+	static inline bool checkInc(int res, char*& buf, unsigned int& len) throw();
+	
+	//! Handy for checking results from functions which manipulate a buffer (see also encodeInc()/decodeInc() ).  If res is 0, displays the specified message on stderr and returns false.
+	/*! Doesn't have to be used with encode/decode, also handy with snprintf, sscanf type operations using %n
+	 *  @param res number of bytes used, or 0 if error
+	 *  @param buf pointer to current position in buffer, will be incremented by @a res bytes
 	 *  @param len number of bytes remain between current place and end of buffer, will be decremented by @a res bytes
 	 *  @param msg Error to display if res is less than or equal to zero
-	 *  @param arg1 An additional argument to be displayed (using %d in the @a msg); intended for things such as line number of error in file being read
 	 *  @return true if everything worked, false otherwise */
-	static bool ChkAdvance(int res, const char** buf, unsigned int* len, const char* msg, int arg1);
+	static inline bool checkInc(int res, char*& buf, unsigned int& len, const char* msg, ...) throw() __attribute__((format(printf,4,5)));
+	
+	//! Handy for checking results from functions which manipulate a buffer (see also encodeInc()/decodeInc() )  If res is 0, throws a std::length_error with the specified message.
+	/*! Doesn't have to be used with encode/decode, also handy with snprintf, sscanf type operations using %n
+	 *  @param res number of bytes used, or 0 if error
+	 *  @param buf pointer to current position in buffer, will be incremented by @a res bytes
+	 *  @param len number of bytes remain between current place and end of buffer, will be decremented by @a res bytes
+	 *  @param msg Error message to throw in the std::length_error if res is less than or equal to zero */
+	static inline void checkIncT(int res, const char*& buf, unsigned int& len, const char* msg="LoadSave::check underflow", ...) throw(std::length_error) __attribute__((format(printf,4,5)));
+	
+	//! Handy for checking results from functions which manipulate a buffer (see also encodeInc()/decodeInc() ).  If res is 0, throws a std::length_error with the specified message.
+	/*! Doesn't have to be used with encode/decode, also handy with snprintf, sscanf type operations using %n
+	 *  @param res number of bytes used, or 0 if error
+	 *  @param buf pointer to current position in buffer, will be incremented by @a res bytes
+	 *  @param len number of bytes remain between current place and end of buffer, will be decremented by @a res bytes
+	 *  @param msg Error message to throw in the std::length_error if res is less than or equal to zero */
+	static inline void checkIncT(int res, char*& buf, unsigned int& len, const char* msg="LoadSave::check underflow", ...) throw(std::length_error) __attribute__((format(printf,4,5)));
+	
+	//! Encodes @a value into the buffer and if successful, increments the the buffer position and decrements the capacity.  If unsuccessful, returns false
+	/*! @param value the value to encode, must be a primitive or a LoadSave subclass (i.e. a value for which encode() is defined)
+	 *  @param buf pointer to current position in buffer, will be incremented by the serialized size of @a value
+	 *  @param cap number of bytes remain between current place and end of buffer, will be decremented by the serialized size of @a value
+	 *  @return true if everything worked, false otherwise */
+	template <class T> static inline bool encodeInc(const T& value, char*& buf, unsigned int& cap) throw();
 
-	//! These are for putting creator codes at the beginning of your data to check for sanity, just optional
+	//! Encodes @a value into the buffer and if successful, increments the the buffer position and decrements the capacity.  If unsuccessful, displays the specified message on stderr and returns false.
+	/*! @param value the value to encode, must be a primitive or a LoadSave subclass (i.e. a value for which encode() is defined)
+	 *  @param buf pointer to current position in buffer, will be incremented by the serialized size of @a value
+	 *  @param cap number of bytes remain between current place and end of buffer, will be decremented by the serialized size of @a value
+	 *  @param msg Error to display if @a buf did not have enough capacity
+	 *  @return true if everything worked, false otherwise */
+	template <class T> static inline bool encodeInc(const T& value, char*& buf, unsigned int& cap, const char* msg, ...) throw() __attribute__((format(printf,4,5)));
+
+	//! Decodes @a value from the buffer and if successful, increments the the buffer position and decrements the capacity.  If unsuccessful, returns false
+	/*! @param value the value to decode into, must be a primitive or a LoadSave subclass (i.e. a value for which decode() is defined)
+	 *  @param buf pointer to current position in buffer, will be incremented by the serialized size of @a value
+	 *  @param cap number of bytes remain between current place and end of buffer, will be decremented by the serialized size of @a value
+	 *  @return true if everything worked, false otherwise */
+	template <class T> static inline bool decodeInc(T& value, const char*& buf, unsigned int& cap) throw();
+	
+	//! Decodes @a value from the buffer and if successful, increments the the buffer position and decrements the capacity.  If unsuccessful, displays the specified message on stderr and returns false.
+	/*! @param value the value to decode into, must be a primitive or a LoadSave subclass (i.e. a value for which decode() is defined)
+	 *  @param buf pointer to current position in buffer, will be incremented by the serialized size of @a value
+	 *  @param cap number of bytes remain between current place and end of buffer, will be decremented by the serialized size of @a value
+	 *  @param msg Error to display if @a buf did not have enough capacity
+	 *  @return true if everything worked, false otherwise */
+	template <class T> static inline bool decodeInc(T& value, const char*& buf, unsigned int& cap, const char* msg, ...) throw() __attribute__((format(printf,4,5)));
+	
+	//! Decodes @a value from the buffer and if successful, increments the the buffer position and decrements the capacity.  If unsuccessful, returns false.
+	/*! @param value the value to decode into, must be a primitive or a LoadSave subclass (i.e. a value for which decode() is defined)
+	 *  @param buf pointer to current position in buffer, will be incremented by the serialized size of @a value
+	 *  @param cap number of bytes remain between current place and end of buffer, will be decremented by the serialized size of @a value
+	 *  @return true if everything worked, false otherwise */
+	template <class T> static inline bool decodeInc(T& value, char*& buf, unsigned int& cap) throw();
+	
+	//! Decodes @a value from the buffer and if successful, increments the the buffer position and decrements the capacity.  If unsuccessful, displays the specified message on stderr and returns false.
+	/*! @param value the value to decode into, must be a primitive or a LoadSave subclass (i.e. a value for which decode() is defined)
+	 *  @param buf pointer to current position in buffer, will be incremented by the serialized size of @a value
+	 *  @param cap number of bytes remain between current place and end of buffer, will be decremented by the serialized size of @a value
+	 *  @param msg Error to display if @a buf did not have enough capacity
+	 *  @return true if everything worked, false otherwise */
+	template <class T> static inline bool decodeInc(T& value, char*& buf, unsigned int& cap, const char* msg, ...) throw() __attribute__((format(printf,4,5)));
+	
+	//! Encodes @a value into the buffer and if successful, increments the the buffer position and decrements the capacity.  If unsuccessful, throws a std::length_error with the specified message.
+	/*! @param value the value to encode, must be a primitive or a LoadSave subclass (i.e. a value for which encode() is defined)
+	 *  @param buf pointer to current position in buffer, will be incremented by the serialized size of @a value
+	 *  @param cap number of bytes remain between current place and end of buffer, will be decremented by the serialized size of @a value
+	 *  @param msg Error to display if @a buf did not have enough capacity */
+	template <class T> static inline void encodeIncT(const T& value, char*& buf, unsigned int& cap, const char* msg="LoadSave::encode overflow", ...) throw(std::length_error) __attribute__((format(printf,4,5)));
+
+	//! Decodes @a value from the buffer and if successful, increments the the buffer position and decrements the capacity.  If unsuccessful, throws a std::length_error with the specified message.
+	/*! @param value the value to decode into, must be a primitive or a LoadSave subclass (i.e. a value for which decode() is defined)
+	 *  @param buf pointer to current position in buffer, will be incremented by the serialized size of @a value
+	 *  @param cap number of bytes remain between current place and end of buffer, will be decremented by the serialized size of @a value
+	 *  @param msg Error to display if @a buf did not have enough capacity */
+	template <class T> static inline void decodeIncT(T& value, const char*& buf, unsigned int& cap, const char* msg="LoadSave::decode underflow", ...) throw(std::length_error) __attribute__((format(printf,4,5)));
+	
+	//! Decodes @a value from the buffer and if successful, increments the the buffer position and decrements the capacity.  If unsuccessful, throws a std::length_error with the specified message.
+	/*! @param value the value to decode into, must be a primitive or a LoadSave subclass (i.e. a value for which decode() is defined)
+	 *  @param buf pointer to current position in buffer, will be incremented by the serialized size of @a value
+	 *  @param cap number of bytes remain between current place and end of buffer, will be decremented by the serialized size of @a value
+	 *  @param msg Error to display if @a buf did not have enough capacity */
+	template <class T> static inline void decodeIncT(T& value, char*& buf, unsigned int& cap, const char* msg="LoadSave::decode underflow", ...) throw(std::length_error) __attribute__((format(printf,4,5)));
+	
+	//! deprecated, use checkInc() instead (provides less error-prone interface (NULL not allowed), mixes better with other new *Inc varients)
+	static bool chkAdvance(int res, const char** buf, unsigned int* len, const char* msg, ...) ATTR_deprecated __attribute__((format(printf,4,5)));
+
+	/*! @brief These are expected to be called from within your own getBinSize implementation in order to add up the size of all the member fields.
+	 *  Use these instead of sizeof() because this allows proper handling of some oddball conditions (bool isn't 1 byte on some platforms, use strlen on char*, etc.) */
+	//! @name Methods to detect the size member fields
+	/*! @brief returns the serialized size of the argument */
+	inline static unsigned int getSerializedSize(const LoadSave& x) throw() { return x.getBinSize(); }
+	inline static unsigned int getSerializedSize(const std::string& x) throw() { return x.size()+stringpad; }
+	inline static unsigned int getSerializedSize(const char* x) throw() { unsigned int sz=strlen(x); return sz+stringpad; }
+	inline static unsigned int getSerializedSize(const void*) throw() { return sizeof(unsigned long long); }
+	inline static unsigned int getSerializedSize(const bool&) throw() { return sizeof(char); }
+	template <class T> inline static unsigned int getSerializedSize(const T& x) throw() { return sizeof(x); }
+	//! this version lets you get the theoretical size of a type, but beware it will throw invalid_argument if you pass a string type! (can't tell the size of the string without an actual instance...)
+	template <class T> inline static unsigned int getSerializedSize() throw() { throw std::invalid_argument("The template argument passed to getSerializedSize() is not supported by LoadSave"); }
+	//@}
+	
+	
+	/*! @brief These are for putting creator codes (a uniquely identifying string, e.g. the name of the class) at the beginning of your data -- 
+	 *  doing so is a good idea to allow polymorphism, version detection (backward compatability), or just a sanity check */
 	//!@name Creator Utilities
 
 	/*!@brief Returns size of the creator code
@@ -218,24 +293,48 @@
 	 * @param len the size remaining in the buffer
 	 * @param isLoading set this to true if you want to output a warning if it doesn't match
 	 * @return the number of bytes used by the creator, or 0 if it didn't match */
-	virtual unsigned int checkCreator(const char* creator, const char buf[], unsigned int len, bool isLoading=true) const;
+	virtual unsigned int checkCreator(const char* creator, const char buf[], unsigned int len, bool isLoading=true) const throw();
+	//! Compares the creator code in the buffer to the one given, increments buf and decrements len if it matches
+	/*!@param creator what the creator should be
+	 * @param buf the buffer to check
+	 * @param len the size remaining in the buffer
+	 * @param isLoading set this to true if you want to output a warning if it doesn't match
+	 * @return true if it matched, false otherwise */
+	virtual bool checkCreatorInc(const char* creator, const char*& buf, unsigned int& len, bool isLoading=true) const throw();
+	//! Compares the creator code in the buffer to the one given, increments buf and decrements len if it matches, throws std::runtime_error if it doesn't match
+	/*!@param creator what the creator should be
+	 * @param buf the buffer to check
+	 * @param len the size remaining in the buffer
+	 * @param isLoading set this to true if you want to output a warning if it doesn't match */
+	virtual void checkCreatorIncT(const char* creator, const char*& buf, unsigned int& len, bool isLoading=true) const throw(std::runtime_error);
 	//! Compares the creator code in the file to the one given, will attempt to reset the file position if fails (so you can check for one of several types)
 	/*!@param creator what the creator should be
 	 * @param f the file pointer to check
 	 * @param isLoading set this to true if you want to output a warning if it doesn't match
 	 * @return the number of bytes consumed by the creator code, or 0 if it didn't match */
-	virtual unsigned int checkCreator(const char* creator, FILE* f, bool isLoading=true) const;
+	virtual unsigned int checkCreator(const char* creator, FILE* f, bool isLoading=true) const throw();
 	//! Saves a creator code to a buffer
 	/*!@param creator the string to use for the creator code
 	 * @param buf the buffer to save the code into
 	 * @param len the space available in the buffer
 	 * @return the number of bytes consumed */
-	virtual unsigned int saveCreator(const char* creator, char buf[], unsigned int len) const;
+	virtual unsigned int saveCreator(const char* creator, char buf[], unsigned int len) const throw();
+	//! Saves a creator code to a buffer, increments buf and decrements len by the amount used
+	/*!@param creator the string to use for the creator code
+	 * @param buf the buffer to save the code into
+	 * @param len the space available in the buffer
+	 * @return true if successful, false otherwise */
+	virtual bool saveCreatorInc(const char* creator, char*& buf, unsigned int& len) const throw();
+	//! Saves a creator code to a buffer, increments buf and decrements len by the amount used
+	/*!@param creator the string to use for the creator code
+	 * @param buf the buffer to save the code into
+	 * @param len the space available in the buffer */
+	virtual void saveCreatorIncT(const char* creator, char*& buf, unsigned int& len) const throw(std::runtime_error);
 	//! Saves a creator code directly to a file
 	/*!@param creator the string to use for the creator code
 	 * @param f the file to save the code into
 	 * @return the number of bytes consumed */
-	virtual unsigned int saveCreator(const char* creator, FILE* f) const;
+	virtual unsigned int saveCreator(const char* creator, FILE* f) const throw();
 	//@}
 
 	/* //if you want to have a default behavior template like this (look up template specialization) (i thought i needed this, nevermind)
@@ -248,133 +347,457 @@
 	//!encode/decode cross-platform compatable (byte order consistancy)
 	//!@name Encode/Decode Utils
 	/*!@brief encode or decode with byte order consistancy*/
-	inline static unsigned int encode(const LoadSave& x, char buf[], unsigned int cap)  { return x.SaveBuffer(buf,cap); }
-	inline static unsigned int decode(LoadSave& x, const char buf[], unsigned int cap)  { return x.LoadBuffer(buf,cap); }
-	inline static unsigned int encode(const LoadSave& x, FILE* f)                  { return x.SaveFileStream(f); }
-	inline static unsigned int decode(LoadSave& x, FILE* f)                        { return x.LoadFileStream(f); }
+	inline static unsigned int encode(const LoadSave& x, char buf[], unsigned int cap) { return x.saveBuffer(buf,cap); }
+	inline static unsigned int decode(LoadSave& x, const char buf[], unsigned int cap) { return x.loadBuffer(buf,cap); }
+	inline static unsigned int encode(const LoadSave& x, FILE* f)                 { return x.saveFileStream(f); }
+	inline static unsigned int decode(LoadSave& x, FILE* f)                       { return x.loadFileStream(f); }
 	
 #if LOADSAVE_SWAPBYTES
 	
-	inline static unsigned int encode(const double x, char buf[], unsigned int cap)          { if(cap<sizeof(x)) return 0; byteswap(*(double*)buf,x); return sizeof(x); }
-	inline static unsigned int decode(double& x, const char buf[], unsigned int cap)         { if(cap<sizeof(x)) return 0; byteswap(x,*(const double*)buf); return sizeof(x);}
-	inline static unsigned int encode(const double x, FILE* f)                          { double t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
-	inline static unsigned int decode(double& x, FILE* f)                               { double t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
+	inline static unsigned int encode(const double x, char buf[], unsigned int cap) throw()         { if(cap<sizeof(x)) return 0; byteswap(*(double*)buf,x); return sizeof(x); }
+	inline static unsigned int decode(double& x, const char buf[], unsigned int cap) throw()        { if(cap<sizeof(x)) return 0; byteswap(x,*(const double*)buf); return sizeof(x);}
+	inline static unsigned int encode(const double x, FILE* f) throw()                         { double t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
+	inline static unsigned int decode(double& x, FILE* f) throw()                              { double t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
 	
-	inline static unsigned int encode(const float x, char buf[], unsigned int cap)           { if(cap<sizeof(x)) return 0; byteswap(*(float*)buf,x); return sizeof(x); }
-	inline static unsigned int decode(float& x, const char buf[], unsigned int cap)          { if(cap<sizeof(x)) return 0; byteswap(x,*(const float*)buf); return sizeof(x);}
-	inline static unsigned int encode(const float x, FILE* f)                           { float t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
-	inline static unsigned int decode(float& x, FILE* f)                                { float t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
+	inline static unsigned int encode(const float x, char buf[], unsigned int cap) throw()          { if(cap<sizeof(x)) return 0; byteswap(*(float*)buf,x); return sizeof(x); }
+	inline static unsigned int decode(float& x, const char buf[], unsigned int cap) throw()         { if(cap<sizeof(x)) return 0; byteswap(x,*(const float*)buf); return sizeof(x);}
+	inline static unsigned int encode(const float x, FILE* f) throw()                          { float t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
+	inline static unsigned int decode(float& x, FILE* f) throw()                               { float t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
 	
-	inline static unsigned int encode(const long x, char buf[], unsigned int cap)            { if(cap<sizeof(x)) return 0; byteswap(*(long*)buf,x); return sizeof(x); }
-	inline static unsigned int decode(long& x, const char buf[], unsigned int cap)           { if(cap<sizeof(x)) return 0; byteswap(x,*(const long*)buf); return sizeof(x);}
-	inline static unsigned int encode(const long x, FILE* f)                            { long t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
-	inline static unsigned int decode(long& x, FILE* f)                                 { long t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
-	inline static unsigned int encode(const unsigned long x, char buf[], unsigned int cap)   { if(cap<sizeof(x)) return 0; byteswap(*(unsigned long*)buf,x); return sizeof(x); }
-	inline static unsigned int decode(unsigned long& x, const char buf[], unsigned int cap)  { if(cap<sizeof(x)) return 0; byteswap(x,*(const unsigned long*)buf); return sizeof(x);}
-	inline static unsigned int encode(const unsigned long x, FILE* f)                   { unsigned long t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
-	inline static unsigned int decode(unsigned long& x, FILE* f)                        { unsigned long t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
-	inline static unsigned int encode(const int x, char buf[], unsigned int cap)             { if(cap<sizeof(x)) return 0; byteswap(*(int*)buf,x); return sizeof(x); }
-	inline static unsigned int decode(int& x, const char buf[], unsigned int cap)            { if(cap<sizeof(x)) return 0; byteswap(x,*(const int*)buf); return sizeof(x);}
-	inline static unsigned int encode(const int x, FILE* f)                             { int t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
-	inline static unsigned int decode(int& x, FILE* f)                                  { int t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
-	inline static unsigned int encode(const unsigned int x, char buf[], unsigned int cap)    { if(cap<sizeof(x)) return 0; byteswap(*(unsigned int*)buf,x); return sizeof(x); }
-	inline static unsigned int decode(unsigned int& x, const char buf[], unsigned int cap)   { if(cap<sizeof(x)) return 0; byteswap(x,*(const unsigned int*)buf); return sizeof(x);}
-	inline static unsigned int encode(const unsigned int x, FILE* f)                    { unsigned int t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
-	inline static unsigned int decode(unsigned int& x, FILE* f)                         { unsigned int t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
+	inline static unsigned int encode(const long long x, char buf[], unsigned int cap) throw()           { if(cap<sizeof(x)) return 0; byteswap(*(long long*)buf,x); return sizeof(x); }
+	inline static unsigned int decode(long long& x, const char buf[], unsigned int cap) throw()          { if(cap<sizeof(x)) return 0; byteswap(x,*(const long long*)buf); return sizeof(x);}
+	inline static unsigned int encode(const long long x, FILE* f) throw()                           { long long t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
+	inline static unsigned int decode(long long& x, FILE* f) throw()                                { long long t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
+	inline static unsigned int encode(const unsigned long long x, char buf[], unsigned int cap) throw()  { if(cap<sizeof(x)) return 0; byteswap(*(unsigned long long*)buf,x); return sizeof(x); }
+	inline static unsigned int decode(unsigned long long& x, const char buf[], unsigned int cap) throw() { if(cap<sizeof(x)) return 0; byteswap(x,*(const unsigned long long*)buf); return sizeof(x);}
+	inline static unsigned int encode(const unsigned long long x, FILE* f) throw()                  { unsigned long long t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
+	inline static unsigned int decode(unsigned long long& x, FILE* f) throw()                       { unsigned long long t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
 	
-	inline static unsigned int encode(const short x, char buf[], unsigned int cap)           { if(cap<sizeof(x)) return 0; byteswap(*(short*)buf,x); return sizeof(x); }
-	inline static unsigned int decode(short& x, const char buf[], unsigned int cap)          { if(cap<sizeof(x)) return 0; byteswap(x,*(const short*)buf); return sizeof(x);}
-	inline static unsigned int encode(const short x, FILE* f)                           { short t; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
-	inline static unsigned int decode(short& x, FILE* f)                                { short t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
-	inline static unsigned int encode(const unsigned short x, char buf[], unsigned int cap)  { if(cap<sizeof(x)) return 0; byteswap(*(unsigned short*)buf,x); return sizeof(x); }
-	inline static unsigned int decode(unsigned short& x, const char buf[], unsigned int cap) { if(cap<sizeof(x)) return 0; byteswap(x,*(const unsigned short*)buf); return sizeof(x);}
-	inline static unsigned int encode(const unsigned short x, FILE* f)                  { unsigned short t; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
-	inline static unsigned int decode(unsigned short& x, FILE* f)                       { unsigned short t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
+	inline static unsigned int encode(const long x, char buf[], unsigned int cap) throw()           { if(cap<sizeof(x)) return 0; byteswap(*(long*)buf,x); return sizeof(x); }
+	inline static unsigned int decode(long& x, const char buf[], unsigned int cap) throw()          { if(cap<sizeof(x)) return 0; byteswap(x,*(const long*)buf); return sizeof(x);}
+	inline static unsigned int encode(const long x, FILE* f) throw()                           { long t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
+	inline static unsigned int decode(long& x, FILE* f) throw()                                { long t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
+	inline static unsigned int encode(const unsigned long x, char buf[], unsigned int cap) throw()  { if(cap<sizeof(x)) return 0; byteswap(*(unsigned long*)buf,x); return sizeof(x); }
+	inline static unsigned int decode(unsigned long& x, const char buf[], unsigned int cap) throw() { if(cap<sizeof(x)) return 0; byteswap(x,*(const unsigned long*)buf); return sizeof(x);}
+	inline static unsigned int encode(const unsigned long x, FILE* f) throw()                  { unsigned long t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
+	inline static unsigned int decode(unsigned long& x, FILE* f) throw()                       { unsigned long t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
+	
+	inline static unsigned int encode(const int x, char buf[], unsigned int cap) throw()            { if(cap<sizeof(x)) return 0; byteswap(*(int*)buf,x); return sizeof(x); }
+	inline static unsigned int decode(int& x, const char buf[], unsigned int cap) throw()           { if(cap<sizeof(x)) return 0; byteswap(x,*(const int*)buf); return sizeof(x);}
+	inline static unsigned int encode(const int x, FILE* f) throw()                            { int t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
+	inline static unsigned int decode(int& x, FILE* f) throw()                                 { int t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
+	inline static unsigned int encode(const unsigned int x, char buf[], unsigned int cap) throw()   { if(cap<sizeof(x)) return 0; byteswap(*(unsigned int*)buf,x); return sizeof(x); }
+	inline static unsigned int decode(unsigned int& x, const char buf[], unsigned int cap) throw()  { if(cap<sizeof(x)) return 0; byteswap(x,*(const unsigned int*)buf); return sizeof(x);}
+	inline static unsigned int encode(const unsigned int x, FILE* f) throw()                   { unsigned int t=0; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
+	inline static unsigned int decode(unsigned int& x, FILE* f) throw()                        { unsigned int t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
+	
+	inline static unsigned int encode(const short x, char buf[], unsigned int cap) throw()          { if(cap<sizeof(x)) return 0; byteswap(*(short*)buf,x); return sizeof(x); }
+	inline static unsigned int decode(short& x, const char buf[], unsigned int cap) throw()         { if(cap<sizeof(x)) return 0; byteswap(x,*(const short*)buf); return sizeof(x);}
+	inline static unsigned int encode(const short x, FILE* f) throw()                          { short t; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
+	inline static unsigned int decode(short& x, FILE* f) throw()                               { short t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
+	inline static unsigned int encode(const unsigned short x, char buf[], unsigned int cap) throw() { if(cap<sizeof(x)) return 0; byteswap(*(unsigned short*)buf,x); return sizeof(x); }
+	inline static unsigned int decode(unsigned short& x, const char buf[], unsigned int cap) throw(){ if(cap<sizeof(x)) return 0; byteswap(x,*(const unsigned short*)buf); return sizeof(x);}
+	inline static unsigned int encode(const unsigned short x, FILE* f) throw()                 { unsigned short t; byteswap(t,x); return sizeof(x)*fwrite(&t,sizeof(x),1,f); }
+	inline static unsigned int decode(unsigned short& x, FILE* f) throw()                      { unsigned short t=0; if(fread(&t,sizeof(x),1,f)==0) return 0; byteswap(x,t); return sizeof(x);}
 
 #else
 	
-	inline static unsigned int encode(const double x, char buf[], unsigned int cap)         { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
-	inline static unsigned int decode(double& x, const char buf[], unsigned int cap)        { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
-	inline static unsigned int encode(const double x, FILE* f)                         { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
-	inline static unsigned int decode(double& x, FILE* f)                              { return sizeof(x)*fread(&x,sizeof(x),1,f); }
+	inline static unsigned int encode(const double x, char buf[], unsigned int cap) throw()        { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
+	inline static unsigned int decode(double& x, const char buf[], unsigned int cap) throw()       { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
+	inline static unsigned int encode(const double x, FILE* f) throw()                        { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
+	inline static unsigned int decode(double& x, FILE* f) throw()                             { return sizeof(x)*fread(&x,sizeof(x),1,f); }
 	
-	inline static unsigned int encode(const float x, char buf[], unsigned int cap)          { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
-	inline static unsigned int decode(float& x, const char buf[], unsigned int cap)         { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
-	inline static unsigned int encode(const float x, FILE* f)                          { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
-	inline static unsigned int decode(float& x, FILE* f)                               { return sizeof(x)*fread(&x,sizeof(x),1,f); }
+	inline static unsigned int encode(const float x, char buf[], unsigned int cap) throw()         { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
+	inline static unsigned int decode(float& x, const char buf[], unsigned int cap) throw()        { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
+	inline static unsigned int encode(const float x, FILE* f) throw()                         { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
+	inline static unsigned int decode(float& x, FILE* f) throw()                              { return sizeof(x)*fread(&x,sizeof(x),1,f); }
 
-	inline static unsigned int encode(const long x, char buf[], unsigned int cap)           { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
-	inline static unsigned int decode(long& x, const char buf[], unsigned int cap)          { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
-	inline static unsigned int encode(const long x, FILE* f)                           { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
-	inline static unsigned int decode(long& x, FILE* f)                                { return sizeof(x)*fread(&x,sizeof(x),1,f); }
-	inline static unsigned int encode(const unsigned long x, char buf[], unsigned int cap)  { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
-	inline static unsigned int decode(unsigned long& x, const char buf[], unsigned int cap) { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
-	inline static unsigned int encode(const unsigned long x, FILE* f)                  { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
-	inline static unsigned int decode(unsigned long& x, FILE* f)                       { return sizeof(x)*fread(&x,sizeof(x),1,f); }
-	inline static unsigned int encode(const int x, char buf[], unsigned int cap)            { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
-	inline static unsigned int decode(int& x, const char buf[], unsigned int cap)           { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
-	inline static unsigned int encode(const int x, FILE* f)                            { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
-	inline static unsigned int decode(int& x, FILE* f)                                 { return sizeof(x)*fread(&x,sizeof(x),1,f); }
-	inline static unsigned int encode(const unsigned int x, char buf[], unsigned int cap)   { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
-	inline static unsigned int decode(unsigned int& x, const char buf[], unsigned int cap)  { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
-	inline static unsigned int encode(const unsigned int x, FILE* f)                   { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
-	inline static unsigned int decode(unsigned int& x, FILE* f)                        { return sizeof(x)*fread(&x,sizeof(x),1,f); }
+	inline static unsigned int encode(const long long x, char buf[], unsigned int cap) throw()          { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
+	inline static unsigned int decode(long long& x, const char buf[], unsigned int cap) throw()         { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
+	inline static unsigned int encode(const long long x, FILE* f) throw()                          { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
+	inline static unsigned int decode(long long& x, FILE* f) throw()                               { return sizeof(x)*fread(&x,sizeof(x),1,f); }
+	inline static unsigned int encode(const unsigned long long x, char buf[], unsigned int cap) throw() { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
+	inline static unsigned int decode(unsigned long long& x, const char buf[], unsigned int cap) throw(){ if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
+	inline static unsigned int encode(const unsigned long long x, FILE* f) throw()                 { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
+	inline static unsigned int decode(unsigned long long& x, FILE* f) throw()                      { return sizeof(x)*fread(&x,sizeof(x),1,f); }
 	
-	inline static unsigned int encode(const short x, char buf[], unsigned int cap)          { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
-	inline static unsigned int decode(short& x, const char buf[], unsigned int cap)         { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
-	inline static unsigned int encode(const short x, FILE* f)                          { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
-	inline static unsigned int decode(short& x, FILE* f)                               { return sizeof(x)*fread(&x,sizeof(x),1,f); }
-	inline static unsigned int encode(const unsigned short x, char buf[], unsigned int cap) { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
+	inline static unsigned int encode(const long x, char buf[], unsigned int cap) throw()          { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
+	inline static unsigned int decode(long& x, const char buf[], unsigned int cap) throw()         { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
+	inline static unsigned int encode(const long x, FILE* f) throw()                          { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
+	inline static unsigned int decode(long& x, FILE* f) throw()                               { return sizeof(x)*fread(&x,sizeof(x),1,f); }
+	inline static unsigned int encode(const unsigned long x, char buf[], unsigned int cap) throw() { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
+	inline static unsigned int decode(unsigned long& x, const char buf[], unsigned int cap) throw(){ if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
+	inline static unsigned int encode(const unsigned long x, FILE* f) throw()                 { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
+	inline static unsigned int decode(unsigned long& x, FILE* f) throw()                      { return sizeof(x)*fread(&x,sizeof(x),1,f); }
+	
+	inline static unsigned int encode(const int x, char buf[], unsigned int cap) throw()           { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
+	inline static unsigned int decode(int& x, const char buf[], unsigned int cap) throw()          { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
+	inline static unsigned int encode(const int x, FILE* f) throw()                           { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
+	inline static unsigned int decode(int& x, FILE* f) throw()                                { return sizeof(x)*fread(&x,sizeof(x),1,f); }
+	inline static unsigned int encode(const unsigned int x, char buf[], unsigned int cap) throw()  { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
+	inline static unsigned int decode(unsigned int& x, const char buf[], unsigned int cap) throw() { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
+	inline static unsigned int encode(const unsigned int x, FILE* f) throw()                  { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
+	inline static unsigned int decode(unsigned int& x, FILE* f) throw()                       { return sizeof(x)*fread(&x,sizeof(x),1,f); }
+	
+	inline static unsigned int encode(const short x, char buf[], unsigned int cap) throw()         { if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
+	inline static unsigned int decode(short& x, const char buf[], unsigned int cap) throw()        { if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
+	inline static unsigned int encode(const short x, FILE* f) throw()                         { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
+	inline static unsigned int decode(short& x, FILE* f) throw()                              { return sizeof(x)*fread(&x,sizeof(x),1,f); }
+	inline static unsigned int encode(const unsigned short x, char buf[], unsigned int cap) throw(){ if(cap<sizeof(x)) return 0; memcpy(buf,&x,sizeof(x)); return sizeof(x); }
 	inline static unsigned int decode(unsigned short& x, const char buf[], unsigned int cap){ if(cap<sizeof(x)) return 0; memcpy(&x,buf,sizeof(x)); return sizeof(x); }
-	inline static unsigned int encode(const unsigned short x, FILE* f)                 { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
-	inline static unsigned int decode(unsigned short& x, FILE* f)                      { return sizeof(x)*fread(&x,sizeof(x),1,f); }
+	inline static unsigned int encode(const unsigned short x, FILE* f) throw()                { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
+	inline static unsigned int decode(unsigned short& x, FILE* f) throw()                     { return sizeof(x)*fread(&x,sizeof(x),1,f); }
 
 #endif //end of big/little endian differences
 	
-	inline static unsigned int encode(const std::string& x, char buf[], unsigned int cap)  { 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 decode(std::string& x, const char buf[], unsigned int cap)  { 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)                  { encode(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)                        { 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; }
+	/* These next two functions will allow you to serialize pointer values, but they are left out for safety -- if you're
+	 * serializing a pointer, you probably meant to serialize the _data at the pointer_ not the pointer itself!
+	 * If you really want to serialize the address in memory (say as an object ID of some sort), it is recommended
+	 * to cast the pointer to unsigned long long (for 64 bit compatability) in your own code, and still not use these. */
 	
-	inline static unsigned int encode(const char* x, char buf[], unsigned int cap)      { 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; }
-	inline static unsigned int decode(char*& x, const char buf[], unsigned int cap)     { 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=new char[sz+1]; strncpy(x,buf+sizeof(unsigned int),sz+1); return sz+stringpad; }
-	inline static unsigned int encode(const char* x, FILE* f)                      { unsigned int sz=strlen(x); encode(sz,f); return sizeof(unsigned int)+fwrite(x,1,sz+1,f); }
-	inline static unsigned int decode(char*& x, FILE* f)                           { unsigned int sz=0; decode(sz,f); x=new char[sz+1]; if(fread(x,1,sz+1,f)!=sz+1) { delete [] x; x=NULL; return 0; } return sz+stringpad; }
+	//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 char x, char buf[], unsigned int cap)          { if(cap<sizeof(x)) return 0; buf[0]=x; return sizeof(x); }
-	inline static unsigned int decode(char& x, const char buf[], unsigned int cap)         { if(cap<sizeof(x)) return 0; x=buf[0]; return sizeof(x);}
-	inline static unsigned int encode(const char x, FILE* f)                          { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
-	inline static unsigned int decode(char& x, FILE* f)                               { return sizeof(x)*fread(&x,sizeof(x),1,f); }
-	inline static unsigned int encode(const unsigned char x, char buf[], unsigned int cap) { if(cap<sizeof(x)) return 0; buf[0]=(char)x; return sizeof(x); }
+	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 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 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; }
+	inline static unsigned int decode(char*& 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=new char[sz+1]; strncpy(x,buf+sizeof(unsigned int),sz+1); return sz+stringpad; }
+	inline static unsigned int encode(const char* x, FILE* f) throw()                     { unsigned int sz=strlen(x); encode(sz,f); return sizeof(unsigned int)+fwrite(x,1,sz+1,f); }
+	inline static unsigned int decode(char*& x, FILE* f) throw()                          { unsigned int sz=0; decode(sz,f); x=new char[sz+1]; if(fread(x,1,sz+1,f)!=sz+1) { delete [] x; x=NULL; return 0; } return sz+stringpad; }
+	
+	inline static unsigned int encode(const char x, char buf[], unsigned int cap) throw()         { if(cap<sizeof(x)) return 0; buf[0]=x; return sizeof(x); }
+	inline static unsigned int decode(char& x, const char buf[], unsigned int cap) throw()        { if(cap<sizeof(x)) return 0; x=buf[0]; return sizeof(x);}
+	inline static unsigned int encode(const char x, FILE* f) throw()                         { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
+	inline static unsigned int decode(char& x, FILE* f) throw()                              { return sizeof(x)*fread(&x,sizeof(x),1,f); }
+	inline static unsigned int encode(const unsigned char x, char buf[], unsigned int cap) throw(){ if(cap<sizeof(x)) return 0; buf[0]=(char)x; return sizeof(x); }
 	inline static unsigned int decode(unsigned char& x, const char buf[], unsigned int cap){ if(cap<sizeof(x)) return 0; x=(unsigned char)buf[0]; return sizeof(x);}
-	inline static unsigned int encode(const unsigned char x, FILE* f)                 { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
-	inline static unsigned int decode(unsigned char& x, FILE* f)                      { return sizeof(x)*fread(&x,sizeof(x),1,f); }
+	inline static unsigned int encode(const unsigned char x, FILE* f) throw()                { return sizeof(x)*fwrite(&x,sizeof(x),1,f); }
+	inline static unsigned int decode(unsigned char& x, FILE* f) throw()                     { return sizeof(x)*fread(&x,sizeof(x),1,f); }
 	
-	inline static unsigned int encode(const bool x, char buf[], unsigned int cap)          { if(cap<sizeof(char)) return 0; buf[0]=(char)(x?1:0); return sizeof(char); }
-	inline static unsigned int decode(bool& x, const char buf[], unsigned int cap)         { if(cap<sizeof(char)) return 0; x=(buf[0]!=(char)0); return sizeof(char);}
-	inline static unsigned int encode(const bool x, FILE* f)                          { char t=(char)(x?1:0); return sizeof(char)*fwrite(&t,sizeof(char),1,f); }
-	inline static unsigned int decode(bool& x, FILE* f)                               { char t='\0'; fread(&t,sizeof(char),1,f); x=(t!=(char)0); return sizeof(char); }
+	inline static unsigned int encode(const bool x, char buf[], unsigned int cap) throw()         { if(cap<sizeof(char)) return 0; buf[0]=(char)(x?1:0); return sizeof(char); }
+	inline static unsigned int decode(bool& x, const char buf[], unsigned int cap) throw()        { if(cap<sizeof(char)) return 0; x=(buf[0]!=(char)0); return sizeof(char);}
+	inline static unsigned int encode(const bool x, FILE* f) throw()                         { char t=(char)(x?1:0); return sizeof(char)*fwrite(&t,sizeof(char),1,f); }
+	inline static unsigned int decode(bool& x, FILE* f) throw()                              { char t='\0'; fread(&t,sizeof(char),1,f); x=(t!=(char)0); return sizeof(char); }
 	//@}	
 protected:
 	//!templated function to swap byte ordering, should allow compiler to unroll the loop; warning don't use this if src==dst!!!
-	template<class T> inline static void byteswap(T& dstc, const T& srcc) {
+	template<class T> inline static void byteswap(T& dstc, const T& srcc) throw() {
 		char* dst=(char*)&dstc;
 		const char* src=(const char*)&srcc;
 		for(unsigned int i=0; i<sizeof(T); i++)
 			dst[sizeof(T)-1-i]=src[i];
 	}
+// It appears that aperios does have vasprintf, it's just not exposed in the header files.
+// Thus, for Aperios, we provide a prototype above instead of this implementation, but it's here if needed on another platform.
+#if defined(NEED_ASPRINTF)
+	int vasprintf(char** ret, const char* format, va_list al) {
+		va_list tmpal;
+		va_copy(tmpal,al);
+		int nc=vsnprintf(NULL,0,format,tmpal);
+		*ret = (char*)malloc(nc+1);
+		if(*ret==NULL) return -1;
+		return vsnprintf(*ret,nc+1,format,al);
+	}
+	int asprintf(char **ret, const char *format, ...) {
+		va_list ap;
+		va_start (ap, format);
+		int nc= vasprintf(ret, format, ap);
+		va_end(ap);
+		return nc;
+	}
+#endif
 };
 
+//hide from doxygen
+#ifndef __DOXYGEN__
+//! template specialization to return serialized size of the specified type
+template <> inline unsigned int LoadSave::getSerializedSize<void*>() throw() { return sizeof(unsigned long long); }
+template <> inline unsigned int LoadSave::getSerializedSize<bool>() throw() { return sizeof(char); }
+template <> inline unsigned int LoadSave::getSerializedSize<char>() throw() { return sizeof(char); }
+template <> inline unsigned int LoadSave::getSerializedSize<unsigned char>() throw() { return sizeof(unsigned char); }
+template <> inline unsigned int LoadSave::getSerializedSize<short>() throw() { return sizeof(short); }
+template <> inline unsigned int LoadSave::getSerializedSize<unsigned short>() throw() { return sizeof(unsigned short); }
+template <> inline unsigned int LoadSave::getSerializedSize<int>() throw() { return sizeof(int); }
+template <> inline unsigned int LoadSave::getSerializedSize<unsigned int>() throw() { return sizeof(unsigned int); }
+template <> inline unsigned int LoadSave::getSerializedSize<long>() throw() { return sizeof(long); }
+template <> inline unsigned int LoadSave::getSerializedSize<unsigned long>() throw() { return sizeof(unsigned long); }
+template <> inline unsigned int LoadSave::getSerializedSize<long long>() throw() { return sizeof(long long); }
+template <> inline unsigned int LoadSave::getSerializedSize<unsigned long long>() throw() { return sizeof(unsigned long long); }
+template <> inline unsigned int LoadSave::getSerializedSize<float>() throw() { return sizeof(float); }
+template <> inline unsigned int LoadSave::getSerializedSize<double>() throw() { return sizeof(double); }
+
+template <> inline unsigned int LoadSave::getSerializedSize<char*>() throw(std::invalid_argument) { throw std::invalid_argument("Cannot pass string as template arg to getSerializedSize() -- need instance to know length!"); }
+template <> inline unsigned int LoadSave::getSerializedSize<std::string>() throw(std::invalid_argument) { throw std::invalid_argument("Cannot pass string as template arg to getSerializedSize() -- need instance to know length!"); }
+template <> inline unsigned int LoadSave::getSerializedSize<LoadSave>() throw(std::invalid_argument) { throw std::invalid_argument("Cannot pass LoadSave subclass as template arg to getSerializedSize() -- need instance to know length!\nIf the subclass in question has a static size, you could add a getSerializedSize() template specialization to do the size calculation (and have getBinSize return that)."); }
+#endif
+
+bool LoadSave::checkInc(int res, const char*& buf, unsigned int& len) throw() {
+	if(res<0 || (unsigned int)res>len)
+		return false;
+	buf+=res;
+	len-=res;
+	return true;
+}
+
+bool LoadSave::checkInc(int res, const char*& buf, unsigned int& len, const char* msg, ...) throw() {
+	if(checkInc(res,buf,len))
+		return true;
+	if(msg[0]!='\0') {
+		if((unsigned int)res>len)
+			fprintf(stderr,"*** WARNING: reported check result length exceeded remaining buffer size; %u (signed %d) vs %u\n",(unsigned int)res,res,len);
+		va_list al;
+		va_start(al,msg);
+		vfprintf(stderr,msg,al);
+		va_end(al);
+	}
+	return false;
+}
+
+bool LoadSave::checkInc(int res, char*& buf, unsigned int& len) throw() {
+	if(res<0 || (unsigned int)res>len)
+		return false;
+	buf+=res;
+	len-=res;
+	return true;
+}
+
+bool LoadSave::checkInc(int res, char*& buf, unsigned int& len, const char* msg, ...) throw() {
+	if(checkInc(res,buf,len))
+		return true;
+	if(msg[0]!='\0') {
+		if((unsigned int)res>len)
+			fprintf(stderr,"*** WARNING: reported check result length exceeded remaining buffer size; %u (signed %d) vs %u\n",(unsigned int)res,res,len);
+		va_list al;
+		va_start(al,msg);
+		vfprintf(stderr,msg,al);
+		va_end(al);
+	}
+	return false;
+}
+
+void LoadSave::checkIncT(int res, const char*& buf, unsigned int& len, const char* msg, ...) throw(std::length_error) {
+	if(res>0 && (unsigned int)res<=len) {
+		buf+=res;
+		len-=res;
+	} else {
+		if((unsigned int)res>len && msg[0]!='\0')
+			fprintf(stderr,"*** WARNING: reported check result length exceeded remaining buffer size; %u (signed %d) vs %u\n",(unsigned int)res,res,len);
+		va_list al;
+		va_start(al,msg);
+		char * errmsg;
+		vasprintf(&errmsg,msg,al);
+		va_end(al);
+		if(errmsg==NULL)
+			throw std::length_error("unspecified");
+		std::string serrmsg=errmsg;
+		free(errmsg);
+		throw std::length_error(serrmsg);
+	}
+}
+
+void LoadSave::checkIncT(int res, char*& buf, unsigned int& len, const char* msg, ...) throw(std::length_error) {
+	if(res>0 && (unsigned int)res<=len) {
+		buf+=res;
+		len-=res;
+	} else {
+		if((unsigned int)res>len && msg[0]!='\0')
+			fprintf(stderr,"*** WARNING: reported check result length exceeded remaining buffer size; %u (signed %d) vs %u\n",(unsigned int)res,res,len);
+		va_list al;
+		va_start(al,msg);
+		char * errmsg;
+		vasprintf(&errmsg,msg,al);
+		va_end(al);
+		if(errmsg==NULL)
+			throw std::length_error("unspecified");
+		std::string serrmsg=errmsg;
+		free(errmsg);
+		throw std::length_error(serrmsg);
+	}
+}
+
+template <class T>
+bool LoadSave::encodeInc(const T& value, char*& buf, unsigned int& cap) throw() {
+	unsigned int res=encode(value,buf,cap);
+	if(res==0)
+		return false;
+#ifdef LOADSAVE_DEBUG
+	if(res>cap) {
+		fprintf(stderr,"*** WARNING: reported encode result length exceeded remaining buffer size; %u (signed %d) vs %u\n",res,(int)res,cap);
+		return false;
+	}
+#endif
+	buf+=res;
+	cap-=res;
+	return true;
+}
+template <class T>
+bool LoadSave::encodeInc(const T& value, char*& buf, unsigned int& cap, const char* msg, ...) throw() {
+	if(encodeInc(value,buf,cap))
+		return true;
+	if(msg[0]!='\0') {
+		va_list al;
+		va_start(al,msg);
+		vfprintf(stderr,msg,al);
+		va_end(al);
+	}
+	return false;
+}
+template <class T>
+bool LoadSave::decodeInc(T& value, const char*& buf, unsigned int& cap) throw() {
+	unsigned int res=decode(value,buf,cap);
+	if(res==0)
+		return false;
+#ifdef LOADSAVE_DEBUG
+	if(res>cap) {
+		fprintf(stderr,"*** WARNING: reported decode result length exceeded remaining buffer size; %u (signed %d) vs %u\n",res,(int)res,cap);
+		return false;
+	}
+#endif
+	buf+=res;
+	cap-=res;
+	return true;
+}
+template <class T>
+bool LoadSave::decodeInc(T& value, const char*& buf, unsigned int& cap, const char* msg, ...) throw() {
+	if(decodeInc(value,buf,cap))
+		return true;
+	if(msg[0]!='\0') {
+		va_list al;
+		va_start(al,msg);
+		vfprintf(stderr,msg,al);
+		va_end(al);
+	}
+	return false;
+}
+template <class T>
+bool LoadSave::decodeInc(T& value, char*& buf, unsigned int& cap) throw() {
+	unsigned int res=decode(value,buf,cap);
+	if(res==0)
+		return false;
+#ifdef LOADSAVE_DEBUG
+	if(res>cap) {
+		fprintf(stderr,"*** WARNING: reported decode result length exceeded remaining buffer size; %u (signed %d) vs %u\n",res,(int)res,cap);
+		return false;
+	}
+#endif
+	buf+=res;
+	cap-=res;
+	return true;
+}
+template <class T>
+bool LoadSave::decodeInc(T& value, char*& buf, unsigned int& cap, const char* msg, ...) throw() {
+	if(decodeInc(value,buf,cap))
+		return true;
+	if(msg[0]!='\0') {
+		va_list al;
+		va_start(al,msg);
+		vfprintf(stderr,msg,al);
+		va_end(al);
+	}
+	return false;
+}
+
+template <class T>
+void LoadSave::encodeIncT(const T& value, char*& buf, unsigned int& cap, const char* msg, ...) throw(std::length_error) {
+	unsigned int res=encode(value,buf,cap);
+#ifdef LOADSAVE_DEBUG
+	if(res==0 || res>cap) {
+		if(res>cap)
+			fprintf(stderr,"*** WARNING: encode reported result length exceeded remaining buffer size; %u (signed %d) vs %u\n",res,(int)res,cap);
+#else
+	if(res==0) {
+#endif
+		va_list al;
+		va_start(al,msg);
+		char * errmsg;
+		vasprintf(&errmsg,msg,al);
+		va_end(al);
+		if(errmsg==NULL)
+			throw std::length_error("unspecified");
+		std::string serrmsg=errmsg;
+		free(errmsg);
+		throw std::length_error(serrmsg);
+// this macro check is just to balance the {}'s for less-than-genius editors
+#ifdef LOADSAVE_DEBUG
+	}
+#else
+	}
+#endif
+	buf+=res;
+	cap-=res;
+}
+template <class T>
+void LoadSave::decodeIncT(T& value, const char*& buf, unsigned int& cap, const char* msg, ...) throw(std::length_error) {
+	unsigned int res=decode(value,buf,cap);
+#ifdef LOADSAVE_DEBUG
+	if(res==0 || res>cap) {
+		if(res>cap)
+			fprintf(stderr,"*** WARNING: decode reported result length exceeded remaining buffer size; %u (signed %d) vs %u\n",res,(int)res,cap);
+#else
+	if(res==0) {
+#endif
+		va_list al;
+		va_start(al,msg);
+		char * errmsg;
+		vasprintf(&errmsg,msg,al);
+		va_end(al);
+		if(errmsg==NULL)
+			throw std::length_error("unspecified");
+		std::string serrmsg=errmsg;
+		free(errmsg);
+		throw std::length_error(serrmsg);
+// this macro check is just to balance the {}'s for less-than-genius editors
+#ifdef LOADSAVE_DEBUG
+	}
+#else
+	}
+#endif
+	buf+=res;
+	cap-=res;
+}
+template <class T>
+void LoadSave::decodeIncT(T& value, char*& buf, unsigned int& cap, const char* msg, ...) throw(std::length_error) {
+	unsigned int res=decode(value,buf,cap);
+#ifdef LOADSAVE_DEBUG
+	if(res==0 || res>cap) {
+		if(res>cap)
+			fprintf(stderr,"*** WARNING: decode reported result length exceeded remaining buffer size; %u (signed %d) vs %u\n",res,(int)res,cap);
+#else
+	if(res==0) {
+#endif
+		va_list al;
+		va_start(al,msg);
+		char * errmsg;
+		vasprintf(&errmsg,msg,al);
+		va_end(al);
+		if(errmsg==NULL)
+			throw std::length_error("unspecified");
+		std::string serrmsg=errmsg;
+		free(errmsg);
+		throw std::length_error(serrmsg);
+// this macro check is just to balance the {}'s for less-than-genius editors
+#ifdef LOADSAVE_DEBUG
+	}
+#else
+	}
+#endif
+	buf+=res;
+	cap-=res;
+}
 
 /*! @file
  * @brief Describes LoadSave, inherit from this to use a standard interface for loading and saving
  * @author ejt (Creator)
+ * @author Daniel Höh (Revisor)
  *
  * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
  * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
+ * $Date: 2006/10/04 04:21:12 $
  */
 
 #endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/MarkScope.h ./Shared/MarkScope.h
--- ../Tekkotsu_2.4.1/Shared/MarkScope.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/MarkScope.h	2006-08-22 17:46:51.000000000 -0400
@@ -0,0 +1,62 @@
+//-*-c++-*-
+#ifndef INCLUDED_MarkScope_h_
+#define INCLUDED_MarkScope_h_
+
+#include "Resource.h"
+
+//! Provides a way to mark a resource as used for the duration of the instance's scope
+/*! This is handy because we don't have to worry about releasing the resource
+ *  if there are multiple return points, exception handling, or other such issues
+ *  which might otherwise cause you to forget to release it -- let C++ do it for you! */
+class MarkScope {
+public:
+	//! constructor, for marking resources which require no data
+	MarkScope(Resource& r) : rsrc(r), data(&Resource::emptyData) {
+		rsrc.useResource(*data);
+	}
+	//! constructor, accepts data parameter to pass to Resource::useResource()
+	MarkScope(Resource& r, Resource::Data& d) : rsrc(r), data(&d) {
+		rsrc.useResource(*data);
+	}
+	//! copy constructor, marks resource used, copying ms's data reference (better make sure the Resource support recursive usage...)
+	MarkScope(const MarkScope& ms) : rsrc(ms.rsrc), data(ms.data) {
+		rsrc.useResource(*data);
+	}
+	//! copy constructor, accepts additional data parameter to pass to Resource::useResource()
+	MarkScope(const MarkScope& ms, Resource::Data& d) : rsrc(ms.rsrc), data(&d) {
+		rsrc.useResource(*data);
+	}
+	//! destructor, releases resource
+	~MarkScope() {
+		rsrc.releaseResource(*data);
+	}
+	
+	//! accessor to return the resource being marked
+	Resource& getResource() const { return rsrc; }
+	//! accessor to return the data used to access the resource
+	Resource::Data& getData() const { return *data; }
+	//! renew the resource usage -- call release and use again, with the same data
+	void reset() { rsrc.releaseResource(*data); rsrc.useResource(*data); }
+	//! renew the resource usage -- call release and use again with the new data
+	void reset(Resource::Data& d) { rsrc.releaseResource(*data); data=&d; rsrc.useResource(*data); }
+	
+protected:
+	Resource& rsrc; //!<the resource we're using
+	Resource::Data * data; //!< data passed to resource when using it and releasing it
+	
+private:
+	MarkScope& operator=(const MarkScope&); //!< assignment prohibited (can't reassign the reference we already hold)
+};
+
+/*! @file
+* @brief Defines MarkScope, which provides a way to mark a resource as used for the duration of the instance's scope
+* @author Ethan Tira-Thompson (ejt) (Creator)
+*
+* $Author: ejt $
+* $Name: HEAD $
+* $Revision: 1.1 $
+* $State: Exp $
+* $Date: 2006/10/04 04:21:12 $
+*/
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/Profiler.cc ./Shared/Profiler.cc
--- ../Tekkotsu_2.4.1/Shared/Profiler.cc	2005-07-28 13:10:07.000000000 -0400
+++ ./Shared/Profiler.cc	2006-07-13 13:25:50.000000000 -0400
@@ -7,6 +7,10 @@
 
 unsigned int Profiler::infosOffset=((size_t)(&static_cast<ProfilerOfSize<1>*>(NULL)[1].infos))-((size_t)(&static_cast<ProfilerOfSize<1>*>(NULL)[1].prof));
 
+ProfilerOfSize<20> * mainProfiler=NULL;
+ProfilerOfSize<06> * motionProfiler=NULL;
+ProfilerOfSize<06> * soundProfiler=NULL;
+
 /*! Tells the profiler that this is now the active timer, so new timers will fit "under" this.\n
  *  Timer isn't actually started here, lets Profiler::setCurrent do that.
  *  @param prof profiler to report results to.  If is NULL, does nothing.
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/Profiler.h ./Shared/Profiler.h
--- ../Tekkotsu_2.4.1/Shared/Profiler.h	2005-08-07 00:11:04.000000000 -0400
+++ ./Shared/Profiler.h	2006-09-16 13:32:40.000000000 -0400
@@ -11,11 +11,13 @@
  *  @param NAME the name of this section for reporting
  *  @param PROF the actual profiler to use
  */
+#ifndef PROFSECTION
 #define PROFSECTION(NAME,PROF) \
-  static unsigned int _PROFSECTION_id=PROF.getNewID(NAME);\
-  Profiler::Timer _PROFSECTION_timer(_PROFSECTION_id,&PROF.prof);
+  static unsigned int _PROFSECTION_id=(PROF).getNewID(NAME);\
+  Profiler::Timer _PROFSECTION_timer(_PROFSECTION_id,&(PROF).prof);
+#endif
 
-//! Managers a hierarchy of timers for profiling time spent in code, gives microsecond resolution
+//! Manages a hierarchy of timers for profiling time spent in code, gives microsecond resolution
 /*! Doesn't use any pointers so it's safe to put this in shared memory regions.\n
  *  That's handy so one process can collate all the profiling information across processes
  *  to give a summary report to the user.\n
@@ -43,7 +45,7 @@
  *  void g() {
  *    PROFSECTION("g",prof);   // <== Most of the time, this is all you need
  *    //...                    // (unless you're doing something fancy like conditional timers)
- *    f(); // will note f's time as g's child time
+ *    f(); // will note f's time as g's child time, as well as g's own time
  *    //...
  *  }
  *  @endcode
@@ -52,6 +54,13 @@
  *  resolution than a function, you can use tricks shown in MMAccessor's documentation to limit
  *  the timer's scope.
  *
+ *  For convenience, there are three global profilers predefined: #mainProfiler, #motionProfiler,
+ *  and #soundProfiler.  These are what are polled by the ProfilerCheckControl -- if you instantiate
+ *  a new profiler, you will have to call its report() function yourself to get the results.  (If it's simply
+ *  a matter of running out of sections in mainProfiler, increase the template parameter at the end
+ *  of Profiler.h)  Keep in mind however, that these global profilers are pointers, and need to be
+ *  dereferenced to use with the macro, e.g. <code>PROFSECTION("g2",*mainProfiler)</code>
+ *
  *  Here were the constraints I set for myself:
  *  - Processes can read each other's Profilers - so must be able to live in shared memory\n
  *    This is so one process can generate a report on performance of the entire system at once
@@ -193,8 +202,8 @@
 	//! Automatically causes initialization of the histogram buckets when the first Profiler is instantiated
 	class AutoInit {
 	public:
-		AutoInit();
-		~AutoInit();
+		AutoInit(); //!< constructor, adds to #refcount and #totalcount, causes initalization if was 0
+		~AutoInit(); //!< destructor, decrements #refcount, does teardown if it hits 0
 	protected:
 		static unsigned int refcount; //!< the number of profilers in existance
 		static unsigned int totalcount; //!< the number of profilers which have been created
@@ -217,6 +226,14 @@
 	Profiler::SectionInfo infos[MaxSections]; //!< the actual profiling information storage
 };
 
+// feel free to ignore these or add your own as well -- these are the ones that framework-included code will use
+typedef ProfilerOfSize<20> mainProfiler_t; //!< defines type for code profiling information for MainObject; use this instead of the templated type so you don't rely on a particular size
+typedef ProfilerOfSize<6> motionProfiler_t; //!< defines type for code profiling information for MotionObject; use this instead of the templated type so you don't rely on a particular size
+typedef ProfilerOfSize<6> soundProfiler_t; //!< defines type for code profiling information for SoundPlay; use this instead of the templated type so you don't rely on a particular size
+extern mainProfiler_t * mainProfiler; //!< holds code profiling information for MainObject
+extern motionProfiler_t * motionProfiler; //!< holds code profiling information for MotoObject
+extern soundProfiler_t * soundProfiler; //!< holds code profiling information for SoundPlay
+
 /*! @file
  * @brief Describes Profiler, which managers a hierarchy of timers for profiling time spent in code
  * @author ejt (Creator)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/ProjectInterface.cc ./Shared/ProjectInterface.cc
--- ../Tekkotsu_2.4.1/Shared/ProjectInterface.cc	2005-08-16 14:00:17.000000000 -0400
+++ ./Shared/ProjectInterface.cc	2006-09-25 19:31:06.000000000 -0400
@@ -1,12 +1,14 @@
 #include "ProjectInterface.h"
 #include "Wireless/Socket.h"
+#include "Vision/SegmentedColorGenerator.h"
+#include "debuget.h"
 #include <exception>
 
 namespace ProjectInterface {
 
 	bool displayException(const char * file, int line, const char * message, const std::exception* ex) {
 		if(file!=NULL) {
-			serr->printf("Exception caught at %s:%d => ",file,line);
+			serr->printf("Exception caught at %s:%d => ",debuget::extractFilename(file),line);
 		} else {
 			serr->printf("Exception => ");
 		}
@@ -20,19 +22,82 @@
 		} else {
 			serr->printf("\n");
 		}
+#ifndef PLATFORM_APERIOS
+		serr->printf("\tWhen running in gdb, try 'catch throw' to break where exceptions are first thrown.\n");
+#endif
 		return true;
 	}
 	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);
+	}
+	unsigned int (*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) {
+		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;
+	
+	//! default implementation assigned to lookupColorRGB(); checks that #defSegmentedColorGenerator is non-NULL and returns getColorRGB on it
+	rgb defLookupColorRGB(unsigned int index) {
+		if(defSegmentedColorGenerator==NULL)
+			return rgb();
+		return defSegmentedColorGenerator->getColorRGB(index);
+	}
+	rgb (*lookupColorRGB)(unsigned int index)=&defLookupColorRGB;
 
-	FilterBankGenerator * defRawCameraGenerator=0;
-	FilterBankGenerator * defInterleavedYUVGenerator=0;
-	JPEGGenerator * defColorJPEGGenerator=0;
-	JPEGGenerator * defGrayscaleJPEGGenerator=0;
-	SegmentedColorGenerator * defSegmentedColorGenerator=0;
-	RLEGenerator * defRLEGenerator=0;
-	RegionGenerator * defRegionGenerator=0;
+	//! default value initially assigned to lookupNumColors(); checks that #defSegmentedColorGenerator is non-NULL and returns getNumColors on it
+	unsigned int defLookupNumColors() {
+		if ( defSegmentedColorGenerator == NULL ) 
+			return -1U; 
+		return defSegmentedColorGenerator->getNumColors();
+	}
+	//! 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
+	FilterBankGenerator * defRawCameraGenerator=NULL;
+	FilterBankGenerator * defInterleavedYUVGenerator=NULL;
+	JPEGGenerator * defColorJPEGGenerator=NULL;
+	JPEGGenerator * defGrayscaleJPEGGenerator=NULL;
+	PNGGenerator * defColorPNGGenerator=NULL;
+	PNGGenerator * defGrayscalePNGGenerator=NULL;
+	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
 	unsigned int visRawCameraSID=0;
 
 	unsigned int visInterleaveSID=0;
@@ -40,6 +105,9 @@
 	unsigned int visColorJPEGSID=0;
 	unsigned int visGrayscaleJPEGSID=1;
 
+	unsigned int visColorPNGSID=0;
+	unsigned int visGrayscalePNGSID=1;
+
 	unsigned int visSegmentSID=0;
 
 	unsigned int visRLESID=0;
@@ -48,14 +116,20 @@
 
 	unsigned int visPinkBallSID=0;
 	unsigned int visBlueBallSID=1;
-	unsigned int visHandSID=2;
+	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 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_2.4.1/Shared/ProjectInterface.h ./Shared/ProjectInterface.h
--- ../Tekkotsu_2.4.1/Shared/ProjectInterface.h	2005-08-16 14:00:17.000000000 -0400
+++ ./Shared/ProjectInterface.h	2006-07-14 02:48:55.000000000 -0400
@@ -2,31 +2,42 @@
 #ifndef INCLUDED_ProjectInterface_h_
 #define INCLUDED_ProjectInterface_h_
 
+#include "Vision/colors.h"
+#include <string>
+
 class BehaviorBase;
 class FilterBankGenerator;
 class SegmentedColorGenerator;
 class RLEGenerator;
 class RegionGenerator;
 class JPEGGenerator;
+class PNGGenerator;
 namespace std {
 	class exception;
 }
 
 //! A collection of the global variables which should be set by a project to use the Tekkotsu framework
-/*! You don't necessarily need to define all of these, but if you want
- *  to use the built in demo behaviors, you may need to set some
- *  values in here appropriately so that the demos can adapt to your
- *  project's configuration.
+/*! This namespace 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
+ *  the actual values used for your own project.  This provides a way
+ *  to reassign conflicts between values provided by the framework vs.
+ *  those you might wish to add to your project.
  *  
- *  Any references should be instantiated in your own project files
- *  (since you can't reassign a reference)
- *
- *  Any pointers are instantiated in ProjectInterface.cc and
- *  initialized to NULL. You can reassign them as you see fit.
- *
  *  Currently, all required members are references (so they can't be
  *  set to NULL and you'll get errors if you leave them out) and all
  *  optional settings are pointers so you can ignore them if you want.
+ *  
+ *  The "optional" variables are used by demo behaviors, and thus
+ *  if you remove all of the demo behaviors, you won't need to define
+ *  the corresponding interface values here.
+ *
+ *  If you want to add new ID values for your project, create a new
+ *  'globals.h' or some such in your project -- you don't need to
+ *  add them here since this file is shared by all projects which
+ *  use the framework, you shouldn't need to modify it for each
+ *  project.
  */
 namespace ProjectInterface {
 	
@@ -62,6 +73,35 @@
 	 *  @param ex The exception which was caught, or NULL if it is was not a std::exception subclass
 	 *  @return true, indicating the exception was handled adequately */
 	bool displayException(const char * file, int line, const char * message, const std::exception* ex);
+	
+	//! 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);
+	//! 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);
+	//! 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);
+	
+	//! 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); }
+	//! 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); }
+	//! 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);
+
 
 	//! 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 */
@@ -70,6 +110,8 @@
 	extern FilterBankGenerator * defInterleavedYUVGenerator;
 	extern JPEGGenerator * defColorJPEGGenerator;
 	extern JPEGGenerator * defGrayscaleJPEGGenerator;
+	extern PNGGenerator * defColorPNGGenerator;
+	extern PNGGenerator * defGrayscalePNGGenerator;
 	extern SegmentedColorGenerator * defSegmentedColorGenerator;
 	extern RLEGenerator * defRLEGenerator;
 	extern RegionGenerator * defRegionGenerator;
@@ -82,11 +124,15 @@
 	extern unsigned int visInterleaveSID;
 	extern unsigned int visColorJPEGSID;
 	extern unsigned int visGrayscaleJPEGSID;
+	extern unsigned int visColorPNGSID;
+	extern unsigned int visGrayscalePNGSID;
 	extern unsigned int visSegmentSID;
 	extern unsigned int visRLESID;
 	extern unsigned int visRegionSID;
 	extern unsigned int visPinkBallSID;
 	extern unsigned int visBlueBallSID;
+	extern unsigned int visGreenBallSID;
+	extern unsigned int visYellowBallSID;
 	extern unsigned int visHandSID;
 	//@}
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/ReferenceCounter.h ./Shared/ReferenceCounter.h
--- ../Tekkotsu_2.4.1/Shared/ReferenceCounter.h	2005-02-02 13:22:29.000000000 -0500
+++ ./Shared/ReferenceCounter.h	2006-10-03 15:13:16.000000000 -0400
@@ -4,10 +4,15 @@
 
 #include <iostream>
 
-//class ReferenceCounter;
-//const char* findname(ReferenceCounter* x); // !< tests if @a x is a behavior and outputs its name, otherwise outputs its address
-
 //! Performs simple reference counting, will delete the object when removing the last reference
+/*! Remember to call SetAutoDelete(false) if you
+ *  instantiate a subclass on the stack instead of the heap -- don't want to try to free memory
+ *  on the stack if/when last reference is removed!  (The stack limits the allocation of the behavior
+ *  to the current scope, so reference counting is moot.)
+ *
+ *  @todo It would be nice if there was a way for ReferenceCounter to automatically know whether it
+ *  has been allocated on the stack... is that possible?
+ */
 class ReferenceCounter {
  public:
 	//! constructor
@@ -25,13 +30,18 @@
 
 	//! adds one to #references
 	virtual void AddReference() { references++; }
-	//! subtracts one from #references AND DELETES the object IF ZERO
-	virtual void RemoveReference() {
+	//! subtracts one from #references AND DELETES the object IF ZERO (and RC_autodelete is set)
+	/*! @return true if the last reference was removed, false otherwise */
+	virtual bool RemoveReference() {
 		if(--references==0) {
 			if(RC_autodelete)
 				delete this;
-		} else if(references==(unsigned int)-1)
+			return true;
+		} else if(references==(unsigned int)-1) {
 			std::cout << "*** WARNING RefCounter went negative" << std::endl;
+			return true;
+		} else
+			return false;
 	}
 	//! returns the number of references
 	/*! @return references */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/Resource.cc ./Shared/Resource.cc
--- ../Tekkotsu_2.4.1/Shared/Resource.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/Resource.cc	2006-06-16 17:49:23.000000000 -0400
@@ -0,0 +1,15 @@
+#include "Resource.h"
+
+Resource::Data Resource::emptyData;
+EmptyResource emptyResource;
+
+/*! @file
+ * @brief Implements Resource (and EmptyResource), which provides a generic interface for resources which need to keep track of when they are in use, such as mutex locks
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/Resource.h ./Shared/Resource.h
--- ../Tekkotsu_2.4.1/Shared/Resource.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/Resource.h	2006-09-16 13:32:40.000000000 -0400
@@ -0,0 +1,41 @@
+//-*-c++-*-
+#ifndef INCLUDED_Resource_h_
+#define INCLUDED_Resource_h_
+
+//! Provides a generic interface for resources which need to keep track of when they are in use, such as mutex locks
+class Resource {
+public:
+	//! base class for holding data required for requesting to use/release the resource
+	class Data {
+	public:
+		virtual ~Data() {} //!< empty virtual destructor to mark this as a base class
+	};
+	static Data emptyData; //!< to use as the data reference when none is needed/specified
+	
+	//! destructor (does nothing -- up to subclass if they need to release resource)
+	virtual ~Resource() {}
+	
+	virtual void useResource(Data& d)=0; //!< marks the resource as in use
+	virtual void releaseResource(Data& d)=0; //!< releases the resource
+};
+
+//! a no-op resource, since we don't want Resource itself to be directly instantiatable
+class EmptyResource : public Resource {
+public:	
+	virtual void useResource(Data&) {} //!< would mark the resource in use, here is a no-op
+	virtual void releaseResource(Data&) {} //!< would mark the resource no longer in use, here is a no-op
+};
+extern EmptyResource emptyResource; //!< a global instance of the empty resource, for no-op situations
+
+/*! @file
+ * @brief Describes Resource (and EmptyResource), which provides a generic interface for resources which need to keep track of when they are in use, such as mutex locks
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/ResourceAccessor.h ./Shared/ResourceAccessor.h
--- ../Tekkotsu_2.4.1/Shared/ResourceAccessor.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/ResourceAccessor.h	2006-09-16 13:32:40.000000000 -0400
@@ -0,0 +1,51 @@
+//-*-c++-*-
+#ifndef INCLUDED_ResourceAccessor_h_
+#define INCLUDED_ResourceAccessor_h_
+
+#include "MarkScope.h"
+
+//! A variation of MarkScope which allows you to forward access to the resource via the '->' operator, smart-pointer style
+template <class R>
+class ResourceAccessor : public MarkScope {
+public:
+	//! constructor, for marking resources which require no data
+	ResourceAccessor(R& r) : MarkScope(r) {}
+	//! constructor, accepts data parameter to pass to Resource::useResource()
+	ResourceAccessor(R& r, Resource::Data& d) : MarkScope(r,d) {}
+	//! copy constructor, marks resource used with default (empty) data
+	ResourceAccessor(const ResourceAccessor& ra) : MarkScope(ra) {}
+	//! copy constructor, accepts additional data parameter to pass to Resource::useResource()
+	ResourceAccessor(const ResourceAccessor& ra, Resource::Data& d) : MarkScope(ra,d) {}
+	
+#if !defined(__GNUC__) || __GNUC__ > 3 || (__GNUC__ == 3 && (__GNUC_MINOR__ > 3))
+	//! returns #rsrc cast as R
+	inline R& accessResource() const __attribute__ ((warn_unused_result)) {
+		return dynamic_cast<R&>(rsrc);
+	}
+#else
+	//! returns #rsrc cast as R
+	inline R& accessResource() const {
+		return dynamic_cast<R&>(rsrc);
+	}
+#endif
+	
+	R* operator->() { return &accessResource(); } //!< smart pointer to the underlying Resource
+	const R* operator->() const { return &accessResource(); } //!< smart pointer to the underlying Resource
+	R& operator*() { return accessResource(); } //!< smart pointer to the underlying Resource
+	const R& operator*() const { return accessResource(); } //!< smart pointer to the underlying Resource
+	R& operator[](int i) { return (&accessResource())[i]; } //!< smart pointer to the underlying Resource
+	const R& operator[](int i) const { return (&accessResource())[i]; } //!< smart pointer to the underlying Resource
+};
+
+/*! @file
+ * @brief Describes ResourceAccessor, a variation of MarkScope which allows you to forward access to the resource via the '->' operator, smart-pointer style
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/RobotInfo.h ./Shared/RobotInfo.h
--- ../Tekkotsu_2.4.1/Shared/RobotInfo.h	2005-06-01 01:47:49.000000000 -0400
+++ ./Shared/RobotInfo.h	2006-10-03 19:06:58.000000000 -0400
@@ -17,10 +17,11 @@
 
 //! 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_ERS210, TGT_ERS220, TGT_ERS7, or the default, TGT_ERS2xx)
+ *  robot target setting (one of TGT_ERS7, TGT_ERS210, TGT_ERS220, or the cross-booting TGT_ERS2xx)
  *
- *  You probably should look at ERS210Info, ERS220Info, ERS2xxInfo, or ERS7Info for the actual
- *  constants used for each model. */
+ *  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
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/SharedQueue.h ./Shared/SharedQueue.h
--- ../Tekkotsu_2.4.1/Shared/SharedQueue.h	2005-03-08 21:59:53.000000000 -0500
+++ ./Shared/SharedQueue.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,143 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_SharedQueue_h_
-#define INCLUDED_SharedQueue_h_
-
-#include "MutexLock.h"
-#include "ProcessID.h"
-#include "LockScope.h"
-
-//! SharedQueue is a shared memory message buffer for interprocess communication
-/*! This doesn't gain you much functionality over the Aperios messages - in fact,
- *  you lose some because you have to poll this for new data whereas Aperios will
- *  notify you.
- *
- *  However, the big advantage of this is that you don't have any lag time from the system
- *  in sending the message from one process to the other - it's instantly available.
- *  Also, you can poll for new data from within a loop, whereas you cannot check
- *  to see if you have any messages waiting from Aperios until you exit to the system.
- *  
- *  This makes no assumptions about the data to be stored - it's all just an array of bytes
- *
- *  Assumptions are made about reception usage: all entries will be processed and then
- *  cleared so that the queue is emptied.  You cannot pop the front, only clear the whole
- *  thing.  This assumption allows much simpler/faster access. (Otherwise we need to
- *  implement a circular buffer and worry about wrap around.  *shrug* Not too hard, but
- *  unnecessary complication for now.) */
-template<unsigned int maxsize, unsigned int maxentries>
-class SharedQueue {
-public:
-	//! maximum capacity of data storage for the queue
-	static const unsigned int MAX_SIZE=maxsize;
-	//! maximum number of entries that can be queued
-	static const unsigned int MAX_ENTRIES=maxentries;
-	
-	//! constructor
-	SharedQueue();
-
-	//! inserts a class into the queue
-	template<class T> bool SharedQueue<maxsize,maxentries>::push(const T& obj);
-
-	//! reserves a number of bytes in the queue, LEAVES QUEUE LOCKED, call done when finished
-	void* reserve(unsigned int size);
-	
-	//! call this when you're finished filling in a buffer you received from reserve
-	void done() { lock.release(); }
-
-	//! checks to see if the number taken by the reader is the number added, and then clears
-	/*! This will allow you to process entries without locking the entire queue, but still
-	 *  not worry about missing one (or more) if it was added while you were processing the
-	 *  last one. */
-	bool clear(unsigned int taken);
-	
-	//! returns current number of entries
-	unsigned int size() const {	return len; }
-	
-	//! returns size of entry @a i
-	unsigned int size(unsigned int i) const { return entries[i].size; }
-
-	//! returns data of entry @a i
-	const void* data(unsigned int i) const { return &buf[entries[i].offset]; }
-
-protected:
-	//! returns the first free byte in buf
-	unsigned int buf_end() { return len==0?0:entries[len-1].offset+entries[len-1].size; }
-	
-	//! returns @a sz rounded up to the nearest word (makes @a sz divisible by sizeof(int))
-	unsigned int round_up(unsigned int sz) { return ((sz-1)/sizeof(int)+1)*sizeof(int); }
-
-	//! provides mutual exclusion on non-const functions
-	MutexLock<ProcessID::NumProcesses> lock;
-	//! for convenience in locking functions
-	typedef LockScope<ProcessID::NumProcesses> AutoLock;
-
-	//! data storage
-	char buf[MAX_SIZE];
-	
-	//! entry information
-	struct entry_t {
-		unsigned int offset; //!< offset within SharedQueue::buf
-		unsigned int size;   //!< size of entry
-	};
-
-	//! holds number of entries
-	unsigned int len;
-	
-	//! holds entry information
-	entry_t entries[MAX_ENTRIES];
-};
-
-template<unsigned int maxsize, unsigned int maxentries>
-SharedQueue<maxsize,maxentries>::SharedQueue()
-	: lock(), len(0)
-{}
-
-//! there's a comment above in header - inserts a class into the queue
-template<unsigned int maxsize, unsigned int maxentries> template<class T>
-bool
-SharedQueue<maxsize,maxentries>::push(const T& obj) {
-	AutoLock autolock(lock,ProcessID::getID());
-	if(len>=MAX_ENTRIES)
-		return false;
-	entries[len].offset=buf_end();
-	entries[len].size=round_up(sizeof(obj));
-	if(entries[len].offset+entries[len].size>=MAX_SIZE)
-		return false;
-	len++;
-	return true;
-}
-
-template<unsigned int maxsize, unsigned int maxentries>
-void*
-SharedQueue<maxsize,maxentries>::reserve(unsigned int sz) {
-	lock.lock(ProcessID::getID()); //note *not* an AutoLock -- we want it to stay locked until done() is called!
-	if(len>=MAX_ENTRIES)
-		return NULL;
-	entries[len].offset=buf_end();
-	entries[len].size=round_up(sz);
-	if(entries[len].offset+entries[len].size>=MAX_SIZE)
-		return NULL;
-	return &buf[entries[len++].offset];
-}
-
-template<unsigned int maxsize, unsigned int maxentries>
-bool
-SharedQueue<maxsize,maxentries>::clear(unsigned int taken) {
-	AutoLock autolock(lock,ProcessID::getID());
-	if(size()!=taken)
-		return false;
-	len=0;
-	return true;
-}
-
-/*! @file
- * @brief Defines SharedQueue, a shared memory message buffer for interprocess communication
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/StackTrace.cc ./Shared/StackTrace.cc
--- ../Tekkotsu_2.4.1/Shared/StackTrace.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/StackTrace.cc	2006-09-16 02:28:08.000000000 -0400
@@ -0,0 +1,710 @@
+#include "StackTrace.h"
+#include <stdio.h>
+
+#if defined(HAVE_BFD) && HAVE_BFD!=0
+#  include <bfd.h>
+#  include "libiberty.h"
+#  include "demangle.h"
+#  include <sys/stat.h>
+#  include <string.h>
+#endif
+
+#ifdef ST_UNUSED 
+#elif defined(__GNUC__) && __GNUC__>3
+//! portable access to compiler hint not to warn if a function argument is ignored (goes in argument list)
+# define ST_UNUSED(x) UNUSED_##x __attribute__((unused)) 
+//! portable access to compiler hint not to warn if a function argument is ignored (goes at beginning of function body)
+# define ST_BODY_UNUSED(x) /*no body necessary*/
+
+#elif defined(__LCLINT__) 
+//! portable access to compiler hint not to warn if a function argument is ignored (goes in argument list)
+# define ST_UNUSED(x) /*@unused@*/ x 
+//! portable access to compiler hint not to warn if a function argument is ignored (goes at beginning of function body)
+# define ST_BODY_UNUSED(x) /*no body necessary*/
+
+#else 
+//! portable access to compiler hint not to warn if a function argument is ignored (goes in argument list)
+# define ST_UNUSED(x) UNUSED_##x 
+//! portable access to compiler hint not to warn if a function argument is ignored (goes at beginning of function body)
+# define ST_BODY_UNUSED(x) (void)UNUSED_##x /* ugly hack to avoid warning */
+#endif
+
+#ifdef __cplusplus
+namespace stacktrace {
+#endif /* __cplusplus */
+
+#if defined(HAVE_BFD) && HAVE_BFD!=0
+char * bfd_objfile=NULL;
+#endif
+
+//! target string to use when opening symbol files if host architecture can't be detected
+const char * BFD_DEFAULT_TARGET="powerpc-apple-darwin8.5.0";
+//const char * BFD_DEFAULT_TARGET="i686-pc-linux-gnu";
+
+#if defined(HAVE_BFD) && HAVE_BFD!=0
+int loadStackTraceSymbols(const char* objfile) {
+	static int bfdInited=0;
+	if(!bfdInited) {
+		bfd_init();
+		if(!bfd_set_default_target(BFD_DEFAULT_TARGET)) {
+			bfd_error_type err=bfd_get_error();
+			fprintf(stderr,"can't set BFD default target to `%s': %s\n",BFD_DEFAULT_TARGET,bfd_errmsg(err));
+			fprintf(stderr,"stacktrace::loadStackTraceSymbols(%s) failed\n",objfile);
+			return err;
+		}
+		bfdInited=1;
+	}
+	/*const char ** tgt=bfd_target_list();
+	while(*tgt)
+		printf("%s\n",*tgt++);
+	free(bfd_objfile);
+	if(objfile==NULL) {
+		bfd_objfile=NULL;
+		return 0;
+	}
+	struct stat sb;
+	if(stat(objfile,&sb)) {
+		char msg[128];
+		snprintf(msg,128,"stacktrace::loadStackTraceSymbols(%s): stat",objfile);
+		perror(msg);
+		return -1;
+	}
+	bfd * abfd = bfd_openr(objfile, NULL);
+	if(abfd==NULL) {
+		bfd_error_type err=bfd_get_error();
+		fprintf(stderr,"Can't open object file `%s': %s\n",objfile,bfd_errmsg(err));
+		fprintf(stderr,"stacktrace::loadStackTraceSymbols(%s) failed\n",objfile);
+		return err;
+	}
+	if(!bfd_close(abfd)) {
+		bfd_error_type err=bfd_get_error();
+		fprintf(stderr,"Can't close object file `%s': %s\n",objfile,bfd_errmsg(err));
+		fprintf(stderr,"stacktrace::loadStackTraceSymbols(%s) failed\n",objfile);
+		return err;
+		}*/
+	bfd_objfile=strdup(objfile);
+	return 0;
+}
+#else
+int loadStackTraceSymbols(const char* ST_UNUSED(objfile)) {
+	ST_BODY_UNUSED(objfile);
+	return 0;
+}
+#endif
+
+int unrollStackFrame(struct StackFrame* curFrame, struct StackFrame* nextFrame) {
+	void* nsp=NULL;
+	machineInstruction * nra=NULL;
+
+#ifdef __i386__
+	if(curFrame==NULL)
+		return 0;
+	curFrame->caller=NULL;
+	if(nextFrame==NULL)
+		return 0;
+	if(curFrame->sp==NULL)
+		return 0;
+	if(((void**)curFrame->sp)-1==NULL)
+		return 0;
+	nsp=((void***)curFrame->sp)[-1];
+	if(nsp==NULL)
+		return 0;
+	nsp=(void**)nsp+1; //move from frame pointer to stack pointer of previous frame
+	nra=*((machineInstruction**)curFrame->sp);
+	if(nsp<=curFrame->sp) {
+		fprintf(stderr,"stacktrace::unrollStackFrame(sp=%p,ra=%p) directed to invalid next frame: (sp=%p,ra=%p)\n",curFrame->sp,curFrame->ra,nsp,nra);
+		return 0;
+	}
+#  ifdef DEBUG_STACKTRACE
+	if(curFrame->debug)
+		printf("( %p %p ) -> { %p %p }\n",curFrame->sp,curFrame->ra,nsp,nra);
+	nextFrame->debug=curFrame->debug;
+#  endif
+	nextFrame->sp=nsp;
+	nextFrame->ra=nra;
+	curFrame->caller=nextFrame;
+	return 1;
+#endif
+#ifdef __POWERPC__
+	if(curFrame==NULL)
+		return 0;
+	curFrame->caller=NULL;
+	if(nextFrame==NULL)
+		return 0;
+	if(curFrame->sp==NULL)
+		return 0;
+	if(*(void**)curFrame->sp==NULL)
+		return 0;
+	nsp=*(void**)curFrame->sp;
+	nra=((machineInstruction**)nsp)[2];
+	if(nsp<=curFrame->sp) {
+		fprintf(stderr,"stacktrace::unrollStackFrame(sp=%p,ra=%p) directed to invalid next frame: (sp=%p,ra=%p)\n",curFrame->sp,curFrame->ra,nsp,nra);
+		return 0;
+	}
+#  ifdef DEBUG_STACKTRACE
+	if(curFrame->debug)
+		printf("( %p %p ) -> { %p %p }\n",curFrame->sp,curFrame->ra,nsp,nra);
+	nextFrame->debug=curFrame->debug;
+#  endif
+	nextFrame->sp=nsp;
+	nextFrame->ra=nra;
+	curFrame->caller=nextFrame;
+	return 1;
+#endif
+#if defined(__MIPSEL__) || defined(__MIPS__) /* we're running on PLATFORM_APERIOS */
+	/* Have to scan through intructions being executed because stack pointer is not stored directly on the stack */
+	machineInstruction * ins;
+	const machineInstruction * INS_BASE=(const machineInstruction *)0x2000; // lowest valid memory address?
+	if(curFrame==NULL)
+		return 0;
+	curFrame->caller=NULL;
+	if(nextFrame==NULL || curFrame==NULL || curFrame->sp==NULL)
+		return 0;
+	
+#ifdef __pic__
+	ins = reinterpret_cast<machineInstruction*>(curFrame->gp-curFrame->ra);
+#else
+	ins = curFrame->ra;
+#endif
+	// find previous return address
+	for(; ins>=INS_BASE; ins--) {
+		// gcc will always save the return address with the instruction
+		//     sw ra, offset(sp)
+		// 
+		// the high word in this case is sw sp ra
+		if ( ( *ins & 0xffff0000 ) == 0xafbf0000 )
+		{
+			// the low word is the offset from sp
+			int offset = *ins & 0x000ffff;
+			
+			// in case things went horribly awry, don't deref the non-aligned ptr
+			if (offset & 0x3)
+				return 0;
+			
+			nra = *reinterpret_cast<machineInstruction**>((char*)curFrame->sp + offset);
+			break; // now search for stack pointer
+		}
+		
+		//it appears the aperios stub entry functions always begin with "ori  t0,ra,0x0"
+		//if we hit one of these, return 0, because we can't unroll any more
+		//(or at least, I don't know how it returns from these... there's no return statements!)
+		if ( *ins  == 0x37e80000 ) {
+#  ifdef DEBUG_STACKTRACE
+			if(curFrame->debug)
+				printf("( %p %p %p ) -> { kernel? }\n",curFrame->sp,curFrame->ra,curFrame->gp);
+#  endif
+			return 0;
+		}
+	}
+	// find previous stack pointer
+	for(; ins>=INS_BASE; ins--) {
+		// gcc will always change the stack frame with the instruction
+		//     addiu sp,sp,offset
+		//
+		// at the beginning of the function the offset will be negative since the stack grows 
+		// from high to low addresses
+		//
+		// first check the high word which will be instruction + regs in this case (I-type)
+		if ( ( *ins & 0xffff0000 ) == 0x27bd0000 ) {
+			// the offset is in the low word. since we're finding occurrence at the start of the function,
+			// it will be negative (increase stack size), so sign extend it
+			int offset = ( *ins & 0x0000ffff ) | 0xffff0000;
+
+			// in case things went horribly awry, don't deref the non-aligned ptr
+			if (offset & 0x3)
+				return 0;
+			
+			nsp = (char*)curFrame->sp - offset;
+			break;
+		}
+	}
+	
+	
+	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]);
+#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);
+#endif
+			return 0;
+		}
+
+#ifdef __pic__
+#  ifdef DEBUG_STACKTRACE
+		if(curFrame->debug)
+			printf("( %p %p %p ) -> { %p %p %p }\n",curFrame->sp,curFrame->ra,curFrame->gp,nsp,nra,reinterpret_cast<size_t*>(nsp)[4]);
+		nextFrame->debug=curFrame->debug;
+#  endif
+		// I'm not actually sure this is a valid stop criteria, but in testing,
+		// after this it seems to cross into some kind of kernel code.
+		// (We get a really low gp (0x106), although a fairly normal nra, and then go bouncing
+		// around in memory until we hit sp=0x80808080, ra=0x2700, which seems to be the 'real' last frame)
+		//if(reinterpret_cast<size_t>(nra)>reinterpret_cast<size_t*>(nsp)[4])
+		//return 0;
+		//instead of this however, now we check for the ori t0,ra,0 statement, and reuse previous gp below
+		
+		nextFrame->sp=nsp;
+		//not sure how valid this is either:
+		if(reinterpret_cast<size_t>(nra)>reinterpret_cast<size_t*>(nsp)[4]) {
+			nextFrame->gp = curFrame->gp;
+		} else {
+			nextFrame->gp = reinterpret_cast<size_t*>(nsp)[4]; // gp is stored 4 words from stack pointer
+		}
+		nextFrame->ra = nextFrame->gp-reinterpret_cast<size_t>(nra);
+#else
+#  ifdef DEBUG_STACKTRACE
+		if(curFrame->debug)
+			printf("( %p %p ) -> { %p %p }\n",curFrame->sp,curFrame->ra,nsp,nra);
+		nextFrame->debug=curFrame->debug;
+#  endif
+		nextFrame->sp=nsp;
+		nextFrame->ra=nra;
+#endif /* __pic__ */
+		curFrame->caller=nextFrame;
+		return 1;
+	}
+#ifdef __pic__
+#  ifdef DEBUG_STACKTRACE
+	if(curFrame->debug)
+		printf("( %p %p %p ) -> { %p %p --- }\n",curFrame->sp,curFrame->ra,curFrame->gp,nsp,nra);
+#  endif
+#else
+#  ifdef DEBUG_STACKTRACE
+	if(curFrame->debug)
+		printf("( %p %p ) -> { %p %p }\n",curFrame->sp,curFrame->ra,nsp,nra);
+#  endif
+#endif
+	return 0;
+#endif
+}
+
+void getCurrentStackFrame(struct StackFrame* frame) {
+	void** csp=NULL;
+	machineInstruction* cra=NULL;
+
+#ifdef __POWERPC__
+	__asm __volatile__ ("mr %0,r1" : "=r"(csp) ); // get the current stack pointer
+	__asm __volatile__ ("mflr %0" : "=r"(cra) );  // get the current return address
+#endif /* __POWERPC__ */
+	
+#if defined(__MIPSEL__) || defined(__MIPS__)
+#ifdef __pic__
+	size_t cgp=0;
+	__asm __volatile__ ("move %0,$gp" : "=r"(cgp) ); //get the gp register so we can compute link addresses
+#endif /* __pic__ */
+	__asm __volatile__ ("move %0,$sp" : "=r"(csp) ); // get the current stack pointer
+	__asm __volatile__ ("jal readepc; nop; readepc: move %0,$ra" : "=r"(cra) ); // get the current return address
+#endif /* __MIPSEL__ */
+	
+#ifdef __i386__
+	__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);
+	frame->gp=cgp;
+#else
+	frame->ra=cra;
+#endif /* __pic__ */
+
+#ifndef __i386__
+	//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);
+#endif /* not __i386__ */
+}
+
+void freeStackTrace(struct StackFrame* frame) {
+	while(frame!=NULL) {
+		struct StackFrame * next=frame->caller;
+		free(frame);
+		if(frame==next)
+			return;
+		frame=next;
+	}
+}
+
+struct StackFrame* allocateStackTrace(unsigned int size) {
+	struct StackFrame * frame=NULL;
+	while(size--!=0) {
+		struct StackFrame * prev = (struct StackFrame *)malloc(sizeof(struct StackFrame));
+		prev->caller=frame;
+		frame=prev;
+	}
+	return frame;
+}
+
+
+struct StackFrame * recordStackTrace(unsigned int limit/*=-1U*/, unsigned int skip/*=0*/) {
+	struct StackFrame cur;
+#ifdef DEBUG_STACKTRACE
+	cur.debug=0;
+#endif
+	if(limit==0)
+		return NULL;
+	getCurrentStackFrame(&cur);
+	for(; skip!=0; skip--)
+		if(!unrollStackFrame(&cur,&cur))
+			return NULL;
+	struct StackFrame * prev = (struct StackFrame *)malloc(sizeof(struct StackFrame));
+#ifdef DEBUG_STACKTRACE
+	prev->debug=0;
+#endif
+	unrollStackFrame(&cur,prev); //unroll once more for the current frame
+	for(; limit!=0; limit--) {
+		struct StackFrame * next = (struct StackFrame *)malloc(sizeof(struct StackFrame));
+#ifdef DEBUG_STACKTRACE
+		next->debug=0;
+#endif
+		if(!unrollStackFrame(prev,next)) {
+			// reached end of trace
+			free(next);
+			prev->caller=NULL; //denotes end was reached
+			return cur.caller;
+		}
+		prev=next;
+	}
+	// reaching here implies limit was reached
+	prev->caller=prev; //denotes limit was reached
+	return cur.caller;
+}
+
+struct StackFrame * recordOverStackTrace(struct StackFrame* frame, unsigned int skip) {
+	struct StackFrame cur;
+#ifdef DEBUG_STACKTRACE
+	cur.debug=0;
+#endif
+	if(frame==NULL)
+		return frame;
+	getCurrentStackFrame(&cur);
+	for(; skip!=0; skip--)
+		if(!unrollStackFrame(&cur,&cur))
+			return frame;
+	unrollStackFrame(&cur,frame); //unroll once more for the current frame
+	for(; frame->caller!=NULL && frame->caller!=frame; frame=frame->caller) {
+		cur.caller=frame->caller; //don't lose remainder of free list if we hit the end
+		if(!unrollStackFrame(frame,frame->caller))
+			return cur.caller; // reached end of trace
+	}
+	// reaching here implies limit was reached
+	frame->caller=frame; //denotes limit was reached
+	return cur.caller;
+}
+
+#if defined(HAVE_BFD) && HAVE_BFD!=0
+bfd * abfd = NULL;
+static asymbol **syms;		/* Symbol table.  */
+#endif
+
+//! attempts to read symbol information and displays stack trace header
+void beginDisplay() {
+#if defined(HAVE_BFD) && HAVE_BFD!=0
+	const char* consolation=", try addr2line or trace_lookup";
+	if(bfd_objfile==NULL) {
+		fprintf(stderr,"No symbols are loaded%s.\n",consolation);
+		return;
+	}
+	abfd = bfd_openr(bfd_objfile, NULL);
+	if(abfd==NULL) {
+		bfd_error_type err=bfd_get_error();
+		fprintf(stderr,"Can't open object file `%s': %s\n",bfd_objfile,bfd_errmsg(err));
+		fprintf(stderr,"stacktrace::beginDisplay() failed%s.\n",consolation);
+		return;
+	}
+	if(bfd_check_format (abfd, bfd_archive)) {
+		bfd_error_type err=bfd_get_error();
+		fprintf(stderr,"Can't get addresses from archive `%s': %s\n",bfd_objfile,bfd_errmsg(err));
+		if(!bfd_close(abfd))
+			fprintf(stderr,"Can't close object file `%s': %s\n",bfd_objfile,bfd_errmsg(bfd_get_error()));
+		fprintf(stderr,"stacktrace::beginDisplay() failed%s.\n",consolation);
+		abfd=NULL;
+		return;
+	}
+	{
+		char **matching;
+		if(!bfd_check_format_matches(abfd, bfd_object, &matching)) {
+			bfd_error_type err=bfd_get_error();
+			fprintf(stderr,"Can't get archive `%s' format doesn't match bfd_object: %s\n",bfd_objfile,bfd_errmsg(err));
+			if (err == bfd_error_file_ambiguously_recognized) {
+				char** p=matching;
+				fprintf(stderr,"Matching formats:");
+				while (*p)
+					fprintf (stderr, " %s", *p++);
+				fputc ('\n', stderr);
+				free (matching);
+			}
+			if(!bfd_close(abfd))
+				fprintf(stderr,"Can't close object file `%s': %s\n",bfd_objfile,bfd_errmsg(bfd_get_error()));
+			fprintf(stderr,"stacktrace::beginDisplay() failed%s.\n",consolation);
+			abfd=NULL;
+		}
+	}
+	{
+		long symcount;
+		unsigned int size;
+		
+		if ((bfd_get_file_flags (abfd) & HAS_SYMS) == 0)
+			return;
+		
+		symcount = bfd_read_minisymbols (abfd, FALSE, (void *) &syms, &size);
+		if (symcount == 0)
+			symcount = bfd_read_minisymbols (abfd, TRUE /* dynamic */, (void *) &syms, &size);
+		
+		if (symcount < 0) {
+			bfd_error_type err=bfd_get_error();
+			fprintf(stderr,"Can't read minisymbols from `%s': %s\n",bfd_get_filename (abfd),bfd_errmsg(err));
+			if(!bfd_close(abfd))
+				fprintf(stderr,"Can't close object file `%s': %s\n",bfd_objfile,bfd_errmsg(bfd_get_error()));
+			fprintf(stderr,"stacktrace::beginDisplay() failed%s.\n",consolation);
+			abfd=NULL;
+		}
+		if(abfd!=NULL) {
+			fprintf(stderr,"Stack trace:\n");
+			return;
+		}
+	}
+	fprintf(stderr,"Stack trace:");
+#else
+# ifdef PLATFORM_APERIOS
+	fprintf(stderr,"Run trace_lookup:");
+#  else
+	const char* consolation=", try addr2line or trace_lookup";
+	fprintf(stderr,"libBFD unavaible%s:\n",consolation);
+	fprintf(stderr,"Stack trace:");
+#  endif
+#endif
+}
+
+#if defined(HAVE_BFD) && HAVE_BFD!=0
+//! from binutils' budemangle
+/*! Wrapper around cplus_demangle.	 Strips leading underscores and
+ *  other such chars that would otherwise confuse the demangler.	 */
+char * demangle (const char *name) {
+	char *res, *alloc;
+	const char *pre, *suf;
+	size_t pre_len;
+
+	if (abfd != NULL && bfd_get_symbol_leading_char (abfd) == name[0])
+		++name;
+
+	/* This is a hack for better error reporting on XCOFF, PowerPC64-ELF
+		 or the MS PE format.	 These formats have a number of leading '.'s
+		 on at least some symbols, so we remove all dots to avoid
+		 confusing the demangler.	 */
+	pre = name;
+	while (*name == '.')
+		++name;
+	pre_len = name - pre;
+
+	alloc = NULL;
+	suf = strchr (name, '@');
+	if (suf != NULL)
+		{
+			alloc = xmalloc (suf - name + 1);
+			memcpy (alloc, name, suf - name);
+			alloc[suf - name] = '\0';
+			name = alloc;
+		}
+
+	res = cplus_demangle (name, DMGL_ANSI | DMGL_PARAMS);
+	if (res != NULL)
+		{
+			/* Now put back any suffix, or stripped dots.	 */
+			if (pre_len != 0 || suf != NULL)
+				{
+					size_t len;
+					size_t suf_len;
+					char *final;
+
+					if (alloc != NULL)
+						free (alloc);
+
+					len = strlen (res);
+					if (suf == NULL)
+						suf = res + len;
+					suf_len = strlen (suf) + 1;
+					final = xmalloc (pre_len + len + suf_len);
+
+					memcpy (final, pre, pre_len);
+					memcpy (final + pre_len, res, len);
+					memcpy (final + pre_len + len, suf, suf_len);
+					free (res);
+					res = final;
+				}
+
+			return res;
+		}
+
+	if (alloc != NULL)
+		free (alloc);
+
+	return xstrdup (pre);
+}
+
+struct AddrLookupInfo {
+	bfd_vma addr;
+	const char *filename;
+	const char *functionname;
+	unsigned int line;
+	bfd_boolean found;
+};
+
+/*! Look for an address in a section. This is called via bfd_map_over_sections.	 */
+static void stackTraceFindAddress (bfd *fabfd, asection *section, void *data) {
+	struct AddrLookupInfo * info=(struct AddrLookupInfo *)data;
+	bfd_vma vma;
+	bfd_size_type size;
+	
+#ifdef bfd_get_section_size
+	printf("searching %p: %s %x-%x\n",info->addr,section->name,bfd_get_section_vma (fabfd, section),bfd_get_section_vma (fabfd, section)+bfd_get_section_size (section));
+#else
+	printf("searching %p: %s %x-%x\n",info->addr,section->name,bfd_get_section_vma (fabfd, section),bfd_get_section_vma (fabfd, section)+bfd_get_section_size_before_reloc (section));
+#endif
+	
+	if (info->found)
+		return;
+	if ((bfd_get_section_flags (fabfd, section) & SEC_ALLOC) == 0)
+		return;
+
+	vma = bfd_get_section_vma (fabfd, section);
+	if (info->addr < vma)
+		return;
+#ifdef bfd_get_section_size
+	size = bfd_get_section_size (section);
+#else
+	size = bfd_get_section_size_before_reloc (section);
+#endif
+	if (info->addr >= vma + size)
+		return;
+	
+	info->found = bfd_find_nearest_line (fabfd, section, syms, info->addr - vma, &info->filename, &info->functionname, &info->line);
+	printf("found %d\n",info->found);
+}
+#endif /* HAVE_BFD */
+
+#if defined(HAVE_BFD) && HAVE_BFD!=0
+void displayStackFrame(unsigned int depth, const struct StackFrame* frame) {
+	if(abfd!=NULL) {
+		struct AddrLookupInfo info={(bfd_vma)frame->ra,NULL,NULL,0,FALSE};
+		asection *p;
+		for (p = abfd->sections; p != NULL; p = p->next)
+			stackTraceFindAddress(abfd, p, &info);
+		//bfd_map_over_sections (abfd, stackTraceFindAddress, &info);
+		if (!info.found) {
+			printf("%u: %p ????\n",depth,frame->ra);
+		} else {
+			const char *name=info.functionname;
+			char *alloc = NULL;
+			if (name == NULL || *name == '\0')
+				name = "??";
+			else {
+				alloc = demangle(name);
+				name = alloc;
+			}
+			
+			printf ("%u: %p %s", depth, frame->ra, name);
+			if (alloc != NULL) {
+				free (alloc);
+				alloc=NULL;
+			}
+	
+			if(info.filename)
+				printf(" (%s:%u)\n", info.filename, info.line);
+			else
+				printf(" (??:?)\n");
+		}
+		return;
+	}
+	fprintf(stderr," %p",frame->ra);
+}
+#else
+void displayStackFrame(unsigned int ST_UNUSED(depth), const struct StackFrame* frame) {
+	ST_BODY_UNUSED(depth);
+	fprintf(stderr," %p",frame->ra);
+}
+#endif
+
+//! releases symbol information used during display
+void completeDisplay(int isend) {
+#if defined(HAVE_BFD) && HAVE_BFD!=0
+	if (syms != NULL) {
+		free(syms);
+		syms = NULL;
+	}
+	if(abfd!=NULL) {
+		if(!bfd_close(abfd)) {
+			bfd_error_type err=bfd_get_error();
+			fprintf(stderr,"Can't close object file `%s': %s\n",bfd_get_filename (abfd),bfd_errmsg(err));
+			fprintf(stderr,"stacktrace::completeDisplay() failed");
+		}
+		abfd=NULL;
+		if(!isend)
+			fprintf(stderr," ...\n");
+		return;
+	}
+#endif
+	if(!isend)
+		fprintf(stderr," ...");
+	fprintf(stderr,"\n");
+}
+
+void displayCurrentStackTrace(unsigned int limit/*=-1U*/, unsigned int skip/*=0*/) {
+	struct StackFrame cur;
+#ifdef DEBUG_STACKTRACE
+	cur.debug=0;
+#endif
+	unsigned int i;
+	int more;
+	if(limit==0)
+		return;
+	getCurrentStackFrame(&cur);
+	//printf(" initial (%p\t%p\t%p)\n",cur.ra,cur.sp,*(void**)cur.sp);
+	beginDisplay();
+	for(; skip!=0; skip--) {
+		if(!unrollStackFrame(&cur,&cur)) {
+			completeDisplay(1);
+			return;
+		}
+		//printf(" skip (%p\t%p\t%p)\n",cur.ra,cur.sp,*(void**)cur.sp);
+	}
+	for(i=0; (more=unrollStackFrame(&cur,&cur)) && i<limit; i++) {
+		//printf(" out (%p\t%p\t%p)\n",cur.ra,cur.sp,*(void**)cur.sp);
+		displayStackFrame(i,&cur);
+	}
+	completeDisplay(!more);
+}
+
+void displayStackTrace(const struct StackFrame* frame) {
+	int i;
+	beginDisplay();
+	for(i=0; frame!=NULL && frame->caller!=frame; i++) {
+		displayStackFrame(i,frame);
+		frame=frame->caller;
+	}
+	if(frame!=NULL)
+		displayStackFrame(i+1,frame);
+	completeDisplay(frame==NULL);
+}
+
+
+#ifdef __cplusplus
+}
+#endif /* __cplusplus */
+
+/*! @file
+ * @brief Implements functionality for performing stack traces
+ * @author ejt (Generalized and implementation for non-MIPS platforms)
+ * @author Stuart Scandrett (original inspiration, Aperios/MIPS stack operations)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/StackTrace.h ./Shared/StackTrace.h
--- ../Tekkotsu_2.4.1/Shared/StackTrace.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/StackTrace.h	2006-05-02 16:46:27.000000000 -0400
@@ -0,0 +1,121 @@
+#ifndef INCLUDED_StackTrace_h_
+#define INCLUDED_StackTrace_h_
+
+#include <stdlib.h>
+
+#ifdef __cplusplus
+//! Holds the C-style interface for the stack trace routines
+namespace stacktrace {
+extern "C" {
+#endif /* __cplusplus */
+
+typedef int machineInstruction; //!< typedef in case type needs to change on other platforms (i.e. long for 64 bit architectures?)
+
+//! Must be called with the object file containing debugging symbols before symbolic output can be displayed
+/*! @param objfile the file containing debugging symbols, in a format supported by libBFD; generally this is the executable itself (compiled with -g), so pass argv[0]
+ *
+ *  Display done before this has been called will display numeric addresses, which may
+ *  still be decoded externally -- this is handy for embedded systems which may not be
+ *  able to hold the debugging symbols and BFD library themselves, but the numerical
+ *  values can be looked up on the desktop workstation.
+ *  @return zero on success, negative if file could not be found, positive if it could not be parsed (wrong file type) or any other internal error */
+int loadStackTraceSymbols(const char* objfile);
+	
+//! Stores information about a single stack frame
+struct StackFrame {
+
+	//! stack pointer, points to end of stack frame
+	void * sp; 
+
+#ifdef __pic__
+	//! return address, points to instruction being executed within current frame
+	/*! Note that this is the address that is being returned to by the @e sub-function,
+	 *  @e not the address that this frame itself is returning to.
+	 *  When executing position independent code (pic), this is the address relative
+	 *  to #gp.  In other words, subtract this from #gp to get current memory address,
+	 *  or subtract from the binary's _gp symbol to get link-time address (for looking up file/line) */
+	size_t ra; 
+	
+	//! global offset used in position independent code (pic)
+	/*! subtract #ra from this to get the actual run-time memory address of the instruction */
+	size_t gp;
+
+#else
+	//! return address, points to instruction being executed within current frame
+	/*! Note that this is the address that is being returned to by the @e sub-function,
+	 *  @e not the address that this frame itself is returning to. */
+	machineInstruction * ra; 
+#endif /* __pic__ */
+
+	//! points to the caller's stack frame (stack frame of function which called this one), may be NULL or self-referential at end of list
+	/*! a self-referential value indicates the frame is not the last on the stack, but is the last recorded. */
+	struct StackFrame * caller;
+
+#ifdef DEBUG_STACKTRACE
+	//! if DEBUG_STACKTRACE is defined, this field is available which, if non-zero, will cause debugging info to be displayed on each unroll
+	int debug;
+#endif
+};
+
+
+//! stores information about the caller's stack frame into @a frame
+void getCurrentStackFrame(struct StackFrame* frame);
+
+//! stores information about the caller to @a curFrame into @a nextFrame
+/*! @return 0 if error occurred (i.e. bottom of the stack), non-zero upon success
+ *  @a nextFrame @e can be the same instance as @a curFrame, will update in place.
+ *  @a curFrame->caller will be set to @a nextFrame. */
+int unrollStackFrame(struct StackFrame* curFrame, struct StackFrame* nextFrame);
+
+//! frees a list of StackFrames, such as is returned by recordStackTrace
+void freeStackTrace(struct StackFrame* frame);
+
+//! preallocates a stack trace of a particular size (doesn't actually perform a stack trace, merely allocates the linked list)
+/*! this is a good idea if you want to do a stack trace within an exception handler, which might have been triggered by running out of heap */
+struct StackFrame* allocateStackTrace(unsigned int size);
+
+//! dumps stored stack trace to stderr
+void displayStackTrace(const struct StackFrame* frame);
+
+#ifndef __cplusplus
+
+//! dumps current stack trace to stderr, up to @a limit depth and skipping the top @a skip frames
+/*! pass -1U for limit to request unlimited trace, and 0 to start with the function calling recordStackTrace */
+void displayCurrentStackTrace(unsigned int limit, unsigned int skip);
+
+//! repeatedly calls unrollStackFrame() until the root frame is reached or @a limit is hit, skipping the top @a skip frames
+/*! pass -1U for limit to request unlimited trace, and 0 to start with the function calling recordStackTrace */
+struct StackFrame * recordStackTrace(unsigned int limit, unsigned int skip);
+//! repeatedly calls unrollStackFrame() until the root frame is reached or end of @a frame list is hit, skipping the top @a skip frames
+/*! This is handy for reusing previously allocated frames, returns the unused portion (if return value equals @a frame, none were used -- implies never cleared @a skip) */
+struct StackFrame * recordOverStackTrace(struct StackFrame* frame, unsigned int skip);
+
+#else /* __cplusplus */
+
+//! dumps current stack trace to stderr, up to @a limit depth and skipping the top @a skip frames
+/*! pass -1U for limit to request unlimited trace, and 0 to start with the function calling recordStackTrace */
+void displayCurrentStackTrace(unsigned int limit=-1U, unsigned int skip=0);
+
+//! repeatedly calls unrollStackFrame() until the root frame is reached or @a limit is hit, skipping the top @a skip frames
+/*! pass -1U for limit to request unlimited trace, and 0 to start with the function calling recordStackTrace */
+struct StackFrame * recordStackTrace(unsigned int limit=-1U, unsigned int skip=0);
+//! repeatedly calls unrollStackFrame() until the root frame is reached or end of @a frame list is hit, skipping the top @a skip frames
+/*! This is handy for reusing previously allocated frames, returns the unused portion (if return value equals @a frame, none were used -- implies never cleared @a skip) */
+struct StackFrame * recordOverStackTrace(struct StackFrame* frame, unsigned int skip=0);
+
+}
+}
+
+#endif /* __cplusplus */
+
+/*! @file
+ * @brief Describes functionality for performing stack traces
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/SystemUtility.h ./Shared/SystemUtility.h
--- ../Tekkotsu_2.4.1/Shared/SystemUtility.h	2003-10-10 13:46:04.000000000 -0400
+++ ./Shared/SystemUtility.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,69 +0,0 @@
-//-*-c++-*-
-/*=========================================================================
-    CMPack'02 Source Code Release for OPEN-R SDK v1.0
-    Copyright (C) 2002 Multirobot Lab [Project Head: Manuela Veloso]
-    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.
-  -------------------------------------------------------------------------
-    Additionally licensed to Sony Corporation under the following terms:
-
-    This software is provided by the copyright holders AS IS and any
-    express or implied warranties, including, but not limited to, the
-    implied warranties of merchantability and fitness for a particular
-    purpose are disclaimed.  In no event shall authors be liable for
-    any direct, indirect, incidental, special, exemplary, or consequential
-    damages (including, but not limited to, procurement of substitute
-    goods or services; loss of use, data, or profits; or business
-    interruption) however caused and on any theory of liability, whether
-    in contract, strict liability, or tort (including negligence or
-    otherwise) arising in any way out of the use of this software, even if
-    advised of the possibility of such damage.
-  =========================================================================
-*/
-#ifndef INCLUDED_SystemUtility_h
-#define INCLUDED_SystemUtility_h
-
-#include <MCOOP.h>
-
-#ifdef PLATFORM_APERIOS
-//! Gets memory from Aperios/OPEN-R using system's NewRegion command
-/*! This seems to be the thing to do when getting large regions?  We've
- *  had some issues with large regions returned from @c new which overlap.
- *  This issue may no longer exist, was never well known. */
-template <class T>
-T *NewLarge(T **dst, int count) {
-  sError result;
-  result=NewRegion(sizeof(T)*count+8096, reinterpret_cast<void **>(dst));
-  if (result != sSUCCESS)
-    *dst=NULL;
-
-  return *dst;
-}
-
-//! Frees memory from Aperios/OPEN-R using system's DeleteRegion command (use only on regions obtained from NewLarge)
-template <class T>
-void DeleteLarge(T *dst) {
-  DeleteRegion(dst);
-}
-#endif
-
-/*! @file
- * @brief Wrappers for getting large memory regions from Aperios
- * @author CMU RoboSoccer 2001-2002 (Creator)
- * 
- * @verbinclude CMPack_license.txt
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/TimeET.cc ./Shared/TimeET.cc
--- ../Tekkotsu_2.4.1/Shared/TimeET.cc	2003-09-25 11:31:53.000000000 -0400
+++ ./Shared/TimeET.cc	2006-03-15 11:44:07.000000000 -0500
@@ -1,6 +1,6 @@
 #include "TimeET.h"
 
-struct timezone TimeET::tz;
+struct timezone TimeET::tz={0,0};
 
 /*! @file
  * @brief Implements TimeET, a nice class for handling time values with high precision (but all that's in the .cc is implementation of struct timezone TimeET::tz)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/TimeET.h ./Shared/TimeET.h
--- ../Tekkotsu_2.4.1/Shared/TimeET.h	2005-06-01 01:47:49.000000000 -0400
+++ ./Shared/TimeET.h	2006-04-14 15:55:10.000000000 -0400
@@ -1,157 +1,238 @@
 #ifndef __TIME_ET_CLASS__
 #define __TIME_ET_CLASS__
 
-#include <iostream>
-#ifndef PLATFORM_APERIOS
-#include <sys/time.h>
-#else
+#ifdef PLATFORM_APERIOS
 #include <MCOOP.h>
-//!would be defined by system - we redefine the same structure in case we're compiling for Aperios
-struct timeval {
-	time_t tv_sec; //!< seconds
-	long tv_usec;        //!< microseconds
-};
-//!would be defined by system - we redefine the same structure in case we're compiling for Aperios
-struct timezone {
-	int     tz_minuteswest; //!< minutes west of Greenwich
-	int     tz_dsttime;     //!< type of dst correction
-};
 #endif
+#include <iostream>
+#include <sys/time.h>
 
 //!a nice class for handling time values with high precision
 /*@test negative times might not be handled properly */
 class TimeET {
 	//! lets the class be displayed easily
-  friend std::ostream& operator<<(std::ostream& o, const TimeET& t);
- public:
+	friend std::ostream& operator<<(std::ostream& o, const TimeET& t);
+	
+public:
 	//@{
 	//!constructor
-  TimeET() : tv() {
-    Set();
-  }
-  TimeET(long ms) : tv() {
-    Set(ms);
-  }
-  TimeET(long sec, long usec) : tv() {
-    Set(sec,usec);
-  }
+	TimeET() : tv() {
+		Set();
+	}
+	TimeET(long ms) : tv() {
+		Set(ms);
+	}
+	TimeET(time_t sec, long usec) : tv() {
+		Set(sec,usec);
+	}
+	TimeET(const timeval& tval) : tv(tval) {}
+	TimeET(const timespec& tspec) : tv() {
+		Set(tspec.tv_sec,tspec.tv_nsec/ns_per_us);
+	}
 	//!constructor, sepecify @a t seconds
-  TimeET(double t) :tv() {
-    Set(t);
-  }
+	TimeET(double t) :tv() {
+		Set(t);
+	}
 	//@}
-
+	
 	//!returns the difference between the current time and the time stored
-  inline TimeET Age() const { return TimeET()-(*this); }
+	inline TimeET Age() const { return TimeET()-(*this); }
 	//@{
 	//!returns the time stored as seconds in a double
-  inline double Value() const { return (double)tv.tv_sec+(double)tv.tv_usec/(double)us_per_sec; }
+	inline double Value() const { return (double)tv.tv_sec+(double)tv.tv_usec/(double)us_per_sec; }
+	//! returns the time as a timeval system construct
+	inline operator timeval &() { return tv; }
+	//! returns the time as a const timeval system construct
+	inline operator const timeval &() const { return tv; }
+	//! returns the time as a timespec system construct (though the nanosecond resolution isn't actually retained)
+	inline operator timespec() {
+		timespec tspec={tv.tv_sec,tv.tv_usec*ns_per_us};
+		return tspec;
+	}
+	//! returns the seconds portion (not rounded)
+	inline time_t getSeconds() const { return tv.tv_sec; }
+	//! returns the millisecond representation (includes both seconds and microseconds contribution); pass 0 to round down, 1000 to round up, 500 to round nearest
+	inline long getMilliseconds(long round=us_per_ms/2) const { return tv.tv_sec*ms_per_sec + (tv.tv_usec+round)/us_per_ms; }
+	//! returns the microseconds portion (doesn't include seconds)
+	inline long getMicroPortion() const { return tv.tv_usec; }
 	//@}
 	
 	//@{
-	//!sets the time stored in the class
-  inline void Set(long ms) {
-    Set(0,ms*us_per_ms);
-  }
-  inline void Set(long sec, long usec) {
-    tv.tv_sec=sec+usec/us_per_sec;
-    tv.tv_usec=usec%us_per_sec;;
-  }
-  inline void Set(double t) {
-    tv.tv_sec=(long)t;
-    tv.tv_usec=(long)((t-tv.tv_sec)*us_per_sec);
-  }
+	//!sets the time stored in the class in terms of milliseconds
+	inline void Set(long ms) {
+		Set(0,ms*us_per_ms);
+	}
+	//!sets the time in terms of seconds and microseconds (aka timeval)
+	inline void Set(time_t sec, long usec) {
+		tv.tv_sec=sec+usec/us_per_sec;
+		tv.tv_usec=usec%us_per_sec;;
+	}
+	//!sets the time in terms of floating-point seconds
+	inline void Set(double t) {
+		tv.tv_sec=(long)t;
+		tv.tv_usec=(long)((t-tv.tv_sec)*us_per_sec);
+	}
 	/*!@brief sets the time to the current time
 	 * @todo not getting timeofday on OPEN-R, is time since boot instead...*/
-  inline void Set() {
-#ifndef PLATFORM_APERIOS
-    gettimeofday(&tv,&tz);
-#else
+	inline void Set() {
+#ifdef PLATFORM_APERIOS
 		static struct SystemTime t;
 		GetSystemTime(&t);
 		Set(t.seconds,t.useconds);
+#else
+		gettimeofday(&tv,&tz);
 #endif
-  }
+	}
 	//@}
-
+	
 	//@{
 	//!for comparing times
-  inline bool operator<(long ms) const { //what if ms is negative?
-    time_t sec = ms/ms_per_sec;
-    return tv.tv_sec<sec || tv.tv_sec==sec && tv.tv_usec<static_cast<long>((ms-sec*ms_per_sec)*us_per_ms);
-  }
-  inline bool operator<(double t) const {
-    return Value()<t;
-  }
-  inline bool operator<(const TimeET& t) const {
-    return tv.tv_sec<t.tv.tv_sec || tv.tv_sec==t.tv.tv_sec && tv.tv_usec<t.tv.tv_usec;
-  }
+	inline bool operator<(long ms) const { //what if ms is negative?
+		time_t sec = ms/ms_per_sec;
+		return tv.tv_sec<sec || tv.tv_sec==sec && tv.tv_usec<static_cast<long>((ms-sec*ms_per_sec)*us_per_ms);
+	}
+	inline bool operator<(double t) const {
+		return Value()<t;
+	}
+	inline bool operator<(const TimeET& t) const {
+		return tv.tv_sec<t.tv.tv_sec || tv.tv_sec==t.tv.tv_sec && tv.tv_usec<t.tv.tv_usec;
+	}
 	//@}
-
+	
 	//@{
 	//!for doing doing math with time
-  inline TimeET operator+(const TimeET& t) const {
-    long usec = tv.tv_usec+t.tv.tv_usec;
-    long sec = tv.tv_sec+t.tv.tv_sec+usec/us_per_sec;
-    usec%=us_per_sec;
-    return TimeET(sec,usec);
-  }
-  inline TimeET operator+=(const TimeET& t) {
-    tv.tv_usec+=t.tv.tv_usec;
-    tv.tv_sec+=t.tv.tv_sec+tv.tv_usec/us_per_sec;
-    tv.tv_usec%=us_per_sec;
-    return *this;
-  }
-  inline TimeET operator-(const TimeET& t) const {
-    long usec = tv.tv_usec-t.tv.tv_usec;
-    long sec = tv.tv_sec-t.tv.tv_sec+usec/us_per_sec;
-    usec%=us_per_sec;
-    if(usec<0) {
-      usec+=us_per_sec;
-      sec--;
-    }
-    return TimeET(sec,usec);
-  }
-  inline TimeET operator-=(const TimeET& t) {
-    tv.tv_usec-=t.tv.tv_usec;
-    tv.tv_sec=tv.tv_sec-t.tv.tv_sec+tv.tv_usec/us_per_sec;
-    tv.tv_usec%=us_per_sec;
-    if(tv.tv_usec<0) {
-      tv.tv_usec+=us_per_sec;
-      tv.tv_sec--;
-    }
-    return *this;
-  }
+	inline TimeET operator+(const TimeET& t) const {
+		long usec = tv.tv_usec+t.tv.tv_usec;
+		long sec = tv.tv_sec+t.tv.tv_sec+usec/us_per_sec;
+		usec%=us_per_sec;
+		return TimeET(sec,usec);
+	}
+	inline TimeET operator+=(const TimeET& t) {
+		tv.tv_usec+=t.tv.tv_usec;
+		tv.tv_sec+=t.tv.tv_sec+tv.tv_usec/us_per_sec;
+		tv.tv_usec%=us_per_sec;
+		return *this;
+	}
+	inline TimeET operator-(const TimeET& t) const {
+		long usec = tv.tv_usec-t.tv.tv_usec;
+		long sec = tv.tv_sec-t.tv.tv_sec+usec/us_per_sec;
+		usec%=us_per_sec;
+		if(usec<0) {
+			usec+=us_per_sec;
+			sec--;
+		}
+		return TimeET(sec,usec);
+	}
+	inline TimeET operator-=(const TimeET& t) {
+		tv.tv_usec-=t.tv.tv_usec;
+		tv.tv_sec=tv.tv_sec-t.tv.tv_sec+tv.tv_usec/us_per_sec;
+		tv.tv_usec%=us_per_sec;
+		if(tv.tv_usec<0) {
+			tv.tv_usec+=us_per_sec;
+			tv.tv_sec--;
+		}
+		return *this;
+	}
+	inline TimeET operator*(double x) const {
+		if(x>1 || x<-1) {
+			double usec = tv.tv_usec*x;
+			long carry=static_cast<long>(usec/us_per_sec);
+			long sec = static_cast<long>(tv.tv_sec*x)+carry;
+			usec-=carry*us_per_sec;
+			return TimeET(sec,static_cast<long>(usec));
+		} else {
+			double secv=tv.tv_sec*x;
+			long sec=static_cast<long>(secv);
+			double carry=secv-sec;
+			long usec=static_cast<long>(tv.tv_usec*x+carry*us_per_sec);
+			return TimeET(sec,usec);
+		}
+	}
+	inline TimeET operator*=(double x) {
+		if(x>1 || x<-1) {
+			double usec = tv.tv_usec*x;
+			long carry=static_cast<long>(usec/us_per_sec);
+			tv.tv_sec = static_cast<long>(tv.tv_sec*x)+carry;
+			tv.tv_usec=static_cast<long>(usec-carry*us_per_sec);
+			return *this;
+		} else {
+			double secv=tv.tv_sec*x;
+			tv.tv_sec=static_cast<long>(secv);
+			double carry=secv-tv.tv_sec;
+			tv.tv_usec=static_cast<long>(tv.tv_usec*x+carry*us_per_sec);
+			return *this;
+		}
+	}
+	inline TimeET operator/(double x) const {
+		if(x>1 || x<-1) {
+			double secv=tv.tv_sec/x;
+			long sec=static_cast<long>(secv);
+			double carry=secv-sec;
+			long usec=static_cast<long>(tv.tv_usec/x+carry*us_per_sec);
+			return TimeET(sec,usec);
+		} else {
+			double usec = tv.tv_usec/x;
+			long carry=static_cast<long>(usec/us_per_sec);
+			long sec = static_cast<long>(tv.tv_sec/x)+carry;
+			usec-=carry*us_per_sec;
+			return TimeET(sec,static_cast<long>(usec));
+		}
+	}
+	inline TimeET operator/=(double x) {
+		if(x>1 || x<-1) {
+			double secv=tv.tv_sec/x;
+			tv.tv_sec=static_cast<long>(secv);
+			double carry=secv-tv.tv_sec;
+			tv.tv_usec=static_cast<long>(tv.tv_usec/x+carry*us_per_sec);
+			return *this;
+		} else {
+			double usec = tv.tv_usec/x;
+			long carry=static_cast<long>(usec/us_per_sec);
+			tv.tv_sec = static_cast<long>(tv.tv_sec/x)+carry;
+			tv.tv_usec=static_cast<long>(usec-carry*us_per_sec);
+			return *this;
+		}
+	}
 	//@}
-
-  static const long us_per_sec=1000000; //!< conversion factor for microseconds to seconds
-  static const long ms_per_sec=1000;    //!< conversion factor for milliseconds to seconds
-  static const long us_per_ms=1000;     //!< conversion factor for microseconds to milliseconds
- protected:
-  timeval tv; //!< stores the time
-  static struct timezone tz; //!< stores the timezone (not really used)
+	
+	static const long us_per_sec=1000000; //!< conversion factor for microseconds to seconds
+	static const long ms_per_sec=1000;    //!< conversion factor for milliseconds to seconds
+	static const long us_per_ms=1000;     //!< conversion factor for microseconds to milliseconds
+	static const long ns_per_us=1000;     //!< conversion factor for nanoseconds to microseconds
+	
+protected:
+	timeval tv; //!< stores the time
+	static struct timezone tz; //!< stores the timezone (not really used)
 };
 
 //@{
 //!for doing doing math with time
 inline TimeET operator+(long t1, const TimeET& t2) { return TimeET(t1)+t2; }
+inline TimeET operator-(long t1, const TimeET& t2) { return TimeET(t1)-t2; }
+inline TimeET operator+(double t1, const TimeET& t2) { return TimeET(t1)+t2; }
 inline TimeET operator-(double t1, const TimeET& t2) { return TimeET(t1)-t2; }
+inline TimeET operator*(double x, const TimeET& t) { return t*x; }
 //@}
 
 //! displays the value as text: secs~usecs
 inline std::ostream& operator<<(std::ostream& o, const TimeET& t) {
-  return (o << t.tv.tv_sec << '~' << t.tv.tv_usec);
+	o << t.tv.tv_sec << '.';
+	o.width(6);
+	o.fill('0');
+	o << t.tv.tv_usec;
+	o.fill(' ');
+	return o;
 }
 
 /*! @file
- * @brief Describes TimeET, a nice class for handling time values with high precision
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
+* @brief Describes TimeET, a nice class for handling time values with high precision
+* @author ejt (Creator)
+*
+* $Author: ejt $
+* $Name: HEAD $
+* $Revision: 1.1 $
+* $State: Exp $
+* $Date: 2006/10/04 04:21:12 $
+*/
 
 #endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/WMclass.h ./Shared/WMclass.h
--- ../Tekkotsu_2.4.1/Shared/WMclass.h	2005-07-25 23:22:04.000000000 -0400
+++ ./Shared/WMclass.h	2006-09-11 19:05:15.000000000 -0400
@@ -133,13 +133,13 @@
   //! Turn on monitoring of changes to the variable described by this entry.
   void watch(void) const {
 		entry->watched = 1; 
-		erouter->postEvent(new EventBase(EventBase::wmVarEGID,reinterpret_cast<unsigned int>(entry),EventBase::activateETID));
+		erouter->postEvent(EventBase::wmVarEGID,reinterpret_cast<size_t>(entry),EventBase::activateETID);
 	};
 
   //! Turn off monitoring of changes to the variable described by this entry.
   void unwatch(void) const {
 		entry->watched = 0;
-		erouter->postEvent(new EventBase(EventBase::wmVarEGID,reinterpret_cast<unsigned int>(entry),EventBase::deactivateETID));
+		erouter->postEvent(EventBase::wmVarEGID,reinterpret_cast<size_t>(entry),EventBase::deactivateETID);
 	};
 
 private:
@@ -250,7 +250,7 @@
 template<class T>
 std::string WMitem<T>::toString(void) const {
   char print_buffer[30];
-  sprintf(print_buffer,"%x",reinterpret_cast<unsigned int>(value));
+  sprintf(print_buffer,"%p",value);
   return "<" + entry->type_name + " at 0x" + print_buffer + ">";
 }
 
@@ -268,7 +268,7 @@
 template<class T>
 void WMitem<T>::announce (const T&) {
   if (entry->watched) {
-		erouter->postEvent(new EventBase(EventBase::wmVarEGID,reinterpret_cast<unsigned int>(entry),EventBase::statusETID));
+		erouter->postEvent(EventBase::wmVarEGID,reinterpret_cast<size_t>(entry),EventBase::statusETID);
 	}
 	/*    if (wmMonitorBehavior!=NULL) {
 				std::string s(entry->item_name);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/WorldState.cc ./Shared/WorldState.cc
--- ../Tekkotsu_2.4.1/Shared/WorldState.cc	2005-07-10 16:02:17.000000000 -0400
+++ ./Shared/WorldState.cc	2006-09-29 12:56:09.000000000 -0400
@@ -1,417 +1,600 @@
-#ifdef PLATFORM_APERIOS
-#include <OPENR/core_macro.h>
-#include <OPENR/ObjcommTypes.h>
-#include <OPENR/OPENR.h>
-#include <OPENR/OPENRAPI.h>
-#include <OPENR/OPENRMessages.h>
-#include <OPENR/OPower.h>
-#endif
-
-#include "WorldState.h"
-#include "Shared/get_time.h"
-#include "Events/EventRouter.h"
-#include "ERS210Info.h"
-#include "ERS220Info.h"
-#include "ERS7Info.h"
-#include "Shared/Config.h"
-
-#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)
-
-const double WorldState::g=9.80665;
-const double WorldState::IROORDist = 900.0;
-
-WorldState * state=NULL;
-
-WorldState::WorldState()
-	: alwaysGenerateStatus(false), vel_x(0), vel_y(0), vel_a(0), vel_time(0),
-		robotStatus(0), batteryStatus(0),
-		lastSensorUpdateTime(0), mainProfile(), motionProfile(),
-		robotDesign(0), curtime(get_time())
-{
-	for(unsigned int i=0; i< NumOutputs; i++)
-		outputs[i]=0;
-	for(unsigned int i=0; i< NumButtons; i++)
-		buttons[i]=0;
-	for(unsigned int i=0; i< NumSensors; i++)
-		sensors[i]=0;
-	for(unsigned int i=0; i< NumPIDJoints; i++)
-		for(unsigned int j=0; j<3; j++)
-			pids[i][j]=0;
-	for(unsigned int i=0; i< NumPIDJoints; i++)
-		pidduties[i]=0;
-	memset(powerFlags,0,sizeof(unsigned int)*PowerSourceID::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
-
-/*! This will cause events to be posted
- *  @todo change to use most recent instead of oldest - is a buffer! */
-void WorldState::read(OSensorFrameVectorData& sensor, EventRouter* er) {
-	curtime=get_time();
-
-	std::vector<EventBase*> evtBuf;
-	unsigned int lastFrame=sensor.GetInfo(0)->numFrames-1;
-
-	if(robotDesign&ERS210Mask) {
-		outputs[LFrLegOffset + RotatorOffset   ] = GETD(ERS210Info::CPCJointLFRotator);
-		outputs[LFrLegOffset + ElevatorOffset  ] = GETD(ERS210Info::CPCJointLFElevator);
-		outputs[LFrLegOffset + KneeOffset      ] = GETD(ERS210Info::CPCJointLFKnee);
-		pidduties[LFrLegOffset + RotatorOffset ] = GETDUTY(ERS210Info::CPCJointLFRotator);
-		pidduties[LFrLegOffset + ElevatorOffset] = GETDUTY(ERS210Info::CPCJointLFElevator);
-		pidduties[LFrLegOffset + KneeOffset    ] = GETDUTY(ERS210Info::CPCJointLFKnee);
-	
-		outputs[RFrLegOffset + RotatorOffset   ] = GETD(ERS210Info::CPCJointRFRotator);
-		outputs[RFrLegOffset + ElevatorOffset  ] = GETD(ERS210Info::CPCJointRFElevator);
-		outputs[RFrLegOffset + KneeOffset      ] = GETD(ERS210Info::CPCJointRFKnee);
-		pidduties[RFrLegOffset + RotatorOffset ] = GETDUTY(ERS210Info::CPCJointRFRotator);
-		pidduties[RFrLegOffset + ElevatorOffset] = GETDUTY(ERS210Info::CPCJointRFElevator);
-		pidduties[RFrLegOffset + KneeOffset    ] = GETDUTY(ERS210Info::CPCJointRFKnee);
-
-		outputs[LBkLegOffset + RotatorOffset   ] = GETD(ERS210Info::CPCJointLHRotator);
-		outputs[LBkLegOffset + ElevatorOffset  ] = GETD(ERS210Info::CPCJointLHElevator);
-		outputs[LBkLegOffset + KneeOffset      ] = GETD(ERS210Info::CPCJointLHKnee);
-		pidduties[LBkLegOffset + RotatorOffset ] = GETDUTY(ERS210Info::CPCJointLHRotator);
-		pidduties[LBkLegOffset + ElevatorOffset] = GETDUTY(ERS210Info::CPCJointLHElevator);
-		pidduties[LBkLegOffset + KneeOffset    ] = GETDUTY(ERS210Info::CPCJointLHKnee);
-
-		outputs[RBkLegOffset + RotatorOffset   ] = GETD(ERS210Info::CPCJointRHRotator);
-		outputs[RBkLegOffset + ElevatorOffset  ] = GETD(ERS210Info::CPCJointRHElevator);
-		outputs[RBkLegOffset + KneeOffset      ] = GETD(ERS210Info::CPCJointRHKnee);
-		pidduties[RBkLegOffset + RotatorOffset ] = GETDUTY(ERS210Info::CPCJointRHRotator);
-		pidduties[RBkLegOffset + ElevatorOffset] = GETDUTY(ERS210Info::CPCJointRHElevator);
-		pidduties[RBkLegOffset + KneeOffset    ] = GETDUTY(ERS210Info::CPCJointRHKnee);
-
-		// Get head tilt,pan,roll joint angles
-		outputs[HeadOffset+TiltOffset] = GETD(ERS210Info::CPCJointNeckTilt);
-		outputs[HeadOffset+PanOffset ] = GETD(ERS210Info::CPCJointNeckPan);
-		outputs[HeadOffset+RollOffset] = GETD(ERS210Info::CPCJointNeckRoll);
-		pidduties[HeadOffset+TiltOffset] = GETDUTY(ERS210Info::CPCJointNeckTilt);
-		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);
-		
-		outputs[ERS210Info::MouthOffset] = GETD(ERS210Info::CPCJointMouth);
-		pidduties[ERS210Info::MouthOffset] = GETDUTY(ERS210Info::CPCJointMouth);
-
-		// Get foot switches
-		chkEvent(evtBuf,ERS210Info::LFrPawOffset,GETB(ERS210Info::CPCSensorLFPaw),buttonNames[ERS210Info::LFrPawOffset]);
-		chkEvent(evtBuf,ERS210Info::RFrPawOffset,GETB(ERS210Info::CPCSensorRFPaw),buttonNames[ERS210Info::RFrPawOffset]);
-		chkEvent(evtBuf,ERS210Info::LBkPawOffset,GETB(ERS210Info::CPCSensorLHPaw),buttonNames[ERS210Info::LBkPawOffset]);
-		chkEvent(evtBuf,ERS210Info::RBkPawOffset,GETB(ERS210Info::CPCSensorRHPaw),buttonNames[ERS210Info::RBkPawOffset]);
-
-		// Get buttons
-		chkEvent(evtBuf,ERS210Info::ChinButOffset,  GETB(ERS210Info::CPCSensorChinSwitch),buttonNames[ERS210Info::ChinButOffset]);
-		chkEvent(evtBuf,ERS210Info::BackButOffset,  GETB(ERS210Info::CPCSensorBackSwitch),buttonNames[ERS210Info::BackButOffset]);
-		chkEvent(evtBuf,ERS210Info::HeadFrButOffset,GETD(ERS210Info::CPCSensorHeadFrontPressure),buttonNames[ERS210Info::HeadFrButOffset]);
-		chkEvent(evtBuf,ERS210Info::HeadBkButOffset,GETD(ERS210Info::CPCSensorHeadBackPressure),buttonNames[ERS210Info::HeadBkButOffset]);
-
-		// Get IR distance sensor
-		sensors[ERS210Info::IRDistOffset]=GETSENSOR(ERS210Info::CPCSensorPSD) / 1000.0f;
-
-		// Get acceleration sensors
-		sensors[BAccelOffset] = GETD(ERS210Info::CPCSensorAccelFB);
-		sensors[LAccelOffset] = GETD(ERS210Info::CPCSensorAccelLR);
-		sensors[DAccelOffset] = GETD(ERS210Info::CPCSensorAccelUD);
-
-		sensors[ERS210Info::ThermoOffset] = GETD(ERS210Info::CPCSensorThermoSensor);
-	}
-
-	// (ERS-220 only)
-	if(robotDesign&ERS220Mask) {
-		outputs[LFrLegOffset + RotatorOffset   ] = GETD(ERS220Info::CPCJointLFRotator);
-		outputs[LFrLegOffset + ElevatorOffset  ] = GETD(ERS220Info::CPCJointLFElevator);
-		outputs[LFrLegOffset + KneeOffset      ] = GETD(ERS220Info::CPCJointLFKnee);
-		pidduties[LFrLegOffset + RotatorOffset ] = GETDUTY(ERS220Info::CPCJointLFRotator);
-		pidduties[LFrLegOffset + ElevatorOffset] = GETDUTY(ERS220Info::CPCJointLFElevator);
-		pidduties[LFrLegOffset + KneeOffset    ] = GETDUTY(ERS220Info::CPCJointLFKnee);
-	
-		outputs[RFrLegOffset + RotatorOffset   ] = GETD(ERS220Info::CPCJointRFRotator);
-		outputs[RFrLegOffset + ElevatorOffset  ] = GETD(ERS220Info::CPCJointRFElevator);
-		outputs[RFrLegOffset + KneeOffset      ] = GETD(ERS220Info::CPCJointRFKnee);
-		pidduties[RFrLegOffset + RotatorOffset ] = GETDUTY(ERS220Info::CPCJointRFRotator);
-		pidduties[RFrLegOffset + ElevatorOffset] = GETDUTY(ERS220Info::CPCJointRFElevator);
-		pidduties[RFrLegOffset + KneeOffset    ] = GETDUTY(ERS220Info::CPCJointRFKnee);
-	
-		outputs[LBkLegOffset + RotatorOffset   ] = GETD(ERS220Info::CPCJointLHRotator);
-		outputs[LBkLegOffset + ElevatorOffset  ] = GETD(ERS220Info::CPCJointLHElevator);
-		outputs[LBkLegOffset + KneeOffset      ] = GETD(ERS220Info::CPCJointLHKnee);
-		pidduties[LBkLegOffset + RotatorOffset ] = GETDUTY(ERS220Info::CPCJointLHRotator);
-		pidduties[LBkLegOffset + ElevatorOffset] = GETDUTY(ERS220Info::CPCJointLHElevator);
-		pidduties[LBkLegOffset + KneeOffset    ] = GETDUTY(ERS220Info::CPCJointLHKnee);
-
-		outputs[RBkLegOffset + RotatorOffset   ] = GETD(ERS220Info::CPCJointRHRotator);
-		outputs[RBkLegOffset + ElevatorOffset  ] = GETD(ERS220Info::CPCJointRHElevator);
-		outputs[RBkLegOffset + KneeOffset      ] = GETD(ERS220Info::CPCJointRHKnee);
-		pidduties[RBkLegOffset + RotatorOffset ] = GETDUTY(ERS220Info::CPCJointRHRotator);
-		pidduties[RBkLegOffset + ElevatorOffset] = GETDUTY(ERS220Info::CPCJointRHElevator);
-		pidduties[RBkLegOffset + KneeOffset    ] = GETDUTY(ERS220Info::CPCJointRHKnee);
-
-		// Get head tilt,pan,roll joint angles
-		outputs[HeadOffset+TiltOffset] = GETD(ERS220Info::CPCJointNeckTilt);
-		outputs[HeadOffset+PanOffset ] = GETD(ERS220Info::CPCJointNeckPan);
-		outputs[HeadOffset+RollOffset] = GETD(ERS220Info::CPCJointNeckRoll);
-		pidduties[HeadOffset+TiltOffset] = GETDUTY(ERS220Info::CPCJointNeckTilt);
-		pidduties[HeadOffset+PanOffset ] = GETDUTY(ERS220Info::CPCJointNeckPan);
-		pidduties[HeadOffset+RollOffset] = GETDUTY(ERS220Info::CPCJointNeckRoll);
-
-	 	chkEvent(evtBuf, ERS220Info::TailLeftButOffset, GETB(ERS220Info::CPCSensorTailLeftSwitch),  buttonNames[ERS220Info::TailLeftButOffset]);
-	 	chkEvent(evtBuf, ERS220Info::TailCenterButOffset, GETB(ERS220Info::CPCSensorTailCenterSwitch),buttonNames[ERS220Info::TailCenterButOffset]);
-	 	chkEvent(evtBuf, ERS220Info::TailRightButOffset, GETB(ERS220Info::CPCSensorTailRightSwitch), buttonNames[ERS220Info::TailRightButOffset]);
-
-		// Get foot switches
-		chkEvent(evtBuf,ERS220Info::LFrPawOffset,GETB(ERS220Info::CPCSensorLFPaw),buttonNames[ERS220Info::LFrPawOffset]);
-		chkEvent(evtBuf,ERS220Info::RFrPawOffset,GETB(ERS220Info::CPCSensorRFPaw),buttonNames[ERS220Info::RFrPawOffset]);
-		chkEvent(evtBuf,ERS220Info::LBkPawOffset,GETB(ERS220Info::CPCSensorLHPaw),buttonNames[ERS220Info::LBkPawOffset]);
-		chkEvent(evtBuf,ERS220Info::RBkPawOffset,GETB(ERS220Info::CPCSensorRHPaw),buttonNames[ERS220Info::RBkPawOffset]);
-
-		// Get buttons
-		chkEvent(evtBuf,ERS220Info::ChinButOffset,  GETB(ERS220Info::CPCSensorChinSwitch),buttonNames[ERS220Info::ChinButOffset]);
-		chkEvent(evtBuf,ERS220Info::BackButOffset,  GETB(ERS220Info::CPCSensorBackSwitch),buttonNames[ERS220Info::BackButOffset]);
-		chkEvent(evtBuf,ERS220Info::HeadFrButOffset,GETD(ERS220Info::CPCSensorHeadFrontPressure),buttonNames[ERS220Info::HeadFrButOffset]);
-		chkEvent(evtBuf,ERS220Info::HeadBkButOffset,GETD(ERS220Info::CPCSensorHeadBackPressure),buttonNames[ERS220Info::HeadBkButOffset]);
-
-		// Get IR distance sensor
-		sensors[ERS220Info::IRDistOffset]=GETSENSOR(ERS220Info::CPCSensorPSD) / 1000.0f;
-
-		// Get acceleration sensors
-		sensors[BAccelOffset] = GETD(ERS220Info::CPCSensorAccelFB);
-		sensors[LAccelOffset] = GETD(ERS220Info::CPCSensorAccelLR);
-		sensors[DAccelOffset] = GETD(ERS220Info::CPCSensorAccelUD);
-
-		sensors[ERS220Info::ThermoOffset] = GETD(ERS220Info::CPCSensorThermoSensor);
-	}
-
-	// (ERS-7 only)
-	if(robotDesign&ERS7Mask) {
-		outputs[LFrLegOffset + RotatorOffset   ] = GETD(ERS7Info::CPCJointLFRotator);
-		outputs[LFrLegOffset + ElevatorOffset  ] = GETD(ERS7Info::CPCJointLFElevator);
-		outputs[LFrLegOffset + KneeOffset      ] = GETD(ERS7Info::CPCJointLFKnee);
-		pidduties[LFrLegOffset + RotatorOffset ] = GETDUTY(ERS7Info::CPCJointLFRotator);
-		pidduties[LFrLegOffset + ElevatorOffset] = GETDUTY(ERS7Info::CPCJointLFElevator);
-		pidduties[LFrLegOffset + KneeOffset    ] = GETDUTY(ERS7Info::CPCJointLFKnee);
-	
-		outputs[RFrLegOffset + RotatorOffset   ] = GETD(ERS7Info::CPCJointRFRotator);
-		outputs[RFrLegOffset + ElevatorOffset  ] = GETD(ERS7Info::CPCJointRFElevator);
-		outputs[RFrLegOffset + KneeOffset      ] = GETD(ERS7Info::CPCJointRFKnee);
-		pidduties[RFrLegOffset + RotatorOffset ] = GETDUTY(ERS7Info::CPCJointRFRotator);
-		pidduties[RFrLegOffset + ElevatorOffset] = GETDUTY(ERS7Info::CPCJointRFElevator);
-		pidduties[RFrLegOffset + KneeOffset    ] = GETDUTY(ERS7Info::CPCJointRFKnee);
-	
-		outputs[LBkLegOffset + RotatorOffset   ] = GETD(ERS7Info::CPCJointLHRotator);
-		outputs[LBkLegOffset + ElevatorOffset  ] = GETD(ERS7Info::CPCJointLHElevator);
-		outputs[LBkLegOffset + KneeOffset      ] = GETD(ERS7Info::CPCJointLHKnee);
-		pidduties[LBkLegOffset + RotatorOffset ] = GETDUTY(ERS7Info::CPCJointLHRotator);
-		pidduties[LBkLegOffset + ElevatorOffset] = GETDUTY(ERS7Info::CPCJointLHElevator);
-		pidduties[LBkLegOffset + KneeOffset    ] = GETDUTY(ERS7Info::CPCJointLHKnee);
-
-		outputs[RBkLegOffset + RotatorOffset   ] = GETD(ERS7Info::CPCJointRHRotator);
-		outputs[RBkLegOffset + ElevatorOffset  ] = GETD(ERS7Info::CPCJointRHElevator);
-		outputs[RBkLegOffset + KneeOffset      ] = GETD(ERS7Info::CPCJointRHKnee);
-		pidduties[RBkLegOffset + RotatorOffset ] = GETDUTY(ERS7Info::CPCJointRHRotator);
-		pidduties[RBkLegOffset + ElevatorOffset] = GETDUTY(ERS7Info::CPCJointRHElevator);
-		pidduties[RBkLegOffset + KneeOffset    ] = GETDUTY(ERS7Info::CPCJointRHKnee);
-
-		// Get head tilt,pan,nod joint angles
-		outputs[HeadOffset+TiltOffset] = GETD(ERS7Info::CPCJointNeckTilt);
-		outputs[HeadOffset+PanOffset ] = GETD(ERS7Info::CPCJointNeckPan);
-		outputs[HeadOffset+RollOffset] = GETD(ERS7Info::CPCJointNeckNod);
-		pidduties[HeadOffset+TiltOffset] = GETDUTY(ERS7Info::CPCJointNeckTilt);
-		pidduties[HeadOffset+PanOffset ] = GETDUTY(ERS7Info::CPCJointNeckPan);
-		pidduties[HeadOffset+RollOffset] = GETDUTY(ERS7Info::CPCJointNeckNod);
-
-		outputs[ERS7Info::TailOffset+TiltOffset] = GETD(ERS7Info::CPCJointTailTilt);
-		outputs[ERS7Info::TailOffset+PanOffset]  = GETD(ERS7Info::CPCJointTailPan);
-		pidduties[ERS7Info::TailOffset+TiltOffset] = GETDUTY(ERS7Info::CPCJointTailTilt);
-		pidduties[ERS7Info::TailOffset+PanOffset]  = GETDUTY(ERS7Info::CPCJointTailPan);
-		
-		outputs[ERS7Info::MouthOffset] = GETD(ERS7Info::CPCJointMouth);
-		pidduties[ERS7Info::MouthOffset] = GETDUTY(ERS7Info::CPCJointMouth);
-
-		// Get foot switches
-		chkEvent(evtBuf,ERS7Info::LFrPawOffset,GETB(ERS7Info::CPCSwitchLFPaw),buttonNames[ERS7Info::LFrPawOffset]);
-		chkEvent(evtBuf,ERS7Info::RFrPawOffset,GETB(ERS7Info::CPCSwitchRFPaw),buttonNames[ERS7Info::RFrPawOffset]);
-		chkEvent(evtBuf,ERS7Info::LBkPawOffset,GETB(ERS7Info::CPCSwitchLHPaw),buttonNames[ERS7Info::LBkPawOffset]);
-		chkEvent(evtBuf,ERS7Info::RBkPawOffset,GETB(ERS7Info::CPCSwitchRHPaw),buttonNames[ERS7Info::RBkPawOffset]);
-
-		// Get buttons/switches
-		// the sensors are scaled to be relatively similar to the pressure values given by the head on the 210
-		chkEvent(evtBuf, ERS7Info::ChinButOffset,       GETSENSOR(ERS7Info::CPCSwitchChin),      buttonNames[ERS7Info::ChinButOffset]);
-		chkEvent(evtBuf, ERS7Info::HeadButOffset,       GETSENSOR(ERS7Info::CPCSensorHead)/120,      buttonNames[ERS7Info::HeadButOffset]);
-	 	chkEvent(evtBuf, ERS7Info::FrontBackButOffset,  GETSENSOR(ERS7Info::CPCSensorBackFront)/150, buttonNames[ERS7Info::FrontBackButOffset]);
-	 	chkEvent(evtBuf, ERS7Info::MiddleBackButOffset, GETSENSOR(ERS7Info::CPCSensorBackMiddle)/150,buttonNames[ERS7Info::MiddleBackButOffset]);
-	 	chkEvent(evtBuf, ERS7Info::RearBackButOffset,   GETSENSOR(ERS7Info::CPCSensorBackRear)/150,  buttonNames[ERS7Info::RearBackButOffset]);
-	 	chkEvent(evtBuf, ERS7Info::WirelessSwOffset,GETSENSOR(ERS7Info::CPCSwitchWireless),  buttonNames[ERS7Info::WirelessSwOffset]);
-
-		// Get IR distance sensor
-		sensors[ERS7Info::NearIRDistOffset] = GETSENSOR(ERS7Info::CPCSensorNearPSD) / 1000.0f;
-		sensors[ERS7Info::FarIRDistOffset] = GETSENSOR(ERS7Info::CPCSensorFarPSD) / 1000.0f;
-		sensors[ERS7Info::ChestIRDistOffset] = GETSENSOR(ERS7Info::CPCSensorChestPSD) / 1000.0f;
-
-		// Get acceleration sensors
-		sensors[BAccelOffset] = GETD(ERS7Info::CPCSensorAccelFB);
-		sensors[LAccelOffset] = GETD(ERS7Info::CPCSensorAccelLR);
-		sensors[DAccelOffset] = GETD(ERS7Info::CPCSensorAccelUD);
-	}
-
-	//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];
-
-	unsigned int dif=curtime-lastSensorUpdateTime;
-	lastSensorUpdateTime=curtime;
-	for(unsigned int i=0; i<evtBuf.size(); i++)
-		er->postEvent(evtBuf[i]);
-	//we don't delete the events in evtBuf - we're handing them off to erouter, which will delete them itself
-	er->postEvent(EventBase::sensorEGID,SensorSourceID::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);
-
-	//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);
-
-	//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);
-	
-	sensors[PowerRemainOffset] = power.remainingCapacity/100.0;
-	sensors[PowerThermoOffset] = power.temperature/100.0;
-	sensors[PowerCapacityOffset] = power.fullyChargedCapacity;
-	sensors[PowerVoltageOffset] = power.voltage/1000.0;
-	sensors[PowerCurrentOffset] = power.current;
-
-	//only generate status events when a change happens
-	for(unsigned int i=0; i<PowerSourceID::NumPowerSIDs; i++) {
-		if(actmasks[i]) { //now on
-			if(!powerFlags[i]) //was off: activation
-				er->postEvent(EventBase::powerEGID,i,EventBase::activateETID,0,actnames[i],1);
-			else if(actmasks[i]!=powerFlags[i]) //already on - change? : status
-				er->postEvent(EventBase::powerEGID,i,EventBase::statusETID,0,actnames[i],1);
-		} else { // now off
-			if(powerFlags[i]) //was on: deactivation
-				er->postEvent(EventBase::powerEGID,i,EventBase::deactivateETID,0,denames[i],0);
-		}
-		powerFlags[i]=actmasks[i];
-	}
-
-	er->postEvent(EventBase::powerEGID,PowerSourceID::UpdatedSID,EventBase::statusETID,0,"PowerSourceID::UpdatedSID",1);
-}
-
-#endif //PLATFORM_APERIOS
-
-void WorldState::chkEvent(std::vector<EventBase*>& evtBuf, unsigned int sid, float newval, const char* name) {
-	if(newval>=0.1) { //now on
-		if(buttons[sid]<0.1) { //was off: activation
-			evtBuf.push_back(new EventBase(EventBase::buttonEGID,sid,EventBase::activateETID,0,name,newval));
-			button_times[sid]=curtime;
-		} else if(alwaysGenerateStatus || buttons[sid]!=newval) { //already on - always or change? : status
-			unsigned int dur=curtime-button_times[sid];
-			evtBuf.push_back(new EventBase(EventBase::buttonEGID,sid,EventBase::statusETID,dur,name,newval));
-		}
-	} else { //now off
-		if(buttons[sid]>=0.1) { //was on: deactivation
-			unsigned int dur=curtime-button_times[sid];
-			button_times[sid]=0;
-			evtBuf.push_back(new EventBase(EventBase::buttonEGID,sid,EventBase::deactivateETID,dur,name,0));
-		}
-	}
-	//update value
-	buttons[sid]=newval;
-}
-
-/*! @file
- * @brief Implements WorldState, maintains information about the robot's environment, namely sensors and power status
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
+#include "WorldState.h"
+#include "Shared/get_time.h"
+#include "Events/EventRouter.h"
+#include "ERS210Info.h"
+#include "ERS220Info.h"
+#include "ERS7Info.h"
+#include "Shared/Config.h"
+#include "IPC/ProcessID.h"
+
+#ifdef PLATFORM_APERIOS
+#  include <OPENR/core_macro.h>
+#  include <OPENR/ObjcommTypes.h>
+#  include <OPENR/OPENR.h>
+#  include <OPENR/OPENRAPI.h>
+#  include <OPENR/OPENRMessages.h>
+#  include <OPENR/OPower.h>
+#else
+#  include "Motion/PostureEngine.h"
+#endif
+
+#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)
+
+const double WorldState::g=9.80665;
+const double WorldState::IROORDist = 900.0;
+
+#ifdef PLATFORM_APERIOS
+WorldState ** WorldState::stateLookupMap=NULL;
+#endif
+
+WorldState * state=NULL;
+
+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)
+{
+	for(unsigned int i=0; i< NumOutputs; i++)
+		outputs[i]=0;
+	for(unsigned int i=0; i< NumButtons; i++)
+		buttons[i]=0;
+	for(unsigned int i=0; i< NumSensors; i++)
+		sensors[i]=0;
+	for(unsigned int i=0; i< NumPIDJoints; i++)
+		for(unsigned int j=0; j<3; j++)
+			pids[i][j]=0;
+	for(unsigned int i=0; i< NumPIDJoints; i++)
+		pidduties[i]=0;
+	memset(powerFlags,0,sizeof(unsigned int)*PowerSourceID::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
+
+/*! This will cause events to be posted */
+void WorldState::read(OSensorFrameVectorData& sensor, WorldState* lastState, EventRouter* er) {
+	//always using GetInfo(0) to get "global" information for the vector, other infos contain metadata for individual data fields
+	unsigned int newFrameNumber=sensor.GetInfo(0)->frameNumber;
+	if(frameNumber>=newFrameNumber)
+		return; //sensors have already been filled in
+	
+	curtime=get_time();
+
+	std::vector<EventBase> evtBuf;
+	unsigned int lastFrame=sensor.GetInfo(0)->numFrames-1;
+
+	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++)
+			powerFlags[i]=lastState->powerFlags[i];
+		
+		//important part -- copy over button_times before calls to chkEvent
+		for(unsigned int i=0; i<NumButtons; i++)
+			button_times[i]=lastState->button_times[i];
+	}
+	
+	if(robotDesign&ERS210Mask) {
+		outputs[LFrLegOffset + RotatorOffset   ] = GETD(ERS210Info::CPCJointLFRotator);
+		outputs[LFrLegOffset + ElevatorOffset  ] = GETD(ERS210Info::CPCJointLFElevator);
+		outputs[LFrLegOffset + KneeOffset      ] = GETD(ERS210Info::CPCJointLFKnee);
+		pidduties[LFrLegOffset + RotatorOffset ] = GETDUTY(ERS210Info::CPCJointLFRotator);
+		pidduties[LFrLegOffset + ElevatorOffset] = GETDUTY(ERS210Info::CPCJointLFElevator);
+		pidduties[LFrLegOffset + KneeOffset    ] = GETDUTY(ERS210Info::CPCJointLFKnee);
+	
+		outputs[RFrLegOffset + RotatorOffset   ] = GETD(ERS210Info::CPCJointRFRotator);
+		outputs[RFrLegOffset + ElevatorOffset  ] = GETD(ERS210Info::CPCJointRFElevator);
+		outputs[RFrLegOffset + KneeOffset      ] = GETD(ERS210Info::CPCJointRFKnee);
+		pidduties[RFrLegOffset + RotatorOffset ] = GETDUTY(ERS210Info::CPCJointRFRotator);
+		pidduties[RFrLegOffset + ElevatorOffset] = GETDUTY(ERS210Info::CPCJointRFElevator);
+		pidduties[RFrLegOffset + KneeOffset    ] = GETDUTY(ERS210Info::CPCJointRFKnee);
+
+		outputs[LBkLegOffset + RotatorOffset   ] = GETD(ERS210Info::CPCJointLHRotator);
+		outputs[LBkLegOffset + ElevatorOffset  ] = GETD(ERS210Info::CPCJointLHElevator);
+		outputs[LBkLegOffset + KneeOffset      ] = GETD(ERS210Info::CPCJointLHKnee);
+		pidduties[LBkLegOffset + RotatorOffset ] = GETDUTY(ERS210Info::CPCJointLHRotator);
+		pidduties[LBkLegOffset + ElevatorOffset] = GETDUTY(ERS210Info::CPCJointLHElevator);
+		pidduties[LBkLegOffset + KneeOffset    ] = GETDUTY(ERS210Info::CPCJointLHKnee);
+
+		outputs[RBkLegOffset + RotatorOffset   ] = GETD(ERS210Info::CPCJointRHRotator);
+		outputs[RBkLegOffset + ElevatorOffset  ] = GETD(ERS210Info::CPCJointRHElevator);
+		outputs[RBkLegOffset + KneeOffset      ] = GETD(ERS210Info::CPCJointRHKnee);
+		pidduties[RBkLegOffset + RotatorOffset ] = GETDUTY(ERS210Info::CPCJointRHRotator);
+		pidduties[RBkLegOffset + ElevatorOffset] = GETDUTY(ERS210Info::CPCJointRHElevator);
+		pidduties[RBkLegOffset + KneeOffset    ] = GETDUTY(ERS210Info::CPCJointRHKnee);
+
+		// Get head tilt,pan,roll joint angles
+		outputs[HeadOffset+TiltOffset] = GETD(ERS210Info::CPCJointNeckTilt);
+		outputs[HeadOffset+PanOffset ] = GETD(ERS210Info::CPCJointNeckPan);
+		outputs[HeadOffset+RollOffset] = GETD(ERS210Info::CPCJointNeckRoll);
+		pidduties[HeadOffset+TiltOffset] = GETDUTY(ERS210Info::CPCJointNeckTilt);
+		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);
+		
+		outputs[ERS210Info::MouthOffset] = GETD(ERS210Info::CPCJointMouth);
+		pidduties[ERS210Info::MouthOffset] = GETDUTY(ERS210Info::CPCJointMouth);
+
+		if(lastState!=NULL && lastState!=this) {
+			// Copy over new buttons
+			buttons[ERS210Info::LFrPawOffset]=GETB(ERS210Info::CPCSensorLFPaw);
+			buttons[ERS210Info::RFrPawOffset]=GETB(ERS210Info::CPCSensorRFPaw);
+			buttons[ERS210Info::LBkPawOffset]=GETB(ERS210Info::CPCSensorLHPaw);
+			buttons[ERS210Info::RBkPawOffset]=GETB(ERS210Info::CPCSensorRHPaw);
+			
+			buttons[ERS210Info::ChinButOffset]=GETB(ERS210Info::CPCSensorChinSwitch);
+			buttons[ERS210Info::BackButOffset]=GETB(ERS210Info::CPCSensorBackSwitch);
+			buttons[ERS210Info::HeadFrButOffset]=GETD(ERS210Info::CPCSensorHeadFrontPressure);
+			buttons[ERS210Info::HeadBkButOffset]=GETD(ERS210Info::CPCSensorHeadBackPressure);
+			
+			//! process changes
+			chkEvent(evtBuf,lastState);
+		} else {
+			// Get foot switches
+			chkEvent(evtBuf,ERS210Info::LFrPawOffset,GETB(ERS210Info::CPCSensorLFPaw),buttonNames[ERS210Info::LFrPawOffset]);
+			chkEvent(evtBuf,ERS210Info::RFrPawOffset,GETB(ERS210Info::CPCSensorRFPaw),buttonNames[ERS210Info::RFrPawOffset]);
+			chkEvent(evtBuf,ERS210Info::LBkPawOffset,GETB(ERS210Info::CPCSensorLHPaw),buttonNames[ERS210Info::LBkPawOffset]);
+			chkEvent(evtBuf,ERS210Info::RBkPawOffset,GETB(ERS210Info::CPCSensorRHPaw),buttonNames[ERS210Info::RBkPawOffset]);
+
+			// Get buttons
+			chkEvent(evtBuf,ERS210Info::ChinButOffset,  GETB(ERS210Info::CPCSensorChinSwitch),buttonNames[ERS210Info::ChinButOffset]);
+			chkEvent(evtBuf,ERS210Info::BackButOffset,  GETB(ERS210Info::CPCSensorBackSwitch),buttonNames[ERS210Info::BackButOffset]);
+			chkEvent(evtBuf,ERS210Info::HeadFrButOffset,GETD(ERS210Info::CPCSensorHeadFrontPressure),buttonNames[ERS210Info::HeadFrButOffset]);
+			chkEvent(evtBuf,ERS210Info::HeadBkButOffset,GETD(ERS210Info::CPCSensorHeadBackPressure),buttonNames[ERS210Info::HeadBkButOffset]);
+		}
+
+		// Get IR distance sensor
+		sensors[ERS210Info::IRDistOffset]=GETSENSOR(ERS210Info::CPCSensorPSD) / 1000.0f;
+
+		// Get acceleration sensors
+		sensors[BAccelOffset] = GETD(ERS210Info::CPCSensorAccelFB);
+		sensors[LAccelOffset] = GETD(ERS210Info::CPCSensorAccelLR);
+		sensors[DAccelOffset] = GETD(ERS210Info::CPCSensorAccelUD);
+
+		sensors[ERS210Info::ThermoOffset] = GETD(ERS210Info::CPCSensorThermoSensor);
+	}
+
+	// (ERS-220 only)
+	if(robotDesign&ERS220Mask) {
+		outputs[LFrLegOffset + RotatorOffset   ] = GETD(ERS220Info::CPCJointLFRotator);
+		outputs[LFrLegOffset + ElevatorOffset  ] = GETD(ERS220Info::CPCJointLFElevator);
+		outputs[LFrLegOffset + KneeOffset      ] = GETD(ERS220Info::CPCJointLFKnee);
+		pidduties[LFrLegOffset + RotatorOffset ] = GETDUTY(ERS220Info::CPCJointLFRotator);
+		pidduties[LFrLegOffset + ElevatorOffset] = GETDUTY(ERS220Info::CPCJointLFElevator);
+		pidduties[LFrLegOffset + KneeOffset    ] = GETDUTY(ERS220Info::CPCJointLFKnee);
+	
+		outputs[RFrLegOffset + RotatorOffset   ] = GETD(ERS220Info::CPCJointRFRotator);
+		outputs[RFrLegOffset + ElevatorOffset  ] = GETD(ERS220Info::CPCJointRFElevator);
+		outputs[RFrLegOffset + KneeOffset      ] = GETD(ERS220Info::CPCJointRFKnee);
+		pidduties[RFrLegOffset + RotatorOffset ] = GETDUTY(ERS220Info::CPCJointRFRotator);
+		pidduties[RFrLegOffset + ElevatorOffset] = GETDUTY(ERS220Info::CPCJointRFElevator);
+		pidduties[RFrLegOffset + KneeOffset    ] = GETDUTY(ERS220Info::CPCJointRFKnee);
+	
+		outputs[LBkLegOffset + RotatorOffset   ] = GETD(ERS220Info::CPCJointLHRotator);
+		outputs[LBkLegOffset + ElevatorOffset  ] = GETD(ERS220Info::CPCJointLHElevator);
+		outputs[LBkLegOffset + KneeOffset      ] = GETD(ERS220Info::CPCJointLHKnee);
+		pidduties[LBkLegOffset + RotatorOffset ] = GETDUTY(ERS220Info::CPCJointLHRotator);
+		pidduties[LBkLegOffset + ElevatorOffset] = GETDUTY(ERS220Info::CPCJointLHElevator);
+		pidduties[LBkLegOffset + KneeOffset    ] = GETDUTY(ERS220Info::CPCJointLHKnee);
+
+		outputs[RBkLegOffset + RotatorOffset   ] = GETD(ERS220Info::CPCJointRHRotator);
+		outputs[RBkLegOffset + ElevatorOffset  ] = GETD(ERS220Info::CPCJointRHElevator);
+		outputs[RBkLegOffset + KneeOffset      ] = GETD(ERS220Info::CPCJointRHKnee);
+		pidduties[RBkLegOffset + RotatorOffset ] = GETDUTY(ERS220Info::CPCJointRHRotator);
+		pidduties[RBkLegOffset + ElevatorOffset] = GETDUTY(ERS220Info::CPCJointRHElevator);
+		pidduties[RBkLegOffset + KneeOffset    ] = GETDUTY(ERS220Info::CPCJointRHKnee);
+
+		// Get head tilt,pan,roll joint angles
+		outputs[HeadOffset+TiltOffset] = GETD(ERS220Info::CPCJointNeckTilt);
+		outputs[HeadOffset+PanOffset ] = GETD(ERS220Info::CPCJointNeckPan);
+		outputs[HeadOffset+RollOffset] = GETD(ERS220Info::CPCJointNeckRoll);
+		pidduties[HeadOffset+TiltOffset] = GETDUTY(ERS220Info::CPCJointNeckTilt);
+		pidduties[HeadOffset+PanOffset ] = GETDUTY(ERS220Info::CPCJointNeckPan);
+		pidduties[HeadOffset+RollOffset] = GETDUTY(ERS220Info::CPCJointNeckRoll);
+
+		if(lastState!=NULL && lastState!=this) {
+			// Copy over new buttons
+			buttons[ERS220Info::LFrPawOffset]=GETB(ERS220Info::CPCSensorLFPaw);
+			buttons[ERS220Info::RFrPawOffset]=GETB(ERS220Info::CPCSensorRFPaw);
+			buttons[ERS220Info::LBkPawOffset]=GETB(ERS220Info::CPCSensorLHPaw);
+			buttons[ERS220Info::RBkPawOffset]=GETB(ERS220Info::CPCSensorRHPaw);
+			
+			buttons[ERS220Info::ChinButOffset]=GETB(ERS220Info::CPCSensorChinSwitch);
+			buttons[ERS220Info::BackButOffset]=GETB(ERS220Info::CPCSensorBackSwitch);
+			buttons[ERS220Info::HeadFrButOffset]=GETD(ERS220Info::CPCSensorHeadFrontPressure);
+			buttons[ERS220Info::HeadBkButOffset]=GETD(ERS220Info::CPCSensorHeadBackPressure);
+			buttons[ERS220Info::TailLeftButOffset]=GETB(ERS220Info::CPCSensorTailLeftSwitch);
+			buttons[ERS220Info::TailCenterButOffset]=GETB(ERS220Info::CPCSensorTailCenterSwitch);
+			buttons[ERS220Info::TailRightButOffset]=GETB(ERS220Info::CPCSensorTailRightSwitch);
+			
+			//! process changes
+			chkEvent(evtBuf,lastState);
+		} else {
+			// Get foot switches
+			chkEvent(evtBuf,ERS220Info::LFrPawOffset,GETB(ERS220Info::CPCSensorLFPaw),buttonNames[ERS220Info::LFrPawOffset]);
+			chkEvent(evtBuf,ERS220Info::RFrPawOffset,GETB(ERS220Info::CPCSensorRFPaw),buttonNames[ERS220Info::RFrPawOffset]);
+			chkEvent(evtBuf,ERS220Info::LBkPawOffset,GETB(ERS220Info::CPCSensorLHPaw),buttonNames[ERS220Info::LBkPawOffset]);
+			chkEvent(evtBuf,ERS220Info::RBkPawOffset,GETB(ERS220Info::CPCSensorRHPaw),buttonNames[ERS220Info::RBkPawOffset]);
+
+			// Get buttons
+			chkEvent(evtBuf,ERS220Info::ChinButOffset,  GETB(ERS220Info::CPCSensorChinSwitch),buttonNames[ERS220Info::ChinButOffset]);
+			chkEvent(evtBuf,ERS220Info::BackButOffset,  GETB(ERS220Info::CPCSensorBackSwitch),buttonNames[ERS220Info::BackButOffset]);
+			chkEvent(evtBuf,ERS220Info::HeadFrButOffset,GETD(ERS220Info::CPCSensorHeadFrontPressure),buttonNames[ERS220Info::HeadFrButOffset]);
+			chkEvent(evtBuf,ERS220Info::HeadBkButOffset,GETD(ERS220Info::CPCSensorHeadBackPressure),buttonNames[ERS220Info::HeadBkButOffset]);
+			chkEvent(evtBuf,ERS220Info::TailLeftButOffset, GETB(ERS220Info::CPCSensorTailLeftSwitch),  buttonNames[ERS220Info::TailLeftButOffset]);
+			chkEvent(evtBuf,ERS220Info::TailCenterButOffset, GETB(ERS220Info::CPCSensorTailCenterSwitch),buttonNames[ERS220Info::TailCenterButOffset]);
+			chkEvent(evtBuf,ERS220Info::TailRightButOffset, GETB(ERS220Info::CPCSensorTailRightSwitch), buttonNames[ERS220Info::TailRightButOffset]);
+		}
+
+		// Get IR distance sensor
+		sensors[ERS220Info::IRDistOffset]=GETSENSOR(ERS220Info::CPCSensorPSD) / 1000.0f;
+
+		// Get acceleration sensors
+		sensors[BAccelOffset] = GETD(ERS220Info::CPCSensorAccelFB);
+		sensors[LAccelOffset] = GETD(ERS220Info::CPCSensorAccelLR);
+		sensors[DAccelOffset] = GETD(ERS220Info::CPCSensorAccelUD);
+
+		sensors[ERS220Info::ThermoOffset] = GETD(ERS220Info::CPCSensorThermoSensor);
+	}
+
+	// (ERS-7 only)
+	if(robotDesign&ERS7Mask) {
+		outputs[LFrLegOffset + RotatorOffset   ] = GETD(ERS7Info::CPCJointLFRotator);
+		outputs[LFrLegOffset + ElevatorOffset  ] = GETD(ERS7Info::CPCJointLFElevator);
+		outputs[LFrLegOffset + KneeOffset      ] = GETD(ERS7Info::CPCJointLFKnee);
+		pidduties[LFrLegOffset + RotatorOffset ] = GETDUTY(ERS7Info::CPCJointLFRotator);
+		pidduties[LFrLegOffset + ElevatorOffset] = GETDUTY(ERS7Info::CPCJointLFElevator);
+		pidduties[LFrLegOffset + KneeOffset    ] = GETDUTY(ERS7Info::CPCJointLFKnee);
+	
+		outputs[RFrLegOffset + RotatorOffset   ] = GETD(ERS7Info::CPCJointRFRotator);
+		outputs[RFrLegOffset + ElevatorOffset  ] = GETD(ERS7Info::CPCJointRFElevator);
+		outputs[RFrLegOffset + KneeOffset      ] = GETD(ERS7Info::CPCJointRFKnee);
+		pidduties[RFrLegOffset + RotatorOffset ] = GETDUTY(ERS7Info::CPCJointRFRotator);
+		pidduties[RFrLegOffset + ElevatorOffset] = GETDUTY(ERS7Info::CPCJointRFElevator);
+		pidduties[RFrLegOffset + KneeOffset    ] = GETDUTY(ERS7Info::CPCJointRFKnee);
+	
+		outputs[LBkLegOffset + RotatorOffset   ] = GETD(ERS7Info::CPCJointLHRotator);
+		outputs[LBkLegOffset + ElevatorOffset  ] = GETD(ERS7Info::CPCJointLHElevator);
+		outputs[LBkLegOffset + KneeOffset      ] = GETD(ERS7Info::CPCJointLHKnee);
+		pidduties[LBkLegOffset + RotatorOffset ] = GETDUTY(ERS7Info::CPCJointLHRotator);
+		pidduties[LBkLegOffset + ElevatorOffset] = GETDUTY(ERS7Info::CPCJointLHElevator);
+		pidduties[LBkLegOffset + KneeOffset    ] = GETDUTY(ERS7Info::CPCJointLHKnee);
+
+		outputs[RBkLegOffset + RotatorOffset   ] = GETD(ERS7Info::CPCJointRHRotator);
+		outputs[RBkLegOffset + ElevatorOffset  ] = GETD(ERS7Info::CPCJointRHElevator);
+		outputs[RBkLegOffset + KneeOffset      ] = GETD(ERS7Info::CPCJointRHKnee);
+		pidduties[RBkLegOffset + RotatorOffset ] = GETDUTY(ERS7Info::CPCJointRHRotator);
+		pidduties[RBkLegOffset + ElevatorOffset] = GETDUTY(ERS7Info::CPCJointRHElevator);
+		pidduties[RBkLegOffset + KneeOffset    ] = GETDUTY(ERS7Info::CPCJointRHKnee);
+
+		// Get head tilt,pan,nod joint angles
+		outputs[HeadOffset+TiltOffset] = GETD(ERS7Info::CPCJointNeckTilt);
+		outputs[HeadOffset+PanOffset ] = GETD(ERS7Info::CPCJointNeckPan);
+		outputs[HeadOffset+RollOffset] = GETD(ERS7Info::CPCJointNeckNod);
+		pidduties[HeadOffset+TiltOffset] = GETDUTY(ERS7Info::CPCJointNeckTilt);
+		pidduties[HeadOffset+PanOffset ] = GETDUTY(ERS7Info::CPCJointNeckPan);
+		pidduties[HeadOffset+RollOffset] = GETDUTY(ERS7Info::CPCJointNeckNod);
+
+		outputs[ERS7Info::TailOffset+TiltOffset] = GETD(ERS7Info::CPCJointTailTilt);
+		outputs[ERS7Info::TailOffset+PanOffset]  = GETD(ERS7Info::CPCJointTailPan);
+		pidduties[ERS7Info::TailOffset+TiltOffset] = GETDUTY(ERS7Info::CPCJointTailTilt);
+		pidduties[ERS7Info::TailOffset+PanOffset]  = GETDUTY(ERS7Info::CPCJointTailPan);
+		
+		outputs[ERS7Info::MouthOffset] = GETD(ERS7Info::CPCJointMouth);
+		pidduties[ERS7Info::MouthOffset] = GETDUTY(ERS7Info::CPCJointMouth);
+
+		if(lastState!=NULL && lastState!=this) {
+			// Copy over new buttons
+			buttons[ERS7Info::LFrPawOffset]=GETB(ERS7Info::CPCSwitchLFPaw);
+			buttons[ERS7Info::RFrPawOffset]=GETB(ERS7Info::CPCSwitchRFPaw);
+			buttons[ERS7Info::LBkPawOffset]=GETB(ERS7Info::CPCSwitchLHPaw);
+			buttons[ERS7Info::RBkPawOffset]=GETB(ERS7Info::CPCSwitchRHPaw);
+			
+			// the sensors are scaled to be relatively similar to the pressure values given by the head on the 210
+			buttons[ ERS7Info::ChinButOffset]=GETSENSOR(ERS7Info::CPCSwitchChin);
+			buttons[ ERS7Info::HeadButOffset]=GETSENSOR(ERS7Info::CPCSensorHead)/120;
+			buttons[ ERS7Info::FrontBackButOffset]=GETSENSOR(ERS7Info::CPCSensorBackFront)/150;
+			buttons[ ERS7Info::MiddleBackButOffset]=GETSENSOR(ERS7Info::CPCSensorBackMiddle)/150;
+			buttons[ ERS7Info::RearBackButOffset]=GETSENSOR(ERS7Info::CPCSensorBackRear)/150;
+			buttons[ ERS7Info::WirelessSwOffset]=GETSENSOR(ERS7Info::CPCSwitchWireless);
+			
+			//! process changes
+			chkEvent(evtBuf,lastState);
+		} else {
+			// Get foot switches
+			chkEvent(evtBuf,ERS7Info::LFrPawOffset,GETB(ERS7Info::CPCSwitchLFPaw),buttonNames[ERS7Info::LFrPawOffset]);
+			chkEvent(evtBuf,ERS7Info::RFrPawOffset,GETB(ERS7Info::CPCSwitchRFPaw),buttonNames[ERS7Info::RFrPawOffset]);
+			chkEvent(evtBuf,ERS7Info::LBkPawOffset,GETB(ERS7Info::CPCSwitchLHPaw),buttonNames[ERS7Info::LBkPawOffset]);
+			chkEvent(evtBuf,ERS7Info::RBkPawOffset,GETB(ERS7Info::CPCSwitchRHPaw),buttonNames[ERS7Info::RBkPawOffset]);
+
+			// Get buttons/switches
+			// the sensors are scaled to be relatively similar to the pressure values given by the head on the 210
+			chkEvent(evtBuf, ERS7Info::ChinButOffset,       GETSENSOR(ERS7Info::CPCSwitchChin),      buttonNames[ERS7Info::ChinButOffset]);
+			chkEvent(evtBuf, ERS7Info::HeadButOffset,       GETSENSOR(ERS7Info::CPCSensorHead)/120,      buttonNames[ERS7Info::HeadButOffset]);
+			chkEvent(evtBuf, ERS7Info::FrontBackButOffset,  GETSENSOR(ERS7Info::CPCSensorBackFront)/150, buttonNames[ERS7Info::FrontBackButOffset]);
+			chkEvent(evtBuf, ERS7Info::MiddleBackButOffset, GETSENSOR(ERS7Info::CPCSensorBackMiddle)/150,buttonNames[ERS7Info::MiddleBackButOffset]);
+			chkEvent(evtBuf, ERS7Info::RearBackButOffset,   GETSENSOR(ERS7Info::CPCSensorBackRear)/150,  buttonNames[ERS7Info::RearBackButOffset]);
+			chkEvent(evtBuf, ERS7Info::WirelessSwOffset,GETSENSOR(ERS7Info::CPCSwitchWireless),  buttonNames[ERS7Info::WirelessSwOffset]);
+		}
+
+		// Get IR distance sensor
+		sensors[ERS7Info::NearIRDistOffset] = GETSENSOR(ERS7Info::CPCSensorNearPSD) / 1000.0f;
+		sensors[ERS7Info::FarIRDistOffset] = GETSENSOR(ERS7Info::CPCSensorFarPSD) / 1000.0f;
+		sensors[ERS7Info::ChestIRDistOffset] = GETSENSOR(ERS7Info::CPCSensorChestPSD) / 1000.0f;
+
+		// Get acceleration sensors
+		sensors[BAccelOffset] = GETD(ERS7Info::CPCSensorAccelFB);
+		sensors[LAccelOffset] = GETD(ERS7Info::CPCSensorAccelLR);
+		sensors[DAccelOffset] = GETD(ERS7Info::CPCSensorAccelUD);
+	}
+
+	//unsigned int dif=curtime-(lastState==NULL ? lastSensorUpdateTime : lastState->lastSensorUpdateTime);
+	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];
+
+	//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);
+}
+
+/*! 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);
+
+	//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);
+
+	//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);
+	
+	sensors[PowerRemainOffset] = power.remainingCapacity/100.0;
+	sensors[PowerThermoOffset] = power.temperature/100.0;
+	sensors[PowerCapacityOffset] = power.fullyChargedCapacity;
+	sensors[PowerVoltageOffset] = power.voltage/1000.0;
+	sensors[PowerCurrentOffset] = power.current;
+
+	//only generate status events when a change happens
+	for(unsigned int i=0; i<PowerSourceID::NumPowerSIDs; i++) {
+		if(actmasks[i]) { //now on
+			if(!powerFlags[i]) //was off: activation
+				er->postEvent(EventBase::powerEGID,i,EventBase::activateETID,0,actnames[i],1);
+			else if(actmasks[i]!=powerFlags[i]) //already on - change? : status
+				er->postEvent(EventBase::powerEGID,i,EventBase::statusETID,0,actnames[i],1);
+		} else { // now off
+			if(powerFlags[i]) //was on: deactivation
+				er->postEvent(EventBase::powerEGID,i,EventBase::deactivateETID,0,denames[i],0);
+		}
+		powerFlags[i]=actmasks[i];
+	}
+
+	er->postEvent(EventBase::powerEGID,PowerSourceID::UpdatedSID,EventBase::statusETID,0,"PowerSourceID::UpdatedSID",1);
+}
+
+#else  //PLATFORM_LOCAL
+
+/*! 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)
+ *
+ *  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)
+ */
+void WorldState::read(const PostureEngine& pose, WorldState* lastState, EventRouter* er) {
+	curtime=get_time();
+	std::vector<EventBase> evtBuf;
+	WorldState* ext=pose.getLoadedSensors();
+
+	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)
+		return; //sensors have already been filled in
+	
+	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++)
+			powerFlags[i]=lastState->powerFlags[i];
+
+		//important part -- copy over button_times before calls to chkEvent
+		for(unsigned int i=0; i<NumButtons; i++)
+			button_times[i]=lastState->button_times[i];
+	}
+	
+	if(ext!=NULL) {
+		if(ext==this) {
+			chkEvent(evtBuf,lastState);
+		} else {
+			if(lastState!=NULL && lastState!=this) {
+				for(unsigned int i=0; i<NumButtons; i++)
+					buttons[i]=ext->buttons[i];
+				chkEvent(evtBuf,lastState);
+			} else {
+				for(unsigned int i=0; i<NumButtons; i++)
+					chkEvent(evtBuf,i,ext->buttons[i],buttonNames[i]);
+			}
+			for(unsigned int i=0; i<NumSensors; i++)
+				sensors[i]=ext->sensors[i];
+			for(unsigned int i=0; i<NumPIDJoints; i++)
+				pidduties[i]=ext->pidduties[i];
+		}
+	} else if(lastState!=NULL && lastState!=this) {
+		// no loaded sensors at all -- copy over previous values
+		for(unsigned int i=0; i<NumButtons; i++)
+			buttons[i]=lastState->buttons[i];
+		for(unsigned int i=0; i<NumSensors; i++)
+			sensors[i]=lastState->sensors[i];
+		for(unsigned int i=0; i<NumPIDJoints; i++)
+			pidduties[i]=lastState->pidduties[i];
+	}
+
+	//unsigned int dif=curtime-(lastState==NULL ? lastSensorUpdateTime : lastState->lastSensorUpdateTime);
+	lastSensorUpdateTime=curtime;
+	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);
+}
+
+#endif //platform-specific sensor updating
+
+void WorldState::chkEvent(std::vector<EventBase>& evtBuf, unsigned int sid, float newval, const char* name) {
+	if(newval>=0.1) { //now on
+		if(buttons[sid]<0.1) { //was off: activation
+			cout << ProcessID::getIDStr() << " post activate" << endl;
+			evtBuf.push_back(EventBase(EventBase::buttonEGID,sid,EventBase::activateETID,0,name,newval));
+			button_times[sid]=curtime;
+		} else if(alwaysGenerateStatus || buttons[sid]!=newval) { //already on - always or change? : status
+			unsigned int dur=curtime-button_times[sid];
+			cout << ProcessID::getIDStr() << " post status" << endl;
+			evtBuf.push_back(EventBase(EventBase::buttonEGID,sid,EventBase::statusETID,dur,name,newval));
+		}
+	} else { //now off
+		if(buttons[sid]>=0.1) { //was on: deactivation
+			unsigned int dur=curtime-button_times[sid];
+			button_times[sid]=0;
+			cout << ProcessID::getIDStr() << " post deactivate" << endl;
+			evtBuf.push_back(EventBase(EventBase::buttonEGID,sid,EventBase::deactivateETID,dur,name,0));
+		}
+	}
+	//update value
+	buttons[sid]=newval;
+}
+
+void WorldState::chkEvent(std::vector<EventBase>& evtBuf, WorldState* lastState) {
+	// posture already loaded data into this instance of WorldState
+	// variation on chkEvent -- instead, we already hold the latest data, need to compare against lastState
+	for(unsigned int sid=0; sid<NumButtons; sid++) {
+		if(buttons[sid]>=0.1) { //now on
+			if(lastState->buttons[sid]<0.1) { //was off: activation
+				evtBuf.push_back(EventBase(EventBase::buttonEGID,sid,EventBase::activateETID,0,buttonNames[sid],buttons[sid]));
+				button_times[sid]=curtime;
+			} else if(alwaysGenerateStatus || lastState->buttons[sid]!=buttons[sid]) { //already on - always or change? : status
+				unsigned int dur=curtime-button_times[sid];
+				evtBuf.push_back(EventBase(EventBase::buttonEGID,sid,EventBase::statusETID,dur,buttonNames[sid],buttons[sid]));
+			}
+		} else { //now off
+			if(lastState->buttons[sid]>=0.1) { //was on: deactivation
+				unsigned int dur=curtime-button_times[sid];
+				button_times[sid]=0;
+				evtBuf.push_back(EventBase(EventBase::buttonEGID,sid,EventBase::deactivateETID,dur,buttonNames[sid],0));
+			}
+		}
+	}
+}
+
+/*! @file
+ * @brief Implements WorldState, maintains information about the robot's environment, namely sensors and power status
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/WorldState.h ./Shared/WorldState.h
--- ../Tekkotsu_2.4.1/Shared/WorldState.h	2004-07-27 10:36:50.000000000 -0400
+++ ./Shared/WorldState.h	2006-10-03 18:00:08.000000000 -0400
@@ -3,16 +3,18 @@
 #define INCLUDED_WorldState_h
 
 #ifdef PLATFORM_APERIOS
+#include "IPC/ProcessID.h"
 #include <OPENR/core_macro.h>
 #include <OPENR/ObjcommTypes.h>
 #include <OPENR/OPENR.h>
 #include <OPENR/OPENRAPI.h>
 #include <OPENR/OPENRMessages.h>
+#else
+class PostureEngine;
 #endif
 
 #include "Shared/RobotInfo.h"
 #include "Events/EventBase.h"
-#include "Shared/Profiler.h"
 #include <math.h>
 #include <vector>
 
@@ -93,11 +95,23 @@
 		NumPowerSIDs
 	};
 }
+
+class WorldState;
+extern WorldState * state; //!< the global state object, is a shared memory region, created by MainObject
 	
 //! The state of the robot and its environment
-/*! Contains sensor readings, current joint positions, etc.\n
- * This is a shared memory region between MainObj, MotoObj, and possibly others in the future
+/*! Contains sensor readings, current joint positions, etc.  Notable members are:
+ * - #outputs - joint positions and current LED values
+ * - #buttons - current button values
+ * - #sensors - values from other sensors (IR, acceleration, temperature, power levels)
+ * - #pids - current PID settings for each joint (more specifically, each PID-controlled joint)
+ * - #pidduties - how hard each of the PID joints is working to get to its target value
  *
+ * Generally you will use enumerated values from a robot-specific namespace to
+ * index into these arrays.  Each of those members' documentation specifies where
+ * to find the list of indices to use with them.
+ *
+ * This is a shared memory region between Main, Motion, and possibly others in the future.
  * Be very careful about including structures that use pointers in
  * this class... they will only be valid from the OObject that created
  * them, others may cause a crash if they try to access them.
@@ -107,11 +121,11 @@
  * events when some of these values change, listed in the
  * SensorSourceID, PowerSourceID namespaces, and the ButtonOffset_t
  * enumeration for your robot model's info
- * namespace. (e.g. ERS210Info::ButtonOffset_t)
+ * namespace. (e.g. ERS7Info::ButtonOffset_t)
  *
  * Status events for buttons only generated if the
- * WorldState::alwaysGenerateStatus flag is turned on, otherwise, by
- * default, they are only generated when a value has changed
+ * WorldState::alwaysGenerateStatus flag is turned on.  Otherwise, by
+ * default, they are only generated when a value has changed.
  * (i.e. when the pressure sensitive buttons get a new pressure
  * reading)
  */
@@ -122,11 +136,11 @@
 
 	bool alwaysGenerateStatus; //!< controls whether status events are generated for the boolean buttons
 
-	float outputs[NumOutputs];     //!< last sensed positions of joints, for ears (or other future "boolean joints"), x<.5 is up, x>=.5 is down; indexes (aka offsets) are defined in the target model's namespace (e.g. ERS210Info)
-	float buttons[NumButtons];     //!< magnitude is pressure for some, 0/1 for others; indexes are defined in the ButtonOffset_t of the target model's namespace (e.g. ERS210Info::ButtonOffset_t)
-	float sensors[NumSensors];     //!< IR, Accel, Thermo, Power stuff; indexes are defined in SensorOffset_t of the target model's namespace (e.g. ERS210Info::SensorOffset_t)
-	float pids[NumPIDJoints][3];   //!< current PID settings (same ordering as the #outputs)
-	float pidduties[NumPIDJoints]; //!< duty cycles - -1 means the motor is trying to move full power in negative direction, 1 means full power in positive direction, in practice, these values stay rather small - 0.15 is significant force. (same ordering as the #outputs)
+	float outputs[NumOutputs];     //!< last sensed positions of joints, last commanded value of LEDs; indexes (aka offsets) are defined in the target model's namespace (e.g. "Output Offsets" section of ERS7Info)
+	float buttons[NumButtons];     //!< magnitude is pressure for some, 0/1 for others; indexes are defined in the ButtonOffset_t of the target model's namespace (e.g. ERS7Info::ButtonOffset_t)
+	float sensors[NumSensors];     //!< IR, Accel, Thermo, Power stuff; indexes are defined in SensorOffset_t of the target model's namespace (e.g. ERS7Info::SensorOffset_t)
+	float pids[NumPIDJoints][3];   //!< current PID settings (same ordering as the #outputs), not sensed -- updated by MotionManager whenever it sends a PID setting to the system; note this is only valid for PID joints, has NumPIDJoint entries (as opposed to NumOutputs)
+	float pidduties[NumPIDJoints]; //!< duty cycles - -1 means the motor is trying to move full power in negative direction, 1 means full power in positive direction, in practice, these values stay rather small - 0.15 is significant force. (same ordering as the #outputs); note this is only valid for PID joints, has NumPIDJoint entries (as opposed to NumOutputs)
 	
 	float vel_x; //!< the current, egocentric rate of forward locomotion, mm/second
 	float vel_y; //!< the current, egocentric rate of sideways (leftward is positive) locomotion, mm/second
@@ -139,17 +153,34 @@
 
 	unsigned int button_times[NumButtons]; //!< value is time of current press, 0 if not down
 	
-	unsigned int lastSensorUpdateTime;     //!<primarily so calcDers can determine the time difference between updates, but others might want to know this too...
+	unsigned int lastSensorUpdateTime;     //!< primarily so calcDers can determine the time difference between updates, but others might want to know this too...
+	unsigned int frameNumber;              //!< the serial number of the currently available frame
+	unsigned int framesProcessed;          //!< the number of sensor updates which have been processed
 
 	static const double g;                 //!< the gravitational acceleration of objects on earth
 	static const double IROORDist;         //!< If IR returns this, we're out of range
 
-	ProfilerOfSize<20> mainProfile;        //!< holds code profiling information for MainObject
-	ProfilerOfSize<06> motionProfile;      //!< holds code profiling information for MotionObject
-
 #ifdef PLATFORM_APERIOS
-	void read(OSensorFrameVectorData& sensor, EventRouter* er); //!< will process a sensor reading as given by OPEN-R
+	void read(OSensorFrameVectorData& sensor, WorldState* lastState, EventRouter* er); //!< will process a sensor reading as given by OPEN-R
 	void read(const OPowerStatus& power, EventRouter* er);      //!< will process a power status update as given by OPEN-R
+	
+	//! returns the current WorldState instance for the running process, needed if your code may be in a shared memory region; otherwise you can directly access ::state
+	/*! Generally you can access ::state directly, but if your code is running as a member of an object in a shared memory region,
+	 *  this handles the shared object context switching problem on Aperios, and simply returns ::state on non-Aperios. */
+	static WorldState* getCurrent() { return stateLookupMap==NULL ? NULL : stateLookupMap[ProcessID::getID()]; }
+	
+	// sets the current WorldState instance for the running process (handles the shared object context switching problem on Aperios, simply returns ::state on non-Aperios)
+	// static void setCurrent(WorldState* st) { stateLookupMap[ProcessID::getID()]=st; }
+	
+	//! sets the lookup table (held in a shared region, WorldStatePool::stateMap) used by getCurrent under Aperios
+	static void setWorldStateLookup(WorldState * curMap[ProcessID::NumProcesses]) { stateLookupMap=curMap; }
+#else
+	void read(const PostureEngine& pose, WorldState* lastState, EventRouter* er); //!< will process the posture's output positions as a new sensor reading
+	
+	//! returns the current WorldState instance for the running process, needed if your code may be in a shared memory region; otherwise you can directly access ::state
+	/*! Generally you can access ::state directly, but if your code is running as a member of an object in a shared memory region,
+	 *  this handles the shared object context switching problem on Aperios, and simply returns ::state on non-Aperios. */
+	static WorldState* getCurrent() { return ::state; }
 #endif
 
 	//! bitmask corresponding to OPENR::GetRobotDesign()
@@ -165,13 +196,16 @@
 	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
 
 	//! Tests to see if the button status has changed and post events as needed
-	void chkEvent(std::vector<EventBase*>& evtBuf, unsigned int off, float newval, const char* name);
+	void chkEvent(std::vector<EventBase>& evtBuf, unsigned int off, float newval, const char* name);
+	//! 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);
 
 	//! sets the names of the flags that will be generating events
 	/*! note that this function does not actually do the event posting,
@@ -201,14 +235,16 @@
 		vel=next;
 		acc=diff*invtimediff;
 	}
-
+	
+#ifdef PLATFORM_APERIOS
+	static WorldState ** stateLookupMap; //!< array used by getCurrent()/setCurrent() to store the state in use by each process -- should be initialized by setWorldStateLookup() to point into a shared memory region
+#endif
+	
 private:
-	WorldState(const WorldState&); //!< don't use
-	WorldState operator=(const WorldState&); //!< don't use
+	WorldState(const WorldState&); //!< this shouldn't be called...
+	WorldState& operator=(const WorldState&); //!< this shouldn't be called...
 };
 
-extern WorldState * state; //!< the global state object, is a shared memory region, created by MainObject
-
 /*! @file
  * @brief Describes WorldState, maintains information about the robot's environment, namely sensors and power status
  * @author ejt (Creator)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/WorldStatePool.cc ./Shared/WorldStatePool.cc
--- ../Tekkotsu_2.4.1/Shared/WorldStatePool.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/WorldStatePool.cc	2006-09-28 16:42:51.000000000 -0400
@@ -0,0 +1,437 @@
+#include "WorldStatePool.h"
+#include "Shared/MarkScope.h"
+#include "Shared/debuget.h"
+#include "IPC/RCRegion.h"
+#ifndef PLATFORM_APERIOS
+#  include "Events/EventRouter.h"
+#  include "local/LoadFileThread.h"
+#endif
+
+//better to put this here instead of the header
+using namespace std; 
+
+WorldStatePool::WorldStatePool() : order(), lock() {
+	//initialize order with 1,2,3...NUM_STATES
+	while(order.size()<order.getMaxCapacity()) {
+		unsigned int i=order.size();
+		reading[i]=writing[i]=frames[i]=0;
+		status[i]=0;
+#ifdef PLATFORM_APERIOS
+		stateLookupMap[i]=NULL;
+#else
+		complete[i]=MutexLockBase::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);
+#endif
+}
+
+void WorldStatePool::doUseResource(Data& d) {
+	Request& r=static_cast<Request&>(d);
+	if(r.isRead) {
+		ReadRequest& rd = static_cast<ReadRequest&>(d);
+		if(rd.depth++==0) {
+			rd.prev=rd.tgt;
+			rd.bufUsed=getCurrentReadState(rd.tgt,rd.bl);
+			//cout << ProcessID::getIDStr() << " reading " << rd.bufUsed << " (" << state << ")" << endl;
+		}
+	} else {
+		WriteRequest& write = static_cast<WriteRequest&>(d);
+		if(write.depth++==0) {
+			useResource(write.srcRequest);
+			write.prev=write.tgt;
+			write.bufUsed=getCurrentWriteState(write.tgt,write.frame,write.bl);
+			if(write.bufUsed!=-1U) {
+				write.setStatus(status[write.bufUsed]);
+				write.setComplete(isComplete(write.bufUsed));
+				//cout << ProcessID::getIDStr() << " writing " << write.bufUsed << " (" << state << ")" << endl;
+			}
+		}
+	}
+#ifdef PLATFORM_APERIOS
+	stateLookupMap[ProcessID::getID()]=state;
+#endif
+}
+void WorldStatePool::doReleaseResource(Data& d) {
+	Request& r=static_cast<Request&>(d);
+	if(r.isRead) {
+		ReadRequest& rd = static_cast<ReadRequest&>(d);
+		if(rd.depth==0)
+			throw std::underflow_error("WorldStatePool read resource usage underflow");
+		if(--rd.depth==0) {
+			if(rd.bufUsed!=-1U) {
+				doneReadingState(rd.bufUsed);
+				rd.bufUsed=-1U;
+			}
+			rd.tgt=rd.prev;
+		}
+	} else {
+		WriteRequest& write = static_cast<WriteRequest&>(d);
+		if(write.depth==0)
+			throw std::underflow_error("WorldStatePool write resource usage underflow");
+		if(--write.depth==0) {
+			if(write.bufUsed!=-1U) {
+				status[write.bufUsed]=write.getStatus();
+				doneWritingState(write.bufUsed,write.getComplete());
+				write.bufUsed=-1U;
+			}
+			write.tgt=write.prev;
+			releaseResource(write.srcRequest);
+		}
+	}
+#ifdef PLATFORM_APERIOS
+	stateLookupMap[ProcessID::getID()]=state;
+#endif
+}
+
+#ifdef PLATFORM_APERIOS
+
+WorldStatePool::UpdateInfo* WorldStatePool::isUnread(OSensorFrameVectorData& msg, unsigned int& lastFrameNumber) {
+	//cout << ProcessID::getIDStr() << " checking tgtFr=" << msg.GetInfo(0)->frameNumber << " lastFr=" << lastFrameNumber << endl;
+	
+	static UpdateInfo info; // avoiding heap allocation by using static here, but this means not threadsafe (shouldn't be a problem...)
+	info.msg=&msg;
+	info.frameNumber=msg.GetInfo(0)->frameNumber;
+	unsigned int toUse=selectWriteState(info.frameNumber,true);
+#ifdef DEBUG
+	info.intendedBuf=toUse;
+#endif
+	if(toUse==-1U)
+		return NULL; //error occurred, should already be reported
+	//cout << ProcessID::getIDStr() << " 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!=NumFrames)
+			cout << ProcessID::getIDStr() << " dropped " << (info.frameNumber-lastFrameNumber-NumFrames)/NumFrames << " sensor frame(s)" << endl;
+		lastFrameNumber=info.frameNumber;
+		//cout << ProcessID::getIDStr() << " decided frame is complete or nothing to contribute" << endl;
+		return NULL;
+	}
+	return &info;
+}
+
+#else //PLATFORM_LOCAL
+
+WorldStatePool::UpdateInfo* WorldStatePool::isUnread(const RCRegion& msg, unsigned int curFrameNumber, unsigned int& lastFrameNumber, bool /*haveFeedback*/, bool /*motionOverride*/) {
+	//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);
+	if(info.payload==NULL)
+		throw std::runtime_error("deserialization of sensor update header failed");
+	if(info.frameNumber<curFrameNumber) {
+		// this means there's a newer one already in the queue -- skip this (and we'll report the drop next time -- no assignment to lastFrameNumber)
+		return NULL;
+	}
+	if(info.payloadSize==0)
+		info.payload=NULL;
+	
+	unsigned int toUse=selectWriteState(info.frameNumber,true);
+#ifdef DEBUG
+	info.intendedBuf=toUse;
+#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;
+	}
+	//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)
+			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;
+		return NULL;
+	}
+	return &info;
+}
+
+bool WorldStatePool::read(const WorldStatePool::UpdateInfo& info, WriteRequest& wsw, bool feedbackGenerated, bool zeroPIDFeedback, const PostureEngine* feedback/*=NULL*/) {
+	//cout << ProcessID::getIDStr() << " writing " << wsw.frame << " state=" << state << "(" << wsw.bufUsed << ") source=" << wsw.src << "("<<wsw.srcRequest.bufUsed<<") status="<<wsw.getStatus() << " complete="<<wsw.getComplete() << endl;
+	
+	ASSERT(feedbackGenerated || feedback==NULL, "feedbackGenerated is false, yet feedback was supplied?");
+	if(wsw.getComplete()) {
+		// this could happen if both processes were trying to get the write lock at the same time
+		// and the first in filled everything by itself (i.e. no feedback required, or the one with feedback was there first)
+		return true;
+	}	
+	ASSERT((wsw.getStatus()&FEEDBACK_APPLIED)==0, "feedback applied, but apparently not completed "<<wsw.getComplete());
+	//ASSERT(wsw.bufUsed==info.intendedBuf,"read() not using expected state buffer"); //not a problem (I think? just fell an even number of frames behind the other process?)
+	
+	if((wsw.getStatus()&SENSORS_APPLIED) != 0) {
+		// sensors already applied, just need to do feedback, if any
+		if(feedback!=NULL) {
+			// have feedback, copy it in
+			if(zeroPIDFeedback) {
+				// copy all values, regardless of PID values
+				for(unsigned int i=0; i<NumOutputs; i++)
+					state->outputs[i]=feedback->getOutputCmd(i).value;
+			} else {
+				// only copy non-zero PID values
+				for(unsigned int i=0; i<NumOutputs; i++)
+					if(!isZeroPID(wsw.src,i))
+						state->outputs[i]=feedback->getOutputCmd(i).value;
+			}
+			wsw.setStatus(wsw.getStatus() | FEEDBACK_APPLIED);
+		}
+	
+	} else {
+		// need to do sensors (if present), as well as feedback (if any)
+		static PostureEngine pose; //this is already thread-unsafe, might as well use another static tmp here to avoid initialization cost
+		if(info.payload==NULL) {
+			
+			// no new sensors, but still have to copy over old values (downside of having multiple state buffers)
+			pose.setLoadedSensors(wsw.src);
+			if(!feedbackGenerated) {
+				// no feedback either, take all of the old positions
+				pose.takeSnapshot(*wsw.src);
+				pose.setWeights(1);
+			} else if(zeroPIDFeedback) {
+				// feedback is applied, regardless of PID settings
+				if(feedback!=NULL) {
+					for(unsigned int i=0; i<NumPIDJoints; ++i)
+						pose(i+PIDJointOffset)=feedback->getOutputCmd(i).value;
+					wsw.setStatus(wsw.getStatus() | FEEDBACK_APPLIED);
+				} //else wait for process with feedback to fill it in
+			} else {
+				// feedback is only applied to non-zero PIDs, the rest need to take the previous value
+				if(feedback!=NULL) {
+					// this process does have the feedback, fill in everything 
+					for(unsigned int i=0; i<NumPIDJoints; ++i)
+						if(isZeroPID(wsw.src,i))
+							pose(i+PIDJointOffset)=wsw.src->outputs[i+PIDJointOffset];
+						else
+							pose(i+PIDJointOffset)=feedback->getOutputCmd(i).value;
+					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)=wsw.src->outputs[i+PIDJointOffset];
+				}
+			}
+			
+		} else {
+			
+			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)) {
+				cerr << "ERROR: Corrupted sensor readings received by Main" << endl;
+				return false;
+			}
+			state->frameNumber=stateFrame; // restore the frame number over what was loaded from the file so state->read doesn't unnecessarily skip it below
+			
+			if(stateFrame>wsw.src->frameNumber)
+				return false; // I'm not sure how this occurs, but sometimes (if doing a lot of paging/kernel stuff that screws up the scheduler) the source is newer than our update
+			ASSERT(stateFrame<wsw.src->frameNumber || stateFrame==1 && wsw.src->frameNumber==1,"already updated (" << stateFrame << " vs " << wsw.src->frameNumber << ")?  So why did " << ProcessID::getIDStr() << " parse...");
+			
+			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
+			} else if(zeroPIDFeedback) {
+				// feedback is applied, regardless of PID settings
+				if(feedback!=NULL) {
+					for(unsigned int i=0; i<NumPIDJoints; ++i)
+						pose(i+PIDJointOffset)=feedback->getOutputCmd(i).value;
+					wsw.setStatus(wsw.getStatus() | FEEDBACK_APPLIED);
+				} //else wait for process with feedback to fill it in
+			} else {
+				// feedback is only applied to non-zero PIDs, the rest need to take the previous value
+				if(feedback!=NULL) {
+					// this process does have the feedback, fill in everything 
+					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");
+					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");
+				}
+			}
+		}
+		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
+		wsw.setStatus(wsw.getStatus() | SENSORS_APPLIED);
+	}
+	wsw.setComplete(feedbackGenerated && wsw.getStatus()==(SENSORS_APPLIED|FEEDBACK_APPLIED) || !feedbackGenerated && (wsw.getStatus()&SENSORS_APPLIED)!=0);
+	//cout << ProcessID::getIDStr() << " fr=" << info.frameNumber << " pyld=" << info.payloadSize << " fdbkG=" << feedbackGenerated << " pidfdbk=" << zeroPIDFeedback << " fdbk=" << feedback << " set status="<<wsw.getStatus() << " complete=" << wsw.getComplete() << endl;
+	return true;
+}
+
+#endif
+
+
+unsigned int WorldStatePool::getCurrentReadState(WorldState*& tgt, bool block) {
+	unsigned int toUse=-1U;
+	if(block) {
+		while(toUse!=order.end()) {
+			{
+				MarkScope l(lock);
+				if(toUse!=-1U) { //newer frame added while we were waiting
+					//std::cerr << ProcessID::getID() << " WARNING WorldStatePool: whoa new frame while blocking read " << toUse << " vs " << order.back() << endl;
+					reading[toUse]--;
+				}
+				toUse=order.back();
+				reading[toUse]++;
+			} //release WorldStatePool lock to allow new readers to come through
+#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)
+#endif
+		}
+	} else {
+		MarkScope l(lock);
+		order_t::index_t idx;
+		for(idx=order.prev(order.end()); idx!=order.end(); idx=order.prev(idx)) {
+			toUse=order[idx];
+			if(isComplete(toUse))
+				break;
+		}
+		if(idx==order.end()) {
+			std::cerr << "ERROR: WorldStatePool unable to read state because none available" << std::endl;
+			return -1U;
+		}
+		reading[toUse]++;
+	}
+	//std::cout << ProcessID::getID() << " reading " << toUse << endl;
+	//ASSERTRETVAL(toUse!=-1U,"toUse was not chosen!",-1U);
+	tgt=&states[toUse];
+	return toUse;
+}
+void WorldStatePool::doneReadingState(unsigned int i) {
+	MarkScope l(lock);
+	reading[i]--;
+	//std::cout << ProcessID::getID() << " reading " << i << " - done" << endl;
+}
+
+bool WorldStatePool::isComplete(unsigned int idx) const {
+#ifdef PLATFORM_APERIOS
+	return static_cast<unsigned int>(complete[idx].owner())==MutexLockBase::NO_OWNER;
+#else
+	return MutexLockBase::getSemaphoreManager()->testZero(complete[idx],false);
+#endif
+}
+
+unsigned int WorldStatePool::selectWriteState(unsigned int frame, bool block, order_t::index_t& idx) const {
+	//check the end to verify a newer (or equivalent) update isn't already in progress
+	idx=order.prev(order.end());
+	unsigned int toUse=order[idx];
+	if(frames[toUse]>frame) {
+		// can happen if one thread (say MotionExec running a motion update) takes too long, another thread (say motion gotSensors updater) blocks on it, is delayed too long
+		// we'll leave it up to the client to detect and display an appropriate message if dropping updates is a problem.
+		//std::cerr << "WARNING: WorldStatePool found a newer write already in progress (writing " << frame << ", found " << frames[toUse] << ")" << std::endl;
+		return -1U;
+	}
+	if(frames[toUse]!=frame || !block) {
+		//start at the beginning and run forward to get the oldest unreferenced entry
+		order_t::index_t fallback=order.end();
+		for(idx=order.begin(); idx!=order.end(); idx=order.next(idx)) {
+			toUse=order[idx];
+			if(frames[toUse]>=frame) {
+				idx=order.end();
+				break;
+			}
+			if(writing[toUse]==0) { //note: could be incomplete -- if this is the oldest frame and it's not currently being written to, but yet wasn't completed, we'll recycle it
+				if(reading[toUse]==0)
+					break; //found our entry!
+			} else if(fallback==order.end())
+				fallback=idx; //in case we don't find an unreferenced one later in the list
+		}
+		if(idx==order.end()) {
+			if(block && fallback!=order.end())
+				toUse=order[idx=fallback];
+			else {
+				std::cerr << "ERROR: WorldStatePool unable to update state because none available" << std::endl;
+				return -1U;
+			}
+		}
+	}
+	return toUse;
+}
+
+unsigned int WorldStatePool::getCurrentWriteState(WorldState*& tgt, unsigned int frame, bool block) {
+	unsigned int toUse;
+	{ //artificial scope to limit lock on next line
+		MarkScope l(lock);
+		order_t::index_t idx;
+		toUse=selectWriteState(frame,block,idx);
+		if(toUse==-1U)
+			return -1U;
+		//std::cout << ProcessID::getID() << " writing " << toUse << " (frame " << frame << ")" << endl;
+		//ASSERTRETVAL(toUse!=-1U,"toUse was not chosen!",-1U);
+		writing[toUse]++;
+		if(frames[toUse]!=frame) {
+			//move this entry to the back of the list, keep frames sorted (in order of write initiation / frame number)
+			order.erase(idx);
+			order.push_back(toUse);
+			frames[toUse]=frame;
+			status[toUse]=0;
+#ifdef PLATFORM_APERIOS
+			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);
+#endif
+		}
+	}
+	if(block) {
+		writeLocks[toUse].lock(ProcessID::getID());
+	} else if(!writeLocks[toUse].try_lock(ProcessID::getID())) {
+		std::cerr << "WARNING: WorldStatePool unable to acquire write lock (blocking reader?).  Trying again..." << std::endl;
+		writeLocks[toUse].lock(ProcessID::getID());
+	}
+	if(toUse!=order.back()) { //newer frame added while we were waiting
+		// This is a very rare case
+		//std::cerr << ProcessID::getID() << " WARNING WorldStatePool: whoa new frame while blocking write " << toUse << " vs " << order.back() << endl;
+		// go back to square one
+		doneWritingState(toUse,false);
+		return getCurrentWriteState(tgt,frame,block);
+	}
+	tgt=&states[toUse];
+	return toUse;
+}
+void WorldStatePool::doneWritingState(unsigned int i, bool completed) {
+	MarkScope l(lock);
+	//std::cout << ProcessID::getID() << " writing " << i << " - done" << endl;
+	writing[i]--;
+	if(completed) {
+#ifdef PLATFORM_APERIOS
+		if(!isComplete(i))
+			complete[i].unlock();
+#else
+		MutexLockBase::getSemaphoreManager()->setValue(complete[i],0);
+#endif
+	}
+	writeLocks[i].unlock();
+}
+
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/WorldStatePool.h ./Shared/WorldStatePool.h
--- ../Tekkotsu_2.4.1/Shared/WorldStatePool.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/WorldStatePool.h	2006-09-19 01:39:33.000000000 -0400
@@ -0,0 +1,282 @@
+//-*-c++-*-
+#ifndef INCLUDED_WorldStatePool_h_
+#define INCLUDED_WorldStatePool_h_
+
+#include "WorldState.h"
+#include "IPC/MutexLock.h"
+#include "IPC/ListMemBuf.h"
+#include "Shared/Resource.h"
+#include "Motion/PostureEngine.h"
+#include <stdexcept>
+
+class RCRegion;
+
+#ifndef WORLDSTATEPOOL_NUM_STATES
+//! provides default value for WorldStatePool::NUM_STATES, allows you to override from build settings, without touching source
+#define WORLDSTATEPOOL_NUM_STATES 3
+#endif
+
+//! holds multiple instances of WorldState, allows one process to be updating while another is reading
+/*! 
+Use the AutoGetReadState and AutoGetWriteState to access individual WorldState entries... their
+constructors and destructors allow WorldStatePool to keep track of which entries are in use.
+
+When a state wants to write, it is given the oldest unused entry to write into.  During writing,
+other accessors can read the newest (complete) entry, or concurrently write into a different
+entry (in case they don't want to wait for the other process to finish).
+
+A global lock (#lock) is used while choosing an entry, and individual locks (#writeLocks) are
+used while writing into entries (to easily allow readers to block on the lock until writing is done)
+
+One point of trickiness is that entries being written are moved to the end of the list when
+the writing begins, not when it is complete.  Readers can always scan backwards in the list
+to find the newest entries, but writers must check the end to see if newer (or equivalent)
+frames are already in progress, as well as the beginning to find the oldest unreferenced.
+
+When a writer tries to access an entry, and another writer is already processing that frame,
+if blocking is set then the writer will given that entry once the original is done with it (so
+check your frame index when you receive it so you can tell if it was already processed).
+If blocking is *not* set, then you will get a separate entry with no indication another process
+is also working on the same frame.
+*/
+class WorldStatePool : public Resource {
+public:
+	class Request : public Resource::Data {
+	protected:
+		//! constructor, sets the WorldState point to be assigned, whether to block, and whether is an instance of ReadRequest
+		/*! @a wantRead is because we can't trust RTTI (i.e. dynamic_cast) to work correctly on Aperios :( */
+		Request(WorldState*& target, bool block, bool wantRead) : Resource::Data(),
+			bufUsed(-1U), tgt(target), prev(NULL), bl(block), depth(0), isRead(wantRead)
+		{}
+		//! shallow copy constructor supported
+		Request(const Request& r) : Resource::Data(r), bufUsed(r.bufUsed), tgt(r.tgt), prev(r.prev), bl(r.bl), depth(r.depth), isRead(r.isRead) {}
+		//! shallow assignment supported
+		Request& operator=(const Request& r) { bufUsed=r.bufUsed; tgt=r.tgt; prev=r.prev; bl=r.bl; depth=r.depth; Resource::Data::operator=(r); return *this; }
+		
+	public:
+		unsigned int bufUsed; //!< the entry index used
+		WorldState*& tgt; //!< reference to pointer, which is set to an element of the pool when the request goes through
+		WorldState* prev; //!< stores previous value at #tgt so it can be restored upon release (needed to support recursive usage)
+		bool bl; //!< whether to block if a write is in progress, or use most recent "complete" entry
+		unsigned int depth; //!< supports recursive read requests
+		bool isRead; //!< true if instance is a read request
+	};
+	//! retrieves the current WorldState entry, and through it's destructor, marks the entry available again when it goes out of scope
+	class ReadRequest : public Request {
+	public:
+		//! stores the current completed WorldState into #tgt, optionally blocking if an update is in progress (otherwise it returns the previous completed entry)
+		ReadRequest(WorldState*& target, bool block) : Request(target,block,true) {}
+		//! shallow copy constructor supported
+		ReadRequest(const ReadRequest& r) : Request(r) {}
+		//! shallow assignment supported
+		ReadRequest& operator=(const ReadRequest& r) { Request::operator=(r); return *this; }
+	};
+	//! retrieves the current WorldState entry, and through it's destructor, marks the entry available again when it goes out of scope
+	/*! By default, when the release occurs, the entry is marked "complete" unless you have called setComplete(false) before then */
+	class WriteRequest : public Request {
+	public:
+		//! stores the oldest unreferenced WorldState into #tgt, optionally blocking if an update is currently in progress for the same frame
+		WriteRequest(WorldState*& target, bool block, unsigned int frame_number) : Request(target,block,false),
+			src(NULL), srcRequest(src,false), frame(frame_number), statusCache(0), completeCache(false)
+		{}
+		//! shallow copy constructor supported
+		WriteRequest(const WriteRequest& r) : Request(r), src(r.src), srcRequest(r.srcRequest), frame(r.frame), statusCache(r.statusCache), completeCache(r.completeCache) {}
+		//! shallow assignment supported
+		WriteRequest& operator=(const WriteRequest& r) { src=r.src; srcRequest=r.srcRequest; frame=r.frame; statusCache=r.statusCache; completeCache=r.completeCache; Request::operator=(r); return *this; }
+		
+		WorldState* src; //!< will be set to the previously written element, so you can copy over unmodified values
+		ReadRequest srcRequest; //!< used to get #src
+		unsigned int frame; //!< should be initialized to the frame number about to be written
+		
+		unsigned int getStatus() const { return statusCache; } //!< returns the WorldStatePool::status value for the target WorldState entry (see documentation for WorldStatePool::status)
+		void setStatus(unsigned int status) { statusCache=status; } //!< sets the WorldStatePool::status value for the target WorldState entry (see documentation for WorldStatePool::status)
+		bool getComplete() const { return completeCache; } //!< returns the WorldStatePool::complete value for the target WorldState entry (see documentation for WorldStatePool::complete)
+		void setComplete(bool complete) { completeCache=complete; } //!< returns the WorldStatePool::complete value for the target WorldState entry (see documentation for WorldStatePool::complete)
+		
+	protected:
+		unsigned int statusCache; //!< when using resource, this field is set to the status field for that entry, and when released, this value is stored back
+		bool completeCache; //!< when using resource, this field is set to the complete flag for that entry, and when released, this value is stored back
+	};
+	
+	//! constructor
+	WorldStatePool();
+	
+#ifdef PLATFORM_APERIOS
+	//! returned by isUnread containing information parsed from the incoming message
+	class UpdateInfo {
+	public:
+		//! constructor, sets #msg to NULL, #frameNumber to -1U
+		UpdateInfo()
+#ifdef DEBUG
+		: msg(NULL), frameNumber(-1U), intendedBuf(-1U) {}
+#else
+		: msg(NULL), frameNumber(-1U) {}
+#endif
+		OSensorFrameVectorData* msg; //!< incoming data
+		unsigned int frameNumber; //!< serial number of the message
+#ifdef DEBUG
+		unsigned int intendedBuf; //!< the write buffer read() is expected to use;  This is for debugging, if this isn't the buffer selected, display warning
+#endif
+	private:
+		UpdateInfo(const UpdateInfo&); //!< not implemented
+		UpdateInfo operator=(const UpdateInfo&); //!< not implemented
+	};
+	
+	//! returns true if the process should call WorldState::read (i.e. @a msg has new or unprocessed data (such as motion needs to supply feedback))
+	/*! only one call to this can be made at a time per process (not threadsafe, but is multi-process safe)
+		*  @param msg the incoming sensor data from the system -- should be const, but accessor functions from Sony aren't marked const themselves :-/
+		*  @param[out] lastFrameNumber if the incoming frame is already complete (no need to read), then the frame's number will be assigned here
+		*  @return returns a static UpdateInfo structure (to be passed to read()) if the message is unread, otherwise returns NULL. The structure is static -- DO NOT DELETE IT */
+	WorldStatePool::UpdateInfo* isUnread(OSensorFrameVectorData& msg, unsigned int& lastFrameNumber);
+		
+#else //PLATFORM_LOCAL
+	//! flags for the status field on each WriteRequest -- tracks partial completion when multiple writers are involved
+	enum status_t {
+		SENSORS_APPLIED=1<<0, //!< bit flag signals sensor data has been applied to the write target
+		FEEDBACK_APPLIED=1<<1 //!< bit flag signals motion feedback has been applied to the write target (only required if feedback is being generated)
+	};
+	
+	//! returned by isUnread containing information parsed from the incoming message
+	class UpdateInfo {
+	public:
+		UpdateInfo()
+#ifdef DEBUG
+			: verbose(false), frameNumber(-1U), filename(), dataInQueue(false), payload(NULL), payloadSize(0), intendedBuf(-1U) {}
+#else
+			: verbose(false), frameNumber(-1U), filename(), dataInQueue(false), payload(NULL), payloadSize(0) {}
+#endif
+		bool 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)
+		char* payload; //!< pointer to beginning of the data (NULL if no data available, i.e. heartbeat message)
+		unsigned int payloadSize; //!< size of data (0 if no data available, i.e. heartbeat message)
+#ifdef DEBUG
+		unsigned int intendedBuf; //!< the write buffer read() is expected to use;  This is for debugging, if this isn't the buffer selected, display warning
+#endif
+	private:
+		UpdateInfo(const UpdateInfo&); //!< not implemented
+		UpdateInfo operator=(const UpdateInfo&); //!< not implemented
+	};
+	
+	//! returns true if the process should call read (i.e. @a msg has new or unprocessed data (such as motion needs to supply feedback))
+	/*! only one call to this can be made at a time per process (not threadsafe, but is multi-process safe)
+	 *  @param msg incoming message to test
+	 *  @param curFrameNumber the most recent frame number sent, i.e. SharedGlobals::MotionSimConfig::frameNumber
+	 *  @param[out] lastFrameNumber if the incoming frame is already complete (no need to read), then the frame's number will be assigned here
+	 *  @param haveFeedback you should pass true if motion feedback <em>can be</em> provided to read() (note the feedback doesn't necessarily need to be available right now, just if the call to read is necessary)
+	 *  @param motionOverride true if motion feedback overrides sensor data (i.e SharedGlobals::MotionSimConfig::override)
+	 *  @return returns a static UpdateInfo structure (to be passed to read()) if the message is unread, otherwise returns NULL. The structure is static -- DO NOT DELETE IT */
+	WorldStatePool::UpdateInfo* isUnread(const RCRegion& msg, unsigned int curFrameNumber, unsigned int& lastFrameNumber, bool haveFeedback, bool motionOverride);
+	//! takes a sensor update from the simulator/system, updates an entry in the pool with the new information
+	/*! If isUnread() returns non-NULL, you should acquire a WriteRequest, and check that it succeeds, is current, and is still incomplete, before calling read()
+	 *  @param info the info structure returned by isUnread
+	 *  @param wsw the WriteRequest aquired before calling read (yes, you should submit a WriteRequest for @a info.frameNumber between isUnread() and read())
+	 *  @param feedbackGenerated pass true if feedback will be generated by a caller to read() -- doesn't need to be <em>this</em> process, but <em>a</em> process.
+	 *  @param zeroPIDFeedback pass true if sensor data should override motion feedback for joints with 0's for PID control (i.e. SharedGlobals::MotionSimConfig::zeroPIDFeedback)
+	 *  @param feedback pointer to actual motion feedback, or NULL if not available in this process (weight values of feedback are ignored, assumes all values are valid) */
+	bool read(const UpdateInfo& info, WriteRequest& wsw, bool feedbackGenerated, bool zeroPIDFeedback, const PostureEngine* feedback=NULL);
+#endif
+
+	//! processes a request, passed as either a ReadRequest or WriteRequest, to access an entry in the pool
+	virtual void useResource(Data& d) { doUseResource(d); }
+	//! completes access to an entry in the pool, you must pass the same request instance here which you originally passed to useResource()
+	virtual void releaseResource(Data& d) { doReleaseResource(d); }
+	
+	//! does the actual work of useResource()
+	/*! this is split off as a non-virtual function to avoid some process
+	 *  identity issues that occur with virtual functions under Aperios */
+	void doUseResource(Data& d);
+	//! does the actual work of releaseResource()
+	/*! this is split off as a non-virtual function to avoid some process
+	 *  identity issues that occur with virtual functions under Aperios */
+	void doReleaseResource(Data& d);
+
+#ifdef PLATFORM_APERIOS
+	//! registers #stateLookupMap with WorldState::setWorldStateLookup()
+	void InitAccess() { WorldState::setWorldStateLookup(stateLookupMap); }
+#endif
+	
+protected:
+	//! number of buffers to set up
+	static const unsigned int NUM_STATES=WORLDSTATEPOOL_NUM_STATES;
+	
+	//! shorthand for the type of #order
+	typedef ListMemBuf<unsigned int, NUM_STATES> order_t;
+	//! indicies of entries, in the order they were written (i.e. corresponding value in #frames should be monotonically increasing)
+	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; }
+	
+	//! called when access to an entry for reading is requested
+	unsigned int getCurrentReadState(WorldState*& tgt, bool block);
+	//! called when an read access to an entry is complete
+	void doneReadingState(unsigned int i);
+	
+	//! returns true if the specified element of #states has been marked completed
+	bool isComplete(unsigned int idx) const;
+	//! returns index of buffer in #states to use for write request
+	unsigned int selectWriteState(unsigned int frame, bool block) const { order_t::index_t idx; return selectWriteState(frame,block,idx); }
+	//! returns index of buffer in #states to use for write request, stores index of corresponding entry of #order in @a idx
+	unsigned int selectWriteState(unsigned int frame, bool block, order_t::index_t& idx) const;
+	//! called when access to an entry for writing is requested
+	unsigned int getCurrentWriteState(WorldState*& tgt, unsigned int frame, bool block);
+	//! called when an write access to an entry is complete
+	void doneWritingState(unsigned int i, bool completed);
+	
+	//! entries to hand out
+	WorldState states[NUM_STATES];
+	//! serial numbers of corresponding entries in #states, set when writing begins, should be monotonically increasing relative to #order (i.e. if you run through #order and look at corresponding values in #frames, should be monotonically increasing serial numbers)
+	unsigned int frames[NUM_STATES];
+	//! flag set when a reader is blocking for writing to finish, until read is satisified
+	unsigned int reading[NUM_STATES];
+	//! count of writers in line for access (occurs when a writer is blocking on another writer of the same frame, or no other frames are free)
+	unsigned int writing[NUM_STATES];
+	//! the status is intended as a bitfield to support communication between writers if they need to cooperatively fill out an entry
+	/*! The value is set to 0 before handing out to a writer with a new frame number */
+	unsigned int status[NUM_STATES];
+#ifdef PLATFORM_APERIOS
+	//! this lock indicates/controls whether the state is available for reading
+	/*! The lock is set before handing out to a writer with a new frame number, and released
+	 *  when a writer has marked the entry complete (via the WriteRequest upon releaseResource()) */
+	MutexLock<ProcessID::NumProcesses> complete[NUM_STATES];
+#else
+	//! this semaphore is set to positive value when writing begins, and then lowered to zero when complete
+	/*! A semaphore is used on "normal" systems because the MutexLock also implies a
+	 *  thread lock, which we actually don't want in this case because a different thread
+	 *  may complete the entry than the one which started it.  Since Aperios does not allow
+	 *  multithreading, we don't have to worry about it there.
+	 *
+	 *  As an aside, we @e could use this to store #writing, but that would only be feasible if
+	 *  Aperios gave us semaphores.  Bah. */
+	SemaphoreManager::semid_t complete[NUM_STATES];
+#endif
+	
+	//! locks to be acquired before handing out corresponding #states entry for writing
+	MutexLock<ProcessID::NumProcesses> writeLocks[NUM_STATES];
+	//! lock on WorldStatePool's own members
+	MutexLock<ProcessID::NumProcesses> lock;
+
+#ifdef PLATFORM_APERIOS
+	//! the current state in use by each process
+	WorldState* stateLookupMap[ProcessID::NumProcesses];
+#endif
+
+private:
+	WorldStatePool(const WorldStatePool&); //!< this shouldn't be called...
+	WorldStatePool& operator=(const WorldStatePool&); //!< this shouldn't be called...
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/XMLLoadSave.cc ./Shared/XMLLoadSave.cc
--- ../Tekkotsu_2.4.1/Shared/XMLLoadSave.cc	2005-07-27 01:58:24.000000000 -0400
+++ ./Shared/XMLLoadSave.cc	2006-09-09 00:33:02.000000000 -0400
@@ -68,7 +68,7 @@
 		if(compressionLevel>=0)
 			xmlSetDocCompressMode(xmldocument,compressionLevel);
 		xmlNode * cur = FindRootXMLElement(xmldocument);
-		SaveXML(cur);
+		saveXML(cur);
 		xmlChar* buf=NULL;
 		int size=0;
 		xmlDocDumpFormatMemory(xmldocument, &buf, &size, autoFormat);
@@ -79,7 +79,7 @@
 		return 0;
 	}
 }
-unsigned int XMLLoadSave::LoadBuffer(const char buf[], unsigned int len) {
+unsigned int XMLLoadSave::loadBuffer(const char buf[], unsigned int len) {
 	if(xmldocument!=NULL)
 		xmlFreeDoc(xmldocument);
 	
@@ -112,7 +112,7 @@
 	
 	try {
 		xmlNodePtr cur = FindRootXMLElement(xmldocument);
-		LoadXML(cur);
+		loadXML(cur);
 		return size;
 	} catch(const bad_format& err) {
 		reportError("During load of memory buffer:",err);
@@ -121,21 +121,21 @@
 		return 0;
 	}
 }
-unsigned int XMLLoadSave::SaveBuffer(char buf[], unsigned int len) const {
+unsigned int XMLLoadSave::saveBuffer(char buf[], unsigned int len) const {
 	try {
 		if(xmldocument==NULL)
 			setParseTree(xmlNewDoc((const xmlChar*)"1.0"));
 		if(compressionLevel>=0)
 			xmlSetDocCompressMode(xmldocument,compressionLevel);
 		xmlNode * cur = FindRootXMLElement(xmldocument);
-		SaveXML(cur);
+		saveXML(cur);
 		xmlChar* xbuf=NULL;
 		int size=0;
 		xmlDocDumpFormatMemory(xmldocument, &xbuf, &size, autoFormat);
 		if((unsigned int)size<=len)
 			memcpy(buf,xbuf,size);
 		else {
-			cerr << "Error: XMLLoadSave::SaveBuffer xmlDocDumpFormatMemory returned larger region than the target buffer" << endl;
+			cerr << "Error: XMLLoadSave::saveBuffer xmlDocDumpFormatMemory returned larger region than the target buffer" << endl;
 			size=0;
 		}
 		return size;
@@ -145,7 +145,7 @@
 	}
 }
 
-unsigned int XMLLoadSave::LoadFile(const char* filename) {
+unsigned int XMLLoadSave::loadFile(const char* filename) {
 	if(xmldocument!=NULL)
 		xmlFreeDoc(xmldocument);
 	
@@ -178,7 +178,7 @@
 	
 	try {
 		xmlNodePtr cur = FindRootXMLElement(xmldocument);
-		LoadXML(cur);
+		loadXML(cur);
 		return size;
 	} catch(const bad_format& err) {
 		string context("During load of '");
@@ -190,17 +190,17 @@
 		return 0;
 	}
 }
-unsigned int XMLLoadSave::SaveFile(const char* filename) const {
+unsigned int XMLLoadSave::saveFile(const char* filename) const {
 	try {
 		if(xmldocument==NULL)
 			setParseTree(xmlNewDoc((const xmlChar*)"1.0"));
 		if(compressionLevel>=0)
 			xmlSetDocCompressMode(xmldocument,compressionLevel);
 		xmlNode * cur = FindRootXMLElement(xmldocument);
-		SaveXML(cur);
+		saveXML(cur);
 		int size=xmlSaveFormatFile (filename, xmldocument, autoFormat);
 		if(size==-1)
-			cerr << "Error: XMLLoadSave::SaveFile: xmlSaveFormatFile(\"" << filename << "\",...) returned -1" << endl;
+			cerr << "Error: XMLLoadSave::saveFile: xmlSaveFormatFile(\"" << filename << "\",...) returned -1" << endl;
 		return size==-1?0:size;
 	} catch(const bad_format& err) {
 		string context("During save to '");
@@ -211,7 +211,7 @@
 	}
 }
 
-unsigned int XMLLoadSave::LoadFileStream(FILE* f) {
+unsigned int XMLLoadSave::loadFileStream(FILE* f) {
 	if(xmldocument!=NULL)
 		xmlFreeDoc(xmldocument);
 	
@@ -236,7 +236,7 @@
 	
 	try {
 		xmlNodePtr cur = FindRootXMLElement(xmldocument);
-		LoadXML(cur);
+		loadXML(cur);
 		return size;
 	} catch(const bad_format& err) {
 		reportError("During load of file stream:",err);
@@ -245,17 +245,17 @@
 		return 0;
 	}
 }
-unsigned int XMLLoadSave::SaveFileStream(FILE* f) const {
+unsigned int XMLLoadSave::saveFileStream(FILE* f) const {
 	try {
 		if(xmldocument==NULL)
 			setParseTree(xmlNewDoc((const xmlChar*)"1.0"));
 		if(compressionLevel>=0)
 			xmlSetDocCompressMode(xmldocument,compressionLevel);
 		xmlNode * cur = FindRootXMLElement(xmldocument);
-		SaveXML(cur);
+		saveXML(cur);
 		int size=xmlDocFormatDump(f, xmldocument, autoFormat);
 		if(size==-1)
-			cerr << "Error: XMLLoadSave::SaveFileStream: xmlDocFormatDump(...) returned -1" << endl;
+			cerr << "Error: XMLLoadSave::saveFileStream: xmlDocFormatDump(...) returned -1" << endl;
 		return size==-1?0:size;
 	} catch(const bad_format& err) {
 		reportError("During save to file stream:",err);
@@ -278,7 +278,7 @@
 		return;
 	try {
 		xmlNodePtr cur = FindRootXMLElement(xmldocument);
-		LoadXML(cur);
+		loadXML(cur);
 	} catch(const bad_format& err) {
 		reportError("During readParseTree:",err);
 		xmlFreeDoc(xmldocument);
@@ -292,7 +292,7 @@
 		if(compressionLevel>=0)
 			xmlSetDocCompressMode(xmldocument,compressionLevel);
 		xmlNode * cur = FindRootXMLElement(xmldocument);
-		SaveXML(cur);
+		saveXML(cur);
 	} catch(const bad_format& err) {
 		reportError("During writeParseTree:",err);
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/XMLLoadSave.h ./Shared/XMLLoadSave.h
--- ../Tekkotsu_2.4.1/Shared/XMLLoadSave.h	2005-08-07 00:11:04.000000000 -0400
+++ ./Shared/XMLLoadSave.h	2006-09-09 00:33:02.000000000 -0400
@@ -6,12 +6,14 @@
 
 //!@name libxml2 forward declarations
 //!forward declaration of the libxml2 struct of the same name
-struct _xmlNode;
-struct _xmlDoc;
-struct _xmlAttr;
-typedef _xmlNode xmlNode;
-typedef _xmlDoc xmlDoc;
-typedef _xmlAttr xmlAttr;
+extern "C" {
+	struct _xmlNode;
+	struct _xmlDoc;
+	struct _xmlAttr;
+	typedef _xmlNode xmlNode;
+	typedef _xmlDoc xmlDoc;
+	typedef _xmlAttr xmlAttr;
+}
 //@}
 
 //! XMLLoadSave adds functions for XML format serialization, although if you write binary LoadSave functions as well, you can do either
@@ -22,17 +24,19 @@
 	class bad_format : std::exception {
 	public:
 		//!constructor
-		bad_format(xmlNode * node, const char * msg="invalid format in plist") throw() : std::exception(), node_(node), msg_(msg) {}
+		bad_format(xmlNode * node) throw() : std::exception(), node_(node), msg_("invalid format in plist") {}
+		//!constructor
+		bad_format(xmlNode * node, const std::string& msg) throw() : std::exception(), node_(node), msg_(msg) {}
 		//!copy constructor
 		bad_format(const bad_format& bf) : std::exception(bf), node_(bf.node_), msg_(bf.msg_) {}
 		//!assignment
 		bad_format& operator=(const bad_format& bf) { std::exception::operator=(bf); node_=bf.node_; msg_=bf.msg_; return *this; }
 		virtual ~bad_format() throw() {} //!< destructor
-		virtual const char * what() const throw() { return msg_; } //!< standard interface for getting the exception's message string
+		virtual const char * what() const throw() { return msg_.c_str(); } //!< standard interface for getting the exception's message string
 		virtual xmlNode * getNode() const throw() { return node_; } //!< returns the xmlNode at which the error occurred
 	protected:
 		xmlNode * node_; //!< the node of the error
-		const char * msg_; //!< message regarding the type of error
+		std::string msg_; //!< message regarding the type of error
 	};
 	
 	XMLLoadSave(); //!< constructor
@@ -43,21 +47,21 @@
 	//! This is called when the subclass needs to update its values from those values in the parse tree
 	/*! @a node is the current node in the tree -- it may be the root, but it
 	 *  may also be a subnode within the tree if a recursive structure is used */
-	virtual void LoadXML(xmlNode* node)=0;
+	virtual void loadXML(xmlNode* node)=0;
 	//! This is called when XMLLoadSave needs to have the subclass update values in the tree currently in memory -- may already be filled out by previous contents
 	/*! @a node is the current node in the tree -- it may be the root, but it
 	 *  may also be a subnode within the tree if a recursive structure is used */
-	virtual void SaveXML(xmlNode * node) const=0;
+	virtual void saveXML(xmlNode * node) const=0;
 	
 	virtual unsigned int getBinSize() const;
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
 
-	virtual	unsigned int LoadFile(const char* filename);
-	virtual unsigned int SaveFile(const char* filename) const;
+	virtual unsigned int loadFile(const char* filename);
+	virtual unsigned int saveFile(const char* filename) const;
 	
-	virtual unsigned int LoadFileStream(FILE* f);
-	virtual unsigned int SaveFileStream(FILE* f) const;
+	virtual unsigned int loadFileStream(FILE* f);
+	virtual unsigned int saveFileStream(FILE* f) const;
 	
 	//! resets the parse tree currently in memory so that a future save will write a "fresh" copy from scratch.
 	/*! You may also want to call this in order to save memory after a Load so that
@@ -75,9 +79,9 @@
 	//! returns the current parse tree, either from a previous Load, Save, or setParseTree()
 	virtual xmlDoc* getParseTree() const { return xmldocument; }
 	
-	//! calls LoadXML with the root of the current parse tree
+	//! calls loadXML with the root of the current parse tree
 	virtual void readParseTree();
-	//! calls SaveXML with the root of the current parse tree
+	//! calls saveXML with the root of the current parse tree
 	virtual void writeParseTree();
 	
 	//! allows you to set the compression level used by libxml2 -- this corresponds to the compression level setting of zlib, i.e. 0-9
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/attributes.h ./Shared/attributes.h
--- ../Tekkotsu_2.4.1/Shared/attributes.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/attributes.h	2006-09-16 02:01:41.000000000 -0400
@@ -0,0 +1,101 @@
+#ifndef INCLUDED_attributes_h
+#define INCLUDED_attributes_h
+
+#if defined(__GNUC__) && __GNUC__ >= 3
+
+#  if __GNUC__ == 3 && (__GNUC_MINOR__ > 4)
+// Currently no 3.5 branch exists, so this boils down to 4.0 or better
+//! indicates that a warning should be given if caller doesn't use the return value, e.g. newly allocated memory regions
+#    define ATTR_must_check	__attribute__ ((warn_unused_result))
+#  else
+// 3.3 doesn't even support warn_unused_result, and 3.4.2 generates spurious errors.
+//! indicates that a warning should be given if caller doesn't use the return value, e.g. newly allocated memory regions
+#    define ATTR_must_check	/* no warn_unused_result */
+#  endif
+
+//! triggers inlining even when no optimization is specified
+#  define ATTR_always_inline		__attribute__ ((always_inline))
+
+//! compiler hint that the function has no side effects and return value depends only on arguments and non-volatile globals
+#  define ATTR_pure		__attribute__ ((pure))
+
+//! like #ATTR_pure, compiler hint that the function has no side effects and return value depends only on arguments -- unlike #ATTR_pure, cannot access globals or dereference pointer arguments.
+#  define ATTR_const	__attribute__ ((const))
+
+//! indicates that the function is 'fatal' and will not return; however, can still throw an exception!
+#  define ATTR_noreturn	__attribute__ ((noreturn))
+
+//! compiler hint that a non-NULL pointer return value is guaranteed to be a unique address (e.g. malloc)
+#  define ATTR_malloc	__attribute__ ((malloc))
+
+//! triggers a warning if the function/variable is referenced by any code which is not itself marked with #ATTR_deprecated
+#  define ATTR_deprecated	__attribute__ ((deprecated))
+
+//! forces the code for the function to be emitted even if nothing appears to reference it -- handy when called by inline assembly
+#  define ATTR_used		__attribute__ ((used))
+
+//! indicates no warning should be given if the specified value goes unused, e.g. fulfilling an interface which requires superfluous arguments
+#  define ATTR_unused	__attribute__ ((unused))
+
+//! requests that members of a struct or union be layed out a densely as possible to minimize memory usage; applied to enums requests smallest storage type be used
+#  define ATTR_packed	__attribute__ ((packed))
+
+//! should be passed a value within an 'if' statement to hint that the value is likely to be 'true' (i.e. non-zero)
+#  define ATTR_likely(x)	__builtin_expect (!!(x), 1)
+
+//! should be passed a value within an 'if' statement to hint that the value is unlikely to be 'true' (i.e. likely to be 'false' or 0)
+#  define ATTR_unlikely(x)	__builtin_expect (!!(x), 0)
+
+#else
+
+//! triggers inlining even when no optimization is specified
+#  define ATTR_always_inline		/* no always_inline */
+
+//! compiler hint that the function has no side effects and return value depends only on arguments and non-volatile globals
+#  define ATTR_pure		/* no pure */
+
+//! like #ATTR_pure, compiler hint that the function has no side effects and return value depends only on arguments -- unlike #ATTR_pure, cannot access globals or dereference pointer arguments.
+#  define ATTR_const	/* no const */
+
+//! indicates that the function is 'fatal' and will not return; however, can still throw an exception!
+#  define ATTR_noreturn	/* no noreturn */
+
+//! compiler hint that a non-NULL pointer return value is guaranteed to be a unique address (e.g. malloc)
+#  define ATTR_malloc	/* no malloc */
+
+//! indicates that a warning should be given if caller doesn't use the return value, e.g. newly allocated memory regions
+#  define ATTR_must_check	/* no warn_unused_result */
+
+//! triggers a warning if the function/variable is referenced by any code which is not itself marked with #ATTR_deprecated
+#  define ATTR_deprecated	/* no deprecated */
+
+//! forces the code for the function to be emitted even if nothing appears to reference it -- handy when called by inline assembly
+#  define ATTR_used		/* no used */
+
+//! indicates no warning should be given if the specified value goes unused, e.g. fulfilling an interface which requires superfluous arguments
+#  define ATTR_unused	/* no unused */
+
+//! requests that members of a struct or union be layed out a densely as possible to minimize memory usage; applied to enums requests smallest storage type be used
+#  define ATTR_packed	/* no packed */
+
+//! should be passed a value within an 'if' statement to hint that the value is likely to be 'true' (i.e. non-zero)
+#  define ATTR_likely(x)	(x)
+
+//! should be passed a value within an 'if' statement to hint that the value is unlikely to be 'true' (i.e. likely to be 'false' or 0)
+#  define ATTR_unlikely(x)	(x)
+
+#endif
+
+/*! @file
+* @brief Defines variants of the __attribute__ macros to provide better portability
+* @author Robert Love (Creator), ejt (more version specificity)
+*
+* Based on code published at http://rlove.org/log/2005102601
+*
+* $Author: ejt $
+* $Name: HEAD $
+* $Revision: 1.1 $
+* $State: Exp $
+* $Date: 2006/10/04 04:21:12 $
+*/
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/debuget.h ./Shared/debuget.h
--- ../Tekkotsu_2.4.1/Shared/debuget.h	2005-08-16 17:23:43.000000000 -0400
+++ ./Shared/debuget.h	2006-09-27 17:12:31.000000000 -0400
@@ -3,128 +3,138 @@
 
 #include <stdio.h>
 #include <ctype.h>
+#include <iostream>
 
 #ifdef DEBUG
-#include <iostream>
 #include <string.h>
+#include <sstream>
 #include <fstream>
-//! for historical reasons - the previous compiler give the entire path for __FILE__, for display, just use the filename
-inline const char* _extractFilename(const char* path) {
-	const char * last=path;
-	while(*path++)
-		if(*path=='/')
-			last=path+1;
-	return last;
-}
-//! if the bool b is false, std::cout the string
-#define ASSERT(b,str) {if(!(b)) std::cout << "ASSERT:"<<_extractFilename(__FILE__)<<'.'<<__LINE__<<':'<< str << std::endl;}
-//! if the bool b is false, std::cout the string and return
-#define ASSERTRET(b,str) {if(!(b)) { std::cout << "ASSERT:"<<_extractFilename(__FILE__)<<'.'<<__LINE__<<':'<< str << std::endl; return; }}
-//! if the bool b is false, std::cout the string and return the value
-#define ASSERTRETVAL(b,str,v) {if(!(b)) { std::cout << "ASSERT:"<<_extractFilename(__FILE__)<<'.'<<__LINE__<<':'<< str << std::endl; return v; }}
-//! if the bool b is false, std::cout the string and exit(x)
-#define ASSERTFATAL(b,str,x) {if(!(b)) { std::cout << "ASSERT:"<<_extractFilename(__FILE__)<<'.'<<__LINE__<<':'<< str << std::endl; exit(x); }}
-//#define FILELOG(fname,type,str) { ofstream f(fname,type); f<<str; }
-#else
-//! if the bool b is false, std::cout the string
-#define ASSERT(b,str) {}
-//! if the bool b is false, std::cout the string and return
-#define ASSERTRET(b,str) {}
-//! if the bool b is false, std::cout the string and return the value
-#define ASSERTRETVAL(b,str,v) {}
-//! if the bool b is false, std::cout the string and exit(x)
-#define ASSERTFATAL(b,str,x) {}
 #endif
 
-//! returns the hex char that corresponds to @a c, which should be 0-16 (returns '.' otherwise)
-inline char hexdigit(int c) {
-	if(c<0)
-		return '.';
-	if(c<10)
-		return '0'+c;
-	if(c<16)
-		return 'a'+(c-10);
-	return ',';
+//! contains some debugging functions and #ASSERT macros (although the macros don't respect the namespace scoping...)
+namespace debuget {
+	//! for display, just use the filename, not the whole path
+	inline const char* extractFilename(const char* path) {
+		const char * last=path;
+		while(*path++)
+			if(*path=='/')
+				last=path+1;
+		return last;
 	}
+	
+	//! mostly for use with a debugger -- set a breakpoint on this function and you can catch anytime an assertion is generated
+	inline void displayAssert(const char* file, unsigned int line,const char* msg) { std::cerr << "ASSERT:"<<extractFilename(file)<<'.'<<line<<':'<< msg << std::endl; }
+	
+	#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()); }}
+	//! 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; }}
+	//! 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; }}
+	//! 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); }}
+	#else
+	//! if the bool b is false, std::cout the string
+	#define ASSERT(b,msgstream) {}
+	//! if the bool b is false, std::cout the string and return
+	#define ASSERTRET(b,msgstream) {}
+	//! if the bool b is false, std::cout the string and return the value
+	#define ASSERTRETVAL(b,msgstream,v) {}
+	//! if the bool b is false, std::cout the string and exit(x)
+	#define ASSERTFATAL(b,msgstream,x) {}
+	#endif
 
-//! printf's the two hex digits coresponding to a byte
-inline void charhexout(char c) {
-	printf("%c%c",hexdigit((c>>4)&0x0F),hexdigit(c&0x0F));
-}
-
-//! charhexout's @a n bytes starting at @a p
-inline void hexout(const void* p, size_t n) {
-	printf("%x:\n",reinterpret_cast<unsigned int>(p));
-	const char* x=(const char*)p;
-	for(unsigned int i=0; i<n;) {
-		printf("%6d ",i);
-		for(unsigned int k=0; k<8 && i<n; k++) {
-			for(unsigned int j=0; j<4 && i<n; j++, i++) {
-				charhexout(x[i]);
-				//				std::cout << flush;
-			}
-			printf(" ");
-		}
-		printf("\n");
+	//! returns the hex char that corresponds to @a c, which should be 0-16 (returns '.' otherwise)
+	inline char hexdigit(int c) {
+		if(c<0)
+			return '.';
+		if(c<10)
+			return '0'+c;
+		if(c<16)
+			return 'a'+(c-10);
+		return ',';
 	}
-}
 
-//! displays hex and ascii values of @a size bytes from @a p
-inline void hexout2(const void* p, size_t size) {
-	const char* buf=static_cast<const char*>(p);
-	unsigned int prev_line=0;
-	const unsigned int cols=4;
-	const unsigned int n_per_col=4;
-	printf("Base: %p\n",buf);
-	for(unsigned int i=0; i<size; i++) {
-		if(i%(cols*n_per_col)==0)
-			printf("%6u  |",i);
-		printf("%02hx",buf[i]);
-		if((i+1)%(cols*n_per_col)==0) {
-			printf("|  ");
-			for(unsigned int j=prev_line; j<=i; j++)
-				printf("%c",isprint(buf[j])?buf[j]:'.');
-			prev_line=i+1;
-			printf("\n");
-		} else if((i+1)%(n_per_col)==0)
-			printf(" ");
+	//! printf's the two hex digits coresponding to a byte
+	inline void charhexout(char c) {
+		printf("%c%c",hexdigit((c>>4)&0x0F),hexdigit(c&0x0F));
 	}
-	for(unsigned int i=size; i%(cols*n_per_col)!=0; i++) {
-		printf("  ");
-		if((i+1)%(cols*n_per_col)==0) {
-			printf("|  ");
-			for(unsigned int j=prev_line; j<size; j++)
-				printf("%c",isprint(buf[j])?buf[j]:'.');
-			prev_line=i;
+
+	//! charhexout's @a n bytes starting at @a p
+	inline void hexout(const void* p, size_t n) {
+		printf("%p:\n",p);
+		const char* x=(const char*)p;
+		for(unsigned int i=0; i<n;) {
+			printf("%6d ",i);
+			for(unsigned int k=0; k<8 && i<n; k++) {
+				for(unsigned int j=0; j<4 && i<n; j++, i++) {
+					charhexout(x[i]);
+					//				std::cout << flush;
+				}
+				printf(" ");
+			}
 			printf("\n");
-		} else if((i+1)%(n_per_col)==0)
-			printf(" ");
+		}
 	}
-}
 
-//! displays hex and ascii values of @a size bytes from @a p
-inline void hexout3(const char* buf, size_t size) {
-	const unsigned int linelen=24;
-	for(unsigned int i=0; i<size; i++) {
-		printf("%.2hx",buf[i]);
-		if((i+1)%linelen==0) {
-			printf("   ");
-			for(unsigned int j=i+1-linelen; j<=i; j++)
-				putchar(isprint(buf[j])?buf[j]:'.');
-			printf("\n");
-		} else if((i+1)%4==0)
-			printf(" ");
+	//! displays hex and ascii values of @a size bytes from @a p
+	inline void hexout2(const void* p, size_t size) {
+		const char* buf=static_cast<const char*>(p);
+		unsigned int prev_line=0;
+		const unsigned int cols=4;
+		const unsigned int n_per_col=4;
+		printf("Base: %p\n",buf);
+		for(unsigned int i=0; i<size; i++) {
+			if(i%(cols*n_per_col)==0)
+				printf("%6u  |",i);
+			printf("%02hx",buf[i]);
+			if((i+1)%(cols*n_per_col)==0) {
+				printf("|  ");
+				for(unsigned int j=prev_line; j<=i; j++)
+					printf("%c",isprint(buf[j])?buf[j]:'.');
+				prev_line=i+1;
+				printf("\n");
+			} else if((i+1)%(n_per_col)==0)
+				printf(" ");
+		}
+		for(unsigned int i=size; i%(cols*n_per_col)!=0; i++) {
+			printf("  ");
+			if((i+1)%(cols*n_per_col)==0) {
+				printf("|  ");
+				for(unsigned int j=prev_line; j<size; j++)
+					printf("%c",isprint(buf[j])?buf[j]:'.');
+				prev_line=i;
+				printf("\n");
+			} else if((i+1)%(n_per_col)==0)
+				printf(" ");
+		}
 	}
-	//finish off the last line (still need to do human-readable version)
-	for(unsigned int i=size; i%linelen!=0; i++) {
-		printf("  ");
-		if((i+1)%linelen==0) {
-			printf("   ");
-			for(unsigned int j=(size/linelen)*linelen; j<size; j++)
-				putchar(isprint(buf[j])?buf[j]:'.');
-			printf("\n");
-		} else if((i+1)%4==0)
-			printf(" ");
+
+	//! displays hex and ascii values of @a size bytes from @a p
+	inline void hexout3(const char* buf, size_t size) {
+		const unsigned int linelen=24;
+		for(unsigned int i=0; i<size; i++) {
+			printf("%.2hx",buf[i]);
+			if((i+1)%linelen==0) {
+				printf("   ");
+				for(unsigned int j=i+1-linelen; j<=i; j++)
+					putchar(isprint(buf[j])?buf[j]:'.');
+				printf("\n");
+			} else if((i+1)%4==0)
+				printf(" ");
+		}
+		//finish off the last line (still need to do human-readable version)
+		for(unsigned int i=size; i%linelen!=0; i++) {
+			printf("  ");
+			if((i+1)%linelen==0) {
+				printf("   ");
+				for(unsigned int j=(size/linelen)*linelen; j<size; j++)
+					putchar(isprint(buf[j])?buf[j]:'.');
+				printf("\n");
+			} else if((i+1)%4==0)
+				printf(" ");
+		}
 	}
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/get_time.cc ./Shared/get_time.cc
--- ../Tekkotsu_2.4.1/Shared/get_time.cc	2005-06-01 01:47:49.000000000 -0400
+++ ./Shared/get_time.cc	2006-10-03 22:40:42.000000000 -0400
@@ -16,6 +16,7 @@
 		return static_cast<unsigned int>(first.Age().Value()*1000);
 	}
 	unsigned int (*get_time_callback)()=&default_get_time_callback;
+	float (*get_timeScale_callback)()=NULL;
 }
 #endif
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/get_time.h ./Shared/get_time.h
--- ../Tekkotsu_2.4.1/Shared/get_time.h	2005-06-14 18:11:46.000000000 -0400
+++ ./Shared/get_time.h	2006-10-03 22:40:42.000000000 -0400
@@ -3,9 +3,12 @@
 
 #ifdef PLATFORM_APERIOS
 
-//!a simple way to get the current time since boot in milliseconds (see TimeET for better accuracy)
+//! a simple way to get the current time since boot in milliseconds (see TimeET for better accuracy)
 unsigned int get_time();
 
+//! just to provide compatability with simulator code, this function always returns '1' since we're running in realtime on real hardware
+float getTimeScale();
+
 #else //PLATFORM_LOCAL
 
 //! If we're running locally, these will let users in "project" space control time for simulation
@@ -15,8 +18,16 @@
 	//! This by default will return the time in milliseconds since the first call was made.  Note this is a function pointer, so you can reassign it to your own implementation!
 	/*! For instance, the simulator can assign a function which forwards
 	 *  the call to SharedGlobals::get_time(), so that all processes get
-	 *  consistent time values under control of the simulator */
+	 *  consistent time values under control of the simulator
+	 *  Note that this is a slightly different usage paradigm than get_timeScale_callback(), which is probably cleaner, but trying to avoid spreading dependency on TimeET.h */
 	extern unsigned int (*get_time_callback)();
+
+	/*! @brief You can reassign this to your own implementation if you might play games with time control.
+	 *  For instance, the simulator can assign a function which 
+	 *  simply returns SharedGlobals::timeScale.
+	 *  By default this is NULL, which indicates to getTimeScale that it should use the default implementation. 
+	 *  Note that this is a slightly different usage paradigm than get_time_callback(), which is assumed to always be non-NULL (at least, unless you assign a value to #simulation_time...)  */
+	extern float (*get_timeScale_callback)();
 }
 
 //! This will call and return project_get_time::get_time_callback if project_get_time::simulation_time is -1.  Otherwise simulation_time is returned.
@@ -31,6 +42,16 @@
 		return project_get_time::simulation_time;
 }
 
+//! If project_get_time::get_timeScale_callback is NULL, this will return 1 if project_get_time::simulation_time is -1U (the default value), and -1 otherwise.  If the callback is available, returns that.
+inline float getTimeScale() {
+	if(project_get_time::get_timeScale_callback)
+		return (*project_get_time::get_timeScale_callback)();
+	else if(project_get_time::simulation_time==-1U)
+		return 1;
+	else
+		return -1;
+}
+
 #endif
 
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/jpeg-6b/jpeg_mem_dest.cc ./Shared/jpeg-6b/jpeg_mem_dest.cc
--- ../Tekkotsu_2.4.1/Shared/jpeg-6b/jpeg_mem_dest.cc	2005-06-01 01:47:52.000000000 -0400
+++ ./Shared/jpeg-6b/jpeg_mem_dest.cc	2005-10-25 17:33:42.000000000 -0400
@@ -43,7 +43,7 @@
 	dest->pub.next_output_byte = dest->buf;
 	dest->pub.free_in_buffer = dest->bufsize;
 
-	return FALSE;
+	return 0;
 	ERREXIT(cinfo, JERR_BUFFER_SIZE);
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/jpeg-6b/jpeg_mem_src.cc ./Shared/jpeg-6b/jpeg_mem_src.cc
--- ../Tekkotsu_2.4.1/Shared/jpeg-6b/jpeg_mem_src.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/jpeg-6b/jpeg_mem_src.cc	2006-06-23 17:55:40.000000000 -0400
@@ -0,0 +1,82 @@
+#include "jpeg_mem_src.h"
+
+#ifdef JPEGMEMSRC_UNUSED 
+#elif defined(__GNUC__) && __GNUC__>3 
+# define JPEGMEMSRC_UNUSED(x) UNUSED_##x __attribute__((unused)) 
+# define JPEGMEMSRC_BODY_UNUSED(x) /*no body necessary*/
+#elif defined(__LCLINT__) 
+# define JPEGMEMSRC_UNUSED(x) /*@unused@*/ x 
+# define JPEGMEMSRC_BODY_UNUSED(x) /*no body necessary*/
+#else 
+# define JPEGMEMSRC_UNUSED(x) UNUSED_##x 
+# define JPEGMEMSRC_BODY_UNUSED(x) (void)UNUSED_##x /* ugly hack to avoid warning */
+#endif
+
+
+#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;
+	JOCTET * buf;
+	size_t bufsize;
+	size_t lastused; /* on completion, set to number of bytes used from buf */
+} JPEGSource;
+
+static void init_sourceFunc(j_decompress_ptr cinfo) {
+	JPEGSource  *src = (JPEGSource*)cinfo->src;
+	src->pub.next_input_byte = src->buf;
+	src->pub.bytes_in_buffer = src->bufsize;
+}
+static boolean fill_input_bufferFunc(j_decompress_ptr JPEGMEMSRC_UNUSED(cinfo)) {
+	JPEGMEMSRC_BODY_UNUSED(cinfo);
+	return FALSE;
+}
+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)
+			src->pub.bytes_in_buffer = 0;
+		else {
+			src->pub.next_input_byte += num_bytes;
+			src->pub.bytes_in_buffer -= num_bytes;
+		}
+	}
+}
+void term_sourceFunc(j_decompress_ptr cinfo) {
+	JPEGSource* src = (JPEGSource*) cinfo->src;
+	if(src->pub.next_input_byte==NULL)
+		src->lastused=0;
+	else
+		src->lastused = src->buf - src->pub.next_input_byte;
+}
+
+GLOBAL(void) 
+jpeg_mem_src (j_decompress_ptr cinfo, JOCTET * inbuf, size_t maxlen) {
+	JPEGSource *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(JPEGSource)); 
+	
+	src = (JPEGSource*) 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->pub.next_input_byte = src->buf = inbuf; 
+	src->pub.bytes_in_buffer = src->bufsize = maxlen; 
+	src->lastused=0;
+} 
+
+#ifdef __cplusplus
+}
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/jpeg-6b/jpeg_mem_src.h ./Shared/jpeg-6b/jpeg_mem_src.h
--- ../Tekkotsu_2.4.1/Shared/jpeg-6b/jpeg_mem_src.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/jpeg-6b/jpeg_mem_src.h	2006-06-23 17:55:40.000000000 -0400
@@ -0,0 +1,17 @@
+#ifndef jpeg_mem_src_h_DEFINED
+#define jpeg_mem_src_h_DEFINED
+
+#include <sys/types.h>
+#include <stdio.h>
+
+#ifdef __cplusplus
+extern "C" {
+#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
+
+#endif /* jpeg_mem_dest_h_DEFINED */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/mathutils.h ./Shared/mathutils.h
--- ../Tekkotsu_2.4.1/Shared/mathutils.h	2003-01-08 21:03:00.000000000 -0500
+++ ./Shared/mathutils.h	2005-10-14 18:25:38.000000000 -0400
@@ -52,6 +52,17 @@
 	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;
+  }
+
 }
 
 #endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/newmat/Makefile ./Shared/newmat/Makefile
--- ../Tekkotsu_2.4.1/Shared/newmat/Makefile	2005-08-09 22:20:09.000000000 -0400
+++ ./Shared/newmat/Makefile	2006-03-28 12:08:21.000000000 -0500
@@ -6,12 +6,13 @@
 ifndef TEKKOTSU_ENVIRONMENT_CONFIGURATION
 $(error An error has occured, TEKKOTSU_ENVIRONMENT_CONFIGURATION was not defined)
 endif
-include $(TEKKOTSU_ENVIRONMENT_CONFIGURATION)
+TEKKOTSU_ROOT:=../..
+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= -fno-inline \
+CXXFLAGS= $(if $(TEKKOTSU_DEBUG),-g -fno-inline -DDEBUG,) \
           -Wall -W -Wlarger-than-8192 -Wpointer-arith -Wcast-qual \
           -Woverloaded-virtual -Wdeprecated -Wnon-virtual-dtor \
           -O3 -frename-registers -fomit-frame-pointer -fno-common \
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/newmat/myexcept.cpp ./Shared/newmat/myexcept.cpp
--- ../Tekkotsu_2.4.1/Shared/newmat/myexcept.cpp	2005-07-25 23:21:59.000000000 -0400
+++ ./Shared/newmat/myexcept.cpp	2006-03-23 19:37:14.000000000 -0500
@@ -220,7 +220,7 @@
 void Terminate()
 {
    cout << "\n\nThere has been an exception with no handler - exiting";
-   const char* what = BaseException::what();
+   const char* what = BaseException::getWhat();
    if (what) cout << what << "\n";
    exit(1);
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/newmat/myexcept.h ./Shared/newmat/myexcept.h
--- ../Tekkotsu_2.4.1/Shared/newmat/myexcept.h	2004-06-16 17:16:41.000000000 -0400
+++ ./Shared/newmat/myexcept.h	2006-03-30 16:52:45.000000000 -0500
@@ -38,7 +38,7 @@
 
 #ifndef EXCEPTION_LIB
 #define EXCEPTION_LIB
-
+#include <exception>
 #ifdef use_namespace
 namespace RBD_COMMON {
 #endif
@@ -66,7 +66,7 @@
 };
 
 
-class BaseException                          // The base exception class
+class BaseException : public std::exception  // The base exception class
 {
 protected:
    static char* what_error;              // error message
@@ -78,8 +78,8 @@
    static void AddInt(int value);        // integer to error message
    static unsigned long Select;          // for identifying exception
    BaseException(const char* a_what = 0);
-   static const char* what() { return what_error; }
-                                         // for getting error message
+   static const char* getWhat() throw() { return what_error; } // for getting the message statically (only used by Terminate, which should probably take the exception as an argument, and then we wouldn't need static storage?)
+   virtual const char* what() const throw() { return what_error; } // for getting error message
 };
 
 #ifdef TypeDefException
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/newmat/newmat.h ./Shared/newmat/newmat.h
--- ../Tekkotsu_2.4.1/Shared/newmat/newmat.h	2005-07-25 23:21:59.000000000 -0400
+++ ./Shared/newmat/newmat.h	2006-03-21 16:30:02.000000000 -0500
@@ -1475,6 +1475,7 @@
 {
    InvertedMatrix(const BaseMatrix* bmx) : NegatedMatrix(bmx) {}
 public:
+   InvertedMatrix(const InvertedMatrix& im) : NegatedMatrix(im) {}
    ~InvertedMatrix() {}
    SolvedMatrix operator*(const BaseMatrix&) const;       // inverse(A) * B
    ScaledMatrix operator*(Real t) const { return BaseMatrix::operator*(t); }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/plist.cc ./Shared/plist.cc
--- ../Tekkotsu_2.4.1/Shared/plist.cc	2005-07-27 01:58:24.000000000 -0400
+++ ./Shared/plist.cc	2006-09-16 16:11:53.000000000 -0400
@@ -1,403 +1,55 @@
 #include "plist.h"
-#include <libxml/xmlmemory.h>
-#include <libxml/parser.h>
-#include <iomanip>
 
 using namespace std;
 
 namespace plist {
 
-	ObjectBase::ObjectBase()
-	  : XMLLoadSave()
-	{}
-	
-	ObjectBase::~ObjectBase() {}
-	
-	void ObjectBase::setParseTree(xmlDoc * doc) const {
-		XMLLoadSave::setParseTree(doc);
-		if(xmldocument==NULL)
-			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");
-	}
-	
-	xmlNode* ObjectBase::FindRootXMLElement(xmlDoc* doc) const {
-		if(doc==NULL)
+	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)
+			obj=new Primitive<double>;
+		else if(ObjectBase::xNodeHasName(node,"integer")==0)
+			obj=new Primitive<long>;
+		else if(ObjectBase::xNodeHasName(node,"string")==0)
+			obj=new Primitive<std::string>;
+		else if(ObjectBase::xNodeHasName(node,"true")==0)
+			obj=new Primitive<bool>;
+		else if(ObjectBase::xNodeHasName(node,"false")==0)
+			obj=new Primitive<bool>;
+		else
 			return NULL;
-		xmlNode* root=XMLLoadSave::FindRootXMLElement(doc);
-		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"))
-			cerr << "Warning: plist " << filename << "does not carry version number, assuming 1.0" << endl;
-		else {
-			xmlChar* strv=xmlGetProp(root,(const xmlChar*)"version");
-			double version=strtod((const char*)strv,NULL);
-			if(version>1.0)
-				cerr << "WARNING: plist " << filename << "is version " << strv << ", this software only knows 1.0.  Trying anyway..." << endl;
-			if(version==0)
-				cerr << "WARNING: plist " << filename << "seems to have invalid version '" << strv << "', this software only knows 1.0.  Trying anyway..." << endl;
-			xmlFree(strv);
-		}
-		
-		// find first element node within the plist
-		xmlNode* cur=root->children;
-		while(cur!=NULL && cur->type!=XML_ELEMENT_NODE)
-			cur=cur->next;
-		if(cur==NULL) //empty plist
-			cur = xmlNewChild(root,NULL,(const xmlChar*)"",NULL);
-		return cur;
-	}
-	
-	int ObjectBase::xStrEqual(const xChar* a, const xChar* b) {
-		return xmlStrEqual(a,b);
-	}
-	int ObjectBase::xStrCaseEqual(const xChar* a, const xChar* b) {
-		return !xmlStrcasecmp(a,b);
-	}
-	ObjectBase::xChar* ObjectBase::xNodeGetContent(xmlNode* node) {
-		return xmlNodeGetContent(node);
-	}
-	void ObjectBase::xNodeSetContent(xmlNode* node, const xChar* content) {
-		xmlNodeSetContent(node,content);
-	}
-	const ObjectBase::xChar* ObjectBase::xNodeGetName(xmlNode* node) {
-		return node->name;
-	}
-	bool ObjectBase::xNodeHasName(xmlNode* node, const char* name) {
-		return xmlStrEqual(node->name,(const xmlChar*)name);
-	}
-	void ObjectBase::xNodeSetName(xmlNode* node, const xChar* name) {
-		xmlNodeSetName(node,name);
-	}
-	xmlAttr* ObjectBase::xHasProperty(xmlNode* node, const xChar* name) {
-		return xmlHasProp(node,name);
-	}
-	ObjectBase::xChar* ObjectBase::xGetProperty(xmlNode* node, const xChar* name) {
-		return xmlGetProp(node,name);
-	}
-	long ObjectBase::xGetLineNo(xmlNode* node) {
-		return xmlGetLineNo(node);
-	}
-	void ObjectBase::xFree(void* ptr) {
-		xmlFree(ptr);
-	}
-
-	Dictionary::~Dictionary() {
-		delete dictionaryListeners;
-		dictionaryListeners=NULL;
-	}
-
-	void Dictionary::addEntry(const std::string& name, ObjectBase& val) {
-		dict_t::iterator it=dict.find(name);
-		if(it!=dict.end()) {
-			cerr << "Warning: addEntry("<<name<<","<<val<<") conflicts with previous addEntry("<<name<<","<<val<<")"<<endl;
-			cerr << "         (use setEntry() if you expect you might need to overwrite)" << endl;
-			it->second=&val;
-			return;
-		}
-		dict[name]=&val;
-	}
-
-	void Dictionary::addEntry(const std::string& name, ObjectBase& val, const std::string& comment) {
-		comments[name]=comment;
-		dict_t::iterator it=dict.find(name);
-		if(it!=dict.end()) {
-			cerr << "Warning: addEntry("<<name<<","<<val<<") conflicts with previous addEntry("<<name<<","<<val<<")"<<endl;
-			cerr << "         (use setEntry() if you expect you might need to overwrite)" << endl;
-			it->second=&val;
-			return;
-		}
-		dict[name]=&val;
-	}
-	
-	const std::string& Dictionary::getComment(const std::string& name) const {
-		comments_t::const_iterator it=comments.find(name);
-		static const std::string empty;
-		return (it!=comments.end()) ? it->second : empty;
-	}
-
-	ObjectBase* Dictionary::findEntry(const std::string& name) const {
-		//do we have a key with this name?
-		dict_t::const_iterator it=dict.find(name);
-		if(it!=dict.end())
-			return it->second; //yes, return it
-		
-		//perhaps there's a sub-dictionary, separated by '.'
-		size_t p=name.find(".");
-		if(p==string::npos)
-			return NULL; //no, '.'s found -- go away
-		it=dict.find(name.substr(0,p));
-		if(it==dict.end())
-			return NULL; //no entry matching prefix -- go away
-		const Dictionary* d=dynamic_cast<const Dictionary*>(it->second);
-		if(d==NULL)
-			return NULL; //matching prefix is not a dictionary -- go away
-		
-		//found a matching sub-dictionary, have it find the rest recursively
-		return d->findEntry(name.substr(p+1));
-	}
-
-	void Dictionary::LoadXML(xmlNode* node) {
-		//check if our node has been set to NULL (invalid or not found)
-		if(node==NULL)
-			return;
-		
-		std::string comment;
-		
-		//process children nodes
-		for(xmlNode* cur = skipToElement(node->children,comment); cur!=NULL; cur = skipToElement(cur->next,comment)) {
-						
-			//find the next key node
-			xmlNode * k=cur;
-			if(xmlStrcmp(k->name, (const xmlChar *)"key"))
-				throw bad_format(k,"Dictionary format error: expect data in pairs of key and value (two values found in a row)");
-			cur=skipToElement(cur->next);
-			
-			//find the following value (non-key) node
-			xmlNode * v=cur;
-			if(v==NULL)
-				throw bad_format(cur,"Dictionary format error: expect data in pairs of key and value (dictionary ended with hanging key)");
-			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;
-			xmlFree(cont);
-			dict_t::const_iterator it=dict.find(key);
-			if(it==dict.end()) {
-				if(warnUnused)
-					cerr << "Warning: reading plist dictionary, key '" << key << "' does not match a registered variable.  Ignoring..." << endl;
-				continue;
-			}
-			if(comment.size()!=0)
-				setComment(key,comment);
-			it->second->LoadXML(v);
-		}
-	}
-	
-	void Dictionary::SaveXML(xmlNode* node) const {
-		//check if our node has been set to NULL (invalid or not found)
-		if(node==NULL)
-			return;
-		
-		//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
-		dict_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;
-		}
-		
-		//This will hold any comments found between elements -- if no comment is found, a new one may be added
-		std::string comment;
-
-		//process children nodes
-		for(xmlNode* cur = skipToElement(node->children,comment); cur!=NULL; cur = skipToElement(cur->next,comment)) {
-			
-			//find the next key node
-			xmlNode * k=cur;
-			if(xmlStrcmp(k->name, (const xmlChar *)"key"))
-				throw bad_format(k,"Dictionary format error: expect data in pairs of key and value (two values found in a row)");
-			cur=skipToElement(cur->next);
-			
-			//find the following value (non-key) node
-			xmlNode * v=cur;
-			if(v==NULL)
-				throw bad_format(cur,"Dictionary format error: expect data in pairs of key and value (dictionary ended with hanging key)");
-			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;
-			xmlFree(cont);
-			dict_t::const_iterator it=dict.find(key);
-			if(it==dict.end()) {
-				if(warnUnused)
-					cerr << "Warning: reading plist dictionary, key '" << key << "' does not match a registered variable.  Ignoring..." << endl;
-				continue;
-			}
-			if(comment.size()==0) {
-				bool isSub=dynamic_cast<Dictionary*>(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);
-		}
-
-		if(seen.size()!=dict.size()) {
-			// 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(dict_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<Dictionary*>(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);
-				}
-			}
-		}
-	}
-
-	unsigned int Dictionary::getLongestKeyLen() const {
-		size_t longest=0;
-		for(Dictionary::dict_t::const_iterator it=dict.begin(); it!=dict.end(); ++it) {
-			size_t cur=it->first.size();
-			if(Dictionary* dp=dynamic_cast<Dictionary*>(it->second))
-				cur+=dp->getLongestKeyLen()+1;
-			longest=std::max(longest,cur);
-		}
-		return longest;
+		obj->loadXML(node);
+		return obj;
 	}
 	
-	void Dictionary::addDictionaryListener(DictionaryListener* vl) {
-		if(vl!=NULL) {
-			if(dictionaryListeners==NULL)
-				dictionaryListeners=new std::list<DictionaryListener*>;
-			dictionaryListeners->push_back(vl);
-		}
-	}
-		
-	void Dictionary::removeDictionaryListener(DictionaryListener* vl) {
-		if(dictionaryListeners==NULL)
-			return;
-		std::list<DictionaryListener*>::iterator it=find(dictionaryListeners->begin(),dictionaryListeners->end(),vl);
-		if(it!=dictionaryListeners->end()) {
-			dictionaryListeners->erase(it);
-			if(dictionaryListeners->empty()) {
-				delete dictionaryListeners;
-				dictionaryListeners=NULL;
-			}
-		}
-	}
+	//! allows us to use the LoadSave suite for loading and parsing general XML functions, but forwards loadXML to plist::loadXML() and stores the result as a member
+	class PolymorphicLoader : public XMLLoadSave {
+	public:
+		PolymorphicLoader() : XMLLoadSave(), obj(NULL) {} //!< constructor
+		virtual ~PolymorphicLoader() {} //!< destructor
+		PolymorphicLoader(const PolymorphicLoader& p) : XMLLoadSave(p), obj(NULL) {} //!< copy constructor -- doesn't copy #obj, sets the local instance to NULL
+		PolymorphicLoader& operator=(const PolymorphicLoader& p) { XMLLoadSave::operator=(p); return *this; } //!< copy constructor -- doesn't copy #obj, keeps current value of #obj
+		virtual void loadXML(xmlNode* node) { obj=plist::loadXML(node); } //!< forward call to the static plist implementation
+		virtual void saveXML(xmlNode * /*node*/) const {*(int*)NULL=0xDEADDEAD;} //!< shouldn't ever be called -- call saveXML() on #obj directly
+		ObjectBase * obj; //!< storage of results from loadXML
+	};
 	
-	void Dictionary::fireEntryAdded(ObjectBase& val) {
-		if(dictionaryListeners==NULL)
-			return;
-		std::list<DictionaryListener*>::iterator it=dictionaryListeners->begin();
-		while(it!=dictionaryListeners->end()) {
-			std::list<DictionaryListener*>::iterator cur=it++; //increment early in case the listener changes subscription
-			(*cur)->plistDictionaryEntryAdded(*this,val);
-		}
-	}
-
-	void Dictionary::fireEntryRemoved(ObjectBase& val) {
-		if(dictionaryListeners==NULL)
-			return;
-		std::list<DictionaryListener*>::iterator it=dictionaryListeners->begin();
-		while(it!=dictionaryListeners->end()) {
-			std::list<DictionaryListener*>::iterator cur=it++; //increment early in case the listener changes subscription
-			(*cur)->plistDictionaryEntryRemoved(*this,val);
-		}
-	}
-
-	std::ostream& operator<<(std::ostream& os, const Dictionary& d) {
-		unsigned int longest=std::max(d.getLongestKeyLen(),static_cast<unsigned int>(os.width()));
-		for(Dictionary::dict_t::const_iterator it=d.dict.begin(); it!=d.dict.end(); ++it)
-			if(Dictionary* dp=dynamic_cast<Dictionary*>(it->second)) {
-				stringstream ss;
-				ss << setw(longest-it->first.size()-1) << *dp;
-				string line;
-				for(getline(ss,line); ss; getline(ss,line))
-					os << it->first << "." << line << endl;
-			} else {
-				os << left << setw(longest) << it->first << " = " << *it->second << endl;
-			}
-		return os;
+	ObjectBase* loadFile(const std::string& file) {
+		PolymorphicLoader loader;
+		if(!loader.loadFile(file.c_str()))
+			return NULL;
+		return loader.obj;
 	}
 	
-	PrimitiveBase::~PrimitiveBase() {
-		delete primitiveListeners;
-		primitiveListeners=NULL;
-	}
-
-	void PrimitiveBase::addPrimitiveListener(PrimitiveListener* vl) {
-		if(vl!=NULL) {
-			if(primitiveListeners==NULL)
-				primitiveListeners=new std::list<PrimitiveListener*>;
-			primitiveListeners->push_back(vl);
-		}
-	}
-	void PrimitiveBase::removePrimitiveListener(PrimitiveListener* vl) {
-		if(primitiveListeners==NULL)
-			return;
-		std::list<PrimitiveListener*>::iterator it=find(primitiveListeners->begin(),primitiveListeners->end(),vl);
-		if(it!=primitiveListeners->end()) {
-			primitiveListeners->erase(it);
-			if(primitiveListeners->empty()) {
-				delete primitiveListeners;
-				primitiveListeners=NULL;
-			}
-		}
-	}
-	void PrimitiveBase::fireValueChanged() 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);
-		}
+	ObjectBase* loadBuffer(const char* buf, unsigned int len) {
+		PolymorphicLoader loader;
+		if(!loader.loadBuffer(buf,len))
+			return NULL;
+		return loader.obj;
 	}
 	
 } //namespace plist
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/plist.h ./Shared/plist.h
--- ../Tekkotsu_2.4.1/Shared/plist.h	2005-08-07 00:11:04.000000000 -0400
+++ ./Shared/plist.h	2006-09-09 00:33:02.000000000 -0400
@@ -2,729 +2,31 @@
 #ifndef INCLUDED_PListSupport_h_
 #define INCLUDED_PListSupport_h_
 
-/*
- From: <!DOCTYPE plist PUBLIC "-//Apple Computer//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;>
-<!ATTLIST plist version CDATA "1.0" >
-
-<!-- Collections -->
-<!ELEMENT array (%plistObject;)*>
-<!ELEMENT dict (key, %plistObject;)*>
-<!ELEMENT key (#PCDATA)>
-
-<!--- Primitive types -->
-<!ELEMENT string (#PCDATA)>
-<!ELEMENT data (#PCDATA)> <!-- Contents interpreted as Base-64 encoded -->
-<!ELEMENT date (#PCDATA)> <!-- Contents should conform to a subset of ISO 8601 (in particular, YYYY '-' MM '-' DD 'T' HH ':' MM ':' SS 'Z'.  Smaller units may be omitted with a loss of precision) -->
-
-<!-- Numerical primitives -->
-<!ELEMENT true EMPTY>  <!-- Boolean constant true -->
-<!ELEMENT false EMPTY> <!-- Boolean constant false -->
-<!ELEMENT real (#PCDATA)> <!-- Contents should represent a floating point number matching ("+" | "-")? d+ ("."d*)? ("E" ("+" | "-") d+)? where d is a digit 0-9.  -->
-<!ELEMENT integer (#PCDATA)> <!-- Contents should represent a (possibly signed) integer number in base 10 -->
-*/
-
-#include "XMLLoadSave.h"
-#include <exception>
-#include <string>
-#include <iostream>
-#include <iomanip>
-#include <sstream>
-#include <map>
-#include <list>
+#include "plistBase.h"
+#include "plistPrimitives.h"
+#include "plistCollections.h"
 
-//! A collection of classes to implement the Propery List data storage format, a XML standard used by Apple and others
 namespace plist {
 	
-	//! Base class for the plist listener callbacks
-	class Listener {
-	public:
-		//! destructor
-		virtual ~Listener() {}
-	};
-	
-	class PrimitiveBase;
-	//! If you wish to be notified any time a particular plist primitive's value has been changed, inherit from this and implement the callback, then register it with the plist object through Primitive::addPrimitiveListener()
-	class PrimitiveListener : public Listener {
-	public:
-		//! This will be called whenever a plist you have registered with is changed
-		/*! @a pl is const to help you avoid infinite recursion from an
-		 *  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;
-	};
-	
-	class ObjectBase;
-	class Dictionary;
-	//! If you wish to be notified any time an entry is added or removed from a Dictionary, inherit from this and implement one or both of the functions, then register it with the dictionary's Dictionary::addDictionaryListener()
-	class DictionaryListener : public Listener {
-	public:
-		//! This will be called whenever an entry is added to the dictionary
-		virtual void plistDictionaryEntryAdded(Dictionary& /*dict*/, ObjectBase& /*primitive*/) {}
-		//! This will be called whenever an entry is added to the dictionary
-		virtual void plistDictionaryEntryRemoved(Dictionary& /*dict*/, ObjectBase& /*primitive*/) {}
-	};
-	
-	//! 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. */
-	class ObjectBase : public XMLLoadSave {
-	public:
-		ObjectBase(); //!< constructor
-		virtual ~ObjectBase()=0; //!< destructor
-		
-	protected:
-		//!@name Inherited from XMLLoadSave
-		virtual void setParseTree(xmlDoc * doc) const;
-		virtual xmlNode* FindRootXMLElement(xmlDoc* doc) const;
-		//@}
-		
-		//!Provides indirect access to the libxml function of the same name
-		//!@name libxml Forwards
-		typedef unsigned char xChar;
-		static int xStrEqual(const xChar* a, const xChar* b);
-		static int xStrCaseEqual(const xChar* a, const xChar* b);
-		static xChar* xNodeGetContent(xmlNode* node);
-		static void xNodeSetContent(xmlNode* node, const xChar* content);
-		static const xChar* xNodeGetName(xmlNode* node);
-		static bool xNodeHasName(xmlNode* node, const char* name);
-		static void xNodeSetName(xmlNode* node, const xChar* name);
-		static xmlAttr* xHasProperty(xmlNode* node, const xChar* name);
-		static xChar* xGetProperty(xmlNode* node, const xChar* name);
-		static long xGetLineNo(xmlNode* node);
-		static void xFree(void* ptr);
-		//@}
-	};
-	
-	//! 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
-	 *  DictionaryListener 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 ObjectBase {
-		friend std::ostream& operator<<(std::ostream& os, const Dictionary& d);
-	public:
-		//! constructor
-		Dictionary() : ObjectBase(), dictionaryListeners(), warnUnused(true), dict(), comments() {autoFormat=false;}
-		//! copy constructor (don't assign listeners)
-		Dictionary(const Dictionary& d) : ObjectBase(d), dictionaryListeners(), warnUnused(d.warnUnused), dict(d.dict), comments(d.comments) {}
-		//! assignment (don't assign listeners)
-		Dictionary& operator=(const Dictionary& d) { if(&d==this) return *this; ObjectBase::operator=(d); warnUnused=d.warnUnused; dict=d.dict; comments=d.comments; return *this; }
-		//! destructor
-		virtual ~Dictionary();
-		
-		//! 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)
-		void addEntry(const std::string& name, ObjectBase& val);
-		//! 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)
-		void addEntry(const std::string& name, ObjectBase& val, const std::string& comment);
-		//! replaces previous entry of the same name, or adds it if it doesn't exist; use addEntry if you want to assert that the name does not already exist
-		void setEntry(const std::string& name, ObjectBase& val) { dict[name]=&val; }
-		//! 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) { comments[name]=comment; }
-		//! returns comment retrieved from loaded file, or any subsequent call to setComment
-		const std::string& getComment(const std::string& name) const;
-		//! remove the entry with key @a name
-		void removeEntry(const std::string& name) { dict.erase(name); }
-		//! return the value of the key @a name, or NULL if it doesn't exist
-		ObjectBase* findEntry(const std::string& name) const;
-		
-		void LoadXML(xmlNode* node);
-		void SaveXML(xmlNode* node) const;
-		
-		void setUnusedWarning(bool b) { warnUnused=b; } //!< set #warnUnused
-		bool getUnusedWarning() { return warnUnused; } //!< returns #warnUnused
-
-		//! get notified of changes; be sure to call removeValueListener before destructing @a vl!
-		virtual void addDictionaryListener(DictionaryListener* vl);
-		//! no longer take notification of changes to this object's value
-		virtual void removeDictionaryListener(DictionaryListener* vl);
-		
-	protected:
-		//! run through #dictionaryListeners, calling DictionaryListener::plistDictionaryEntryAdded(*this,val)
-		virtual void fireEntryAdded(ObjectBase& val);
-		//! run through #dictionaryListeners, calling DictionaryListener::plistDictionaryEntryRemoved(*this,val)
-		virtual void fireEntryRemoved(ObjectBase& val);
-		//! stores a list of the current listeners
-		std::list<DictionaryListener*>* dictionaryListeners;
-
-		//! return the length of the longest key for formatting purposes
-		unsigned int getLongestKeyLen() const;
-		//! if true (the default) LoadXML will give warnings if there are unused entries in the node it is passed
-		bool warnUnused;
-
-		//! shorthand for the type of #dict
-		typedef std::map<std::string,ObjectBase*> dict_t;
-		//! storage of entries -- mapping from keys to value pointers
-		dict_t dict;
-
-		//! shorthand for the type of #comments
-		typedef std::map<std::string,std::string> comments_t;
-		//! storage of entry comments -- mapping from keys to help text comments for manual editing or user feedback
-		/*! not every key necessarily has a comment! */
-		comments_t comments;
-	};
-	//! provides textual output
-	std::ostream& operator<<(std::ostream& os, const Dictionary& d);
-
-
-	//! 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
-	 *  PrimitiveListener 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) */
-	class PrimitiveBase : public ObjectBase {
-	public:
-		//! constructor
-		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); return *this; }
-		//! destructor
-		~PrimitiveBase();
-		
-		//! assign a new value
-		virtual void set(const std::string& str)=0;
-		//! return current value as a string
-		virtual std::string get() const=0;
-
-		//! get notified of changes; be sure to call removeValueListener before destructing @a vl!
-		virtual void addPrimitiveListener(PrimitiveListener* vl);
-		//! no longer take notification of changes to this object's value
-		virtual void removePrimitiveListener(PrimitiveListener* vl);
-
-	protected:
-		//! run through #primitiveListeners, calling PrimitiveListener::plistValueChanged(*this)
-		virtual void fireValueChanged() const;
-		//! stores a list of the current listeners
-		std::list<PrimitiveListener*>* primitiveListeners;
-	};
-	//! output stringified value (from PrimitiveBase::get()) to stream
-	inline std::ostream& operator<<(std::ostream& os, const PrimitiveBase& pb) {
-		return os << pb.get();
-	}
-	//! input value from next word in @a is, via PrimitiveBase::set()
-	inline std::istream& operator>>(std::istream& is, PrimitiveBase& pb) {
-		std::string s;
-		is >> s;
-		pb.set(s);
-		return is;
-	}
-	
-
-	//! 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
-	 *  to and from the value type so you can almost always treat
-	 *  the Primitive as if it was the value itself. */
-	template<typename T>
-	class Primitive : public PrimitiveBase {
-	public:
-		Primitive() : ObjectBase(), val() {} //!< constructor
-		Primitive(const T& v) : ObjectBase(), val(v) {} //!< constructor, automatic casting from the value type
-		Primitive& operator=(const T& v) { val=v; fireValueChanged(); return *this; } //!< assignment
-		//T& operator*() { return val; } //!< access value -- if #val is modified, this won't know, so PrimitiveListeners are going to be clueless
-		const T& operator*() const { return val; } //!< smart pointer access to value
-		//T* operator->() { return &val; } //!< smart pointer access to value -- if #val is modified, this won't know, so PrimitiveListeners are going to be clueless
-		const T* operator->() const { return &val; } //!< smart pointer access to value
-		operator T() const { return val; } //!< automatic casting to the value type
-/*		void LoadXML(xmlNode* node) {
-			if(node==NULL)
-				return;
-			//decode base64 from xml node
-			//val->LoadBuffer(buf,bufsize);
-			fireValueChanged(); 
-		}
-		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;
-		}*/
-	protected:
-		T val; //!< value storage
-	};
-
-	//! provides a @c bool specialization of Primitive<T>
-	/*! A @c bool can be treated as either a string or an integer\n
-	 *  When saving, "true" or "false" will be used, but users could
-	 *  also specify "yes"/"no" or "on"/"off".  If an integer is used,
-	 *  it will be interpreted as usual: 0==false, otherwise true. */
-	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
-		//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) {
-			if(node==NULL)
-				return;
-			if(xNodeHasName(node,"true")) {
-				val=true;
-				fireValueChanged(); 
-			} else if(xNodeHasName(node,"false")) {
-				val=false;
-				fireValueChanged(); 
-			} else if(xNodeHasName(node,"integer") || xNodeHasName(node,"real")) {
-				xChar * cont=xNodeGetContent(node);
-				std::stringstream str((char*)cont);
-				str >> val;
-				xFree(cont);
-				fireValueChanged(); 
-			} else if(xNodeHasName(node,"string")) {
-				xChar * cont=xNodeGetContent(node);
-				try {
-					set((char*)cont);
-					std::cerr << "Warning: plist boolean expects value of '<true/>', '<false/>', or numeric.  String value of '" << (char*)cont << "' is not recommended." << std::endl;
-				} catch(const bad_format& err) {
-					xFree(cont);
-					throw bad_format(node,err.what());
-				} catch(...) {
-					xFree(cont);
-					throw;
-				}
-				xFree(cont);
-			} else
-				throw bad_format(node,"Error: plist boolean must be 'true', 'false', or numeric type");
-		}
-		void SaveXML(xmlNode* node) const {
-			if(node==NULL)
-				return;
-			xNodeSetName(node,(const xChar*)(val?"true":"false"));
-			xNodeSetContent(node,NULL);
-		}
-		void set(const std::string& str) {
-			if(str=="true" || str=="yes" || str=="on")
-				val=true;
-			else if(str=="false" || str=="no" || str=="off")
-				val=false;
-			else {
-				float t;
-				if(sscanf(str.c_str(),"%g",&t)==0)
-					throw bad_format(NULL,"Error: plist boolean must be 'true', 'false', or numeric type");
-				val=t;
-			}
-			fireValueChanged(); 
-		}
-		std::string get() const {
-			return val?"true":"false";
-		}
-	protected:
-		bool val; //!< the actual data storage
-	};
-
-	//! provides a @c char specialization of Primitive<T>
-	/*! A @c char can be treated as either a string or an integer, you can use
-	 *  the setNumeric(bool) function to indicate which style to use when saving */
-	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
-		//char& operator*() { return val; }
-		const char& operator*() const { return val; } //!< dereference will return data storage
-		//char* operator->() { return &val; }
-		const char* operator->() const { return &val; } //!< can use -> to access members of data storage
-		operator char() const { return val; } //!< casting operator
-		void setNumeric(bool isNum) { numeric=isNum; } //!< sets #numeric
-		bool getNumeric() const { return numeric; } //!< returns #numeric
-		void LoadXML(xmlNode* node) {
-			if(node==NULL)
-				return;
-			xChar* cont=xNodeGetContent(node);
-			try {
-				if(xNodeHasName(node,"string")) {
-					set((char*)cont);
-				} else if(xNodeHasName(node,"integer")) {
-					val=strtol((const char*)cont,NULL,0);
-					fireValueChanged(); 
-				} else if(xNodeHasName(node,"real")) {
-					val=(char)strtod((const char*)cont,NULL);
-					fireValueChanged(); 
-				} else if(xNodeHasName(node,"true")) {
-					val=true;
-					fireValueChanged(); 
-				} else if(xNodeHasName(node,"false")) {
-					val=false;
-					fireValueChanged(); 
-				} else {
-					throw bad_format(node,"Error: plist char must be either a string or integer");
-				} 
-			} catch(const bad_format& err) {
-				xFree(cont);
-				throw bad_format(node,err.what());
-			} catch(...) {
-				xFree(cont);
-				throw;
-			}
-			xFree(cont);
-		}
-		void SaveXML(xmlNode* node) const {
-			if(node==NULL)
-				return;
-			if(numeric) {
-				xNodeSetName(node,(const xChar*)"integer");
-				std::stringstream str;
-				str << (int)val;
-				xNodeSetContent(node,(const xChar*)str.str().c_str());
-			} else {
-				xNodeSetName(node,(const xChar*)"string");
-				xChar str[2] = {val,'\0'};
-				xNodeSetContent(node,(const xChar*)str);
-			}
-		}
-		void set(const std::string& str) {
-			if(str.size()==0)
-				throw bad_format(NULL,"Error: plist char must have non-empty content");
-			val=str[0];
-			if(str.size()!=1)
-				std::cerr << "Warning: plist expected single char, found multi-char string '" << str << "'" << std::endl;
-			fireValueChanged(); 
-		}
-		std::string get() const {
-			return std::string(1,val);
-		}
-	protected:
-		char val; //!< data storage
-		bool numeric; //!< if true, requests that saves store the numeric value instead of corresponding character
-	};
-	
-	//! provides an @c unsigned @c char specialization of Primitive<T>
-	/*! A @c char can be treated as either a string or an integer, you can use
-	 *  the setNumeric(bool) function to indicate which style to use when saving */
-	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
-		//unsigned char& operator*() { return val; }
-		const unsigned char& operator*() const { return val; } //!< dereference will return data storage
-		//unsigned char* operator->() { return &val; }
-		const unsigned char* operator->() const { return &val; } //!< can use -> to access members of data storage
-		operator unsigned char() const { return val; } //!< casting operator
-		void setNumeric(bool isNum) { numeric=isNum; } //!< sets #numeric
-		bool getNumeric() const { return numeric; } //!< returns #numeric
-		void LoadXML(xmlNode* node) {
-			if(node==NULL)
-				return;
-			xChar* cont=xNodeGetContent(node);
-			try {
-				if(xNodeHasName(node,"string")) {
-					set((char*)cont);
-				} else if(xNodeHasName(node,"integer")) {
-					val=strtol((const char*)cont,NULL,0);
-					fireValueChanged(); 
-				} else if(xNodeHasName(node,"real")) {
-					val=(char)strtod((const char*)cont,NULL);
-					fireValueChanged(); 
-				} else if(xNodeHasName(node,"true")) {
-					val=true;
-					fireValueChanged(); 
-				} else if(xNodeHasName(node,"false")) {
-					val=false;
-					fireValueChanged(); 
-				} else {
-					throw bad_format(node,"Error: plist unsigned char must be either a string or integer");
-				} 
-			} catch(const bad_format& err) {
-				xFree(cont);
-				throw bad_format(node,err.what());
-			} catch(...) {
-				xFree(cont);
-				throw;
-			}
-			xFree(cont);
-		}
-		void SaveXML(xmlNode* node) const {
-			if(node==NULL)
-				return;
-			if(numeric) {
-				xNodeSetName(node,(const xChar*)"integer");
-				std::stringstream str;
-				str << (int)val;
-				xNodeSetContent(node,(const xChar*)str.str().c_str());
-			} else {
-				xNodeSetName(node,(const xChar*)"string");
-				xChar str[2] = {val,'\0'};
-				xNodeSetContent(node,(const xChar*)str);
-			}
-		}
-		void set(const std::string& str) {
-			if(str.size()==0)
-				throw bad_format(NULL,"Error: plist char must have non-empty content");
-			val=str[0];
-			if(str.size()!=1)
-				std::cerr << "Warning: plist expected single char, found multi-char string '" << str << "'" << std::endl;
-		}
-		std::string get() const {
-			return std::string(1,val);
-		}
-	protected:
-		unsigned char val; //!< data storage
-		bool numeric; //!< if true, requests that saves store the numeric value instead of corresponding character
-	};
-
-	
-//! 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: \
-		Primitive() : PrimitiveBase(), val() {} \
-		Primitive(const T& v) : PrimitiveBase(), val(v) {} \
-		Primitive& operator=(const T& v) { val=v; fireValueChanged(); return *this; } \
-		Primitive& operator+=(const T& v) { val+=v; fireValueChanged(); return *this; } \
-		Primitive& operator-=(const T& v) { val-=v; fireValueChanged(); return *this; } \
-		Primitive& operator*=(const T& v) { val*=v; fireValueChanged(); return *this; } \
-		Primitive& operator/=(const T& v) { val/=v; fireValueChanged(); return *this; } \
-		/*T& operator*() { return val; }*/ \
-		const T& operator*() const { return val; } \
-		/*T* operator->() { return &val; }*/ \
-		const T* operator->() const { return &val; } \
-		operator T() const { return val; } \
-		void 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 " << xGetLineNo(node) << ")" << std::endl; \
-			if(bt) \
-				val = true; \
-			else if(bf) \
-				val = false; \
-			else { \
-				xChar * cont=xNodeGetContent(node); \
-				std::stringstream str((const char*)cont); \
-				str >> val; \
-				xFree(cont); \
-			} \
-			fireValueChanged(); \
-		} \
-		void SaveXML(xmlNode* node) const { \
-			if(node==NULL) \
-				return; \
-			xNodeSetName(node,(const xChar*)PRIM); \
-			std::stringstream str; \
-			str <<std::setprecision(128)<< val; \
-			xNodeSetContent(node,(const xChar*)str.str().c_str()); \
-		} \
-		void set(const std::string& str) { \
-			std::stringstream sstr(str); \
-			sstr >> val; \
-			fireValueChanged(); \
-		} \
-		std::string get() const { \
-			std::stringstream sstr; \
-			sstr <<std::setprecision(128)<< val; \
-			return sstr.str(); \
-		} \
-	protected: \
-		T val; \
-	}
-	
-	PLIST_OBJECT_SPECIALIZATION(short,"integer"); //!< short instance of PrimitiveBase ("integer")
-	PLIST_OBJECT_SPECIALIZATION(unsigned short,"integer"); //!< unsigned short instance of PrimitiveBase ("integer")
-	PLIST_OBJECT_SPECIALIZATION(int,"integer"); //!< int instance of PrimitiveBase ("integer")
-	PLIST_OBJECT_SPECIALIZATION(unsigned int,"integer"); //!< unsigned int instance of PrimitiveBase ("integer")
-	PLIST_OBJECT_SPECIALIZATION(long,"integer"); //!< long instance of PrimitiveBase ("integer")
-	PLIST_OBJECT_SPECIALIZATION(unsigned long,"integer"); //!< unsigned long instance of PrimitiveBase ("integer")
-	PLIST_OBJECT_SPECIALIZATION(long long,"integer"); //!< long long instance of PrimitiveBase ("integer")
-	PLIST_OBJECT_SPECIALIZATION(unsigned long long,"integer"); //!< unsigned long long instance of PrimitiveBase ("integer")
-	PLIST_OBJECT_SPECIALIZATION(float,"real"); //!< float instance of PrimitiveBase ("real")
-	PLIST_OBJECT_SPECIALIZATION(double,"real"); //!< double instance of PrimitiveBase ("real")
-
-	//! 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& operator=(const std::string& v) { std::string::operator=(v); fireValueChanged(); return *this; } //!< assignment
-		//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; }
-		const std::string* operator->() const { return this; } //!< returns a pointer to this (for uniformity with the other Primitives, although unnecessary with this instantiation)
-		//no casting operator because we subclass string
-		void LoadXML(xmlNode* node) {
-			if(node==NULL)
-				return;
-			if(xNodeHasName(node,"string")) {
-				xChar * cont=xNodeGetContent(node);
-				*this=(char*)cont;
-				xFree(cont);
-			} else {
-				if(xNodeHasName(node,"integer") || xNodeHasName(node,"real")) {
-					xChar * cont=xNodeGetContent(node);
-					*this=(char*)cont;
-					xFree(cont);
-				} else if(xNodeHasName(node,"true"))
-					*this="true";
-				else if(xNodeHasName(node,"false"))
-					*this="false";
-				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 " << xGetLineNo(node) << std::endl;
-				fireValueChanged(); 
-			}
-		}
-		void SaveXML(xmlNode* node) const {
-			if(node==NULL)
-				return;
-			xNodeSetName(node,(const xChar*)"string");
-			xNodeSetContent(node,(const xChar*)c_str());
-		}
-		void set(const std::string& str) {
-			*this=str;
-			fireValueChanged(); 
-		}
-		std::string get() const {
-			return *this;
-		}
-	};
+	//! From the name of @a node, will instantiate a new ObjectBase subclass to load it
+	/*! The mapping from node names to actual instantiated types is: 
+	 *    - 'array' -> Vector
+	 *    - 'dict' -> Map
+	 *    - 'real' -> Primitive<double>
+	 *    - 'integer' -> Primitive<long>
+	 *    - 'string' -> Primitive<std::string>
+	 *    - 'true', 'false' -> Primitive<bool>
+	 *  
+	 *  If successful, returns a pointer to a newly allocated region, which the caller is
+	 *  responsible for freeing.  If an error occurs, NULL is returned.
+	 */
+	ObjectBase* loadXML(xmlNode* node);
 	
-	//! 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 */
-	template<typename T> 
-	class NamedEnumeration : public PrimitiveBase {
-	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)
-		NamedEnumeration& operator=(const std::string& v) { set(v); return *this; } //!< assignment from string
-		NamedEnumeration& operator=(const NamedEnumeration& ne) { PrimitiveBase::operator=(ne); val=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()
-
-		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;
-			} else if(xNodeHasName(node,"integer") || xNodeHasName(node,"real") || xNodeHasName(node,"string")) {
-				xChar * cont=xNodeGetContent(node);
-				try {
-					set((char*)cont);
-				} catch(const bad_format& err) {
-					xFree(cont);
-					throw bad_format(node,err.what());
-				} catch(...) {
-					xFree(cont);
-					throw;
-				}
-				xFree(cont);
-			} else
-				throw bad_format(node,"Error: plist NamedEnumeration must be numeric or valid string");
-		}
-		void SaveXML(xmlNode* node) const {
-			if(node==NULL)
-				return;
-			if(names!=NULL && names[val]!=NULL && val>0 && (unsigned int)val<max) {
-				xNodeSetName(node,(const xChar*)"string");
-			} else {
-				xNodeSetName(node,(const xChar*)"integer");
-			}
-			xNodeSetContent(node,(const xChar*)get().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(); 
-		}
-		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();
-		}
-	protected:
-		//! returns the enum corresponding to @a name
-		unsigned int findName(const char* name) {
-			if(name==NULL || names==NULL)
-				return -1U;
-			for(unsigned int i=0; i<max; i++)
-				if(names[i] && strcmp(name,names[i])==0)
-					return i;
-			return -1U;
-		}
-		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
-	};
+	//! Attempts to parse the file found at @a file, using plist::loadXML()
+	ObjectBase* loadFile(const std::string& file);
 	
-	//! output of an ObjectBase to a stream
-	inline std::ostream& operator<<(std::ostream& os, const ObjectBase& pb) {
-		if(const PrimitiveBase * pbp=dynamic_cast<const PrimitiveBase*>(&pb))
-			os << *pbp;
-		else if(const Dictionary * dp=dynamic_cast<const Dictionary*>(&pb))
-			os << *dp;
-		else
-			os << "[Unknown ObjectBase subclass, edit " << __FILE__ << ":" << __LINE__ << "]";
-		return os;
-	}
+	//! Attempts to parse the buffer found at @a buf, using plist::loadXML()
+	ObjectBase* loadBuffer(const char* buf, unsigned int len);
 	
 } //namespace plist
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/plistBase.cc ./Shared/plistBase.cc
--- ../Tekkotsu_2.4.1/Shared/plistBase.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/plistBase.cc	2005-12-22 16:32:28.000000000 -0500
@@ -0,0 +1,135 @@
+#include "plistBase.h"
+#include <libxml/xmlmemory.h>
+#include <libxml/parser.h>
+
+//better to put this here instead of the header
+using namespace std; 
+
+namespace plist {
+	
+	ObjectBase::ObjectBase()
+	: XMLLoadSave()
+	{}
+	
+	ObjectBase::~ObjectBase() {}
+	
+	void ObjectBase::setParseTree(xmlDoc * doc) const {
+		XMLLoadSave::setParseTree(doc);
+		if(xmldocument==NULL)
+			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");
+	}
+	
+	xmlNode* ObjectBase::FindRootXMLElement(xmlDoc* doc) const {
+		if(doc==NULL)
+			return NULL;
+		xmlNode* root=XMLLoadSave::FindRootXMLElement(doc);
+		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"))
+			cerr << "Warning: plist " << filename << "does not carry version number, assuming 1.0" << endl;
+		else {
+			xmlChar* strv=xmlGetProp(root,(const xmlChar*)"version");
+			double version=strtod((const char*)strv,NULL);
+			if(version>1.0)
+				cerr << "WARNING: plist " << filename << "is version " << strv << ", this software only knows 1.0.  Trying anyway..." << endl;
+			if(version==0)
+				cerr << "WARNING: plist " << filename << "seems to have invalid version '" << strv << "', this software only knows 1.0.  Trying anyway..." << endl;
+			xmlFree(strv);
+		}
+		
+		// find first element node within the plist
+		xmlNode* cur=root->children;
+		while(cur!=NULL && cur->type!=XML_ELEMENT_NODE)
+			cur=cur->next;
+		if(cur==NULL) //empty plist
+			cur = xmlNewChild(root,NULL,(const xmlChar*)"",NULL);
+		return cur;
+	}
+	
+	bool ObjectBase::xNodeHasName(xmlNode* node, const char* name) {
+		return xmlStrcasecmp(node->name,(const xmlChar*)name)==0;
+	}
+	const xmlChar* ObjectBase::xNodeGetName(xmlNode* node) {
+		return node->name;
+	}
+	xmlNode* ObjectBase::xNodeGetChildren(xmlNode* node) {
+		return node->children;
+	}
+	xmlNode* ObjectBase::xNodeGetNextNode(xmlNode* node) {
+		return node->next;
+	}
+	xmlNode* ObjectBase::xNodeGetParent(xmlNode* node) {
+		return node->parent;
+	}
+	xmlDoc* ObjectBase::xNodeGetDoc(xmlNode* node) {
+		return node->doc;
+	}
+	
+	
+	PrimitiveBase::~PrimitiveBase() {
+		delete primitiveListeners;
+		primitiveListeners=NULL;
+	}
+	
+	void PrimitiveBase::addPrimitiveListener(PrimitiveListener* vl) {
+		if(vl!=NULL) {
+			if(primitiveListeners==NULL)
+				primitiveListeners=new std::list<PrimitiveListener*>;
+			primitiveListeners->push_back(vl);
+		}
+	}
+	void PrimitiveBase::removePrimitiveListener(PrimitiveListener* vl) {
+		if(primitiveListeners==NULL)
+			return;
+		std::list<PrimitiveListener*>::iterator it=find(primitiveListeners->begin(),primitiveListeners->end(),vl);
+		if(it!=primitiveListeners->end()) {
+			primitiveListeners->erase(it);
+			if(primitiveListeners->empty()) {
+				delete primitiveListeners;
+				primitiveListeners=NULL;
+			}
+		}
+	}
+	bool PrimitiveBase::isPrimitiveListener(PrimitiveListener* vl) {
+		if(vl==NULL)
+			return false;
+		if(primitiveListeners==NULL)
+			return false;
+		std::list<PrimitiveListener*>::iterator it=find(primitiveListeners->begin(),primitiveListeners->end(),vl);
+		return it!=primitiveListeners->end();
+	}
+	void PrimitiveBase::fireValueChanged() 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);
+		}
+	}
+		
+} //namespace plist
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/plistBase.h ./Shared/plistBase.h
--- ../Tekkotsu_2.4.1/Shared/plistBase.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/plistBase.h	2006-09-22 16:29:45.000000000 -0400
@@ -0,0 +1,232 @@
+//-*-c++-*-
+#ifndef INCLUDED_plistBase_h_
+#define INCLUDED_plistBase_h_
+
+#include "XMLLoadSave.h"
+#include "Cloneable.h"
+#include <exception>
+#include <string>
+#include <iostream>
+#include <iomanip>
+#include <sstream>
+#include <list>
+
+/*
+ From: <!DOCTYPE plist PUBLIC "-//Apple Computer//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;>
+ <!ATTLIST plist version CDATA "1.0" >
+ 
+ <!-- Collections -->
+ <!ELEMENT array (%plistObject;)*>
+ <!ELEMENT dict (key, %plistObject;)*>
+ <!ELEMENT key (#PCDATA)>
+ 
+ <!--- Primitive types -->
+ <!ELEMENT string (#PCDATA)>
+ <!ELEMENT data (#PCDATA)> <!-- Contents interpreted as Base-64 encoded -->
+ <!ELEMENT date (#PCDATA)> <!-- Contents should conform to a subset of ISO 8601 (in particular, YYYY '-' MM '-' DD 'T' HH ':' MM ':' SS 'Z'.  Smaller units may be omitted with a loss of precision) -->
+ 
+ <!-- Numerical primitives -->
+ <!ELEMENT true EMPTY>  <!-- Boolean constant true -->
+ <!ELEMENT false EMPTY> <!-- Boolean constant false -->
+ <!ELEMENT real (#PCDATA)> <!-- Contents should represent a floating point number matching ("+" | "-")? d+ ("."d*)? ("E" ("+" | "-") d+)? where d is a digit 0-9.  -->
+ <!ELEMENT integer (#PCDATA)> <!-- Contents should represent a (possibly signed) integer number in base 10 -->
+ */
+
+extern "C" {
+	struct _xmlNode;
+	struct _xmlDoc;
+	struct _xmlAttr;
+	struct _xmlNs;
+	typedef _xmlNode xmlNode; //!< forward declaration of xmlNode to avoid including actual header here
+	typedef _xmlDoc xmlDoc; //!< forward declaration of xmlDoc to avoid including actual header here
+	typedef _xmlAttr xmlAttr; //!< forward declaration of xmlAttr to avoid including actual header here
+	typedef _xmlNs xmlNs; //!< forward declaration of xmlNs to avoid including actual header here
+	typedef unsigned char xmlChar; //!< forward declaration of xmlChar to avoid including actual header here
+}	
+
+//! A collection of classes to implement the Propery List data storage format, a XML standard used by Apple and others
+namespace plist {
+	
+#ifdef PLIST_CLONE_ABS
+#  error PLIST_CLONE_ABS already defined!
+#else
+#  if !defined(__GNUC__) || __GNUC__ > 3 || (__GNUC__ == 3 && (__GNUC_MINOR__ > 3))
+//! defines abstract clone() (=0) using polymorphic return type @a TYPE if supported by current version of gcc, Cloneable otherwise
+#    define PLIST_CLONE_ABS(TYPE)		virtual TYPE* clone() const __attribute__ ((warn_unused_result)) =0;
+#  else
+//! defines abstract clone() (=0) using polymorphic return type @a TYPE if supported by current version of gcc, Cloneable otherwise
+#    define PLIST_CLONE_ABS(TYPE)		virtual Cloneable* clone() const =0;
+#  endif
+#endif
+	
+#ifdef PLIST_CLONE_DEF
+#  error PLIST_CLONE_DEF already defined!
+#else
+#  if !defined(__GNUC__) || __GNUC__ > 3 || (__GNUC__ == 3 && (__GNUC_MINOR__ > 3))
+//! 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 TYPE* clone() const __attribute__ ((warn_unused_result));
+//! 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; }
+#  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; }
+//! 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)
+//! 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)
+#  endif
+#endif
+	
+	//! Base class for the plist listener callbacks
+	class Listener {
+	public:
+		//! destructor
+		virtual ~Listener() {}
+	};
+	
+	class PrimitiveBase;
+	//! If you wish to be notified any time a particular plist primitive's value has been changed, inherit from this and implement the callback, then register it with the plist object through Primitive::addPrimitiveListener()
+	class PrimitiveListener : public Listener {
+	public:
+		//! This will be called whenever a plist you have registered with is changed
+		/*! @a pl is const to help you avoid infinite recursion from an
+		 *  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;
+	};
+	
+	class ObjectBase;
+	class Collection;
+	//! If you wish to be notified any time an entry is added, removed, or replaced from a Dictionary, Array, or Vector, inherit from this and implement one or both of the functions, then register it with the collection's addCollectionListener()
+	class CollectionListener : public Listener {
+	public:
+		//! This will be called whenever an entry is added to the collection
+		virtual void plistCollectionEntryAdded(Collection& /*col*/, ObjectBase& /*primitive*/) {}
+		//! This will be called whenever an entry is added to the collection
+		virtual void plistCollectionEntryRemoved(Collection& /*col*/, ObjectBase& /*primitive*/) {}
+		//! This will be called whenever an entry is replaced, or multiple entries are added/removed at once, such as when an assignment occurs
+		virtual void plistCollectionEntriesChanged(Collection& /*col*/) {}
+	};
+	
+	//! 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. */
+	class ObjectBase : public XMLLoadSave, public Cloneable {
+		friend ObjectBase* loadXML(xmlNode* node);
+	public:
+		ObjectBase(); //!< constructor
+		virtual ~ObjectBase()=0; //!< destructor
+		
+		//! return current value as a string
+		virtual std::string toString() const=0;
+		
+		//! subclasses are expected to provide a working implementation
+		virtual void loadXML(xmlNode* node)=0;
+		//! subclasses are expected to provide a working implementation
+		virtual void saveXML(xmlNode* node) const=0;
+		
+		//! allows a copy to be made of an event, supporting polymorphism
+		PLIST_CLONE_ABS(ObjectBase);
+			
+	protected:
+		//!@name Inherited from XMLLoadSave
+		virtual void setParseTree(xmlDoc * doc) const;
+		virtual xmlNode* FindRootXMLElement(xmlDoc* doc) const;
+		//@}
+		
+		//!Provides accessor functions to struct fields without having to include libxml.h everywhere
+		//!@name libxml Forwards
+		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* xNodeGetNextNode(xmlNode* node); //!< returns next node (sibling) after @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)
+		 //@}
+		
+		//! returns true if @a str is some form of affirmative (e.g. "true" or "yes")
+		static bool matchTrue(const std::string& str) { return str=="true" || str=="yes"; }
+		//! returns true if @a str is some form of negative (e.g. "false" or "no")
+		static bool matchFalse(const std::string& str) { return str=="false" || str=="no"; }
+	};
+	//! output of an ObjectBase to a stream
+	inline std::ostream& operator<<(std::ostream& os, const ObjectBase& pb) {
+		return os << pb.toString();
+	}
+	
+	
+	//! 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
+	 *  PrimitiveListener 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) */
+	class PrimitiveBase : public ObjectBase {
+	public:
+		//! constructor
+		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; }
+		//! destructor
+		~PrimitiveBase();
+		
+		//! assign a new value
+		virtual void set(const std::string& str)=0;
+		//! return current value as a string
+		virtual std::string get() const=0;
+		
+		virtual std::string toString() const { return get(); }
+		
+		//! get notified of changes; be sure to call removeValueListener before destructing @a vl!
+		virtual void addPrimitiveListener(PrimitiveListener* vl);
+		//! no longer take notification of changes to this object's value
+		virtual void removePrimitiveListener(PrimitiveListener* vl);
+		//! test if @a l is currently registered as a listener
+		virtual bool isPrimitiveListener(PrimitiveListener * vl);
+
+	protected:
+		//! run through #primitiveListeners, calling PrimitiveListener::plistValueChanged(*this)
+		virtual void fireValueChanged() const;
+		//! stores a list of the current listeners
+		std::list<PrimitiveListener*>* primitiveListeners;
+	};
+	//! output stringified value (from PrimitiveBase::get()) to stream
+	inline std::ostream& operator<<(std::ostream& os, const PrimitiveBase& pb) {
+		return os << pb.get();
+	}
+	//! input value from next word in @a is, via PrimitiveBase::set()
+	inline std::istream& operator>>(std::istream& is, PrimitiveBase& pb) {
+		std::string s;
+		is >> s;
+		pb.set(s);
+		return is;
+	}
+
+} //namespace plist
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/plistCollections.cc ./Shared/plistCollections.cc
--- ../Tekkotsu_2.4.1/Shared/plistCollections.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/plistCollections.cc	2006-09-16 02:01:41.000000000 -0400
@@ -0,0 +1,1082 @@
+#include "plistCollections.h"
+#include <libxml/xmlmemory.h>
+#include <libxml/parser.h>
+#include <iomanip>
+
+//better to put this here instead of the header
+using namespace std; 
+
+namespace plist {
+
+	Collection::~Collection() {
+		delete collectionListeners;
+		collectionListeners=NULL;
+	}
+	
+	void Collection::addCollectionListener(CollectionListener* l) {
+		if(l!=NULL) {
+			if(collectionListeners==NULL)
+				collectionListeners=new std::list<CollectionListener*>;
+			collectionListeners->push_back(l);
+		}
+	}
+		
+	void Collection::removeCollectionListener(CollectionListener* l) {
+		if(collectionListeners==NULL)
+			return;
+		std::list<CollectionListener*>::iterator it=find(collectionListeners->begin(),collectionListeners->end(),l);
+		if(it!=collectionListeners->end()) {
+			collectionListeners->erase(it);
+			if(collectionListeners->empty()) {
+				delete collectionListeners;
+				collectionListeners=NULL;
+			}
+		}
+	}
+	
+	bool Collection::isCollectionListener(CollectionListener* l) {
+		if(l==NULL)
+			return false;
+		if(collectionListeners==NULL)
+			return false;
+		std::list<CollectionListener*>::iterator it=find(collectionListeners->begin(),collectionListeners->end(),l);
+		return it!=collectionListeners->end();
+	}
+		
+	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);
+		}
+	}
+	
+	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);
+		}
+	}
+	
+	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);
+		}
+	}
+	
+
+
+	
+	
+	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;
+			}
+			//if still here, no sub-collection, fall through to add new entry
+		}
+		dict[name]=&val;
+		fireEntryAdded(val);
+	}
+	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);
+	}
+	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;
+			}
+			//if still here, no sub-collection, fall through to add new entry
+		}
+		dict[name]=val;
+		takeObject(name,val);
+		fireEntryAdded(*val);
+	}
+	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
+				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
+		}
+		dict[name]=val;
+		if(comment.size()>0)
+			comments[name]=comment;
+		takeObject(name,val);
+		fireEntryAdded(*val);
+	}
+	
+	
+	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));
+			}
+		}
+	}
+
+	ObjectBase* Dictionary::getEntry(const std::string& name) const {
+		//do we have a key with this name?
+		const_iterator it=dict.find(name);
+		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));
+		}
+		
+		//got nothin'
+		return NULL;
+	}
+
+	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;
+			}
+		}
+		if(comment.size()>0)
+			comments[name]=comment;
+		else
+			comments.erase(name);
+	}
+
+	const std::string& Dictionary::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));
+			}
+			return emptyStr();
+		}
+	}
+
+	void Dictionary::loadXML(xmlNode* node) {
+		//check if our node has been set to NULL (invalid or not found)
+		if(node==NULL)
+			return;
+		
+		std::string comment;
+		set<std::string> seen;
+		//process children nodes
+		for(xmlNode* cur = skipToElement(node->children,comment); cur!=NULL; cur = skipToElement(cur->next,comment)) {
+						
+			//find the next key node
+			xmlNode * k=cur;
+			if(xmlStrcmp(k->name, (const xmlChar *)"key"))
+				throw bad_format(k,"Dictionary format error: expect data in pairs of key and value (two values found in a row)");
+			cur=skipToElement(cur->next);
+			
+			//find the following value (non-key) node
+			xmlNode * v=cur;
+			if(v==NULL)
+				throw bad_format(cur,"Dictionary format error: expect data in pairs of key and value (dictionary ended with hanging key)");
+			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;
+			xmlFree(cont);
+			seen.insert(key);
+			loadXMLNode(key,v,comment);
+		}
+		if(trimExtraLoad && seen.size()!=size()) {
+			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)
+				removeEntry(*it);
+		}
+	}
+	
+	void Dictionary::saveXML(xmlNode* node) const {
+		//check if our node has been set to NULL (invalid or not found)
+		if(node==NULL)
+			return;
+		
+		//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;
+		}
+		
+		//This will hold any comments found between elements -- if no comment is found, a new one may be added
+		std::string comment;
+
+		//process children nodes
+		xmlNode* prev=node->children;
+		for(xmlNode* cur = skipToElement(node->children,comment); cur!=NULL; cur = skipToElement(cur,comment)) {
+			
+			//find the next key node
+			xmlNode * k=cur;
+			if(xmlStrcmp(k->name, (const xmlChar *)"key"))
+				throw bad_format(k,"Dictionary format error: expect data in pairs of key and value (two values found in a row)");
+			cur=skipToElement(cur->next);
+			
+			//find the following value (non-key) node
+			xmlNode * v=cur;
+			if(v==NULL)
+				throw bad_format(cur,"Dictionary format error: expect data in pairs of key and value (dictionary ended with hanging key)");
+			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;
+			xmlFree(cont);
+			storage_t::const_iterator it=dict.find(key);
+			if(it==dict.end()) {
+				cur=xNodeGetNextNode(cur);
+				if(trimExtraSave) {
+					while(prev!=cur) {
+						xmlNode* n=prev;
+						prev=xNodeGetNextNode(prev);
+						xmlUnlinkNode(n);
+						xmlFreeNode(n);
+					}
+				} else {
+					if(warnUnused)
+						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()) {
+			// 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);
+				}
+			}
+		}
+	}
+
+	std::string Dictionary::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 {
+		size_t longest=0;
+		size_t seplen=subCollectionSep().size();
+		for(Dictionary::const_iterator it=begin(); it!=end(); ++it) {
+			size_t cur=it->first.size();
+			if(Collection* dp=dynamic_cast<Collection*>(it->second))
+				cur+=getLongestKeyLenOther(*dp)+seplen;
+			longest=std::max(longest,cur);
+		}
+		return longest;
+	}
+	
+	Dictionary::iterator Dictionary::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
+		iterator it=dict.find(name.substr(0,seppos));
+		if(it==dict.end())
+			return dict.end(); //no entry matching prefix -- go away
+		const Collection* d=dynamic_cast<const Collection*>(it->second);
+		if(d==NULL)
+			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 {
+		seppos=name.find(subCollectionSep());
+		if(seppos==string::npos)
+			return dict.end(); //no '.'s found -- go away
+		const_iterator it=dict.find(name.substr(0,seppos));
+		if(it==dict.end())
+			return dict.end(); //no entry matching prefix -- go away
+		const Collection* d=dynamic_cast<const Collection*>(it->second);
+		if(d==NULL)
+			return dict.end(); //matching prefix is not a collection -- go away
+		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 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;
+			}
+			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);
+		}
+		if(comment.size()>0)
+			setComment(index,comment);
+		fireEntryAdded(val);
+	}
+	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;
+			}
+			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();
+		}
+	}
+	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);
+		} else {
+			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);
+	}
+	
+	void Array::removeEntry(size_t index) {
+		storage_t::iterator it=arr.begin();
+		advance(it,index);
+		ObjectBase* obj=*it;
+		arr.erase(it);
+		fireEntryRemoved(*obj);
+	}
+	
+
+	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 {
+			return &getEntry(index);
+		}
+	}
+		
+	void Array::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 {
+		comments_t::const_iterator it=comments.find(index);
+		if(it==comments.end())
+			return emptyStr();
+		else
+			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) {
+		//check if our node has been set to NULL (invalid or not found)
+		if(node==NULL)
+			return;
+		
+		std::string comment;
+		unsigned int i=0;
+		for(xmlNode* cur = skipToElement(node->children,comment); cur!=NULL; cur = skipToElement(cur->next,comment)) {
+			if(!loadXMLNode(i++, cur, comment))
+				 break;
+		}
+		if(trimExtraLoad) {
+			while(i<size())
+				removeEntry(size()-1);
+		} 
+	}
+	
+	void Array::saveXML(xmlNode* node) const {
+		//check if our node has been set to NULL (invalid or not found)
+		if(node==NULL)
+			return;
+		
+		//set the type of the current node
+		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 parentIndent;
+		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;
+		
+		//This will be the index of the item we're loading next
+		unsigned int i=0;
+		
+		//process children nodes
+		xmlNode * prev=node->children;
+		for(xmlNode* cur = skipToElement(node->children,comment); cur!=NULL; cur = skipToElement(cur,comment)) {
+			
+			if(i==arr.size()) {
+				if(trimExtraSave) {
+					while(prev!=NULL) {
+						xmlNode* n=prev;
+						prev=xNodeGetNextNode(prev);
+						xmlUnlinkNode(n);
+						xmlFreeNode(n);
+					}
+				} else {
+					if(warnUnused)
+						cerr << "Warning: plist::Array ignoring extraneous items in destination during save..." << endl;
+				}
+				break;
+			}
+			if(comment.size()==0) {
+				comments_t::const_iterator cit=comments.find(i);
+				if(cit!=comments.end()) {
+					char buf[20];
+					unsigned int len;
+					snprintf(buf,20,"%u%n",i,&len);
+					if(/*isSub ||*/ strncmp(cit->second.c_str(),buf,len)==0)
+						comment=cit->second;
+					else { //if not a sub-dictionary, and comment doesn't already start with entry name, prepend entry name
+						comment=buf;
+						comment+=": "+cit->second;
+					}
+					xmlAddPrevSibling(cur,xmlNewText((const xmlChar*)"\n"));
+					xmlAddPrevSibling(cur,xmlNewComment((const xmlChar*)comment.c_str()));
+					xmlAddPrevSibling(cur,xmlNewText((const xmlChar*)("\n"+indentStr).c_str()));
+				}
+			}
+			arr[i]->saveXML(cur);
+			prev=cur=xNodeGetNextNode(cur);
+		}
+		
+		bool hadUnsaved = (i<arr.size());
+		for(; i<arr.size(); ++i) {
+			comments_t::const_iterator cit=comments.find(i);
+			if(cit!=comments.end()) {
+				char buf[20];
+				unsigned int len;
+				snprintf(buf,20,"%u%n",i,&len);
+				if(/*isSub ||*/ strncmp(cit->second.c_str(),buf,len)==0)
+					comment=cit->second;
+				else { //if not a sub-dictionary, and comment doesn't already start with entry name, prepend entry name
+					comment=buf;
+					comment+=": "+cit->second;
+				}
+				xmlAddChild(node,xmlNewText((const xmlChar*)("\n"+parentIndent).c_str()));
+				xmlAddChild(node,xmlNewComment((const xmlChar*)comment.c_str()));
+			}
+			xmlAddChild(node,xmlNewText((const xmlChar*)("\n"+indentStr).c_str()));
+			xmlNode* v=xmlNewChild(node,NULL,(const xmlChar*)"",NULL);
+			if(v==NULL)
+				throw bad_format(node,"Error: plist Array xml error on saving value");
+			arr[i]->saveXML(v);
+		}
+		if(hadUnsaved)
+			xmlAddChild(node,xmlNewText((const xmlChar*)("\n"+parentIndent).c_str()));
+	}
+	
+	std::string Array::toString() const {
+		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 {
+		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));
+			if(Collection* dp=dynamic_cast<Collection*>(arr[i]))
+				cur+=getLongestKeyLenOther(*dp)+seplen;
+			longest=std::max(longest,cur);
+		}
+		return longest;
+	}
+	
+	Array::iterator Array::getSubEntry(const std::string& name, std::string::size_type& seppos) {
+		seppos=name.find(subCollectionSep());
+		if(seppos==string::npos)
+			return arr.end(); //no '.'s found -- go away
+		size_t index=getIndex(name.substr(0,seppos));
+		if(index>=size())
+			return arr.end(); //no entry matching prefix -- go away
+		iterator it=arr.begin();
+		advance(it,index);
+		const Collection* d=dynamic_cast<const Collection*>(*it);
+		if(d==NULL)
+			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 {
+		seppos=name.find(subCollectionSep());
+		if(seppos==string::npos)
+			return arr.end(); //no '.'s found -- go away
+		size_t index=getIndex(name.substr(0,seppos));
+		if(index>=size())
+			return arr.end(); //no entry matching prefix -- go away
+		const_iterator it=arr.begin();
+		advance(it,index);
+		const Collection* d=dynamic_cast<const Collection*>(*it);
+		if(d==NULL)
+			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() {
+		for(iterator dit=arr.begin(); dit!=arr.end(); ++dit) {
+			std::set<ObjectBase*>::iterator rit=myRef.find(*dit);
+			if(rit!=myRef.end()) {
+				myRef.erase(rit);
+				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;
+	}
+	
+	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);
+			}
+		} 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;
+		}
+		ObjectBase * obj=plist::loadXML(val);
+		if(obj==NULL)
+			throw bad_format(val,"Array encountered an unknown value type");
+		addEntry(index,obj,comment);
+		return true;
+	}
+	
+} //namespace plist
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/plistCollections.h ./Shared/plistCollections.h
--- ../Tekkotsu_2.4.1/Shared/plistCollections.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/plistCollections.h	2006-09-19 01:39:33.000000000 -0400
@@ -0,0 +1,471 @@
+//-*-c++-*-
+#ifndef INCLUDED_plistCollections_h_
+#define INCLUDED_plistCollections_h_
+
+#include "plistPrimitives.h"
+#include <map>
+#include <vector>
+#include <set>
+
+namespace plist {
+	
+	//! Provides a common base class for the collection-oriented primitives, Dictionary, Map, Array, and Vector
+	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);
+
+		//! 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;
+		
+		//! 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); }
+		//! remove all entries in one fell swoop
+		virtual void clear()=0;
+		
+		//! 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
+
+		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
+		
+	protected:
+		//! constructor
+		explicit Collection(bool bl, bool bs) : ObjectBase(), collectionListeners(), warnUnused(true), trimExtraLoad(bl), trimExtraSave(bs) {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();
+		
+		//! run through #collectionListeners, calling CollectionListener::plistCollectionEntryAdded(*this,val)
+		virtual void fireEntryAdded(ObjectBase& val);
+		//! run through #collectionListeners, calling CollectionListener::plistCollectionEntryRemoved(*this,val)
+		virtual void fireEntryRemoved(ObjectBase& val);
+		//! run through #collectionListeners, calling CollectionListener::plistCollectionEntriesChanged(*this)
+		virtual void fireEntriesChanged();
+		//! stores a list of the current listeners
+		std::list<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(); }
+		
+		//! 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;
+		
+		//! 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 std::string mt;
+			return mt;
+		}
+		//! 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& Collection::subCollectionSep() {
+			static std::string sep=".";
+			return sep;
+		}
+	};
+	
+	//! 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);
+	public:
+		//! shorthand for the type of the storage
+		typedef std::map<std::string,ObjectBase*> storage_t;
+		//! shorthand for iterators to be returned
+		typedef storage_t::iterator iterator;
+		//! 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); }
+		
+		//! 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;
+				
+		virtual void clear();
+		
+		//! return an STL const_iterator to the first entry
+		const_iterator begin() const { return dict.begin(); }
+		//! 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(); }
+		
+		//! 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);
+		//! returns comment retrieved from loaded file, or any subsequent call to setComment
+		const std::string& getComment(const std::string& name) const;
+		
+		virtual void loadXML(xmlNode* node);
+		virtual void saveXML(xmlNode* node) const;
+		
+		virtual std::string toString() const;
+		
+		//! clone implementation for Dictionary
+		PLIST_CLONE_DEF(Dictionary,new Dictionary(*this));
+		
+	protected:
+		virtual void fireEntryRemoved(ObjectBase& val);
+		
+		//! 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;
+		
+		//! returns an entry matching just the prefix
+		/*! @param[in] name the name being looked up
+		 *  @param[out] seppos the position of the separator (sub-collections are separated by '.')
+		 *  @return iterator of the sub entry*/
+		iterator getSubEntry(const std::string& name, std::string::size_type& seppos);
+		//! returns an entry matching just the prefix
+		/*! @param[in] name the name being looked up
+		 *  @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
+		storage_t dict;
+		
+		//! objects which have been handed over to the collection for eventual de-allocation
+		std::set<ObjectBase*> myRef;
+
+		//! shorthand for the type of #comments
+		typedef std::map<std::string,std::string> comments_t;
+		//! storage of entry comments -- mapping from keys to help text comments for manual editing or user feedback
+		/*! 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.
+	 *
+	 *  The other class, Vector, takes the opposite tack -- it handles loading a variable
+	 *  number of entries, but handles the allocation of those objects internally.
+	 */
+	class Array : public Collection {
+		friend std::ostream& operator<<(std::ostream& os, const Array& d);
+	public:
+		//! shorthand for the type of the storage
+		typedef std::vector<ObjectBase*> storage_t;
+		//! shorthand for iterators to be returned
+		typedef storage_t::iterator iterator;
+		//! 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(); }
+		
+		//! 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()); }
+		
+		//! 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()); }
+		
+		//! 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); }
+		
+		//! 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="");
+		
+		//! 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="");
+		
+		//! remove the entry at position @a index
+		virtual void removeEntry(size_t index);
+		//! return the value at position @a index
+		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))
+		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 void clear();
+		
+		//! 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(); }
+		//! return the size of the dictionary
+		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);
+		
+		//! 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;
+		
+		//! returns an entry matching just the prefix
+		/*! @param[in] name the name being looked up
+		 *  @param[out] seppos the position of the separator (sub-collections are separated by '.')
+		 *  @return iterator of the sub entry*/
+		iterator getSubEntry(const std::string& name, std::string::size_type& seppos);
+		//! returns an entry matching just the prefix
+		/*! @param[in] name the name being looked up
+		 *  @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
+		storage_t arr;
+		
+		//! objects which have been handed over to the collection for eventual de-allocation
+		std::set<ObjectBase*> myRef;
+		
+		//! shorthand for the type of #comments
+		typedef std::map<size_t,std::string> comments_t;
+		//! storage of entry comments -- mapping from keys to help text comments for manual editing or user feedback
+		/*! 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); }
+		
+	//! 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); }
+	
+	//! 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); }
+	
+	//! 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); }
+	
+} //namespace plist
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/plistPrimitives.cc ./Shared/plistPrimitives.cc
--- ../Tekkotsu_2.4.1/Shared/plistPrimitives.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/plistPrimitives.cc	2006-09-16 13:32:40.000000000 -0400
@@ -0,0 +1,305 @@
+#include "plistPrimitives.h"
+
+namespace plist {
+	
+	void Primitive<bool>::loadXML(xmlNode* node) {
+		if(node==NULL)
+			return;
+		if(xNodeHasName(node,"true")) {
+			val=true;
+			fireValueChanged(); 
+		} else if(xNodeHasName(node,"false")) {
+			val=false;
+			fireValueChanged(); 
+		} else if(xNodeHasName(node,"integer") || xNodeHasName(node,"real")) {
+			xmlChar * cont=xmlNodeGetContent(node);
+			std::stringstream str((char*)cont);
+			str >> val;
+			xmlFree(cont);
+			fireValueChanged(); 
+		} else if(xNodeHasName(node,"string")) {
+			xmlChar * cont=xmlNodeGetContent(node);
+			try {
+				set((char*)cont);
+				std::cerr << "Warning: plist boolean expects value of '<true/>', '<false/>', or numeric.  String value of '" << (char*)cont << "' is not recommended." << std::endl;
+			} catch(const bad_format& err) {
+				xmlFree(cont);
+				throw bad_format(node,err.what());
+			} catch(...) {
+				xmlFree(cont);
+				throw;
+			}
+			xmlFree(cont);
+		} else
+			throw bad_format(node,"Error: plist boolean must be 'true', 'false', or numeric type");
+	}
+	void Primitive<bool>::saveXML(xmlNode* node) const {
+		if(node==NULL)
+			return;
+		xmlNodeSetName(node,(const xmlChar*)(val?"true":"false"));
+		xmlNodeSetContent(node,NULL);
+	}
+	void Primitive<bool>::set(const std::string& str) {
+		if(matchTrue(str))
+			val=true;
+		else if(matchFalse(str))
+			val=false;
+		else {
+			float t;
+			if(sscanf(str.c_str(),"%g",&t)==0)
+				throw bad_format(NULL,"Error: plist boolean must be 'true', 'false', or numeric type");
+			val=t;
+		}
+		fireValueChanged(); 
+	}
+	//! implements the clone function for Primitive<bool>
+	PLIST_CLONE_IMP(Primitive<bool>,new Primitive<bool>(val));
+
+	
+	void Primitive<char>::loadXML(xmlNode* node) {
+		if(node==NULL)
+			return;
+		xmlChar* cont=xmlNodeGetContent(node);
+		try {
+			if(xNodeHasName(node,"string")) {
+				set((char*)cont);
+			} else if(xNodeHasName(node,"integer")) {
+				val=strtol((const char*)cont,NULL,0);
+				fireValueChanged(); 
+			} else if(xNodeHasName(node,"real")) {
+				val=(char)strtod((const char*)cont,NULL);
+				fireValueChanged(); 
+			} else if(xNodeHasName(node,"true")) {
+				val=true;
+				fireValueChanged(); 
+			} else if(xNodeHasName(node,"false")) {
+				val=false;
+				fireValueChanged(); 
+			} else {
+				throw bad_format(node,"Error: plist char must be either a string or integer");
+			} 
+		} catch(const bad_format& err) {
+			xmlFree(cont);
+			throw bad_format(node,err.what());
+		} catch(...) {
+			xmlFree(cont);
+			throw;
+		}
+		xmlFree(cont);
+	}
+	void Primitive<char>::saveXML(xmlNode* node) const {
+		if(node==NULL)
+			return;
+		if(numeric) {
+			xmlNodeSetName(node,(const xmlChar*)"integer");
+			std::stringstream str;
+			str << (int)val;
+			xmlNodeSetContent(node,(const xmlChar*)str.str().c_str());
+		} else {
+			xmlNodeSetName(node,(const xmlChar*)"string");
+			xmlChar str[2] = {val,'\0'};
+			xmlNodeSetContent(node,(const xmlChar*)str);
+		}
+	}
+	void Primitive<char>::set(const std::string& str) {
+		if(str.size()==0)
+			throw bad_format(NULL,"Error: plist char must have non-empty content");
+		val=str[0];
+		if(str.size()>1) {
+			std::cerr << "Warning: plist expected single char, found multi-char string '" << str << "'";
+			if(matchTrue(str))
+				val=true;
+			else if(matchFalse(str))
+				val=false;
+			else {
+				std::cerr << " (using first character '" << val << "')" << std::endl;
+				return;
+			}
+			std::cerr << " (interpreted as boolean " << (bool)val << ")" << std::endl;
+		}
+		fireValueChanged(); 
+	}
+	//! 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;
+		xmlChar* cont=xmlNodeGetContent(node);
+		try {
+			if(xNodeHasName(node,"string")) {
+				set((char*)cont);
+			} else if(xNodeHasName(node,"integer")) {
+				val=strtol((const char*)cont,NULL,0);
+				fireValueChanged(); 
+			} else if(xNodeHasName(node,"real")) {
+				val=(char)strtod((const char*)cont,NULL);
+				fireValueChanged(); 
+			} else if(xNodeHasName(node,"true")) {
+				val=true;
+				fireValueChanged(); 
+			} else if(xNodeHasName(node,"false")) {
+				val=false;
+				fireValueChanged(); 
+			} else {
+				throw bad_format(node,"Error: plist unsigned char must be either a string or integer");
+			} 
+		} catch(const bad_format& err) {
+			xmlFree(cont);
+			throw bad_format(node,err.what());
+		} catch(...) {
+			xmlFree(cont);
+			throw;
+		}
+		xmlFree(cont);
+	}
+	void Primitive<unsigned char>::saveXML(xmlNode* node) const {
+		if(node==NULL)
+			return;
+		if(numeric) {
+			xmlNodeSetName(node,(const xmlChar*)"integer");
+			std::stringstream str;
+			str << (int)val;
+			xmlNodeSetContent(node,(const xmlChar*)str.str().c_str());
+		} else {
+			xmlNodeSetName(node,(const xmlChar*)"string");
+			xmlChar str[2] = {val,'\0'};
+			xmlNodeSetContent(node,(const xmlChar*)str);
+		}
+	}
+	void Primitive<unsigned char>::set(const std::string& str) {
+		if(str.size()==0)
+			throw bad_format(NULL,"Error: plist char must have non-empty content");
+		val=str[0];
+		if(str.size()>1) {
+			std::cerr << "Warning: plist expected single char, found multi-char string '" << str << "'";
+			if(matchTrue(str))
+				val=true;
+			else if(matchFalse(str))
+				val=false;
+			else {
+				std::cerr << " (using first character '" << val << "')" << std::endl;
+				return;
+			}
+			std::cerr << " (interpreted as boolean " << (bool)val << ")" << std::endl;
+		}
+		fireValueChanged(); 
+	}
+	//! 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) {
+		if(node==NULL)
+			return;
+		if(xNodeHasName(node,"string")) {
+			xmlChar * cont=xmlNodeGetContent(node);
+			*this=(char*)cont;
+			xmlFree(cont);
+		} else {
+			if(xNodeHasName(node,"integer") || xNodeHasName(node,"real")) {
+				xmlChar * cont=xmlNodeGetContent(node);
+				*this=(char*)cont;
+				xmlFree(cont);
+			} else if(xNodeHasName(node,"true"))
+				*this="true";
+			else if(xNodeHasName(node,"false"))
+				*this="false";
+			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 {
+		if(node==NULL)
+			return;
+		xmlNodeSetName(node,(const xmlChar*)"string");
+		xmlNodeSetContent(node,(const xmlChar*)c_str());
+	}
+	//! implements the clone function for Primitive<std::string>
+	PLIST_CLONE_IMP(Primitive<std::string>,new Primitive<std::string>(get()));
+
+} //namespace plist
+
+/*! @file
+* @brief 
+* @author Ethan Tira-Thompson (ejt) (Creator)
+*
+* $Author: ejt $
+* $Name: HEAD $
+* $Revision: 1.1 $
+* $State: Exp $
+* $Date: 2006/10/04 04:21:12 $
+*/
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/plistPrimitives.h ./Shared/plistPrimitives.h
--- ../Tekkotsu_2.4.1/Shared/plistPrimitives.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/plistPrimitives.h	2006-09-27 16:11:38.000000000 -0400
@@ -0,0 +1,398 @@
+//-*-c++-*-
+#ifndef INCLUDED_plistPrimitives_h_
+#define INCLUDED_plistPrimitives_h_
+
+#include "plistBase.h"
+
+//!@name libxml2 forward declarations
+//!forward declaration of the libxml2 struct of the same name
+extern "C" {
+	xmlNode* xmlAddPrevSibling(xmlNode* node, xmlNode* sibling);
+	xmlNode* xmlNewText(const xmlChar* s);
+	xmlNode* xmlNewComment(const xmlChar* s);
+	xmlNode* xmlAddChild(xmlNode * parent, xmlNode* child);
+	xmlNode* xmlNewChild(xmlNode* parent, xmlNs* ns, const xmlChar * name, const xmlChar * content);
+	int xmlStrEqual(const xmlChar* a, const xmlChar* b);
+	xmlChar* xmlNodeGetContent(xmlNode* node);
+	void xmlNodeSetContent(xmlNode* node, const xmlChar* content);
+	xmlAttr* xmlHasProperty(xmlNode* node, const xmlChar* name);
+	xmlChar* xmlGetProperty(xmlNode* node, const xmlChar* name);
+	long xmlGetLineNo(xmlNode* node);
+	extern void (*xmlFree)(void* ptr);
+	void xmlNodeSetName(xmlNode* node, const xmlChar* name);
+	void xmlFreeNode(xmlNode* node);
+	void xmlUnlinkNode(xmlNode* node);
+}
+
+namespace plist {
+
+	//! 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
+	 *  to and from the value type so you can almost always treat
+	 *  the Primitive as if it was the value itself. */
+	template<typename T>
+	class Primitive : public PrimitiveBase {
+	public:
+		//! constructor
+		Primitive() : ObjectBase(), val() {}
+		//! constructor, provides automatic casting from the value type
+		Primitive(const T& v) : ObjectBase(), val(v) {} 
+		//! 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) { 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
+		
+		//! smart pointer access to value
+		const T& operator*() const { return val; }
+		//! smart pointer access to value
+		const T* operator->() const { return &val; }
+		
+		//! automatic casting to the 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(); 
+		}
+		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;
+		}*/
+		
+		//! clone definition for Primitive<T>
+		PLIST_CLONE_DEF(Primitive<T>,new Primitive<T>(val));
+
+	protected:
+		T val; //!< value storage
+	};
+	//! implements the clone function for Primitive<T>
+	PLIST_CLONE_IMPT(class T,Primitive<T>,new Primitive<T>(val));
+
+	
+/*! @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
+	 *  When saving, "true" or "false" will be used, but users could
+	 *  also specify "yes"/"no" or "on"/"off".  If an integer is used,
+	 *  it will be interpreted as usual: 0==false, otherwise true. */
+	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
+		//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);
+		std::string get() const {
+			return val?"true":"false";
+		}
+		//! clone definition for Primitive<bool>
+		PLIST_CLONE_DEF(Primitive<bool>,new Primitive<bool>(val));
+		
+	protected:
+		bool val; //!< the actual data storage
+	};
+	
+/*! @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
+	 *  the setNumeric(bool) function to indicate which style to use when saving */
+	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
+		//char& operator*() { return val; }
+		const char& operator*() const { return val; } //!< dereference will return data storage
+		//char* operator->() { return &val; }
+		const char* operator->() const { return &val; } //!< can use -> to access members of data storage
+		operator char() const { return val; } //!< casting operator
+		
+		void setNumeric(bool isNum) { numeric=isNum; } //!< sets #numeric
+		bool getNumeric() const { return numeric; } //!< returns #numeric
+		
+		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);
+		std::string get() const {
+			if(numeric) {
+				std::stringstream sstr;
+				sstr << (int)val;
+				return sstr.str();
+			} else
+				return std::string(1,val);
+		}
+		//! clone definition for Primitive<char>
+		PLIST_CLONE_DEF(Primitive<char>,new Primitive<char>(val));
+		
+	protected:
+		char val; //!< data storage
+		bool numeric; //!< if true, requests that saves store the numeric value instead of corresponding character
+	};
+	
+	//! provides an @c unsigned @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
+	 *  the setNumeric(bool) function to indicate which style to use when saving */
+	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
+		//unsigned char& operator*() { return val; }
+		const unsigned char& operator*() const { return val; } //!< dereference will return data storage
+		//unsigned char* operator->() { return &val; }
+		const unsigned char* operator->() const { return &val; } //!< can use -> to access members of data storage
+		operator unsigned char() const { return val; } //!< casting operator
+		
+		void setNumeric(bool isNum) { numeric=isNum; } //!< sets #numeric
+		bool getNumeric() const { return numeric; } //!< returns #numeric
+		
+		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);
+		std::string get() const {
+			if(numeric) {
+				std::stringstream sstr;
+				sstr << (int)val;
+				return sstr.str();
+			} else
+				return std::string(1,val);
+		}
+		//! clone definition for Primitive<unsigned char>
+		PLIST_CLONE_DEF(Primitive<unsigned char>,new Primitive<unsigned char>(val));
+		
+	protected:
+		unsigned char val; //!< data storage
+		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
+		//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; }
+		const std::string* operator->() const { return this; } //!< returns a pointer to this (for uniformity with the other Primitives, although unnecessary with this instantiation)
+		//no casting operator because we subclass string
+		
+		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
+		std::string get() const { return *this; }
+		//! clone definition for Primitive<std::string>
+		PLIST_CLONE_DEF(Primitive<std::string>,new Primitive<std::string>(get()));
+	};
+	
+	//! 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 */
+	template<typename T> 
+	class NamedEnumeration : public PrimitiveBase {
+	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)
+		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
+		//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()
+
+		//! 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;
+			} else if(xNodeHasName(node,"integer") || xNodeHasName(node,"real") || xNodeHasName(node,"string")) {
+				xmlChar * cont=xmlNodeGetContent(node);
+				try {
+					set((char*)cont);
+				} catch(const bad_format& err) {
+					xmlFree(cont);
+					throw bad_format(node,err.what());
+				} catch(...) {
+					xmlFree(cont);
+					throw;
+				}
+				xmlFree(cont);
+			} else
+				throw bad_format(node,"Error: plist NamedEnumeration must be numeric or valid string");
+		}
+		//! saves name of current value (if available, index used otherwise) into @a node
+		void saveXML(xmlNode* node) const {
+			if(node==NULL)
+				return;
+			if(names!=NULL && names[val]!=NULL && val>0 && (unsigned int)val<max) {
+				xmlNodeSetName(node,(const xmlChar*)"string");
+			} else {
+				xmlNodeSetName(node,(const xmlChar*)"integer");
+			}
+			xmlNodeSetContent(node,(const xmlChar*)get().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(); 
+		}
+		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();
+		}
+		//! implements the clone function for NamedEnumeration<T>
+		PLIST_CLONE_DEF(NamedEnumeration<T>,new NamedEnumeration<T>(*this));
+
+	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;
+		}
+		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
+	};
+	//! implements the clone function for NamedEnumeration<T>
+	PLIST_CLONE_IMPT(class T,NamedEnumeration<T>,new NamedEnumeration<T>(*this));
+
+} //namespace plist
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/string_util.cc ./Shared/string_util.cc
--- ../Tekkotsu_2.4.1/Shared/string_util.cc	2005-06-01 01:47:49.000000000 -0400
+++ ./Shared/string_util.cc	2006-03-16 17:07:28.000000000 -0500
@@ -1,31 +1,61 @@
 #include "string_util.h"
 #include <ctype.h>
+#include <pwd.h>
+#include <stdlib.h>
+
+using namespace std;
 
 namespace string_util {
 
-	std::string makeLower(const std::string& s) {
-		std::string ans(s.size(),'#');
+	string makeLower(const string& s) {
+		string ans(s.size(),'#');
 		unsigned int i=s.size();
 		while(i--!=0)
 			ans[i]=::tolower(s[i]);
 		return ans;
 	}
 
-	std::string makeUpper(const std::string& s) {
-		std::string ans(s.size(),'#');
+	string makeUpper(const string& s) {
+		string ans(s.size(),'#');
 		unsigned int i=s.size();
 		while(i--!=0)
 			ans[i]=::toupper(s[i]);
 		return ans;
 	}
 
-	std::string removePrefix(const std::string& str, const std::string& pre) {
+	string removePrefix(const string& str, const string& pre) {
 		if(str.compare(0,pre.size(),pre)==0)
 			return str.substr(pre.size());
-		return std::string();
+		return string();
+	}
+	
+	string tildeExpansion(const string& str) {
+		string ans;
+		if(str[0]!='~') {
+			return str;
+		}
+#ifndef PLATFORM_APERIOS
+		else if(str=="~" || str[1]=='/') {
+			char* home=getenv("HOME");
+			if(home==NULL)
+				return str;
+			if(str=="~")
+				return home;
+			return home+str.substr(1);
+		} else {
+			string::size_type p=str.find('/');
+			struct passwd * pw;
+			pw=getpwnam(str.substr(1,p-1).c_str());
+			if(pw==NULL)
+				return str;
+			return pw->pw_dir+str.substr(p);
+		}
+#else
+		return str.substr(1);
+#endif
 	}
 
-	std::string trim(const std::string& str) {
+	string trim(const string& str) {
 		if(str.size()==0)
 			return str;
 		unsigned int b=0;
@@ -37,8 +67,8 @@
 		return str.substr(b,e-b+1);
 	}
 	
-	bool parseArgs(const std::string& input, std::vector<std::string>& args, std::vector<unsigned int>& offsets) {
-		std::string cur;
+	bool parseArgs(const string& input, vector<string>& args, vector<unsigned int>& offsets) {
+		string cur;
 		bool isDoubleQuote=false;
 		bool isSingleQuote=false;
 		args.clear();
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Shared/string_util.h ./Shared/string_util.h
--- ../Tekkotsu_2.4.1/Shared/string_util.h	2005-06-01 01:47:49.000000000 -0400
+++ ./Shared/string_util.h	2006-03-16 17:24:30.000000000 -0500
@@ -2,25 +2,29 @@
 #ifndef INCLUDED_string_util_h
 #define INCLUDED_string_util_h
 
+#include "attributes.h"
 #include <string>
 #include <vector>
 
 //! some common string processing functions, for std::string
 namespace string_util {
 	//! returns lower case version of @a s
-	std::string makeLower(const std::string& s);
+	std::string makeLower(const std::string& s) ATTR_must_check;
 
 	//! returns upper case version of @a s
-	std::string makeUpper(const std::string& s);
+	std::string makeUpper(const std::string& s) ATTR_must_check;
 
 	//! returns @a str with @a pre removed - if @a pre is not fully matched, @a str is returned unchanged
-	std::string removePrefix(const std::string& str, const std::string& pre);
+	std::string removePrefix(const std::string& str, const std::string& pre) ATTR_must_check;
 	
 	//! removes whitespace (as defined by isspace()) from the beginning and end of @a str, and returns the result
-	std::string trim(const std::string& str);
+	std::string trim(const std::string& str) ATTR_must_check;
 	
 	//! parses the input string into an arg list, with corresponding offsets of each arg in the original input
 	bool parseArgs(const std::string& input, std::vector<std::string>& args, std::vector<unsigned int>& offsets); 
+
+	//! 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;
 };
 
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Sound/PitchDetector.cc ./Sound/PitchDetector.cc
--- ../Tekkotsu_2.4.1/Sound/PitchDetector.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Sound/PitchDetector.cc	2006-09-22 12:16:55.000000000 -0400
@@ -0,0 +1,228 @@
+#include "PitchDetector.h"
+#include "Events/EventRouter.h"
+#include "Events/EventBase.h"
+#include "Events/DataEvent.h"
+#include "Events/PitchEvent.h"
+#include "Shared/newmat/newmatap.h"
+#include "Shared/Config.h"
+#include "Shared/debuget.h"
+
+#include "Shared/ODataFormats.h"
+#ifdef PLATFORM_APERIOS
+#  include "OPENR/OPENRAPI.h"
+#endif
+
+//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}
+
+PitchDetector::~PitchDetector() {
+	ASSERT(pitch_info==NULL,"pitch_info wasn't deleted before destructor");
+	ASSERT(pitch_bin==NULL,"pitch_bin wasn't deleted before destructor");
+}
+
+void PitchDetector::DoStart() {
+	EventGeneratorBase::DoStart(); // do this first (required)
+	
+	ASSERT(pitch_info==NULL,"pitch_info was already allocated?");
+	ASSERT(pitch_bin==NULL,"pitch_bin was already allocated?");
+	
+	pitch_info = new PitchInfo[num_pitches];
+	for (unsigned int i = 0; i != num_pitches; ++i) {
+		float freq = base_pitch * powf(half_step, i);
+		pitch_info[i].freq = freq;
+		pitch_info[i].sigma = sqrtf((freq * half_step - freq) / 0.5f);
+		pitch_info[i].duration = 0;
+	}
+
+	// processEvent will initialize before use
+	pitch_bin = new float[num_pitches];
+
+	cur_frame = 0;
+	have_fft = false;
+	//printf("writing to file..\n");
+	//fprintf(fft_file, "\n======starting fft collection=======\n");
+	//printf("done writing to file..\n");
+}
+
+void PitchDetector::DoStop() {
+	//fclose(fft_file);
+	if(pitch_info!=NULL) {
+		delete [] pitch_info;
+		pitch_info=NULL;
+	}
+	if(pitch_bin!=NULL) {
+		delete [] pitch_bin;
+		pitch_bin=NULL;
+	}
+	EventGeneratorBase::DoStop(); // do this last (required)
+}
+
+void PitchDetector::processEvent(const EventBase& event) {
+	if( event.getGeneratorID() != EventBase::micOSndEGID) {
+		EventGeneratorBase::processEvent(event);
+		return;
+	}
+	
+	// Get to the sound buffer
+	// getData() is not specified for const data
+	unsigned int i, j;
+	const DataEvent<const OSoundVectorData*> *de = reinterpret_cast<const DataEvent<const OSoundVectorData*>*>( &event);
+	
+	OSoundVectorData *svd = const_cast<OSoundVectorData*>(de->getData());
+	const short *d = ( const short *)svd->GetData(0);
+	
+	if ( ! frame_sz ) { /* we need to initialize _everything_ */
+		//printf("building vectors for first time..\n");
+		frame_sz = svd->GetInfo(0)->frameSize;
+		rate = svd->GetInfo(0)->samplingRate;
+		//printf("frame_sz %d, rate %d\n",frame_sz,rate);
+		win_sz = frame_sz * fft_frames;
+		
+		left.ReSize(win_sz);
+		right.ReSize(win_sz);
+		iml.ReSize(win_sz / 2 + 1);
+		imr.ReSize(win_sz / 2 + 1);
+		rel.ReSize(win_sz / 2 + 1);
+		rer.ReSize(win_sz / 2 + 1);
+		pol.ReSize(win_sz / 2 + 1);
+		por.ReSize(win_sz / 2 + 1);
+		po.ReSize(win_sz / 2 + 1);
+	}
+	
+	//printf("saving audio data to vectors [%u]..\n", cur_frame);
+	for (i = 0; i != frame_sz; ++i) {
+		left ((cur_frame * frame_sz) + i + 1) = d[(i<<1)  ];
+		right((cur_frame * frame_sz) + i + 1) = d[(i<<1)+1];
+	}
+	
+	if (++cur_frame == fft_frames) {
+		cur_frame = 0;
+		
+		hamming(left);
+		hamming(right);
+		
+		//printf("calling fft!\n");
+		NEWMAT::RealFFT(left, rel, iml);
+		NEWMAT::RealFFT(right, rer, imr);
+		for (i = 1; i <= win_sz / 2 + 1; ++i) {
+			NEWMAT::Real a, b;
+			a = rel(i);
+			b = iml(i);
+			pol(i) = sqrtf(a*a + b*b);
+			a = rer(i);
+			b = imr(i);
+			por(i) = sqrtf(a*a + b*b);
+			//based on whether stereo info actually used, remove all
+			//stereo separation altogether or merge even later..
+			po(i) = (pol(i) + por(i)) / 2;
+			
+			//fprintf(fft_file, "[frequency %f] pow[%d] = %f\n", rate * i * 1.0 / win_sz, i, po(i));
+		}
+		have_fft = true;
+		
+	} else if (cur_frame == 1 && have_fft) { //hack to split processing..
+		float mean = 0.0f;
+		unsigned int max = 0; //if we see this value twice.. oops
+		//turbo slow for now..
+		//printf("building pitch bins!\n");
+		local_maxes = 0;
+		for (i = 0; i != num_pitches; ++i) {
+			float sigma = pitch_info[i].sigma;
+			float freq = pitch_info[i].freq;
+			float bin = 0.0f;
+			
+			for (j = 1; j <= win_sz / 2 + 1; ++j)
+				bin += po(j) * gaussian_pdf(j * rate * 1.0 / win_sz, sigma, freq);
+			mean += (pitch_bin[i] = bin);
+			
+			
+			//prep for global max check
+			max = (bin > pitch_bin[max]) ? i : max;
+			
+			//check if prev a local max
+			pitch_info[i].local_max = pitch_info[i].global_max = 0.0f;
+			if (i == 1) {
+				float prev = pitch_bin[i-1];
+				if (bin < prev) {
+					pitch_info[0].local_max = 1.0f - (bin / prev);
+					++local_maxes;
+				}
+			} else if (i > 1) {
+				float a = pitch_bin[i-2], b = pitch_bin[i-1], c = pitch_bin[i];
+				if (b > a && b > c) {
+					pitch_info[i-1].local_max = 1.0f - (a + c) / (2.f * b);
+					++local_maxes;
+				}
+			}
+			if (i == num_pitches - 1) { //intentionally not else-if !
+				float prev = pitch_bin[i - 1];
+				if (bin > prev) {
+					pitch_info[i].local_max = 1.0f - (prev / bin);
+					++local_maxes;
+				}
+			}
+		}
+		mean /= num_pitches;
+		
+		pitch_info[max].global_max = 1.0f - mean / pitch_bin[max];
+		
+		//final pass through on whether this is a pitch or not.
+		//compute overtone properties and confidence..
+		for (i = 0; i < num_pitches; ++i) {
+			float c, f = 1.0f;
+			if (i % 4 && is_pitch(confidence(i/4, pitch_bin[i/4])))
+				f /= 2.0f;
+			if (i % 3 && is_pitch(confidence(i/3, pitch_bin[i/3])))
+				f /= 2.0f;
+			if (i % 3 && is_pitch(confidence(i*2/3, pitch_bin[i*2/3])))
+				f /= 2.0f;
+			if (i % 2 && is_pitch(confidence(i/2, pitch_bin[i/2])))
+				f /= 2.0f;
+			pitch_info[i].overtone = 1.0f - f;
+			pitch_info[i].confidence = (c = confidence(i, pitch_bin[i]));
+			
+			if (is_pitch(c)) {
+				//printf("pitch number %u, frequency %f, name %s, confidence %f went on\nstrength %f gmax %f lmax %f otone %f lmaxes %u\n", i, pitch_info[i].freq, pitch_name(i), c, pitch_bin[i],pitch_info[i].global_max, pitch_info[i].local_max, pitch_info[i].overtone, local_maxes);
+				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));
+			} 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));
+					pitch_info[i].duration = 0;
+					pitch_info[i].amplitude = 0;
+				}
+			}
+			//fprintf(fft_file, "pitch %d freq %f name %s amp %f dur %u\n\tgmax %f lmax %f otone %f lmaxes %u confidence %f\n",i, pitch_info[i].freq, pitch_name(i),pitch_bin[i], pitch_info[i].duration,pitch_info[i].global_max, pitch_info[i].local_max,pitch_info[i].overtone, local_maxes, c);
+		}
+	}
+	//printf("done with mic event in class Pitch\n");
+}
+
+bool PitchDetector::is_pitch(float conf) {
+	return (conf >= config->sound.pitchConfidenceThreshold);
+}
+
+
+
+/*! @file
+ * @brief Implements PitchDetector, which generates a PitchEvent whenever a notable frequency is detected using FFT
+ * @author Matus Telgarsky and Jonah Sherman (Creators)
+ * @author Ethan Tira-Thompson (imported into framework)
+ *
+ * Originally written as a part of a final project at Carnegie Mellon (15-494 Cognitive Robotics, Spring 2006)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Sound/PitchDetector.h ./Sound/PitchDetector.h
--- ../Tekkotsu_2.4.1/Sound/PitchDetector.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Sound/PitchDetector.h	2006-09-28 17:00:28.000000000 -0400
@@ -0,0 +1,134 @@
+//-*-c++-*-
+#ifndef INCLUDED_PitchDetector_h_
+#define INCLUDED_PitchDetector_h_
+
+#include "Events/EventGeneratorBase.h"
+#include "Shared/newmat/newmat.h"
+#include <math.h>
+
+//! Generates a PitchEvent whenever a notable frequency is detected using FFT
+class PitchDetector : public EventGeneratorBase {
+public:
+	static const unsigned int fft_frames; //!< number frames to use for fft
+	static const unsigned int num_pitches; //!< 5 octaves, 12 pitches per octave
+	static const float base_pitch; //!< two octaves below tuning A (440)
+	static const float half_step; //!< twelfth root of two: @f$ \sqrt[12]{2} @f$
+	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), 
+		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)
+	{
+		//fft_file = fopen("ms/data/sound/fft.dat", "w");
+	} 
+	
+	//! destructor, asserts that #pitch_info and #pitch_bin have been deleted by DoStop()
+	~PitchDetector();
+	
+	virtual void DoStart(); //!< allocates and sets up #pitch_info and #pitch_bin, relies on EventGeneratorBase to manage event subscriptions
+	virtual void DoStop(); //!< deletes #pitch_info and #pitch_bin
+	virtual void processEvent(const EventBase& event);
+
+	static std::string getClassDescription() { return "Generates a PitchEvent whenever a notable frequency is detected using FFT"; }
+	virtual std::string getDescription() const { return getClassDescription(); }
+	
+
+protected:
+	//! stores info about the pitch currently being detected
+	struct PitchInfo {
+		//! constructor -- sets everything to 0 (additional initialization is done for each #pitch_info entry during DoStart())
+		PitchInfo() : freq(0), sigma(0), local_max(0), global_max(0), overtone(0), confidence(0), amplitude(0), duration(0) {}
+		
+		float freq, //!< frequency of this pitch (calculated on instantiation)
+		sigma,//!< standard dev to use (sqrt(var)), calc'd on start
+		//following set only relevant if the pitch is on
+		local_max, //!< [0,1] value: how much stronger it is than neighbors, else zero
+		global_max, //!< [0,1] value: how much stronger than mean if global max, else zero
+		overtone, //!< value in [0,1] with confidence that it is overtone            
+		confidence, //!< value in [0,1] with confidence that this is a pitch, not noise (should confidence have a rolling average as well?)
+		amplitude; //!< rolling average amplitude
+		unsigned int duration; //!< number of windows it has been on 
+	};
+	
+	//keep temporaries for efficiency
+	NEWMAT::ColumnVector left, //!< the waveform of the left channel 
+		right, //!< the waveform of the right channel
+		iml, //!< imaginary outputs of the FFT for left channel
+		imr, //!< imaginary outputs of the FFT for right channel
+		rel, //!< real outputs of the FFT for the left channel
+		rer, //!< real outputs of the FFT for the right channel
+		pol, //!< absolute value (magnitude) of results of FFT for left channel
+		por, //!< absolute value (magnitude) of results of FFT for right channel
+		po; //!< average of #pol and #por for each bin
+	unsigned int frame_sz, //!< number of samples given by system for each frame (assumed that once started, this won't change)
+		win_sz, //!< number of samples to be recorded before running FFT (#frame_sz * #fft_frames)
+		rate, //!< sampling frequence (Hz)
+		cur_frame, //!< the current frame index to be filled in next, up to #fft_frames, when the FFT is run
+		local_maxes; //!< number of individual peaks
+	PitchInfo *pitch_info; //!< an array of PitchInfos, one for each of #num_pitches, allocated for scope spanning DoStart()/DoStop()
+	float *pitch_bin; //!< array, holds current amplitude for each #num_pitches (mono)
+	bool have_fft; //!< set to true after FFT has been computed, differentiates first filling of buffers from subsequent rewrites
+	//FILE *fft_file;
+	
+	//! returns true if the confidence is above a threshold obtained from configuration
+	static bool is_pitch(float conf);
+	
+	//! returns a confidence estimate of a pitch in bin @a p... (actual computation used is not obvious, you'll have to stare at the code /ejt)
+	inline float confidence(unsigned int p, float strength) {
+		float l = pitch_info[p].local_max,
+		g = pitch_info[p].global_max,
+		o = pitch_info[p].overtone;
+		//XXX this sucks. add variance
+		
+		if (strength < win_sz * 5.0f)
+			return 0.0f;
+		
+		if (g > 0.0f)
+			return 3*g / 4.0f + (1.0f - o) / 8.0f + (1.0f - 2.0f * local_maxes / num_pitches) / 8.0f;
+		else
+			return l / 3.0f + (1.0f - o) / 4.0f + (1.0f - 2.0f * local_maxes / num_pitches) / 8.0f;
+	}
+	
+	//! returns the value at @a x of a gaussian with the parameters @a mu and @a sigma
+	static inline float gaussian_pdf(float mu, float sigma, float x) {
+		float dist = x - mu;
+		return exp(-dist * dist / (2.0f * sigma * sigma)) / (sqrt_2_pi * sigma);
+	}
+	
+	//! returns a string representing the musical note of a given frequency
+	static const char *pitch_name(unsigned int i) {
+		static const char *pitch_names[12] = {
+			"A", "A#", "B", "C", "C#", "D", "D#", "E", "F", "F#", "G", "G#"
+		};
+		
+		return pitch_names[i % 12];
+	}
+	
+	//! unknown calculation, does some kind of rescaling of @a v (/ejt)
+	static void hamming(NEWMAT::ColumnVector &v) {
+		for (int i = 0; i != v.size(); ++i)
+			v.element(i) = v.element(i) * (0.53836f - 0.46164f * cosf(2 * float(M_PI) * i / (v.size() - 1)));
+	}
+	
+private:
+	PitchDetector(const PitchDetector&); //!< don't call (copy constructor)
+	PitchDetector& operator=(const PitchDetector&); //!< don't call (assignment operator)
+};
+
+/*! @file
+ * @brief Defines PitchDetector, which generates a PitchEvent whenever a notable frequency is detected using FFT
+ * @author Matus Telgarsky and Jonah Sherman (Creators)
+ * @author Ethan Tira-Thompson (imported into framework)
+ *
+ * Originally written as a part of a final project at Carnegie Mellon (15-494 Cognitive Robotics, Spring 2006)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Sound/SoundManager.cc ./Sound/SoundManager.cc
--- ../Tekkotsu_2.4.1/Sound/SoundManager.cc	2005-06-01 01:47:53.000000000 -0400
+++ ./Sound/SoundManager.cc	2006-09-18 14:08:08.000000000 -0400
@@ -1,6 +1,6 @@
 #include "Shared/Config.h"
 #include "SoundManager.h"
-#include "IPC/LockScope.h"
+#include "Shared/MarkScope.h"
 #include "WAV.h"
 #include "Events/EventRouter.h"
 #include <sys/types.h>
@@ -17,7 +17,7 @@
 SoundManager * sndman=NULL;
 
 //!for convenience when locking each of the functions
-typedef LockScope<ProcessID::NumProcesses> AutoLock;
+typedef MarkScope AutoLock;
 
 SoundManager::SoundManager()
 : mixerBuffer(0), mixerBufferSize(0), sndlist(),playlist(),chanlist(),mix_mode(Fast),queue_mode(Override),max_chan(4),lock(),sn(0)
@@ -36,7 +36,7 @@
 #endif //PLATFORM-specific initialization
 
 SoundManager::~SoundManager() {
-	StopPlay();
+	stopPlay();
 	if(!sndlist.empty())
 		cerr << "Warning: SoundManager was deleted with active sound buffer references" << endl;
 	while(!sndlist.empty()) {
@@ -54,11 +54,11 @@
 
 //!@todo this does one more copy than it really needs to
 SoundManager::Snd_ID
-SoundManager::LoadFile(std::string const &name) {
-	AutoLock autolock(lock,ProcessID::getID());
+SoundManager::loadFile(std::string const &name) {
+	AutoLock autolock(lock);
 	if (name.size() == 0) {
-	  cout << "SoundManager::LoadFile() null filename" << endl;
-	  return invalid_Snd_ID;
+		cout << "SoundManager::loadFile() null filename" << endl;
+		return invalid_Snd_ID;
 	};
 	std::string path(config->sound.makePath(name));
 	Snd_ID id=lookupPath(path);
@@ -69,7 +69,7 @@
 		//		cout << "load new file" << endl;
 		struct stat buf;
 		if(stat(path.c_str(),&buf)==-1) {
-			cout << "SoundManager::LoadFile(): Sound file not found: " << path << endl;
+			cout << "SoundManager::loadFile(): Sound file not found: " << path << endl;
 			return invalid_Snd_ID;
 		}
 		byte * sndbuf=new byte[buf.st_size];
@@ -78,15 +78,15 @@
 		WAV wav;
 		WAVError error = wav.Set(sndbuf);
 		if (error != WAV_SUCCESS) {
-			printf("%s : %s %d: '%s'","SoundManager::LoadFile()","wav.Set() FAILED",error, path.c_str());
+			printf("%s : %s %d: '%s'","SoundManager::loadFile()","wav.Set() FAILED",error, path.c_str());
 			return invalid_Snd_ID;
 		}
 		if(wav.GetSamplingRate()!=config->sound.sample_rate || wav.GetBitsPerSample()!=config->sound.sample_bits) {
-			printf("%s : %s %d","SoundManager::LoadFile()","bad sample rate/bits", error);
+			printf("%s : %s %d","SoundManager::loadFile()","bad sample rate/bits", error);
 			return invalid_Snd_ID;
 		}
-		//cout << "Loading " << name << endl;
-		id=LoadBuffer(reinterpret_cast<char*>(wav.GetDataStart()),wav.GetDataEnd()-wav.GetDataStart());
+		cout << "Loading " << name << endl;
+		id=loadBuffer(reinterpret_cast<char*>(wav.GetDataStart()),wav.GetDataEnd()-wav.GetDataStart());
 		delete [] sndbuf;
 		if(path.size()>MAX_NAME_LEN)
 			strncpy(sndlist[id].name,path.substr(path.size()-MAX_NAME_LEN).c_str(),MAX_NAME_LEN);
@@ -97,11 +97,11 @@
 }
 
 SoundManager::Snd_ID
-SoundManager::LoadBuffer(const char buf[], unsigned int len) {
-	cout << "SoundManager::LoadBuffer() of " << len << " bytes" << endl;
+SoundManager::loadBuffer(const char buf[], unsigned int len) {
+  // cout << "SoundManager::loadBuffer() of " << len << " bytes" << endl;
 	if(buf==NULL || len==0)
 		return invalid_Snd_ID;
-	AutoLock autolock(lock,ProcessID::getID());
+	AutoLock autolock(lock);
 	//setup region
 	RCRegion * region=initRegion(len+MSG_SIZE);
 	//setup message
@@ -145,20 +145,20 @@
 }
 	
 void
-SoundManager::ReleaseFile(std::string const &name) {
-	AutoLock autolock(lock,ProcessID::getID());
-	Release(lookupPath(config->sound.makePath(name)));
+SoundManager::releaseFile(std::string const &name) {
+	AutoLock autolock(lock);
+	release(lookupPath(config->sound.makePath(name)));
 }
 
 void
-SoundManager::Release(Snd_ID id) {
+SoundManager::release(Snd_ID id) {
 	if(id==invalid_Snd_ID)
 		return;
 	if(sndlist[id].ref==0) {
-		cerr << "SoundManager::Release() " << id << " extra release" << endl;
+		cerr << "SoundManager::release() " << id << " extra release" << endl;
 		return;
 	}
-	AutoLock autolock(lock,ProcessID::getID());
+	AutoLock autolock(lock);
 	sndlist[id].ref--;
 	if(sndlist[id].ref==0) {
 		if(sndlist[id].rcr!=NULL) {
@@ -197,35 +197,36 @@
 }
 
 SoundManager::Play_ID
-SoundManager::PlayFile(std::string const &name) {
+SoundManager::playFile(std::string const &name) {
   if(playlist.size()>=playlist_t::MAX_ENTRIES)
 		return invalid_Play_ID;	
-	AutoLock autolock(lock,ProcessID::getID());
-	Snd_ID sndid=LoadFile(name);
+	AutoLock autolock(lock);
+	Snd_ID sndid=loadFile(name);
 	if(sndid==invalid_Snd_ID)
 		return invalid_Play_ID;
 	sndlist[sndid].ref--;
-	return Play(sndid);
+	cout << "Playing " << name /*<< " from process " << ProcessID::getID()*/ << endl;
+	return play(sndid);
 }
 
 SoundManager::Play_ID
-SoundManager::PlayBuffer(const char buf[], unsigned int len) {
+SoundManager::playBuffer(const char buf[], unsigned int len) {
 	if(playlist.size()>=playlist_t::MAX_ENTRIES || buf==NULL || len==0)
 		return invalid_Play_ID;	
-	AutoLock autolock(lock,ProcessID::getID());
-	Snd_ID sndid=LoadBuffer(buf,len);
+	AutoLock autolock(lock);
+	Snd_ID sndid=loadBuffer(buf,len);
 	if(sndid==invalid_Snd_ID)
 		return invalid_Play_ID;
 	sndlist[sndid].ref--;
-	return Play(sndid);
+	return play(sndid);
 }
 	
 SoundManager::Play_ID
-SoundManager::Play(Snd_ID id) {
-	//	cout << "Play " << id << endl;
+SoundManager::play(Snd_ID id) {
+        // cout << "Play " << id << endl;
 	if(id==invalid_Snd_ID)
 		return invalid_Play_ID;
-	AutoLock autolock(lock,ProcessID::getID());
+	AutoLock autolock(lock);
 	Play_ID playid=playlist.new_front();
 	if(playid!=invalid_Play_ID) {
 		sndlist[id].ref++;
@@ -267,16 +268,16 @@
 }
 	
 SoundManager::Play_ID
-SoundManager::ChainFile(Play_ID base, std::string const &next) {
+SoundManager::chainFile(Play_ID base, std::string const &next) {
        if(base==invalid_Play_ID)
-		return base;
+		return playFile(next);
 	Play_ID orig=base;
 	while(playlist[base].next_id!=invalid_Play_ID)
 		base=playlist[base].next_id;
 	Play_ID nplay=playlist.new_front();
 	if(nplay==invalid_Play_ID)
 		return nplay;
-	Snd_ID nsnd=LoadFile(next);
+	Snd_ID nsnd=loadFile(next);
 	if(nsnd==invalid_Snd_ID) {
 		playlist.pop_front();
 		return invalid_Play_ID;
@@ -287,16 +288,16 @@
 }
 
 SoundManager::Play_ID
-SoundManager::ChainBuffer(Play_ID base, const char buf[], unsigned int len) {
+SoundManager::chainBuffer(Play_ID base, const char buf[], unsigned int len) {
 	if(base==invalid_Play_ID || buf==NULL || len==0)
-		return base;
+		return playBuffer(buf,len);
 	Play_ID orig=base;
 	while(playlist[base].next_id!=invalid_Play_ID)
 		base=playlist[base].next_id;
 	Play_ID nplay=playlist.new_front();
 	if(nplay==invalid_Play_ID)
 		return nplay;
-	Snd_ID nsnd=LoadBuffer(buf,len);
+	Snd_ID nsnd=loadBuffer(buf,len);
 	if(nsnd==invalid_Snd_ID) {
 		playlist.pop_front();
 		return invalid_Play_ID;
@@ -307,9 +308,9 @@
 }
 
 SoundManager::Play_ID
-SoundManager::Chain(Play_ID base, Snd_ID next) {
+SoundManager::chain(Play_ID base, Snd_ID next) {
 	if(base==invalid_Play_ID || next==invalid_Snd_ID)
-		return base;
+		return play(next);
 	Play_ID orig=base;
 	while(playlist[base].next_id!=invalid_Play_ID)
 		base=playlist[base].next_id;
@@ -322,22 +323,22 @@
 }
 
 void
-SoundManager::StopPlay() {
+SoundManager::stopPlay() {
 	while(!playlist.empty())
-		StopPlay(playlist.begin());
+		stopPlay(playlist.begin());
 }
 
 void
-SoundManager::StopPlay(Play_ID id) {
+SoundManager::stopPlay(Play_ID id) {
 	if(id==invalid_Play_ID)
 		return;
-	AutoLock autolock(lock,ProcessID::getID());
+	AutoLock autolock(lock);
 	//cout << "Stopping sound " << id << ": " << sndlist[playlist[id].snd_id].name << endl;
 	//we start at the back (oldest) since these are the most likely to be removed...
 	for(chanlist_t::index_t it=chanlist.prev(chanlist.end()); it!=chanlist.end(); it=chanlist.prev(it))
 		if(chanlist[it]==id) {
 			std::string name=sndlist[playlist[id].snd_id].name;
-			Release(playlist[id].snd_id);
+			release(playlist[id].snd_id);
 			playlist.erase(id);
 			chanlist.erase(it);
 			playlist[id].cumulative+=playlist[id].offset;
@@ -348,14 +349,14 @@
 				erouter->postEvent(EventBase::audioEGID,id,EventBase::deactivateETID,ms);
 			return;
 		}
-	cerr << "SoundManager::StopPlay(): " << id << " does not seem to be playing" << endl;
+	cerr << "SoundManager::stopPlay(): " << id << " does not seem to be playing" << endl;
 }
 
 void
-SoundManager::PausePlay(Play_ID id) {
+SoundManager::pausePlay(Play_ID id) {
 	if(id==invalid_Play_ID)
 		return;
-	AutoLock autolock(lock,ProcessID::getID());
+	AutoLock autolock(lock);
 	for(chanlist_t::index_t it=chanlist.begin(); it!=chanlist.end(); it=chanlist.next(it))
 		if(chanlist[it]==id) {
 			chanlist.erase(it);
@@ -364,10 +365,10 @@
 }
 	
 void
-SoundManager::ResumePlay(Play_ID id) {
+SoundManager::resumePlay(Play_ID id) {
 	if(id==invalid_Play_ID)
 		return;
-	AutoLock autolock(lock,ProcessID::getID());
+	AutoLock autolock(lock);
 	for(chanlist_t::index_t it=chanlist.begin(); it!=chanlist.end(); it=chanlist.next(it))
 		if(chanlist[it]==id)
 			return;
@@ -375,16 +376,16 @@
 }
 	
 void
-SoundManager::SetMode(unsigned int max_channels, MixMode_t mixer_mode, QueueMode_t queuing_mode) {
-	AutoLock autolock(lock,ProcessID::getID());
+SoundManager::setMode(unsigned int max_channels, MixMode_t mixer_mode, QueueMode_t queuing_mode) {
+	AutoLock autolock(lock);
 	max_chan=max_channels;
 	mix_mode=mixer_mode;
 	queue_mode=queuing_mode;
 }
 
 unsigned int
-SoundManager::GetRemainTime(Play_ID id) const {
-	AutoLock autolock(lock,ProcessID::getID());
+SoundManager::getRemainTime(Play_ID id) const {
+	AutoLock autolock(lock);
 	unsigned int t=0;
 	while(id!=invalid_Play_ID) {
 		t+=sndlist[playlist[id].snd_id].len-playlist[id].offset;
@@ -395,7 +396,7 @@
 }
 
 void
-SoundManager::MixChannel(Play_ID channelId, void* buf, size_t destSize) {
+SoundManager::mixChannel(Play_ID channelId, void* buf, size_t destSize) {
 	char *dest = (char*) buf;
 	
 	PlayState& channel = playlist[channelId];
@@ -425,7 +426,7 @@
 }
 
 void
-SoundManager::MixChannelAdditively(Play_ID channelId, int bitsPerSample, MixMode_t mode,
+SoundManager::mixChannelAdditively(Play_ID channelId, int bitsPerSample, MixMode_t mode,
                                    short scalingFactor, void* buf, size_t destSize)
 {
 	PlayState& channel = playlist[channelId];
@@ -496,7 +497,7 @@
 #ifdef PLATFORM_APERIOS
 unsigned int
 SoundManager::CopyTo(OSoundVectorData* data) {
-	AutoLock autolock(lock,ProcessID::getID());
+	AutoLock autolock(lock);
 	return CopyTo(data->GetData(0), data->GetInfo(0)->dataSize);
 }
 
@@ -509,7 +510,7 @@
 #endif
 
 unsigned int SoundManager::CopyTo(void * dest, size_t destSize) {
-	AutoLock autolock(lock,ProcessID::getID());
+	AutoLock autolock(lock);
 
 	void * origdest=dest;
 	size_t origDestSize=destSize;
@@ -526,7 +527,7 @@
 		memset(dest, 0, destSize); 
 	} else if (channels.size() == 1) {
 		// One channel to mix
-		MixChannel(channels.front(), dest, destSize);
+		mixChannel(channels.front(), dest, destSize);
 	} else {
 		// Several channels to mix	
 		const MixMode_t mode = mix_mode;
@@ -550,7 +551,7 @@
 		const int channelCount = channels.size();
 		const short scalingFactor = (short) ((mode == Fast) ? channelCount : 1);  
 		for(std::vector<Play_ID>::iterator i = channels.begin(); i != channels.end(); i++)
-			MixChannelAdditively(*i, bitsPerSample, mode, scalingFactor, dest, destSize);
+			mixChannelAdditively(*i, bitsPerSample, mode, scalingFactor, dest, destSize);
 		
 		if (mode == Quality) {
 			// Quality mixing uses an intermediate buffer
@@ -649,7 +650,8 @@
 #ifdef PLATFORM_APERIOS
 	unsigned int pagesize=4096;
 	sError err=GetPageSize(&pagesize);
-	ASSERT(err==sSUCCESS,"Error "<<err<<" getting page size");
+	if(err!=sSUCCESS)
+		cerr << "Error "<<err<<" getting page size " << pagesize << endl;
 	unsigned int pages=(size+pagesize-1)/pagesize;
 	return new RCRegion(pages*pagesize);
 #else
@@ -773,13 +775,13 @@
 bool
 SoundManager::endPlay(Play_ID id) {
 	if(playlist[id].next_id==invalid_Play_ID) {
-		StopPlay(id);
+		stopPlay(id);
 		return true;
 	} else {
 		//copies the next one into current so that the Play_ID consistently refers to the same "sound"
 		Play_ID next=playlist[id].next_id;
 		//		cout << "play " << id << " moving from " << playlist[id].snd_id << " to " << playlist[next].snd_id << endl;
-		Release(playlist[id].snd_id);
+		release(playlist[id].snd_id);
 		playlist[id].snd_id=playlist[next].snd_id;
 		playlist[id].cumulative+=playlist[id].offset;
 		playlist[id].offset=0;
@@ -806,6 +808,25 @@
 {}
 
 
+SoundManager::Snd_ID SoundManager::LoadFile(std::string const &name) { return loadFile(name); }
+SoundManager::Snd_ID SoundManager::LoadBuffer(const char buf[], unsigned int len) { return loadBuffer(buf,len); }
+void SoundManager::ReleaseFile(std::string const &name) { releaseFile(name); }
+void SoundManager::Release(Snd_ID id) { release(id); }
+SoundManager::Play_ID SoundManager::PlayFile(std::string const &name) { return playFile(name); }
+SoundManager::Play_ID SoundManager::PlayBuffer(const char buf[], unsigned int len) { return playBuffer(buf,len); }
+SoundManager::Play_ID SoundManager::Play(Snd_ID id) { return play(id); }
+SoundManager::Play_ID SoundManager::ChainFile(Play_ID base, std::string const &next) { return chainFile(base,next); }
+SoundManager::Play_ID SoundManager::ChainBuffer(Play_ID base, const char buf[], unsigned int len) { return chainBuffer(base,buf,len); }
+SoundManager::Play_ID SoundManager::Chain(Play_ID base, Snd_ID next) { return chain(base,next); }
+void SoundManager::StopPlay() { stopPlay(); }
+void SoundManager::StopPlay(Play_ID id) { stopPlay(id); }
+void SoundManager::PausePlay(Play_ID id) { pausePlay(id); }
+void SoundManager::ResumePlay(Play_ID id) { resumePlay(id); }
+void SoundManager::SetMode(unsigned int max_channels, MixMode_t mixer_mode, QueueMode_t queuing_mode) { setMode(max_channels,mixer_mode,queuing_mode); }
+unsigned int SoundManager::GetRemainTime(Play_ID id) const { return getRemainTime(id); }
+unsigned int SoundManager::GetNumPlaying() { return getNumPlaying(); }
+
+
 /*! @file
  * @brief Implements SoundManager, which provides sound effects and caching services, as well as mixing buffers for the SoundPlay process
  * @author ejt (Creator)
@@ -872,7 +893,7 @@
 					for(;beg<(unsigned int*)end; beg++)
 						*beg+=offset>>shift;
 					playlist[mixs[c]].offset=sndlist[playlist[mixs[c]].snd_id].len;
-					StopPlay(mixs[c]);
+					stopPlay(mixs[c]);
 				}
 			}
 			unsigned int leftover=(offset>>shift)*((1<<shift)-mixs.size());
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Sound/SoundManager.h ./Sound/SoundManager.h
--- ../Tekkotsu_2.4.1/Sound/SoundManager.h	2005-08-07 00:11:04.000000000 -0400
+++ ./Sound/SoundManager.h	2006-09-29 12:56:10.000000000 -0400
@@ -11,6 +11,7 @@
 #include "IPC/MutexLock.h"
 #include "SoundManagerMsg.h"
 #include "IPC/ProcessID.h"
+#include "Shared/attributes.h"
 
 #ifdef PLATFORM_APERIOS
 class OSubject;
@@ -29,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
+ *  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
+ *  played.  Just be sure to release the file (releaseFile()) again
  *  when you're done with it ;)
  *
  *  All functions will attempt to lock the SoundManager.  Remember,
@@ -46,14 +47,15 @@
  *  synthesizer, ...?)
  *
  *  @todo Volume control, variable playback speed, support more wav
- *  file formats (latter two are the same thing if you think about it
- *  - need to be able to resample on the fly)
+ *  file formats (latter two are the same thing if you think about it - need
+ *  to be able to resample on the fly)
  *  
  *  @todo Add functions to hand out regions to be filled out to avoid
  *  copying into the buffer.
  */
 class SoundManager {
 public:
+	//! destructor
 	virtual ~SoundManager();
 
 	//!constructor, should only be called by the receiving process (SoundPlay)
@@ -86,6 +88,7 @@
 		Quality  //!< uses real division to maintain volume level, using an intermediary higher precision buffer for mixing
 	};
 
+	//! indicates how to handle channel overflow (trying to play more sounds than maximum number of mixing channels). See #queue_mode
 	enum QueueMode_t {
 		Enqueue,        //!< newer sounds are played when a channel opens up (when old sound finishes)
 		Pause,          //!< newer sounds pause oldest sound, which continues when a channel opens
@@ -97,66 +100,66 @@
 	/*!Since the SoundManager does the loading, if the same file is being played more than once, only once copy is stored in memory 
 	 * @param name can be either a full path, or a partial path relative to Config::sound_config::root
 	 * @return ID number for future references (can also use name)
-	 * The sound data will be cached until ReleaseFile() or Release() is called a matching number of times*/
-	Snd_ID LoadFile(std::string const &name);
+	 * The sound data will be cached until releaseFile() or release() is called a matching number of times*/
+	Snd_ID loadFile(std::string const &name);
 
 	//!loads raw samples from a buffer (assumes matches Config::sound_config settings)
-	/*!The sound data will be cached until Release() is called a matching number of times.\n
+	/*!The sound data will be cached until release() is called a matching number of times.\n
 	 * This function is useful for dynamic sound sources.  A copy will be made. */
-	Snd_ID LoadBuffer(const char buf[], unsigned int len);
+	Snd_ID loadBuffer(const char buf[], unsigned int len);
 	
 	//!Marks the sound buffer to be released after the last play command completes (or right now if not being played)
-	void ReleaseFile(std::string const &name);
+	void releaseFile(std::string const &name);
 
 	//!Marks the sound buffer to be released after the last play command completes (or right now if not being played)
-	void Release(Snd_ID id);
+	void release(Snd_ID id);
 	
 	//!play a wav file (if it matches Config::sound_config settings - can't do resampling yet)
-	/*!Will do a call to LoadFile() first, and then automatically release the sound again when complete.
+	/*!Will do a call to loadFile() first, and then automatically release the sound again when complete.
 	 * @param name can be either a full path, or a partial path relative to Config::sound_config::root
 	 * @return ID number for future references
-	 * The sound data will not be cached after done playing unless a call to LoadFile is made*/
-	Play_ID PlayFile(std::string const &name);
+	 * The sound data will not be cached after done playing unless a call to loadFile is made*/
+	Play_ID playFile(std::string const &name);
 
 	//!loads raw samples from a buffer (assumes buffer matches Config::sound_config settings)
 	/*!The sound data will be released after done playing*/
-	Play_ID PlayBuffer(const char buf[], unsigned int len);
+	Play_ID playBuffer(const char buf[], unsigned int len);
 	
 	//!plays a previously loaded buffer or file
-	Play_ID Play(Snd_ID id);
+	Play_ID play(Snd_ID id);
 	
 	//!allows automatic queuing of sounds - good for dynamic sound sources!
 	/*!if you chain more than once to the same base, the new buffers are appended
 	 * to the end of the chain - the new buffer doesn't replace the current chain
 	 * @return @a base - just for convenience of multiple calls*/
-	Play_ID ChainFile(Play_ID base, std::string const &next);
+	Play_ID chainFile(Play_ID base, std::string const &next);
 
 	//!allows automatic queuing of sounds - good for dynamic sound sources!
 	/*!if you chain more than once to the same base, the new buffers are appended
 	 * to the end of the chain - the new buffer doesn't replace the current chain
 	 * @return @a base - just for convenience of multiple calls*/
-	Play_ID ChainBuffer(Play_ID base, const char buf[], unsigned int len);
+	Play_ID chainBuffer(Play_ID base, const char buf[], unsigned int len);
 
 	//!allows automatic queuing of sounds - good for dynamic sound sources!
 	/*!if you chain more than once to the same base, the new buffers are appended
 	 * to the end of the chain - the new buffer doesn't replace the current chain
 	 * @return @a base - just for convenience of multiple calls*/
-	Play_ID Chain(Play_ID base, Snd_ID next);
+	Play_ID chain(Play_ID base, Snd_ID next);
 	
 	//!Lets you stop playback of all sounds
-	void StopPlay();
+	void stopPlay();
 
 	//!Lets you stop playback of a sound
-	void StopPlay(Play_ID id);
+	void stopPlay(Play_ID id);
 	
 	//!Lets you pause playback
-	void PausePlay(Play_ID id);
+	void pausePlay(Play_ID id);
 	
 	//!Lets you resume playback
-	void ResumePlay(Play_ID id);
+	void resumePlay(Play_ID id);
 	
 	//!Lets you control the maximum number of channels (currently playing sounds), method for mixing (applies when max_chan>1), and queuing method (for when overflow channels)
-	void SetMode(unsigned int max_channels, MixMode_t mixer_mode, QueueMode_t queuing_mode);
+	void setMode(unsigned int max_channels, MixMode_t mixer_mode, QueueMode_t queuing_mode);
 
 	//!Gives the time until the sound finishes, in milliseconds.  Subtract 32 to get guarranteed valid time for this ID.
 	/*!You should be passing the beginning of a chain to get proper results...\n
@@ -168,7 +171,7 @@
 	 * (and cause the ID to go invalid) up to RobotInfo::SoundBufferTime (32 ms)
 	 * before the sound finishes.  So subtract SoundBufferTime if you want to be
 	 * absolutely sure the ID will still valid. */
-	unsigned int GetRemainTime(Play_ID id) const;
+	unsigned int getRemainTime(Play_ID id) const;
 	
 #ifdef PLATFORM_APERIOS
 	//!Copies the sound data to the OPENR buffer, ready to be passed to the system, only called by SoundPlay
@@ -187,16 +190,41 @@
 	void ProcessMsg(RCRegion * rcr);
 	
 	//! returns number of sounds currently playing
-	unsigned int GetNumPlaying() { return chanlist.size(); }
+	unsigned int getNumPlaying() { return chanlist.size(); }
+	
+	//! return the next region serial number -- doesn't actually increment it though, repeated calls will return the same value until the value is actually used
+	virtual unsigned int getNextKey() { return sn+1; }
+	
+	/*! @brief These functions retain an older style first-letter capitalization derived from the OPEN-R
+	 *  sample code.  You should use the Java-style naming convention instead (first letter lowercase) */
+	//!@name Deprecated
+	Snd_ID LoadFile(std::string const &name) ATTR_deprecated; //!< deprecated, use loadFile() (note first letter lower case)
+	Snd_ID LoadBuffer(const char buf[], unsigned int len) ATTR_deprecated; //!< deprecated, use loadBuffer() (note first letter lower case)
+	void ReleaseFile(std::string const &name) ATTR_deprecated; //!< deprecated, use releaseFile() (note first letter lower case)
+	void Release(Snd_ID id) ATTR_deprecated; //!< deprecated, use release() (note first letter lower case)
+	Play_ID PlayFile(std::string const &name) ATTR_deprecated; //!< deprecated, use playFile() (note first letter lower case)
+	Play_ID PlayBuffer(const char buf[], unsigned int len) ATTR_deprecated; //!< deprecated, use playBuffer() (note first letter lower case)
+	Play_ID Play(Snd_ID id) ATTR_deprecated; //!< deprecated, use play() (note first letter lower case)
+	Play_ID ChainFile(Play_ID base, std::string const &next) ATTR_deprecated; //!< deprecated, use chainFile() (note first letter lower case)
+	Play_ID ChainBuffer(Play_ID base, const char buf[], unsigned int len) ATTR_deprecated; //!< deprecated, use chainBuffer() (note first letter lower case)
+	Play_ID Chain(Play_ID base, Snd_ID next) ATTR_deprecated; //!< deprecated, use chain() (note first letter lower case)
+	void StopPlay() ATTR_deprecated; //!< deprecated, use stopPlay() (note first letter lower case)
+	void StopPlay(Play_ID id) ATTR_deprecated; //!< deprecated, use stopPlay() (note first letter lower case)
+	void PausePlay(Play_ID id) ATTR_deprecated; //!< deprecated, use pausePlay() (note first letter lower case)
+	void ResumePlay(Play_ID id) ATTR_deprecated; //!< deprecated, use resumePlay() (note first letter lower case)
+	void SetMode(unsigned int max_channels, MixMode_t mixer_mode, QueueMode_t queuing_mode) ATTR_deprecated; //!< deprecated, use setMode() (note first letter lower case)
+	unsigned int GetRemainTime(Play_ID id) const ATTR_deprecated; //!< deprecated, use getRemainTime() (note first letter lower case)
+	unsigned int GetNumPlaying() ATTR_deprecated; //!< deprecated, use getNumPlaying() (note first letter lower case)
+	//@}
 	
 protected:
 	//!Mixes the channel into the buffer
-	void MixChannel(Play_ID channelId, void* buf, size_t size);
+	void mixChannel(Play_ID channelId, void* buf, size_t size);
 	
 	//!Mixes the channel into the buffer additively
 	/*!If mode is Quality, then the size of the buffer should be double the normal
 	* size. */
-	void MixChannelAdditively(Play_ID channelId, int bitsPerSample, MixMode_t mode, short scalingFactor, void* buf, size_t size);
+	void mixChannelAdditively(Play_ID channelId, int bitsPerSample, MixMode_t mode, short scalingFactor, void* buf, size_t size);
 	
 	//!The intermediate mixer buffer used for Quality mode mixing
 	int* mixerBuffer;
@@ -216,7 +244,7 @@
 	//!update the offsets of sounds which weren't mixed (when needed depending on queue_mode)
 	void updateChannels(const std::vector<Play_ID>& mixs,size_t used);
 
-	//!called when a buffer end is reached, may reset buffer to next in chain, or just StopPlay()
+	//!called when a buffer end is reached, may reset buffer to next in chain, or just stopPlay()
 	bool endPlay(Play_ID id);
 
 	//!Holds data about the loaded sounds
@@ -254,10 +282,10 @@
 	//!Holds a list of all currently playing sounds, ordered newest (front) to oldest(back)
 	chanlist_t chanlist;
 	
-	//!Current mixing mode, set by SetMode();
+	//!Current mixing mode, set by setMode();
 	MixMode_t mix_mode;
 
-	//!Current queuing mode, set by SetMode();
+	//!Current queuing mode, set by setMode();
 	QueueMode_t queue_mode;
 
 	//!Current maximum number of sounds to mix together
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Sound/SoundManagerMsg.h ./Sound/SoundManagerMsg.h
--- ../Tekkotsu_2.4.1/Sound/SoundManagerMsg.h	2005-06-01 01:47:54.000000000 -0400
+++ ./Sound/SoundManagerMsg.h	2006-09-16 16:11:53.000000000 -0400
@@ -13,7 +13,12 @@
 	typedef unsigned short Snd_ID;
 
 	//! Denotes what type of message this is
-	enum MsgType { add, del, wakeup, unknown } type;
+	enum MsgType {
+		add, //!< indicates a new sound to be played
+		del, //!< indicates the sound with #id should be stopped
+		wakeup, //!< indicates that it's time to start sending sounds to the system
+		unknown //!< initial value for #type until one of the others is assigned
+	} type; //!< indicates how this message should be processed
 	
 	//! The id of the sound this is in reference to
 	Snd_ID id;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/BallDetectionGenerator.cc ./Vision/BallDetectionGenerator.cc
--- ../Tekkotsu_2.4.1/Vision/BallDetectionGenerator.cc	2005-07-06 18:49:22.000000000 -0400
+++ ./Vision/BallDetectionGenerator.cc	2006-09-11 19:05:18.000000000 -0400
@@ -1,10 +1,10 @@
 #include "BallDetectionGenerator.h"
 #include "Events/EventRouter.h"
 #include "Shared/Util.h"
-#include "Shared/WorldState.h"
 #include "Wireless/Wireless.h"
 #include "Shared/Config.h"
 #include "Events/VisionObjectEvent.h"
+#include "Shared/Profiler.h"
 
 #include "Vision/SegmentedColorGenerator.h"
 #include "Vision/RegionGenerator.h"
@@ -17,7 +17,7 @@
 
 void
 BallDetectionGenerator::processEvent(const EventBase& e) {
-	PROFSECTION("BallDetection::processEvent()",state->mainProfile);
+	PROFSECTION("BallDetection::processEvent()",*mainProfiler);
 	EventGeneratorBase::processEvent(e);
 	if(e.getGeneratorID()!=getListenGeneratorID() || e.getSourceID()!=getListenSourceID())
 		return;
@@ -260,18 +260,19 @@
 	float cx2=2.0f*(regX2+1)/dim - cw;
 	float cy1=2.0f*regY1/dim - ch;
 	float cy2=2.0f*(regY2+1)/dim - ch;
+	float carea=4.0f*area/(dim*dim);
 	unsigned int frame_number=ev.getFrameNumber();	
 
 	if (conf>confidenceThreshold) {
 		if (present) {
 			count=0;
-			createEvent(EventBase::statusETID,cx1,cx2,cy1,cy2,area,cw,ch,frame_number);
+			createEvent(EventBase::statusETID,cx1,cx2,cy1,cy2,carea,cw,ch,frame_number);
 		} else {
 			count++;
 			if (count>noiseThreshold) {
 				count=0;
 				present=true;
-				createEvent(EventBase::activateETID,cx1,cx2,cy1,cy2,area,cw,ch,frame_number);
+				createEvent(EventBase::activateETID,cx1,cx2,cy1,cy2,carea,cw,ch,frame_number);
 			}
 		}
 	} else {
@@ -282,9 +283,9 @@
 			if (count>noiseThreshold) {
 				count=0;
 				present=false;
-				createEvent(EventBase::deactivateETID,0,0,0,0,area,cw,ch,frame_number);
+				createEvent(EventBase::deactivateETID,0,0,0,0,carea,cw,ch,frame_number);
 			} else {
-				createEvent(EventBase::statusETID,cx1,cx2,cy1,cy2,area,cw,ch,frame_number);
+				createEvent(EventBase::statusETID,cx1,cx2,cy1,cy2,carea,cw,ch,frame_number);
 			}
 		}
 	}
@@ -292,8 +293,8 @@
 
 void
 BallDetectionGenerator::createEvent(EventBase::EventTypeID_t etid, float bbX1,float bbX2,float bbY1,float bbY2,float area,float rx,float ry,unsigned int frame) const {
-	VisionObjectEvent * vo=new VisionObjectEvent(mySourceID,etid,bbX1,bbX2,bbY1,bbY2,area,rx,ry,frame);
-	vo->setName(getName());
+	VisionObjectEvent vo(mySourceID,etid,bbX1,bbX2,bbY1,bbY2,area,rx,ry,frame);
+	vo.setName(getName());
 	erouter->postEvent(vo);
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/BallDetectionGenerator.h ./Vision/BallDetectionGenerator.h
--- ../Tekkotsu_2.4.1/Vision/BallDetectionGenerator.h	2005-06-23 14:46:15.000000000 -0400
+++ ./Vision/BallDetectionGenerator.h	2005-11-04 18:28:21.000000000 -0500
@@ -3,6 +3,7 @@
 #define INCLUDED_BallDetectionGenerator_h_
 
 #include "Events/EventGeneratorBase.h"
+#include <math.h>
 
 class FilterBankEvent;
 class RegionGenerator;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/BufferedImageGenerator.cc ./Vision/BufferedImageGenerator.cc
--- ../Tekkotsu_2.4.1/Vision/BufferedImageGenerator.cc	2005-08-15 19:19:01.000000000 -0400
+++ ./Vision/BufferedImageGenerator.cc	2006-09-11 19:05:19.000000000 -0400
@@ -1,12 +1,12 @@
+#ifndef PLATFORM_APERIOS
+
 #include "BufferedImageGenerator.h"
 #include "Events/DataEvent.h"
 #include "Events/FilterBankEvent.h"
 #include "Wireless/Socket.h"
 #include "Events/EventRouter.h"
 #include "Shared/debuget.h"
-#ifndef PLATFORM_APERIOS
-#  include "IPC/MessageReceiver.h"
-#endif
+#include "Shared/ProjectInterface.h"
 
 using namespace std;
 
@@ -15,7 +15,6 @@
 	if(event.getGeneratorID()!=getListenGeneratorID() || event.getSourceID()!=getListenSourceID())
 		return;
 	if(event.getTypeID()==EventBase::activateETID) {
-		accessed=false;
 		const DataEvent<ImageSource>* data=dynamic_cast<const DataEvent<ImageSource>*>(&event);
 		if(data==NULL) {
 			serr->printf("Error: %s(%s) received event of the wrong type",getClassName().c_str(),getName().c_str());
@@ -24,81 +23,67 @@
 		if(imgsrc.layer!=data->getData().layer || imgsrc.channels!=data->getData().channels) {
 			//can "quietly" switch the layer of transmission as long as the width and height were scaled properly
 			//just need to reset the increments if a different layer is being used.
-			for(unsigned int i=0; i<=data->getData().layer; i++) {
-				increments[i] = (1<<(data->getData().layer-i))*data->getData().channels;
-				strides[i]=(1<<(data->getData().layer-i))*data->getData().width*data->getData().channels;
-				skips[i]=strides[i]-data->getData().width*data->getData().channels;
+			unsigned int i;
+			for(i=0; i<data->getData().layer; i++) {
+				increments[i] = 1;
+				strides[i]=data->getData().width>>(data->getData().layer-i);
+				skips[i]=0;
 			}
-			for(unsigned int i=data->getData().layer+1; i<numLayers; i++) {
+			increments[i] = data->getData().channels;
+			strides[i]=data->getData().width*data->getData().channels;
+			skips[i]=0;
+			for(++i; i<numLayers; i++) {
 				increments[i] = 1;
-				strides[i]=data->getData().width*(1<<(i-data->getData().layer));
+				strides[i]=data->getData().width<<(i-data->getData().layer);
 				skips[i]=0;
 			}
 		}
 		imgsrc=data->getData();
 		sysFrameNumber=frameNumber=imgsrc.frameIndex;
-		// -- invalidate dependant images: --
-		//images in every channel beyond the received channels is invalid
-		for(unsigned int i=0; i<numLayers; i++)
-			for(unsigned int j=imgsrc.channels; j<numChannels; j++) {
-				if(!isAllocated[i][j]) //in case the imgsrc layer changes
-					images[i][j]=NULL;
-				imageValids[i][j]=false;
-			}
-		//images in every layer above the received layer is invalid
-		for(unsigned int i=imgsrc.layer+1; i<numLayers; i++)
-			for(unsigned int j=0; j<imgsrc.channels; j++) { //already covered src.channels to numChannels in previous loop
-				if(!isAllocated[i][j]) //in case the imgsrc layer changes
-					images[i][j]=NULL;
-				imageValids[i][j]=false;
-			}
-		// -- check if the size has changed: --
+		invalidateCaches(); //mark everything invalid
 		if(numLayers>0) {
+			// have images, check if the dimensions have changed
 			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, 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]);
 			} else if(strides[numLayers-1]==0) {
 				// first frame, set it anyway
 				setDimensions();
 			}
 		}
 		// -- reassign to the new buffer: --
-		for(unsigned int i=imgsrc.layer; i!=-1U; i--) {
-			for(unsigned int j=0; j<imgsrc.channels; j++) {
-				if(isAllocated[i][j]) { //in case the imgsrc layer changes
-					delete [] images[i][j];
-					images[i][j]=NULL;
-					isAllocated[i][j]=false;
-				}
-				imageValids[i][j]=true;
+		unsigned int i=imgsrc.layer;
+		for(unsigned int j=0; j<imgsrc.channels; j++) {
+			if(isAllocated[i][j]) { //in case the imgsrc layer changes
+				delete [] images[i][j];
+				images[i][j]=NULL;
+				isAllocated[i][j]=false;
 			}
-			images[i][RawCameraGenerator::CHAN_Y]=imgsrc.img+0;
-			images[i][RawCameraGenerator::CHAN_U]=imgsrc.img+2; //note U is *third*
-			images[i][RawCameraGenerator::CHAN_V]=imgsrc.img+1; //note V is *second*
+			imageValids[i][j]=true;
 		}
+		images[i][RawCameraGenerator::CHAN_Y]=imgsrc.img+0;
+		images[i][RawCameraGenerator::CHAN_U]=imgsrc.img+1;
+		images[i][RawCameraGenerator::CHAN_V]=imgsrc.img+2;
 		framesProcessed++;
 	}
-	erouter->postEvent(new FilterBankEvent(this,getGeneratorID(),getSourceID(),event.getTypeID()));
+	erouter->postEvent(FilterBankEvent(this,getGeneratorID(),getSourceID(),event.getTypeID()));
 }
 
 unsigned int
 BufferedImageGenerator::getBinSize() const {
 	unsigned int used=FilterBankGenerator::getBinSize();
-	used+=strlen("RawImage")+LoadSave::stringpad;
+	used+=getSerializedSize("RawImage");
 	used+=widths[selectedSaveLayer]*heights[selectedSaveLayer];
 	return used;
 }
 
 unsigned int
-BufferedImageGenerator::LoadBuffer(const char buf[], unsigned int len) {
+BufferedImageGenerator::loadBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
-	unsigned int used;
+	if(!checkInc(FilterBankGenerator::loadBuffer(buf,len),buf,len)) return 0;
 	std::string tmp;
-	if(0==(used=FilterBankGenerator::LoadBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(tmp,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(decode(tmp,buf,len)) return 0;
 	if(tmp!="RawImage") {
 		serr->printf("Unhandled image type for BufferedImageGenerator: %s",tmp.c_str());
 		return 0;
@@ -109,7 +94,7 @@
 		if(images[selectedSaveLayer][selectedSaveChannel]==NULL)
 			images[selectedSaveLayer][selectedSaveChannel]=createImageCache(selectedSaveLayer,selectedSaveChannel);
 		unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
-		used=widths[selectedSaveLayer]*heights[selectedSaveLayer];
+		unsigned int used=widths[selectedSaveLayer]*heights[selectedSaveLayer];
 		ASSERTRETVAL(used<=len,"buffer too small",0);
 		memcpy(img,buf,used);
 		len-=used; buf+=used;
@@ -119,24 +104,21 @@
 }
 
 unsigned int
-BufferedImageGenerator::SaveBuffer(char buf[], unsigned int len) const {
+BufferedImageGenerator::saveBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=FilterBankGenerator::SaveBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode("RawImage",buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkInc(FilterBankGenerator::saveBuffer(buf,len),buf,len)) return 0;
+	if(!encodeInc("RawImage",buf,len)) return 0;
 	
 	if(images[selectedSaveLayer][selectedSaveChannel]==NULL) {
-		serr->printf("BufferedImageGenerator::SaveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("BufferedImageGenerator::saveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	if(!imageValids[selectedSaveLayer][selectedSaveChannel]) {
-		serr->printf("BufferedImageGenerator::SaveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("BufferedImageGenerator::saveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
-	used=widths[selectedSaveLayer]*heights[selectedSaveLayer];
+	unsigned int used=widths[selectedSaveLayer]*heights[selectedSaveLayer];
 	ASSERTRETVAL(used<=len,"buffer too small",0);
 	unsigned int inc=getIncrement(selectedSaveLayer);
 	if(inc==1) {
@@ -163,20 +145,20 @@
 }
 
 unsigned int
-BufferedImageGenerator::SaveFileStream(FILE * f) const {
+BufferedImageGenerator::saveFileStream(FILE * f) const {
 	unsigned int totalused=0;
 	unsigned int used;
-	{ //sigh, inheritance has failed me (I wouldn't want FilterBankGenerator::SaveFileStream() to call the virtuals...)
+	{ //sigh, inheritance has failed me (I wouldn't want FilterBankGenerator::saveFileStream() to call the virtuals...)
 		unsigned int sz=FilterBankGenerator::getBinSize();
 		char * buf = new char[sz];
 		memset(buf,0xF0,sz);
 		if(buf==NULL) {
-			std::cout << "*** WARNING could not allocate " << sz << " bytes for LoadFile";
+			std::cout << "*** WARNING could not allocate " << sz << " bytes for loadFile";
 			return 0;
 		}
-		unsigned int resp=FilterBankGenerator::SaveBuffer(buf,sz);
+		unsigned int resp=FilterBankGenerator::saveBuffer(buf,sz);
 		if(resp==0) {
-			std::cout << "*** WARNING SaveBuffer didn't write any data (possibly due to overflow or other error)" << std::endl;
+			std::cout << "*** WARNING saveBuffer didn't write any data (possibly due to overflow or other error)" << std::endl;
 			fwrite(buf,1,sz,f);
 		}	else {
 			unsigned int wrote=fwrite(buf,1,resp,f);
@@ -192,11 +174,11 @@
 	totalused+=used;
 	
 	if(images[selectedSaveLayer][selectedSaveChannel]==NULL) {
-		serr->printf("BufferedImageGenerator::SaveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("BufferedImageGenerator::saveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	if(!imageValids[selectedSaveLayer][selectedSaveChannel]) {
-		serr->printf("BufferedImageGenerator::SaveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("BufferedImageGenerator::saveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
@@ -231,16 +213,6 @@
 	return totalused;
 }
 
-unsigned char * BufferedImageGenerator::getImage(unsigned int layer, unsigned int channel) {
-	if(!accessed && imgsrc.receiver!=NULL) {
-		accessed=true;
-#ifndef PLATFORM_APERIOS
-		imgsrc.receiver->markRead();
-#endif
-	}
-	return FilterBankGenerator::getImage(layer,channel);
-}
-
 void BufferedImageGenerator::freeCaches() {
 	FilterBankGenerator::freeCaches();
 	for(unsigned int i=0; i<numLayers; i++)
@@ -258,31 +230,48 @@
 }
 
 unsigned char * BufferedImageGenerator::createImageCache(unsigned int layer, unsigned int channel) const {
-	isAllocated[layer][channel]=true;
-	return new unsigned char[widths[layer]*heights[layer]];
+	if(layer!=imgsrc.layer || imgsrc.channels==1) {
+		isAllocated[layer][channel]=true;
+		return new unsigned char[widths[layer]*heights[layer]];
+	} else {
+		ASSERT(channel>=imgsrc.channels,"createImageCache for image that should come from src")
+		// increment is set to imgsrc.channels, so we need to allocate multiple images at once for the generate channels
+		unsigned int base=(channel/imgsrc.channels)*imgsrc.channels; // round down to nearest multiple of imgsrc.channels
+		if(images[layer][base]==NULL)
+			images[layer][base]=new unsigned char[widths[layer]*heights[layer]*imgsrc.channels];
+		for(unsigned int i=base+1; i<base+imgsrc.channels; ++i) {
+			ASSERT(!isAllocated[layer][i],"createImageCache for image already allocated!");
+			ASSERT(images[layer][i]==NULL,"createImageCache for image already assigned!");
+			images[layer][i]=images[layer][i-1]+1;
+		}
+		isAllocated[layer][base]=true;
+		return images[layer][channel];
+	}
 }
 void BufferedImageGenerator::calcImage(unsigned int layer, unsigned int channel) {
 	//cout << "BufferedImageGenerator::calcImage(" << layer << ',' << channel << ')' << endl;
+	ASSERTRET(layer!=imgsrc.layer || channel>=imgsrc.channels, "calcImage on src channel?");
 	switch(channel) {
 		case RawCameraGenerator::CHAN_Y:
-			upsampleImage(imgsrc.layer,channel,layer); break;
+			if(layer>imgsrc.layer) upsampleImage(imgsrc.layer,channel,layer);
+			else downsampleImage(layer,channel);
+			break;
 		case RawCameraGenerator::CHAN_U:
 		case RawCameraGenerator::CHAN_V:
-			if(imgsrc.channels>1)
-				upsampleImage(imgsrc.layer,channel,layer);
-			else
+			if(imgsrc.channels>1) {
+				if(layer>imgsrc.layer) upsampleImage(imgsrc.layer,channel,layer);
+				else downsampleImage(layer,channel);
+			} else //grayscale image, use blank U and V channels
 				memset(images[layer][channel],128,widths[layer]*heights[layer]);
 			break;
-		case RawCameraGenerator::CHAN_Y_DY:
 		case RawCameraGenerator::CHAN_Y_DX:
+			calcDx(layer);
+			break;
+		case RawCameraGenerator::CHAN_Y_DY:
+			calcDy(layer);
+			break;
 		case RawCameraGenerator::CHAN_Y_DXDY:
-			if(layer<=imgsrc.layer) {
-				//todo
-				memset(images[layer][channel],128,widths[layer]*heights[layer]);
-			} else if(layer>imgsrc.layer) {
-				getImage(imgsrc.layer,channel);
-				upsampleImage(imgsrc.layer,channel,layer);
-			}
+			calcDxDy(layer);
 			break;
 		default:
 			cerr << "Bad layer selection!" << endl;
@@ -301,7 +290,7 @@
 		//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;
-		cout << "setDimensions() " << widths[i] << ' ' << skips[i] << ' ' << strides[i] << endl;
+		//cout << "setDimensions() " << widths[i] << ' ' << skips[i] << ' ' << strides[i] << endl;
 	}
 	//set dimensions for layers above the input layer, these are not interleaved
 	for(unsigned int i=imgsrc.layer+1; i<numLayers; i++) {
@@ -326,12 +315,16 @@
 		return;
 	FilterBankGenerator::setNumImages(nLayers,nChannels);
 	isAllocated=new bool*[numLayers];
-	for(unsigned int i=0; i<numLayers; i++)
+	for(unsigned int i=0; i<numLayers; i++) {
 		isAllocated[i]=new bool[numChannels];
+		for(unsigned int j=0; j<numChannels; j++)
+			isAllocated[i][j]=false;
+	}
 	setDimensions();
 }
 
 void BufferedImageGenerator::upsampleImage(unsigned int srcLayer, unsigned int chan, unsigned int destLayer) {
+	ASSERTRET(destLayer!=imgsrc.layer,"upsample into source layer")
 	unsigned char * cur=images[destLayer][chan];
 	ASSERTRET(cur!=NULL,"destination layer is NULL");
 	unsigned char * orig=getImage(srcLayer,chan);
@@ -347,8 +340,8 @@
 		unsigned char * const row=cur;
 		unsigned char * const rowend=cur+width;
 		//upsample pixels within one row
-		while(cur!=rowend) {
-			for(int p=power; p>=0; p--)
+		while(cur<rowend) {
+			for(int p=1<<power; p>0; p--)
 				*cur++=*orig;
 			orig+=inc;
 		}
@@ -360,11 +353,108 @@
 		}
 		orig+=getSkip(srcLayer);
 	}
+	imageValids[destLayer][chan]=true;
+}
+
+void BufferedImageGenerator::downsampleImage(unsigned int destLayer, unsigned int chan) {
+	ASSERTRET(destLayer!=imgsrc.layer,"downsample into source layer")
+	// find closest available layer to source from
+	unsigned int layer=destLayer;
+	while(layer<numLayers && !imageValids[layer][chan])
+		layer++;
+	ASSERTRET(layer<numLayers,"valid layer to downsample from could not be found!");
+	// we'll compute in-between layers as we go (easier computation and might be able to reuse them anyway)
+	// layer is the current layer we're downsampling into (layer+1 is the one we're sampling from)
+	for(unsigned int srcL=layer--; layer>=destLayer; srcL=layer--) {
+		unsigned int srcInc=getIncrement(srcL); // destination increment is guaranteed to be 1, but source increment isn't
+		unsigned char * s=getImage(srcL,chan);
+		if(images[layer][chan]==NULL)
+			images[layer][chan]=createImageCache(layer,chan);
+		unsigned char * dst=images[layer][chan];
+		unsigned char * const dstEnd=dst+widths[layer]*heights[layer];
+		while(dst!=dstEnd) {
+			unsigned char * const rowEnd=dst+widths[layer];
+			while(dst!=rowEnd) {
+				unsigned short x=*s;
+				x+=*(s+strides[srcL]);
+				s+=srcInc;
+				x+=*s;
+				x+=*(s+strides[srcL]);
+				s+=srcInc;
+				*dst++ = x/4;
+			}
+			s+=strides[srcL];
+		}
+		imageValids[layer][chan]=true;
+	}
+}
+
+void BufferedImageGenerator::calcDx(unsigned int layer, unsigned int srcChan/*=RawCameraGenerator::CHAN_Y*/, unsigned int dstChan/*=RawCameraGenerator::CHAN_Y_DX*/) {
+	unsigned char * s=getImage(layer,srcChan);
+	unsigned char * dst=images[layer][dstChan];
+	unsigned int inc=getIncrement(layer);
+	unsigned int skip=getSkip(layer)+inc;
+	unsigned char * const dstEnd=dst+getStride(layer)*heights[layer];
+	unsigned int sc=2;  // i think this should be 1, but this is to provide better compatability with the OPEN-R implementation
+	while(dst!=dstEnd) {
+		unsigned char * const rowEnd=dst+widths[layer]*inc-inc;
+		unsigned char left,right;
+		while(dst!=rowEnd) {
+			left=(*s)>>sc;
+			s+=inc;
+			right=(*s)>>sc;
+			*dst=right+128-left;
+			dst+=inc;
+		}
+		*dst=128; //rightmost column is always 128 to retain image dimensions
+		dst+=skip;
+		s+=skip;
+	}
+	imageValids[layer][dstChan]=true;
+}
+void BufferedImageGenerator::calcDy(unsigned int layer, unsigned int srcChan/*=RawCameraGenerator::CHAN_Y*/, unsigned int dstChan/*=RawCameraGenerator::CHAN_Y_DY*/) {
+	unsigned char * s=getImage(layer,srcChan);
+	unsigned char * dst=images[layer][dstChan];
+	unsigned int inc=getIncrement(layer);
+	unsigned int stride=getStride(layer);
+	unsigned char * const dstEnd=dst+widths[layer]*inc;
+	unsigned int sc=2;  // i think this should be 1, but this is to provide better compatability with the OPEN-R implementation
+	while(dst!=dstEnd) {
+		unsigned char * const colEnd=dst+heights[layer]*stride-stride;
+		unsigned char top,bottom;
+		while(dst!=colEnd) {
+			top=(*s)>>sc;
+			s+=stride;
+			bottom=(*s)>>sc;
+			*dst=bottom+128-top;
+			dst+=stride;
+		}
+		*dst=128; //bottommost column is always 128 to retain image dimensions
+		dst-=heights[layer]*stride-stride;
+		s-=heights[layer]*stride-stride;
+		dst+=inc;
+		s+=inc;
+	}
+	imageValids[layer][dstChan]=true;
+}
+void BufferedImageGenerator::calcDxDy(unsigned int layer) {
+	// if one of the dx or dy channel is already available, go from there
+	if(imageValids[layer][RawCameraGenerator::CHAN_Y_DX]) {
+		calcDy(layer,RawCameraGenerator::CHAN_Y_DX,RawCameraGenerator::CHAN_Y_DXDY);
+		imageValids[layer][RawCameraGenerator::CHAN_Y_DXDY]=true;
+	} else if(imageValids[layer][RawCameraGenerator::CHAN_Y_DY]) {
+		calcDx(layer,RawCameraGenerator::CHAN_Y_DY,RawCameraGenerator::CHAN_Y_DXDY);
+		imageValids[layer][RawCameraGenerator::CHAN_Y_DXDY]=true;
+	} else {
+		// if neither are available, calculate one of them (dx), and then the other from that
+		getImage(layer,RawCameraGenerator::CHAN_Y_DX);
+		calcDy(layer,RawCameraGenerator::CHAN_Y_DX,RawCameraGenerator::CHAN_Y_DXDY);
+	}
 }
 
 
 /*! @file
- * @brief 
+ * @brief Implements BufferedImageGenerator, which receives camera frames as they are loaded by the simulator -- or eventually other sources
  * @author Ethan Tira-Thompson (ejt) (Creator)
  *
  * $Author: ejt $
@@ -368,8 +458,10 @@
  * @author Ethan Tira-Thompson (ejt) (Creator)
  *
  * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
  * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
+ * $Date: 2006/10/04 04:21:12 $
  */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/BufferedImageGenerator.h ./Vision/BufferedImageGenerator.h
--- ../Tekkotsu_2.4.1/Vision/BufferedImageGenerator.h	2005-08-07 00:11:04.000000000 -0400
+++ ./Vision/BufferedImageGenerator.h	2006-09-09 00:33:04.000000000 -0400
@@ -5,19 +5,17 @@
 #include "FilterBankGenerator.h"
 #include "RawCameraGenerator.h"
 
-class MessageReceiver;
-
-//! description of BufferedImageGenerator
+//! Receives camera frames as they are loaded by the simulator -- or eventually other sources
 class BufferedImageGenerator : public FilterBankGenerator {
 public:
 	//!Stores information about the current frame, (not the image itself, but meta data a pointer to it)
 	struct ImageSource {
 		//!constructor
-		ImageSource() : width(0), height(0), channels(0), frameIndex(0), layer(0), receiver(NULL), img(NULL) {}
+		ImageSource() : width(0), height(0), channels(0), frameIndex(0), layer(0), img(NULL) {}
 		//!copy constructor
-		ImageSource(const ImageSource& src) : width(src.width), height(src.height), channels(src.channels), frameIndex(src.frameIndex), layer(src.layer), receiver(src.receiver), img(src.img) {}
+		ImageSource(const ImageSource& src) : width(src.width), height(src.height), channels(src.channels), frameIndex(src.frameIndex), layer(src.layer), img(src.img) {}
 		//!assignment operator
-		ImageSource& operator=(const ImageSource& src) { width=src.width; height=src.height; channels=src.channels; frameIndex=src.frameIndex; layer=src.layer; receiver=src.receiver; img=src.img; return *this; } 
+		ImageSource& operator=(const ImageSource& src) { width=src.width; height=src.height; channels=src.channels; frameIndex=src.frameIndex; layer=src.layer; img=src.img; return *this; } 
 		unsigned int width; //!< the width of #img
 		unsigned int height; //!< the height of #img
 		unsigned int channels; //!< the number of color channels in #img
@@ -28,10 +26,6 @@
 		 *  Non-negative values are interpreted as direct layer values, so 0 indicates bottommost layer, 1 indicates next-to-bottom, and so on. */
 		unsigned int layer; 
 
-		//! a pointer back to the MessageReceiver which got the image
-		/*! If this value is non-NULL, when getImage is called, MessageReceiver::markRead() will be called on the receiver */
-		MessageReceiver * receiver;
-
 		//! pointer to the first byte of the image buffer
 		/*! img should be stored in a channel-interleaved format, e.g. RGBRGBRGB... */
 		unsigned char * img;
@@ -39,7 +33,7 @@
 
 	//! constructor
 	BufferedImageGenerator(const std::string& name,EventBase::EventGeneratorID_t mgid, unsigned int msid, unsigned int nLayers, EventBase::EventGeneratorID_t srcgid, unsigned int srcsid)
-		: FilterBankGenerator("BufferedImageGenerator",name,mgid,msid,srcgid,srcsid), imgsrc(), isAllocated(NULL), accessed(true)
+		: FilterBankGenerator("BufferedImageGenerator",name,mgid,msid,srcgid,srcsid), imgsrc(), isAllocated(NULL)
 	{ 
 		/* As a root stage, we need to listen to all incoming image
 		 * events, even if we don't currently have listeners of our own --
@@ -50,6 +44,7 @@
 		
 		setNumImages(nLayers,RawCameraGenerator::NUM_CHANNELS);
 	}
+	//!destructor
 	virtual ~BufferedImageGenerator() { destruct(); }
 	
 	//! need to override EventGeneratorBase's lazy listening -- as a root stage, need to remember each frame, just in case it might be used
@@ -59,20 +54,19 @@
 	
 	virtual unsigned int getBinSize() const;
 	
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
 	
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
 	
-	virtual unsigned int SaveFileStream(FILE* f) const; //!< overrridden to allow saving direct to file without an extra buffer copy
+	virtual unsigned int saveFileStream(FILE* f) const; //!< overrridden to allow saving direct to file without an extra buffer copy
 
-	virtual unsigned char * getImage(unsigned int layer, unsigned int channel);
 	virtual void freeCaches();
 	virtual void invalidateCaches();
 	
 protected:
 	//! constructor for subclasses
 	BufferedImageGenerator(const std::string& classname,const std::string& instancename,EventBase::EventGeneratorID_t mgid, unsigned int msid, unsigned int nLayers,EventBase::EventGeneratorID_t srcgid, unsigned int srcsid)
-		: FilterBankGenerator(classname,instancename,mgid,msid,srcgid,srcsid), imgsrc(), isAllocated(NULL), accessed(true)
+		: FilterBankGenerator(classname,instancename,mgid,msid,srcgid,srcsid), imgsrc(), isAllocated(NULL)
 	{setNumImages(nLayers,RawCameraGenerator::NUM_CHANNELS);}
 	
 	virtual unsigned char * createImageCache(unsigned int layer, unsigned int channel) const;
@@ -84,10 +78,17 @@
 	//! duplicates pixels to make a higher resolution version of @a srcLayer, @a chan into @a destLayer, @a chan
 	/*! Doesn't do anything fancy like blurring or smoothing */
 	virtual void upsampleImage(unsigned int srcLayer, unsigned int chan, unsigned int destLayer);
-
+	//! averages blocks of pixels to make smaller images
+	virtual void downsampleImage(unsigned int destLayer, unsigned int chan);
+	//! calculates the x-derivative
+	virtual void calcDx(unsigned int layer, unsigned int srcChan=RawCameraGenerator::CHAN_Y, unsigned int dstChan=RawCameraGenerator::CHAN_Y_DX);
+	//! calculates the x-derivative
+	virtual void calcDy(unsigned int layer, unsigned int srcChan=RawCameraGenerator::CHAN_Y, unsigned int dstChan=RawCameraGenerator::CHAN_Y_DY);
+	//! calculates the diagonal derivative
+	virtual void calcDxDy(unsigned int layer);
+	
 	ImageSource imgsrc; //!< the data storage of the current image (not the image itself, but meta data a pointer to it)
 	bool ** isAllocated; //!< for each image in the filterbank, a bool to account whether the pointer is to an external resource or a self-allocated resource
-	bool accessed; //!< marked true once getImage is called, reset to false with each new image (i.e. processEvent())
 	
 private:
 	BufferedImageGenerator(const BufferedImageGenerator&); //!< don't call
@@ -95,7 +96,7 @@
 };
 
 /*! @file
- * @brief 
+ * @brief Describes BufferedImageGenerator, which receives camera frames as they are loaded by the simulator -- or eventually other sources
  * @author Ethan Tira-Thompson (ejt) (Creator)
  *
  * $Author: ejt $
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/CDTGenerator.cc ./Vision/CDTGenerator.cc
--- ../Tekkotsu_2.4.1/Vision/CDTGenerator.cc	2005-06-03 18:56:30.000000000 -0400
+++ ./Vision/CDTGenerator.cc	2006-09-11 19:05:19.000000000 -0400
@@ -4,7 +4,7 @@
 #include "Events/SegmentedColorFilterBankEvent.h"
 #include "Wireless/Wireless.h"
 #include "Shared/Config.h"
-#include "Shared/WorldState.h"
+#include "Shared/Profiler.h"
 
 #include "Shared/ODataFormats.h"
 #include "OFbkImage.h"
@@ -81,7 +81,7 @@
 		framesProcessed++;
 	}
 	// todo - i wish we had some color infomation to pass here so we could use the event for CMVision's RLE, etc.
-	erouter->postEvent(new SegmentedColorFilterBankEvent(this,getGeneratorID(),getSourceID(),event.getTypeID(),NULL,0,NULL,NULL));
+	erouter->postEvent(SegmentedColorFilterBankEvent(this,getGeneratorID(),getSourceID(),event.getTypeID(),NULL,0,NULL,NULL));
 }
 
 unsigned int
@@ -95,17 +95,17 @@
 }
 
 unsigned int
-CDTGenerator::LoadBuffer(const char [] /*buf*/, unsigned int /*len*/) {
+CDTGenerator::loadBuffer(const char [] /*buf*/, unsigned int /*len*/) {
 	//all our memory is in system controlled buffers - we probably shouldn't overwrite it...
 	serr->printf("Can't load into CDTGenerator");
 	return 0;
 }
 
 unsigned int
-CDTGenerator::SaveBuffer(char buf[], unsigned int len) const {
+CDTGenerator::saveBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
 	unsigned int used;
-	if(0==(used=FilterBankGenerator::SaveBuffer(buf,len))) return 0;
+	if(0==(used=FilterBankGenerator::saveBuffer(buf,len))) return 0;
 	len-=used; buf+=used;
 	// todo - once we have color information - we could make this interoperable with SegmentedColorGenerator
 	// by following the same serialization format
@@ -113,11 +113,11 @@
 	len-=used; buf+=used;
 	
 	if(images[selectedSaveLayer][selectedSaveChannel]==NULL) {
-		serr->printf("CDTImage::SaveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("CDTImage::saveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	if(!imageValids[selectedSaveLayer][selectedSaveChannel]) {
-		serr->printf("CDTImage::SaveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("CDTImage::saveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
@@ -198,7 +198,7 @@
 
 void
 CDTGenerator::calcImage(unsigned int layer, unsigned int chan) {
-	PROFSECTION("CDTGenerator::calcImage(...)",state->mainProfile);
+	PROFSECTION("CDTGenerator::calcImage(...)",*mainProfiler);
 	unsigned int numNotRealLayers=numLayers-numRealLayers;
 	if(layer>=numNotRealLayers) {
 		unsigned int fbkdatChan=ofbkimageBAND_CDT;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/CDTGenerator.h ./Vision/CDTGenerator.h
--- ../Tekkotsu_2.4.1/Vision/CDTGenerator.h	2005-06-01 01:47:58.000000000 -0400
+++ ./Vision/CDTGenerator.h	2006-09-09 00:33:04.000000000 -0400
@@ -70,9 +70,9 @@
 
 	virtual unsigned int getBinSize() const;
 
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
 
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
 
 protected:
 	virtual void setNumImages(unsigned int nLayers, unsigned int nChannels);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/FilterBankGenerator.cc ./Vision/FilterBankGenerator.cc
--- ../Tekkotsu_2.4.1/Vision/FilterBankGenerator.cc	2005-07-06 18:49:22.000000000 -0400
+++ ./Vision/FilterBankGenerator.cc	2006-09-09 00:33:04.000000000 -0400
@@ -64,36 +64,24 @@
 	return used;
 }
 
-/*! The LoadBuffer() functions of the included subclasses aren't tested, so don't assume they'll work without a little debugging... */
-unsigned int FilterBankGenerator::LoadBuffer(const char buf[], unsigned int len) {
+/*! The loadBuffer() functions of the included subclasses aren't tested, so don't assume they'll work without a little debugging... */
+unsigned int FilterBankGenerator::loadBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
-	unsigned int used=0;
-	if(0==(used=checkCreator("FbkImage",buf,len,true))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(widths[selectedSaveLayer],buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(heights[selectedSaveLayer],buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(selectedSaveLayer,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(selectedSaveChannel,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkCreatorInc("FbkImage",buf,len,true)) return 0;
+	if(!decodeInc(widths[selectedSaveLayer],buf,len)) return 0;
+	if(!decodeInc(heights[selectedSaveLayer],buf,len)) return 0;
+	if(!decodeInc(selectedSaveLayer,buf,len)) return 0;
+	if(!decodeInc(selectedSaveChannel,buf,len)) return 0;
 	return origlen-len;	
 }
 
-unsigned int FilterBankGenerator::SaveBuffer(char buf[], unsigned int len) const {
+unsigned int FilterBankGenerator::saveBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used=0;
-	if(0==(used=saveCreator("FbkImage",buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(widths[selectedSaveLayer],buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(heights[selectedSaveLayer],buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(selectedSaveLayer,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode(selectedSaveChannel,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!saveCreatorInc("FbkImage",buf,len)) return 0;
+	if(!encodeInc(widths[selectedSaveLayer],buf,len)) return 0;
+	if(!encodeInc(heights[selectedSaveLayer],buf,len)) return 0;
+	if(!encodeInc(selectedSaveLayer,buf,len)) return 0;
+	if(!encodeInc(selectedSaveChannel,buf,len)) return 0;
 	return origlen-len;
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/FilterBankGenerator.h ./Vision/FilterBankGenerator.h
--- ../Tekkotsu_2.4.1/Vision/FilterBankGenerator.h	2005-08-07 00:11:04.000000000 -0400
+++ ./Vision/FilterBankGenerator.h	2006-09-09 00:33:04.000000000 -0400
@@ -25,8 +25,8 @@
  *  First, be sure to get a good overview of the LoadSave style.  Most
  *  serialization is handled using this interface.
  *
- *  When, for instance, RawCameraGenerator::SaveBuffer() is called, it
- *  first calls it's super class, FilterBankGenerator::SaveBuffer(),
+ *  When, for instance, RawCameraGenerator::saveBuffer() is called, it
+ *  first calls it's super class, FilterBankGenerator::saveBuffer(),
  *  which will write out the general image information, common to all
  *  subclasses of FilterBankGenerator. (i'll cover the specifics in a
  *  second) Once that's done, the RawCameraGenerator adds it's own bit
@@ -45,7 +45,7 @@
  *  it's a binary stream).  Each field is of the form '<@c type:name>
  *  <i>(notes)</i>'
  *  
- *  FilterBankGenerator Header: (from FilterBankGenerator::SaveBuffer())
+ *  FilterBankGenerator Header: (from FilterBankGenerator::saveBuffer())
  *  - <@c string: "FbkImage">  <i>(remember a 'string' is len+str+0; so this is the literal "\010\0\0\0FbkImage\0"; also remember "\010" is octal for 8)</i>
  *  - <@c unsigned @c int: width> 
  *  - <@c unsigned @c int: height> 
@@ -54,13 +54,13 @@
  * 
  *  Generator Specific Header (selected examples follow, or similarly, any of the other generators)
  *  
- *  - RawCameraGenerator: (from RawCameraGenerator::SaveBuffer())
+ *  - RawCameraGenerator: (from RawCameraGenerator::saveBuffer())
  *    - <@c string: "RawImage">
  *    - <<tt>char[</tt>width<tt>*</tt>height<tt>]</tt>: image data> <i>(note, just once channel being stored)</i>
- *  - InterleavedYUVGenerator: (from InterleavedYUVGenerator::SaveBuffer())
+ *  - InterleavedYUVGenerator: (from InterleavedYUVGenerator::saveBuffer())
  *    - <@c string: "InterleavedYUVImage">
  *    - <<tt>char[</tt>width<tt>*</tt>height<tt>*3]</tt>: image data> <i>(in YVU order, technically YCbCr)</i>
- *  - SegmentedColorGenerator: (from SegmentedColorGenerator::SaveBuffer())
+ *  - SegmentedColorGenerator: (from SegmentedColorGenerator::saveBuffer())
  *    - <@c string: "SegColorImage">
  *    - <<tt>char[</tt>width<tt>*</tt>height<tt>]</tt>: image data> <i>(one byte per sample)</i>
  *    - <@c unsigned @c int: num_cols> <i>(number of different colors available)</i>
@@ -68,7 +68,7 @@
  *      - <@c char: red> <i>red color to use for display of this index</i>
  *      - <@c char: green> <i>green color to use for display of this index</i>
  *      - <@c char: blue> <i>blue color to use for display of this index</i>
- *  - RLEGenerator: (from RLEGenerator::SaveBuffer())
+ *  - RLEGenerator: (from RLEGenerator::saveBuffer())
  *    - <@c string: "RLEImage">  <i>(remember a 'string' is len+str+0; so this is the literal "\010\0\0\0RLEImage\0"; also remember "\010" is octal for 8)</i>
  *    - <@c unsigned @c int: num_runs> <i>(how many runs will follow)</i>
  *    - for each of num_runs:
@@ -143,6 +143,11 @@
 	/*! this will cause the data to be calculated and cached if it's not already available */
 	virtual unsigned char * getImage(unsigned int layer, unsigned int channel);
 
+	//! returns whether or not an image has already been calculated for the current frame
+	/*! If you call this immediately after getImage() and this still returns false, 
+	 *  then an error must have occurred during processing */
+	virtual bool getImageCached(unsigned int layer, unsigned int channel) const { return imageValids[layer][channel]; }
+
 	//! returns width (in samples) of the image in a given layer
 	unsigned int getWidth(unsigned int layer) const { return widths[layer]; }
 
@@ -241,13 +246,13 @@
 
 	virtual unsigned int getBinSize() const;
 
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
 
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
 
 	//! Not actually part of the LoadSave interface, but allows you to select which image of the bank will be saved
 	/*! Calling this will also cause the image data for that image to be calculated,
-	 *  otherwise SaveBuffer won't have up-to-date data to save.
+	 *  otherwise saveBuffer won't have up-to-date data to save.
 	 *  
 	 *  When loading, the saved image's layer and channel will reset this */
 	virtual void selectSaveImage(unsigned int layer, unsigned int channel) { selectedSaveLayer=layer; selectedSaveChannel=channel; getImage(layer,channel);}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/Graphics.cc ./Vision/Graphics.cc
--- ../Tekkotsu_2.4.1/Vision/Graphics.cc	2005-07-10 16:02:39.000000000 -0400
+++ ./Vision/Graphics.cc	2006-07-02 21:54:58.000000000 -0400
@@ -9,7 +9,7 @@
 // ! check memory boundaries of image, first that we are after the start of the image, second that we are before the end of the image, and third that we are within a valid row (in case of interleaved rows), fourth that we are within a valid column (interleaved pixels)
 #define CHKBOUNDS(p,ERR_F) { \
 	unsigned int rowoffset=(p-img)-(p-img)/yInc*yInc; \
-	if(p<img || p>=img+w*xInc+h*yInc || rowoffset>=w*xInc || rowoffset/xInc*xInc!=rowoffset) { \
+	if(p<img || p>=img+h*yInc || rowoffset>=w*xInc || rowoffset/xInc*xInc!=rowoffset) { \
 		cout << "Graphics Bad draw! line:" << __LINE__ << " frame=" << (gen!=NULL?gen->getFrameNumber():0) << ' '  /*<< (void*)p << '-' << (void*)img << '='*/ << (int)(p-img) << " w=" << w << " xInc=" << xInc << " h=" << h << " yInc=" << yInc << endl; \
 		ERR_F; \
 	} \
@@ -53,8 +53,8 @@
 		return;
 	unsigned int left=x>0?x:0;
 	unsigned int top=y>0?y:0;
-	unsigned int right=x+width>=(int)w?w:x+width; //not inclusive
-	unsigned int bot=y+height>=(int)h?h:y+height; //not inclusive
+	unsigned int right=( (x+width>=(int)w) ? w : x+width); //not inclusive
+	unsigned int bot=( (y+height>=(int)h) ? h : y+height); //not inclusive
 	//left vertical
 	if(x>=0) {
 		unsigned char * p=img+top*yInc+left*xInc;
@@ -96,7 +96,7 @@
 		}
 	}
 	//bottom right corner
-	if((unsigned int)right<w && (unsigned int)bot<h) {
+	if(right<w && bot<h) {
 		unsigned char * p=img+bot*yInc+right*xInc;
 		CHKBOUNDS(p,return);
 		*p=c;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/InterleavedYUVGenerator.cc ./Vision/InterleavedYUVGenerator.cc
--- ../Tekkotsu_2.4.1/Vision/InterleavedYUVGenerator.cc	2005-08-15 18:57:16.000000000 -0400
+++ ./Vision/InterleavedYUVGenerator.cc	2006-09-11 19:05:20.000000000 -0400
@@ -2,7 +2,7 @@
 #include "Events/EventRouter.h"
 #include "Events/FilterBankEvent.h"
 #include "Wireless/Wireless.h"
-#include "Shared/WorldState.h"
+#include "Shared/Profiler.h"
 
 #include "Shared/debuget.h"
 
@@ -30,9 +30,12 @@
 InterleavedYUVGenerator::processEvent(const EventBase& event) {
 	FilterBankGenerator::processEvent(event);
 	if(event.getGeneratorID()==getListenGeneratorID() && event.getSourceID()==getListenSourceID()) {
-		erouter->postEvent(new FilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::activateETID));
-		erouter->postEvent(new FilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::statusETID));
-		erouter->postEvent(new FilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::deactivateETID));
+		FilterBankEvent fbkev(this,getGeneratorID(),getSourceID(),EventBase::activateETID);
+		erouter->postEvent(fbkev);
+		fbkev.setTypeID(EventBase::statusETID);
+		erouter->postEvent(fbkev);
+		fbkev.setTypeID(EventBase::deactivateETID);
+		erouter->postEvent(fbkev);
 	}
 }
 
@@ -45,19 +48,16 @@
 }
 
 unsigned int
-InterleavedYUVGenerator::LoadBuffer(const char buf[], unsigned int len) {
+InterleavedYUVGenerator::loadBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
-	unsigned int used;
+	if(!checkInc(FilterBankGenerator::loadBuffer(buf,len),buf,len)) return 0;
 	std::string tmp;
-	if(0==(used=FilterBankGenerator::LoadBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(tmp,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!decodeInc(tmp,buf,len)) return 0;
 	if(tmp!="InterleavedYUVImage") {
 		serr->printf("Unhandled image type for InterleavedYUVGenerator: %s",tmp.c_str());
 		return 0;
 	} else {
-		used=widths[selectedSaveLayer]*heights[selectedSaveLayer]*3;
+		unsigned int used=widths[selectedSaveLayer]*heights[selectedSaveLayer]*3;
 		if(used>len)
 			return 0;
 		if(images[selectedSaveLayer][selectedSaveChannel]==NULL)
@@ -73,23 +73,20 @@
 }
 
 unsigned int
-InterleavedYUVGenerator::SaveBuffer(char buf[], unsigned int len) const {
+InterleavedYUVGenerator::saveBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=FilterBankGenerator::SaveBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode("InterleavedYUVImage",buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkInc(FilterBankGenerator::saveBuffer(buf,len),buf,len)) return 0;
+	if(!encodeInc("InterleavedYUVImage",buf,len)) return 0;
 	
-	used=widths[selectedSaveLayer]*heights[selectedSaveLayer]*3;
+	unsigned int used=widths[selectedSaveLayer]*heights[selectedSaveLayer]*3;
 	if(used>len)
 		return 0;
 	if(images[selectedSaveLayer][selectedSaveChannel]==NULL) {
-		serr->printf("InterleavedYUVGenerator::SaveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("InterleavedYUVGenerator::saveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	if(!imageValids[selectedSaveLayer][selectedSaveChannel]) {
-		serr->printf("InterleavedYUVGenerator::SaveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("InterleavedYUVGenerator::saveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
@@ -163,7 +160,7 @@
 
 void
 InterleavedYUVGenerator::calcImage(unsigned int layer, unsigned int chan) {
-	PROFSECTION("InterleavedYUVGenerator::calcImage(...)",state->mainProfile);
+	PROFSECTION("InterleavedYUVGenerator::calcImage(...)",*mainProfiler);
 	if(imageValids[layer][chan]) //check if createCache set valid flag
 		return; //indicates pass through from previous stage
 	
@@ -177,15 +174,15 @@
 	for(unsigned int y=0; y<getHeight(layer); y++) {
 		for(unsigned int x=0; x<getWidth(layer); x++) {
 			*dimg++=*syimg;
-			*dimg++=*svimg;
 			*dimg++=*suimg;
+			*dimg++=*svimg;
 			syimg+=inc;
-			svimg+=inc;
 			suimg+=inc;
+			svimg+=inc;
 		}
 		syimg+=skip;
-		svimg+=skip;
 		suimg+=skip;
+		svimg+=skip;
 	}
 	imageValids[layer][chan]=true;
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/InterleavedYUVGenerator.h ./Vision/InterleavedYUVGenerator.h
--- ../Tekkotsu_2.4.1/Vision/InterleavedYUVGenerator.h	2005-06-13 14:03:15.000000000 -0400
+++ ./Vision/InterleavedYUVGenerator.h	2006-09-09 00:33:04.000000000 -0400
@@ -4,26 +4,14 @@
 
 #include "Vision/FilterBankGenerator.h"
 
-//! Generates FilterBankEvents containing raw camera images with interleaved pixels (YVUYVUYVU... instead of YYY...UUU...VVV...)
-/*! @note That's not a typo - the byte ordering is YVU, @e not YUV
- *
- *  Sorry about the misleading name... This @e takes filter banks
- *  containing YUV information, however.  The main reason for this
- *  class is to interleave the image in order to pass it to the jpeg
- *  compression routines.  JPEG expect YCbCr, which corresponds to YVU
- *  order.
- *
- *  Also, I should point out that mathematically, V!=Cb, and U!=Cr,
- *  but they do carry the same information.  It's just a matter of
- *  scaling and offset.  These comments use the "Y", "U", and "V"
- *  labels loosely.
- *
+//! Generates FilterBankEvents containing raw camera images with interleaved pixels (YUVYUVYUV... instead of YYY...UUU...VVV...)
+/*!
  *  There's only one channel, which holds the interleaved data.  The
  *  increment is set to 3, but if you want to access each component in
  *  order, just use 1 instead (as you would expect hopefully, since
- *  that's the whole point of this class)
+ *  the very specific memory layout is the whole point of this class)
  *  
- *  The generated events use 0 for their event source IDs.  The row
+ *  The row
  *  skip is always 0, and the row stride is always width*3.  But it
  *  would be better to use the proper accessor functions to be more
  *  general.
@@ -45,7 +33,7 @@
 		destruct();
 	}
 
-	static const unsigned int CHAN_YUV=0; //!< so you can refer to the YUV channel symbolically.
+	static const unsigned int CHAN_YUV=0; //!< so you can refer to the YUV channel symbolically. (as opposed to others that might be added?)
 
 	static std::string getClassDescription() { return "Converts a FilterBankGenerator's data into interleaved format"; }
 
@@ -54,9 +42,9 @@
 	
 	virtual unsigned int getBinSize() const;
 
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
 
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
 
 	virtual void freeCaches();
 	virtual void invalidateCaches();
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/JPEGGenerator.cc ./Vision/JPEGGenerator.cc
--- ../Tekkotsu_2.4.1/Vision/JPEGGenerator.cc	2005-08-16 14:08:51.000000000 -0400
+++ ./Vision/JPEGGenerator.cc	2006-09-11 19:05:20.000000000 -0400
@@ -5,7 +5,7 @@
 #include "Events/FilterBankEvent.h"
 #include "Wireless/Wireless.h"
 #include "Shared/Config.h"
-#include "Shared/WorldState.h"
+#include "Shared/Profiler.h"
 
 #include "Shared/jpeg-6b/jpeg_mem_dest.h"
 
@@ -76,16 +76,28 @@
 			else
 				curMode=SRC_GRAYSCALE;
 		}
-		erouter->postEvent(new FilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::activateETID));
-		erouter->postEvent(new FilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::statusETID));
-		erouter->postEvent(new FilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::deactivateETID));
+		FilterBankEvent fbkev(this,getGeneratorID(),getSourceID(),EventBase::activateETID);
+		erouter->postEvent(fbkev);
+		fbkev.setTypeID(EventBase::statusETID);
+		erouter->postEvent(fbkev);
+		fbkev.setTypeID(EventBase::deactivateETID);
+		erouter->postEvent(fbkev);
 	}
 }
 
 unsigned int
 JPEGGenerator::getBinSize() const {
 	unsigned int used=FilterBankGenerator::getBinSize();
-	used+=strlen("JPEGColor")+LoadSave::stringpad;
+	char * type;
+	if(getCurrentSourceFormat()==SRC_COLOR)
+		type="JPEGColor";
+	else if(getCurrentSourceFormat()==SRC_GRAYSCALE)
+		type="JPEGGrayscale";
+	else {
+		serr->printf("getBinSize failed - unsuitable or unknown mode/generator pair");
+		return 0;
+	}
+	used+=strlen(type)+LoadSave::stringpad;
 	if(bytesUsed[selectedSaveLayer][selectedSaveChannel]!=0)
 		used+=bytesUsed[selectedSaveLayer][selectedSaveChannel];
 	else
@@ -94,15 +106,12 @@
 }
 
 unsigned int
-JPEGGenerator::LoadBuffer(const char buf[], unsigned int len) {
+JPEGGenerator::loadBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
-	unsigned int used;
+	if(!checkInc(FilterBankGenerator::loadBuffer(buf,len),buf,len)) return 0;
 	std::string tmp;
-	if(0==(used=FilterBankGenerator::LoadBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(tmp,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(tmp!="JPEGColor" && tmp!="JPEGGray") {
+	if(!decodeInc(tmp,buf,len)) return 0;
+	if(tmp!="JPEGColor" && tmp!="JPEGGrayscale") {
 		serr->printf("Unhandled image type for JPEGGenerator: %s",tmp.c_str());
 		return 0;
 	} else {
@@ -111,14 +120,13 @@
 		if(tmp=="JPEGGrayscale" && getCurrentSourceFormat()==SRC_COLOR)
 			serr->printf("Warning: loading color into grayscale image");
 		unsigned int tmpL;
-		if(0==(used=decode(tmpL,buf,len))) return 0;
-		len-=used; buf+=used;
+		if(!decodeInc(tmpL,buf,len)) return 0;
 		if(tmpL>len)
 			return 0;
 		if(images[selectedSaveLayer][selectedSaveChannel]!=NULL)
 			delete [] images[selectedSaveLayer][selectedSaveChannel];
 		images[selectedSaveLayer][selectedSaveChannel]=createImageCache(selectedSaveLayer,selectedSaveChannel);
-		used=bytesUsed[selectedSaveLayer][selectedSaveChannel]=tmpL;
+		unsigned int used=bytesUsed[selectedSaveLayer][selectedSaveChannel]=tmpL;
 		unsigned char* img=getImage(selectedSaveLayer,selectedSaveChannel);
 		if(img==NULL)
 			return 0;
@@ -130,11 +138,9 @@
 }
 
 unsigned int
-JPEGGenerator::SaveBuffer(char buf[], unsigned int len) const {
+JPEGGenerator::saveBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=FilterBankGenerator::SaveBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkInc(FilterBankGenerator::saveBuffer(buf,len),buf,len)) return 0;
 
 	char * type;
 	if(getCurrentSourceFormat()==SRC_COLOR)
@@ -142,26 +148,24 @@
 	else if(getCurrentSourceFormat()==SRC_GRAYSCALE)
 		type="JPEGGrayscale";
 	else {
-		serr->printf("SaveBuffer failed - unsuitable or unknown mode/generator pair");
+		serr->printf("saveBuffer failed - unsuitable or unknown mode/generator pair");
 		return 0;
 	}
-	if(0==(used=encode(type,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!encodeInc(type,buf,len)) return 0;
 	
 	if(images[selectedSaveLayer][selectedSaveChannel]==NULL) {
-		serr->printf("JPEGGenerator::SaveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("JPEGGenerator::saveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	if(!imageValids[selectedSaveLayer][selectedSaveChannel]) {
-		serr->printf("JPEGGenerator::SaveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("JPEGGenerator::saveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
 	if(img==NULL)
 		return 0;
-	if(0==(used=encode(bytesUsed[selectedSaveLayer][selectedSaveChannel],buf,len))) return 0;
-	len-=used; buf+=used;
-	used=bytesUsed[selectedSaveLayer][selectedSaveChannel];
+	if(!encodeInc(bytesUsed[selectedSaveLayer][selectedSaveChannel],buf,len)) return 0;
+	unsigned int used=bytesUsed[selectedSaveLayer][selectedSaveChannel];
 	if(used>len)
 		return 0;
 	memcpy(buf,img,used);
@@ -198,7 +202,7 @@
  */
 void
 JPEGGenerator::calcImage(unsigned int layer, unsigned int chan) {
-	PROFSECTION("JPEGGenerator::calcImage(...)",state->mainProfile);
+	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);
@@ -278,7 +282,7 @@
 	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==" << (void*)cinfo.next_scanline << " image_height==" << cinfo.image_height << 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);
 }
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/JPEGGenerator.h ./Vision/JPEGGenerator.h
--- ../Tekkotsu_2.4.1/Vision/JPEGGenerator.h	2005-08-07 00:11:04.000000000 -0400
+++ ./Vision/JPEGGenerator.h	2006-09-16 13:32:40.000000000 -0400
@@ -29,16 +29,22 @@
  *  and others might find the interleaved format handy for passing to
  *  other libraries which expect that format, such as what happened
  *  with libjpeg.
+ *  
+ *  This class shares a lot of non-JPEG specific code with PNGGenerator,
+ *  so you may want to replicate any changes made in that class as well.
  *
  *  @todo possible speedup by using jpeg_write_raw_data
+ *  @todo create a common super class with PNGGenerator to hold common setup code
  */
 class JPEGGenerator : public FilterBankGenerator {
 public:
 	static const unsigned int JPEG_HEADER_PAD=500; //!< add a bit to the expected size in getBinSize just to leave a little extra room for small images
+	
+	//! defines how to interpret the source images (see #srcMode and #curMode)
 	enum src_mode_t {
 		SRC_AUTO,       //!< if src is not a InterleavedYUVGenerator, SRC_GREYSCALE, otherwise SRC_COLOR
-		SRC_GRAYSCALE,
-		SRC_COLOR
+		SRC_GRAYSCALE,  //!< indicates each channel of source should be compressed individually as grayscale images
+		SRC_COLOR       //!< indicates first channel should be in an interleaved layout which can be compressed into a "color" image
 	};
 
 	//! constructor
@@ -56,17 +62,18 @@
 	//! returns #curMode
 	virtual src_mode_t getCurrentSourceFormat() const { return curMode; }
 
-	static std::string getClassDescription() { return "Converts a compresses its source FilterBankGenerator's data into JPEG format"; }
+	static std::string getClassDescription() { return "Compresses its source FilterBankGenerator's data into JPEG format"; }
 
 	//! should receive FilterBankEvents from a RawCameraGenerator (or a subclass thereof)
 	virtual void processEvent(const EventBase& event);
 	
 	//! if we don't already know bytesUsed, let's assume the size will be smaller than the original uncompressed. If we fail this assumption, probably better to fail anyway.
 	virtual unsigned int getBinSize() const;
-
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
-
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
+	
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
+	
+	//! you probably don't want to be calling this to access the JPEG -- use getImage() instead (saveBuffer will prepend some header information before the actual image data)
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
 
 	//! returns #quality
 	virtual unsigned int getQuality() const { return quality; }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/PNGGenerator.cc ./Vision/PNGGenerator.cc
--- ../Tekkotsu_2.4.1/Vision/PNGGenerator.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Vision/PNGGenerator.cc	2006-09-16 02:01:41.000000000 -0400
@@ -0,0 +1,287 @@
+#include "PNGGenerator.h"
+#include "InterleavedYUVGenerator.h"
+#include "Events/DataEvent.h"
+#include "Events/EventRouter.h"
+#include "Events/FilterBankEvent.h"
+#include "Shared/Profiler.h"
+#include "Wireless/Socket.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)
+{
+	if(dynamic_cast<const InterleavedYUVGenerator*>(src)!=NULL)
+		curMode=SRC_COLOR;
+	else
+		curMode=SRC_GRAYSCALE;
+	
+	//this part is only necessary if you override setNumImages yourself
+	if(fbg!=NULL) {
+		numLayers=numChannels=0; //this is to force setNumImages to override settings provided by FilterBankGenerator
+		setNumImages(fbg->getNumLayers(),fbg->getNumChannels());
+	}
+}
+
+PNGGenerator::PNGGenerator(unsigned int mysid, src_mode_t mode, FilterBankGenerator* fbg, EventBase::EventTypeID_t tid)
+: FilterBankGenerator("PNGGenerator","PNGGenerator",EventBase::visPNGEGID,mysid,fbg,tid), srcMode(mode), curMode(mode), bytesUsed(NULL)
+{
+	if(srcMode==SRC_AUTO) {
+		if(dynamic_cast<const InterleavedYUVGenerator*>(src)!=NULL)
+			curMode=SRC_COLOR;
+		else
+			curMode=SRC_GRAYSCALE;
+	}
+	
+	//this part is only necessary if you override setNumImages yourself
+	if(fbg!=NULL) {
+		numLayers=numChannels=0; //this is to force setNumImages to override settings provided by FilterBankGenerator
+		setNumImages(fbg->getNumLayers(),fbg->getNumChannels());
+	}
+}
+
+PNGGenerator::~PNGGenerator() {
+	freeCaches();
+	destruct();
+}
+
+
+/*! The const casts in this function are regretable but necessary
+*  since the corresponding OPEN-R functions require mutable
+*  arguments, even though they shouldn't be modifying the data
+*/
+void
+PNGGenerator::processEvent(const EventBase& event) {
+	FilterBankGenerator::processEvent(event);
+	if(event.getGeneratorID()==getListenGeneratorID() && event.getSourceID()==getListenSourceID()) {
+		if(getSourceMode()==SRC_AUTO) { //if not auto, curMode was already set when srcMode was set
+			if(dynamic_cast<const InterleavedYUVGenerator*>(src)!=NULL)
+				curMode=SRC_COLOR;
+			else
+				curMode=SRC_GRAYSCALE;
+		}
+		FilterBankEvent fbkev(this,getGeneratorID(),getSourceID(),EventBase::activateETID);
+		erouter->postEvent(fbkev);
+		fbkev.setTypeID(EventBase::statusETID);
+		erouter->postEvent(fbkev);
+		fbkev.setTypeID(EventBase::deactivateETID);
+		erouter->postEvent(fbkev);
+	}
+}
+
+unsigned int
+PNGGenerator::getBinSize() const {
+	unsigned int used=FilterBankGenerator::getBinSize();
+	char * type;
+	if(getCurrentSourceFormat()==SRC_COLOR)
+		type="PNGColor";
+	else if(getCurrentSourceFormat()==SRC_GRAYSCALE)
+		type="PNGGrayscale";
+	else {
+		serr->printf("getBinSize failed - unsuitable or unknown mode/generator pair");
+		return 0;
+	}
+	used+=strlen(type)+LoadSave::stringpad;
+	if(bytesUsed[selectedSaveLayer][selectedSaveChannel]!=0)
+		used+=bytesUsed[selectedSaveLayer][selectedSaveChannel];
+	else
+		used+=widths[selectedSaveLayer]*heights[selectedSaveLayer]*3+PNG_HEADER_PAD;
+	return used;
+}
+
+unsigned int
+PNGGenerator::loadBuffer(const char buf[], unsigned int len) {
+	unsigned int origlen=len;
+	if(!FilterBankGenerator::loadBuffer(buf,len)) return 0;
+	std::string tmp;
+	if(!decodeInc(tmp,buf,len)) return 0;
+	if(tmp!="PNGColor" && tmp!="PNGGrayscale") {
+		serr->printf("Unhandled image type for PNGGenerator: %s",tmp.c_str());
+		return 0;
+	} else {
+		if(tmp=="PNGColor" && getCurrentSourceFormat()==SRC_GRAYSCALE)
+			serr->printf("Warning: loading grayscale into color image");
+		if(tmp=="PNGGrayscale" && getCurrentSourceFormat()==SRC_COLOR)
+			serr->printf("Warning: loading color into grayscale image");
+		unsigned int tmpL;
+		if(!decodeInc(tmpL,buf,len)) return 0;
+		if(tmpL>len)
+			return 0;
+		if(images[selectedSaveLayer][selectedSaveChannel]!=NULL)
+			delete [] images[selectedSaveLayer][selectedSaveChannel];
+		images[selectedSaveLayer][selectedSaveChannel]=createImageCache(selectedSaveLayer,selectedSaveChannel);
+		unsigned int used=bytesUsed[selectedSaveLayer][selectedSaveChannel]=tmpL;
+		unsigned char* img=getImage(selectedSaveLayer,selectedSaveChannel);
+		if(img==NULL)
+			return 0;
+		memcpy(img,buf,used);
+		len-=used; buf+=used;
+		imageValids[selectedSaveLayer][selectedSaveChannel]=true;
+		return origlen-len;	
+	}
+}
+
+unsigned int
+PNGGenerator::saveBuffer(char buf[], unsigned int len) const {
+	unsigned int origlen=len;
+	if(!checkInc(FilterBankGenerator::saveBuffer(buf,len),buf,len)) return 0;
+	
+	char * type;
+	if(getCurrentSourceFormat()==SRC_COLOR)
+		type="PNGColor";
+	else if(getCurrentSourceFormat()==SRC_GRAYSCALE)
+		type="PNGGrayscale";
+	else {
+		serr->printf("saveBuffer failed - unsuitable or unknown mode/generator pair");
+		return 0;
+	}
+	if(!encodeInc(type,buf,len)) return 0;
+	
+	if(images[selectedSaveLayer][selectedSaveChannel]==NULL) {
+		serr->printf("PNGGenerator::saveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
+		return 0;
+	}
+	if(!imageValids[selectedSaveLayer][selectedSaveChannel]) {
+		serr->printf("PNGGenerator::saveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
+		return 0;
+	}
+	unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
+	if(img==NULL)
+		return 0;
+	if(!encodeInc(bytesUsed[selectedSaveLayer][selectedSaveChannel],buf,len)) return 0;
+	unsigned int used=bytesUsed[selectedSaveLayer][selectedSaveChannel];
+	if(used>len)
+		return 0;
+	memcpy(buf,img,used);
+	len-=used;
+	return origlen-len;
+}
+
+void
+PNGGenerator::setNumImages(unsigned int nLayers, unsigned int nChannels) {
+	if(nLayers==numLayers && nChannels==numChannels)
+		return;
+	FilterBankGenerator::setNumImages(nLayers,nChannels);
+	for(unsigned int i=0; i<numLayers; i++)
+		strides[i]=skips[i]=0;
+	bytesUsed=new unsigned int*[numLayers];
+	for(unsigned int res=0; res<numLayers; res++) {
+		increments[res]=3;
+		bytesUsed[res]=new unsigned int[numChannels];
+		for(unsigned int i=0; i<numChannels; i++)
+			bytesUsed[res][i]=0;
+	}
+}
+
+unsigned char *
+PNGGenerator::createImageCache(unsigned int layer, unsigned int /*chan*/) const {
+	return new unsigned char[widths[layer]*heights[layer]*3+PNG_HEADER_PAD];
+}
+
+void
+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);
+	
+	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);
+		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;
+}
+
+void
+PNGGenerator::destruct() {
+	FilterBankGenerator::destruct();
+	for(unsigned int res=0; res<numLayers; res++)
+		delete [] bytesUsed[res];
+	delete [] bytesUsed;
+	bytesUsed=NULL;
+}
+
+/*! @file
+ * @brief Implements PNGGenerator, which generates FilterBankEvents containing PNG compressed images
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/PNGGenerator.h ./Vision/PNGGenerator.h
--- ../Tekkotsu_2.4.1/Vision/PNGGenerator.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Vision/PNGGenerator.h	2006-09-16 13:32:40.000000000 -0400
@@ -0,0 +1,88 @@
+//-*-c++-*-
+#ifndef INCLUDED_PNGGenerator_h_
+#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
+/*!
+ *  This class shares a lot of non-PNG specific code with JPEGGenerator,
+ *  so you may want to replicate any changes made in that class as well.
+ *
+ *  @todo create a common super class with JPEGGenerator to hold common setup code
+*/
+class PNGGenerator : public FilterBankGenerator {
+public:
+	static const unsigned int PNG_HEADER_PAD=500; //!< add a bit to the expected size in getBinSize just to leave a little extra room for small images
+	
+	//! defines how to interpret the source images (see #srcMode and #curMode)
+	enum src_mode_t {
+		SRC_AUTO,       //!< if src is not a InterleavedYUVGenerator, SRC_GREYSCALE, otherwise SRC_COLOR
+		SRC_GRAYSCALE,  //!< indicates each channel of source should be compressed individually as grayscale images
+		SRC_COLOR       //!< indicates first channel should be in an interleaved layout which can be compressed into a "color" image
+	};
+	
+	//! constructor
+	PNGGenerator(unsigned int mysid, FilterBankGenerator* fbg, EventBase::EventTypeID_t tid);
+	//! constructor
+	PNGGenerator(unsigned int mysid, PNGGenerator::src_mode_t sMode, FilterBankGenerator* fbg, EventBase::EventTypeID_t tid);
+
+	//! destructor
+	virtual ~PNGGenerator();
+
+	//! set #srcMode and #curMode as well if @a mode==SRC_AUTO
+	virtual void setSourceMode(src_mode_t mode) { srcMode=mode; if(mode!=SRC_AUTO) curMode=mode;}
+	//! returns #srcMode
+	virtual src_mode_t getSourceMode() const { return srcMode; }
+	//! returns #curMode
+	virtual src_mode_t getCurrentSourceFormat() const { return curMode; }
+	
+	static std::string getClassDescription() { return "Compresses its source FilterBankGenerator's data into PNG format"; }
+	
+	//! should receive FilterBankEvents from a RawCameraGenerator (or a subclass thereof)
+	virtual void processEvent(const EventBase& event);
+	
+	//! if we don't already know bytesUsed, let's assume the size will be smaller than the original uncompressed. If we fail this assumption, probably better to fail anyway.
+	virtual unsigned int getBinSize() const;
+	
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
+	
+	//! you probably don't want to be calling this to access the PNG -- use getImage() instead (saveBuffer will prepend some header information before the actual image data)
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
+
+	//! returns the number of bytes used for the image returned by getImage() - will return 0 if the image hasn't been calculated yet (so call it @e after getImage())
+	virtual unsigned int getImageSize(unsigned int layer, unsigned int chan) const { return bytesUsed[layer][chan]; }
+	
+protected:
+	virtual void setNumImages(unsigned int nLayers, unsigned int nChannels);
+	virtual unsigned char * createImageCache(unsigned int layer, unsigned int chan) const;
+	virtual void calcImage(unsigned int layer, unsigned int chan);
+	virtual void destruct();
+	
+	src_mode_t srcMode;   //!< how to interpret source channel of next filter bank event
+	src_mode_t curMode;   //!< how to interpret getImage's current image
+	
+	unsigned int ** bytesUsed; //!< number of bytes used per image to actually store data;
+		
+private:
+	PNGGenerator(const PNGGenerator& fbk); //!< don't call
+	const PNGGenerator& operator=(const PNGGenerator& fbk); //!< don't call
+};
+
+/*! @file
+ * @brief Describes PNGGenerator, which generates FilterBankEvents containing PNG compressed images
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/RLEGenerator.cc ./Vision/RLEGenerator.cc
--- ../Tekkotsu_2.4.1/Vision/RLEGenerator.cc	2005-06-13 17:24:11.000000000 -0400
+++ ./Vision/RLEGenerator.cc	2006-09-11 19:05:21.000000000 -0400
@@ -2,7 +2,7 @@
 #include "Events/EventRouter.h"
 #include "Events/SegmentedColorFilterBankEvent.h"
 #include "Wireless/Wireless.h"
-#include "Shared/WorldState.h"
+#include "Shared/Profiler.h"
 
 #include "Shared/debuget.h"
 
@@ -24,21 +24,29 @@
 		//Technically, we should do things this way:
 		/*
 		if(const SegmentedColorFilterBankEvent * segsrc=dynamic_cast<const SegmentedColorFilterBankEvent *>(&event)) {
-			erouter->postEvent(new SegmentedColorFilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::activateETID,*segsrc));
-			erouter->postEvent(new SegmentedColorFilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::statusETID,*segsrc));
-			erouter->postEvent(new SegmentedColorFilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::deactivateETID,*segsrc));
+			SegmentedColorFilterBankEvent segev(this,getGeneratorID(),getSourceID(),EventBase::activateETID,*segsrc);
+			erouter->postEvent(fbkev);
+			segev.setTypeID(EventBase::statusETID);
+			erouter->postEvent(fbkev);
+			segev.setTypeID(EventBase::deactivateETID);
+			erouter->postEvent(fbkev);
 		} else {
-			erouter->postEvent(new FilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::activateETID));
-			erouter->postEvent(new FilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::statusETID));
-			erouter->postEvent(new FilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::deactivateETID));
+			FilterBankEvent fbkev(this,getGeneratorID(),getSourceID(),EventBase::activateETID);
+			erouter->postEvent(fbkev);
+			fbkev.setTypeID(EventBase::statusETID);
+			erouter->postEvent(fbkev);
+			fbkev.setTypeID(EventBase::deactivateETID);
+			erouter->postEvent(fbkev);
 		}
 		*/
 		//But until RLEGraphics is in place, we'll do it this way so recompression can be triggered
 		//after drawing into segmented image
 		if(const SegmentedColorFilterBankEvent * segsrc=dynamic_cast<const SegmentedColorFilterBankEvent *>(&event)) {
-			erouter->postEvent(new SegmentedColorFilterBankEvent(this,getGeneratorID(),getSourceID(),event.getTypeID(),*segsrc));
+			SegmentedColorFilterBankEvent segev(this,getGeneratorID(),getSourceID(),event.getTypeID(),*segsrc);
+			erouter->postEvent(segev);
 		} else {
-			erouter->postEvent(new FilterBankEvent(this,getGeneratorID(),getSourceID(),event.getTypeID()));
+			FilterBankEvent fbkev(this,getGeneratorID(),getSourceID(),event.getTypeID());
+			erouter->postEvent(fbkev);
 		}
 	}
 }
@@ -57,20 +65,16 @@
 
 /*! this isn't really tested, don't rely on it working without a little debugging... specifically, doesn't set parent or next fields*/
 unsigned int
-RLEGenerator::LoadBuffer(const char buf[], unsigned int len) {
+RLEGenerator::loadBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
-	unsigned int used;
 	std::string tmp;
-	if(0==(used=FilterBankGenerator::LoadBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(tmp,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkInc(FilterBankGenerator::loadBuffer(buf,len),buf,len)) return 0;
+	if(!decodeInc(tmp,buf,len)) return 0;
 	if(tmp!="RLEImage") {
 		serr->printf("Unhandled image type for RLEGenerator: %s",tmp.c_str());
 		return 0;
 	} else {
-		if(0==(used=decode(numRuns[selectedSaveLayer][selectedSaveChannel],buf,len))) return 0;
-		len-=used; buf+=used;
+		if(!decodeInc(numRuns[selectedSaveLayer][selectedSaveChannel],buf,len)) return 0;
 		if(maxRuns[selectedSaveLayer]<numRuns[selectedSaveLayer][selectedSaveChannel])
 			return 0;
 		if(images[selectedSaveLayer][selectedSaveChannel]==NULL)
@@ -80,12 +84,9 @@
 			return 0;
 		unsigned int y=0;
 		for(unsigned int i=0; i<numRuns[selectedSaveLayer][selectedSaveChannel]; i++) {
-			if(0==(used=decode(runs[i].color,buf,len))) return 0;
-			len-=used; buf+=used;
-			if(0==(used=decode(runs[i].x,buf,len))) return 0;
-			len-=used; buf+=used;
-			if(0==(used=decode(runs[i].width,buf,len))) return 0;
-			len-=used; buf+=used;
+			if(!decodeInc(runs[i].color,buf,len)) return 0;
+			if(!decodeInc(runs[i].x,buf,len)) return 0;
+			if(!decodeInc(runs[i].width,buf,len)) return 0;
 			if((unsigned int)(runs[i].x+runs[i].width)>=getWidth(selectedSaveLayer))
 				y++;
 			runs[i].y=y;
@@ -96,35 +97,28 @@
 }
 
 unsigned int
-RLEGenerator::SaveBuffer(char buf[], unsigned int len) const {
+RLEGenerator::saveBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=FilterBankGenerator::SaveBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode("RLEImage",buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkInc(FilterBankGenerator::saveBuffer(buf,len),buf,len)) return 0;
+	if(!encodeInc("RLEImage",buf,len)) return 0;
 	
 	if(images[selectedSaveLayer][selectedSaveChannel]==NULL) {
-		serr->printf("RLEGenerator::SaveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("RLEGenerator::saveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	if(!imageValids[selectedSaveLayer][selectedSaveChannel]) {
-		serr->printf("RLEGenerator::SaveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("RLEGenerator::saveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
 	run * runs=reinterpret_cast<run*>(img);
 	if(runs==NULL)
 		return 0;
-	if(0==(used=encode(numRuns[selectedSaveLayer][selectedSaveChannel],buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!encodeInc(numRuns[selectedSaveLayer][selectedSaveChannel],buf,len)) return 0;
 	for(unsigned int i=0; i<numRuns[selectedSaveLayer][selectedSaveChannel]; i++) {
-		if(0==(used=encode(runs[i].color,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=encode(runs[i].x,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=encode(runs[i].width,buf,len))) return 0;
-		len-=used; buf+=used;
+		if(!encodeInc(runs[i].color,buf,len)) return 0;
+		if(!encodeInc(runs[i].x,buf,len)) return 0;
+		if(!encodeInc(runs[i].width,buf,len)) return 0;
 	}
 	return origlen-len;
 }
@@ -158,7 +152,7 @@
 //! a single call to the CMVision library to do the work, and we're done.
 void
 RLEGenerator::calcImage(unsigned int layer, unsigned int chan) {
-	PROFSECTION("RLEGenerator::calcImage(...)",state->mainProfile);
+	PROFSECTION("RLEGenerator::calcImage(...)",*mainProfiler);
   numRuns[layer][chan] = CMVision::EncodeRuns(reinterpret_cast<run*>(images[layer][chan]),src->getImage(layer,chan),getWidth(layer),getHeight(layer),maxRuns[layer]);
 	imageValids[layer][chan]=true; // <--- don't forget to do this, otherwise you'll recompute on every access, even if the cache is still valid
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/RLEGenerator.h ./Vision/RLEGenerator.h
--- ../Tekkotsu_2.4.1/Vision/RLEGenerator.h	2005-06-01 01:47:58.000000000 -0400
+++ ./Vision/RLEGenerator.h	2006-09-09 00:33:04.000000000 -0400
@@ -42,7 +42,7 @@
  *  flat color.  However, if you have some kind of other preprocessing
  *  that also provides suitable data, this can encode it for you.
  *  
- *  The format used for serialization is: (code is in SaveBuffer())
+ *  The format used for serialization is: (code is in saveBuffer())
  *  - <@c FilterBankGenerator: superclass header> <i>(First saves the superclass's info)</i>
  *  - <@c string: "RLEImage">  <i>(remember a 'string' is len+str+0; so this is the literal "\010\0\0\0RLEImage\0"; also remember "\010" is octal for 8)</i>
  *  - <@c unsigned @c int: num_runs> <i>(how many runs will follow)</i>
@@ -63,7 +63,7 @@
  */
 class RLEGenerator : public FilterBankGenerator {
 public:
-	typedef uchar cmap_t; //!< the type to use for a color index
+	typedef CMVision::uchar cmap_t; //!< the type to use for a color index
 	typedef CMVision::run<cmap_t> run; //!< use the CMVision library's run structure
 	
 	//! constructor
@@ -81,8 +81,8 @@
 	virtual void processEvent(const EventBase& event);
 
 	virtual unsigned int getBinSize() const;
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
 
 	//! returns the number of runs for the image
 	virtual unsigned int getNumRuns(unsigned int layer, unsigned int chan) { if(!imageValids[layer][chan]) getImage(layer,chan); return numRuns[layer][chan]; }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/RawCameraGenerator.cc ./Vision/RawCameraGenerator.cc
--- ../Tekkotsu_2.4.1/Vision/RawCameraGenerator.cc	2005-06-06 15:33:31.000000000 -0400
+++ ./Vision/RawCameraGenerator.cc	2006-09-11 19:05:22.000000000 -0400
@@ -4,7 +4,7 @@
 #include "Events/FilterBankEvent.h"
 #include "Wireless/Wireless.h"
 #include "Shared/Config.h"
-#include "Shared/WorldState.h"
+#include "Shared/Profiler.h"
 
 #include "Shared/ODataFormats.h"
 #include "OFbkImage.h"
@@ -94,7 +94,7 @@
 		invalidateCaches();	
 		framesProcessed++;
 	}
-	erouter->postEvent(new FilterBankEvent(this,getGeneratorID(),getSourceID(),event.getTypeID()));
+	erouter->postEvent(FilterBankEvent(this,getGeneratorID(),getSourceID(),event.getTypeID()));
 }
 
 unsigned int
@@ -106,14 +106,11 @@
 }
 
 unsigned int
-RawCameraGenerator::LoadBuffer(const char buf[], unsigned int len) {
+RawCameraGenerator::loadBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
-	unsigned int used;
 	std::string tmp;
-	if(0==(used=FilterBankGenerator::LoadBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(tmp,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkInc(FilterBankGenerator::loadBuffer(buf,len),buf,len)) return 0;
+	if(!decodeInc(tmp,buf,len)) return 0;
 	if(tmp!="RawImage") {
 		serr->printf("Unhandled image type for RawCameraGenerator: %s",tmp.c_str());
 		return 0;
@@ -124,7 +121,7 @@
 		if(images[selectedSaveLayer][selectedSaveChannel]==NULL)
 			images[selectedSaveLayer][selectedSaveChannel]=createImageCache(selectedSaveLayer,selectedSaveChannel);
 		unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
-		used=widths[selectedSaveLayer]*heights[selectedSaveLayer];
+		unsigned int used=widths[selectedSaveLayer]*heights[selectedSaveLayer];
 		ASSERTRETVAL(used<=len,"buffer too small",0);
 		memcpy(img,buf,used);
 		len-=used; buf+=used;
@@ -134,24 +131,21 @@
 }
 
 unsigned int
-RawCameraGenerator::SaveBuffer(char buf[], unsigned int len) const {
+RawCameraGenerator::saveBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=FilterBankGenerator::SaveBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode("RawImage",buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkInc(FilterBankGenerator::saveBuffer(buf,len),buf,len)) return 0;
+	if(!encodeInc("RawImage",buf,len)) return 0;
 	
 	if(images[selectedSaveLayer][selectedSaveChannel]==NULL) {
-		serr->printf("RawCameraGenerator::SaveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("RawCameraGenerator::saveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	if(!imageValids[selectedSaveLayer][selectedSaveChannel]) {
-		serr->printf("RawCameraGenerator::SaveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("RawCameraGenerator::saveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
-	used=widths[selectedSaveLayer]*heights[selectedSaveLayer];
+	unsigned int used=widths[selectedSaveLayer]*heights[selectedSaveLayer];
 	ASSERTRETVAL(used<=len,"buffer too small",0);
 	unsigned int inc=getIncrement(selectedSaveLayer);
 	if(inc==1) {
@@ -178,20 +172,20 @@
 }
 
 unsigned int
-RawCameraGenerator::SaveFileStream(FILE * f) const {
+RawCameraGenerator::saveFileStream(FILE * f) const {
 	unsigned int totalused=0;
 	unsigned int used;
-	{ //sigh, inheritance has failed me (I wouldn't want FilterBankGenerator::SaveFileStream() to call the virtuals...)
+	{ //sigh, inheritance has failed me (I wouldn't want FilterBankGenerator::saveFileStream() to call the virtuals...)
 		unsigned int sz=FilterBankGenerator::getBinSize();
 		char * buf = new char[sz];
 		memset(buf,0xF0,sz);
 		if(buf==NULL) {
-			std::cout << "*** WARNING could not allocate " << sz << " bytes for LoadFile";
+			std::cout << "*** WARNING could not allocate " << sz << " bytes for loadFile";
 			return 0;
 		}
-		unsigned int resp=FilterBankGenerator::SaveBuffer(buf,sz);
+		unsigned int resp=FilterBankGenerator::saveBuffer(buf,sz);
 		if(resp==0) {
-			std::cout << "*** WARNING SaveBuffer didn't write any data (possibly due to overflow or other error)" << std::endl;
+			std::cout << "*** WARNING saveBuffer didn't write any data (possibly due to overflow or other error)" << std::endl;
 			fwrite(buf,1,sz,f);
 		}	else {
 			unsigned int wrote=fwrite(buf,1,resp,f);
@@ -207,11 +201,11 @@
 	totalused+=used;
 	
 	if(images[selectedSaveLayer][selectedSaveChannel]==NULL) {
-		serr->printf("RawCameraGenerator::SaveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("RawCameraGenerator::saveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	if(!imageValids[selectedSaveLayer][selectedSaveChannel]) {
-		serr->printf("RawCameraGenerator::SaveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("RawCameraGenerator::saveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
@@ -298,7 +292,7 @@
 
 void
 RawCameraGenerator::calcImage(unsigned int layer, unsigned int chan) {
-	PROFSECTION("RawCameraGenerator::calcImage(...)",state->mainProfile);
+	PROFSECTION("RawCameraGenerator::calcImage(...)",*mainProfiler);
 	unsigned int numNotRealLayers=numLayers-1-numRealLayers;
 	if(layer==numLayers-1) {
 		//This is the only layer for which we calculate and store any data of our own...
@@ -367,9 +361,9 @@
 	case CHAN_Y:
 		return ofbkimageBAND_Y;
 	case CHAN_U:
-		return ofbkimageBAND_Cr;
-	case CHAN_V:
 		return ofbkimageBAND_Cb;
+	case CHAN_V:
+		return ofbkimageBAND_Cr;
 	case CHAN_Y_DY:
 		return ofbkimageBAND_Y_LH;
 	case CHAN_Y_DX:
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/RawCameraGenerator.h ./Vision/RawCameraGenerator.h
--- ../Tekkotsu_2.4.1/Vision/RawCameraGenerator.h	2005-06-03 18:56:30.000000000 -0400
+++ ./Vision/RawCameraGenerator.h	2006-09-09 00:33:04.000000000 -0400
@@ -40,8 +40,8 @@
 	//! holds id values for specifying image channel/bands
 	enum channel_id_t {
 		CHAN_Y,      //!< Y (intensity) channel
-		CHAN_U,      //!< Cr (approx. pink,red,yellow) channel
-		CHAN_V,      //!< Cb (approx. blue,green,yellow) channel
+		CHAN_U,      //!< Cb (approx. blue,green,yellow) channel
+		CHAN_V,      //!< Cr (approx. pink,red,yellow) channel
 		CHAN_Y_DY,   //!< vertical derivative of Y channel (aka LH)
 		CHAN_Y_DX,   //!< horizontal derivative of Y channel (aka HL)
 		CHAN_Y_DXDY, //!< vert. & horiz. derivatives of Y channel (aka HH)
@@ -59,11 +59,11 @@
 
 	virtual unsigned int getBinSize() const;
 
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
 
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
 
-	virtual unsigned int SaveFileStream(FILE* f) const; //!< overrridden to allow saving direct to file without an extra buffer copy
+	virtual unsigned int saveFileStream(FILE* f) const; //!< overrridden to allow saving direct to file without an extra buffer copy
 
 protected:
 	//! ohh, this is so yucky.  But we need to get around heap allocation bugs with large regions in Aperios :(
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/RegionGenerator.cc ./Vision/RegionGenerator.cc
--- ../Tekkotsu_2.4.1/Vision/RegionGenerator.cc	2005-06-06 16:23:15.000000000 -0400
+++ ./Vision/RegionGenerator.cc	2006-09-11 19:05:23.000000000 -0400
@@ -1,19 +1,25 @@
 #include "RegionGenerator.h"
 #include "Events/EventRouter.h"
 #include "Wireless/Wireless.h"
-#include "Shared/WorldState.h"
+#include "Shared/Profiler.h"
+#include "SegmentedColorGenerator.h"
 
 #include "Vision/RLEGenerator.h"
 
 #include "Shared/debuget.h"
 
 RegionGenerator::RegionGenerator(unsigned int mysid, RLEGenerator* rleg, EventBase::EventTypeID_t tid)
-	: FilterBankGenerator("RegionGenerator","RegionGenerator",EventBase::visRegionEGID,mysid,rleg,tid), srcNumColors(0), srcColors(0), regions(NULL)
+	: FilterBankGenerator("RegionGenerator","RegionGenerator",EventBase::visRegionEGID,mysid,rleg,tid), srcNumColors(0), srcColors(NULL), regions(NULL)
 {
-	//this part is only necessary if you override setNumImages yourself
 	if(rleg!=NULL) {
 		numLayers=numChannels=0; //this is to force setNumImages to override settings provided by FilterBankGenerator
 		setNumImages(rleg->getNumLayers(),rleg->getNumChannels());
+		if(const SegmentedColorGenerator* seg=dynamic_cast<const SegmentedColorGenerator*>(rleg->getSourceGenerator())) {
+			srcNumColors=seg->getNumColors();
+			srcColors=seg->getColors();
+		} else {
+			serr->printf("WARNING: Region generator expects it's source's source to be a SegmentedColorGenerator so that it can access color table information.\n");
+		}
 	}
 }
 
@@ -45,9 +51,12 @@
 			freeCaches();
 		srcNumColors=segev->getNumColors();
 		srcColors=segev->getColors();
-		erouter->postEvent(new SegmentedColorFilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::activateETID,*segev));
-		erouter->postEvent(new SegmentedColorFilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::statusETID,*segev));
-		erouter->postEvent(new SegmentedColorFilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::deactivateETID,*segev));
+		SegmentedColorFilterBankEvent fbkev(this,getGeneratorID(),getSourceID(),EventBase::activateETID,*segev);
+		erouter->postEvent(fbkev);
+		fbkev.setTypeID(EventBase::statusETID);
+		erouter->postEvent(fbkev);
+		fbkev.setTypeID(EventBase::deactivateETID);
+		erouter->postEvent(fbkev);
 	}
 }
 
@@ -75,21 +84,17 @@
 }
 
 unsigned int
-RegionGenerator::LoadBuffer(const char buf[], unsigned int len) {
+RegionGenerator::loadBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
-	unsigned int used;
+	if(!checkInc(FilterBankGenerator::loadBuffer(buf,len),buf,len)) return 0;
 	std::string tmp;
-	if(0==(used=FilterBankGenerator::LoadBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(tmp,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!decodeInc(tmp,buf,len)) return 0;
 	if(tmp!="RegionImage") {
 		serr->printf("Unhandled image type for RegionGenerator: %s",tmp.c_str());
 		return 0;
 	} else {
 		unsigned int tmpNumClr=0;
-		if(0==(used=decode(tmpNumClr,buf,len))) return 0;
-		len-=used; buf+=used;
+		if(!decodeInc(tmpNumClr,buf,len)) return 0;
 		if(tmpNumClr!=srcNumColors)
 			freeCaches();
 		srcNumColors=tmpNumClr;
@@ -100,42 +105,29 @@
 			return 0;
 		for(unsigned int i=0; i<srcNumColors; i++) {
 			unsigned int tmpNumReg=0;
-			if(0==(used=decode(tmpNumReg,buf,len))) return 0;
-			len-=used; buf+=used;
+			if(!decodeInc(tmpNumReg,buf,len)) return 0;
 			if(MAX_REGIONS<=tmpNumReg)
 				return 0;
 			for(unsigned int j=0; j<tmpNumReg; j++) {
 				region * curreg=&regions[selectedSaveLayer][selectedSaveChannel][j];
-				if(0==(used=decode(curreg->color,buf,len))) return 0;
-				len-=used; buf+=used;
-				if(0==(used=decode(curreg->x1,buf,len))) return 0;
-				len-=used; buf+=used;
-				if(0==(used=decode(curreg->y1,buf,len))) return 0;
-				len-=used; buf+=used;
-				if(0==(used=decode(curreg->x2,buf,len))) return 0;
-				len-=used; buf+=used;
-				if(0==(used=decode(curreg->y2,buf,len))) return 0;
-				len-=used; buf+=used;
-				if(0==(used=decode(curreg->cen_x,buf,len))) return 0;
-				len-=used; buf+=used;
-				if(0==(used=decode(curreg->cen_y,buf,len))) return 0;
-				len-=used; buf+=used;
-				if(0==(used=decode(curreg->area,buf,len))) return 0;
-				len-=used; buf+=used;
-				if(0==(used=decode(curreg->run_start,buf,len))) return 0;
-				len-=used; buf+=used;
+				if(!decodeInc(curreg->color,buf,len)) return 0;
+				if(!decodeInc(curreg->x1,buf,len)) return 0;
+				if(!decodeInc(curreg->y1,buf,len)) return 0;
+				if(!decodeInc(curreg->x2,buf,len)) return 0;
+				if(!decodeInc(curreg->y2,buf,len)) return 0;
+				if(!decodeInc(curreg->cen_x,buf,len)) return 0;
+				if(!decodeInc(curreg->cen_y,buf,len)) return 0;
+				if(!decodeInc(curreg->area,buf,len)) return 0;
+				if(!decodeInc(curreg->run_start,buf,len)) return 0;
 				if(j==tmpNumReg-1)
 					curreg->next=NULL;
 				else
 					curreg->next=&regions[selectedSaveLayer][selectedSaveChannel][j+1];
 			}
 			//we're only going to save the region part (not the color info)
-			if(0==(used=decode(stats[i].min_area,buf,len))) return 0;
-			len-=used; buf+=used;
-			if(0==(used=decode(stats[i].total_area,buf,len))) return 0;
-			len-=used; buf+=used;
-			if(0==(used=decode(stats[i].merge_threshold,buf,len))) return 0;
-			len-=used; buf+=used;
+			if(!decodeInc(stats[i].min_area,buf,len)) return 0;
+			if(!decodeInc(stats[i].total_area,buf,len)) return 0;
+			if(!decodeInc(stats[i].merge_threshold,buf,len)) return 0;
 			stats[i].list=regions[selectedSaveLayer][selectedSaveChannel];
 			stats[i].num=tmpNumReg;
 		}
@@ -145,60 +137,43 @@
 }
 
 unsigned int
-RegionGenerator::SaveBuffer(char buf[], unsigned int len) const {
+RegionGenerator::saveBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=FilterBankGenerator::SaveBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode("RegionImage",buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkInc(FilterBankGenerator::saveBuffer(buf,len),buf,len)) return 0;
+	if(!encodeInc("RegionImage",buf,len)) return 0;
 	
 	if(images[selectedSaveLayer][selectedSaveChannel]==NULL) {
-		serr->printf("RegionGenerator::SaveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("RegionGenerator::saveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	if(!imageValids[selectedSaveLayer][selectedSaveChannel]) {
-		serr->printf("RegionGenerator::SaveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("RegionGenerator::saveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
 	region_stats * stats=reinterpret_cast<region_stats*>(img);
 	if(stats==NULL)
 		return 0;
-	if(0==(used=encode(srcNumColors,buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!encodeInc(srcNumColors,buf,len)) return 0;
 	for(unsigned int i=0; i<srcNumColors; i++) {
-		if(0==(used=encode(stats[i].num,buf,len))) return 0;
-		len-=used; buf+=used;
+		if(!encodeInc(stats[i].num,buf,len)) return 0;
 		region * curreg=stats[i].list;
 		for(int j=0; j<stats[i].num; j++) {
-			if(0==(used=encode(curreg->color,buf,len))) return 0;
-			len-=used; buf+=used;
-			if(0==(used=encode(curreg->x1,buf,len))) return 0;
-			len-=used; buf+=used;
-			if(0==(used=encode(curreg->y1,buf,len))) return 0;
-			len-=used; buf+=used;
-			if(0==(used=encode(curreg->x2,buf,len))) return 0;
-			len-=used; buf+=used;
-			if(0==(used=encode(curreg->y2,buf,len))) return 0;
-			len-=used; buf+=used;
-			if(0==(used=encode(curreg->cen_x,buf,len))) return 0;
-			len-=used; buf+=used;
-			if(0==(used=encode(curreg->cen_y,buf,len))) return 0;
-			len-=used; buf+=used;
-			if(0==(used=encode(curreg->area,buf,len))) return 0;
-			len-=used; buf+=used;
-			if(0==(used=encode(curreg->run_start,buf,len))) return 0;
-			len-=used; buf+=used;
+			if(!encodeInc(curreg->color,buf,len)) return 0;
+			if(!encodeInc(curreg->x1,buf,len)) return 0;
+			if(!encodeInc(curreg->y1,buf,len)) return 0;
+			if(!encodeInc(curreg->x2,buf,len)) return 0;
+			if(!encodeInc(curreg->y2,buf,len)) return 0;
+			if(!encodeInc(curreg->cen_x,buf,len)) return 0;
+			if(!encodeInc(curreg->cen_y,buf,len)) return 0;
+			if(!encodeInc(curreg->area,buf,len)) return 0;
+			if(!encodeInc(curreg->run_start,buf,len)) return 0;
 			curreg=curreg->next;
 		}
 		//we're only going to save the region part (not the color info)
-		if(0==(used=encode(stats[i].min_area,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=encode(stats[i].total_area,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=encode(stats[i].merge_threshold,buf,len))) return 0;
-		len-=used; buf+=used;
+		if(!encodeInc(stats[i].min_area,buf,len)) return 0;
+		if(!encodeInc(stats[i].total_area,buf,len)) return 0;
+		if(!encodeInc(stats[i].merge_threshold,buf,len)) return 0;
 	}
 	return origlen-len;
 }
@@ -233,7 +208,7 @@
 
 void
 RegionGenerator::calcImage(unsigned int layer, unsigned int chan) {
-	PROFSECTION("RegionGenerator::calcImage(...)",state->mainProfile);
+	PROFSECTION("RegionGenerator::calcImage(...)",*mainProfiler);
 	
 	//some shorthand to make the rest of the code more readable
 	RLEGenerator& srcRLE=dynamic_cast<RLEGenerator&>(*src); //source generator
@@ -246,6 +221,7 @@
   unsigned int maxArea = CMVision::SeparateRegions(stats,srcNumColors,regions[layer][chan],numReg);
   CMVision::SortRegions(stats,srcNumColors,maxArea);
   CMVision::MergeRegions(stats,(int)srcNumColors,rmap); //yes that (int) is necessary or compiler complains of ambiguous function call
+  CMVision::CalcTotalArea(stats,srcNumColors);
 
 	//and set the flag so we don't recompute if getImage() is called again before the next frame
 	imageValids[layer][chan]=true;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/RegionGenerator.h ./Vision/RegionGenerator.h
--- ../Tekkotsu_2.4.1/Vision/RegionGenerator.h	2005-06-29 18:06:11.000000000 -0400
+++ ./Vision/RegionGenerator.h	2006-09-09 00:33:04.000000000 -0400
@@ -49,8 +49,8 @@
 	virtual void processEvent(const EventBase& event);
 
 	virtual unsigned int getBinSize() const;
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
 
 protected:
 	typedef SegmentedColorFilterBankEvent::color_class_state color_class_state; //!< use the same color info as SegmentedColorFilterBankEvent (since that's what's supplying the color info)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/SegmentedColorGenerator.cc ./Vision/SegmentedColorGenerator.cc
--- ../Tekkotsu_2.4.1/Vision/SegmentedColorGenerator.cc	2005-06-06 15:33:31.000000000 -0400
+++ ./Vision/SegmentedColorGenerator.cc	2006-09-22 18:31:44.000000000 -0400
@@ -2,7 +2,7 @@
 #include "Events/EventRouter.h"
 #include "Events/SegmentedColorFilterBankEvent.h"
 #include "Wireless/Wireless.h"
-#include "Shared/WorldState.h"
+#include "Shared/Profiler.h"
 #include "Shared/Config.h"
 
 #include "Shared/debuget.h"
@@ -44,9 +44,12 @@
 SegmentedColorGenerator::processEvent(const EventBase& event) {
 	FilterBankGenerator::processEvent(event);
 	if(event.getGeneratorID()==getListenGeneratorID() && event.getSourceID()==getListenSourceID()) {
-		erouter->postEvent(new SegmentedColorFilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::activateETID,this,getNumColors(),getColors(),&colorNames));
-		erouter->postEvent(new SegmentedColorFilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::statusETID,this,getNumColors(),getColors(),&colorNames));
-		erouter->postEvent(new SegmentedColorFilterBankEvent(this,getGeneratorID(),getSourceID(),EventBase::deactivateETID,this,getNumColors(),getColors(),&colorNames));
+		SegmentedColorFilterBankEvent segev(this,getGeneratorID(),getSourceID(),EventBase::activateETID,this,getNumColors(),getColors(),&colorNames);
+		erouter->postEvent(segev);
+		segev.setTypeID(EventBase::statusETID);
+		erouter->postEvent(segev);
+		segev.setTypeID(EventBase::deactivateETID);
+		erouter->postEvent(segev);
 	}
 }
 
@@ -102,26 +105,21 @@
 unsigned int
 SegmentedColorGenerator::getBinSize() const {
 	unsigned int used=FilterBankGenerator::getBinSize();
-	used+=strlen("SegColorImage")+LoadSave::stringpad;
+	used+=creatorSize("SegColorImage");
 	used+=widths[selectedSaveLayer]*heights[selectedSaveLayer];
 	return used;
 }
 
 unsigned int
-SegmentedColorGenerator::LoadBuffer(const char buf[], unsigned int len) {
+SegmentedColorGenerator::loadBuffer(const char buf[], unsigned int len) {
 	unsigned int origlen=len;
-	unsigned int used;
-	std::string tmp;
-	if(0==(used=FilterBankGenerator::LoadBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=decode(tmp,buf,len))) return 0;
-	len-=used; buf+=used;
-	if(tmp!="SegColorImage") {
-		serr->printf("Unhandled image type for SegmentedColorGenerator: %s",tmp.c_str());
+	if(!checkInc(FilterBankGenerator::loadBuffer(buf,len),buf,len)) return 0;
+	if(!checkCreatorInc("SegColorImage",buf,len)) {
+		serr->printf("Unhandled image type for SegmentedColorGenerator: %s",buf+getSerializedSize<unsigned int>());
 		return 0;
 	} else {
 		// actual image
-		used=widths[selectedSaveLayer]*heights[selectedSaveLayer];
+		unsigned int used=widths[selectedSaveLayer]*heights[selectedSaveLayer];
 		if(used>len)
 			return 0;
 		if(images[selectedSaveLayer][selectedSaveChannel]==NULL)
@@ -133,8 +131,7 @@
 		len-=used; buf+=used;
 
 		// color table
-		if(0==(used=decodeColors(buf,len))) return 0;
-		len-=used; buf+=used;
+		if(!decodeColorsInc(buf,len)) return 0;
 		
 		imageValids[selectedSaveLayer][selectedSaveChannel]=true;
 		return origlen-len;	
@@ -142,24 +139,21 @@
 }
 
 unsigned int
-SegmentedColorGenerator::SaveBuffer(char buf[], unsigned int len) const {
+SegmentedColorGenerator::saveBuffer(char buf[], unsigned int len) const {
 	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=FilterBankGenerator::SaveBuffer(buf,len))) return 0;
-	len-=used; buf+=used;
-	if(0==(used=encode("SegColorImage",buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!checkInc(FilterBankGenerator::saveBuffer(buf,len),buf,len)) return 0;
+	if(!saveCreatorInc("SegColorImage",buf,len)) return 0;
 	
 	// actual image
-	used=widths[selectedSaveLayer]*heights[selectedSaveLayer];
+	unsigned int used=widths[selectedSaveLayer]*heights[selectedSaveLayer];
 	if(used>len)
 		return 0;
 	if(images[selectedSaveLayer][selectedSaveChannel]==NULL) {
-		serr->printf("SegmentedColorGenerator::SaveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("SegmentedColorGenerator::saveBuffer() failed because selected image is NULL -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	if(!imageValids[selectedSaveLayer][selectedSaveChannel]) {
-		serr->printf("SegmentedColorGenerator::SaveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
+		serr->printf("SegmentedColorGenerator::saveBuffer() failed because selected image is invalid -- call selectSaveImage first to make sure it's up to date\n");
 		return 0;
 	}
 	unsigned char* img=images[selectedSaveLayer][selectedSaveChannel];
@@ -169,44 +163,31 @@
 	len-=used; buf+=used;
 
 	// color table
-	if(0==(used=encodeColors(buf,len))) return 0;
-	len-=used; buf+=used;
+	if(!encodeColorsInc(buf,len)) return 0;
 	
 	return origlen-len;
 }
 
-unsigned int
-SegmentedColorGenerator::encodeColors(char buf[], unsigned int len) const {
-	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=encode(numColors,buf,len))) return 0;
-	len-=used; buf+=used;
+bool
+SegmentedColorGenerator::encodeColorsInc(char*& buf, unsigned int& len) const {
+	if(!encodeInc(numColors,buf,len)) return false;
 	for(unsigned int i=0; i<numColors; i++) {
-		if(0==(used=encode(colors[i].color.red,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=encode(colors[i].color.green,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=encode(colors[i].color.blue,buf,len))) return 0;
-		len-=used; buf+=used;
+		if(!encodeInc(colors[i].color.red,buf,len)) return false;
+		if(!encodeInc(colors[i].color.green,buf,len)) return false;
+		if(!encodeInc(colors[i].color.blue,buf,len)) return false;
 	}
-	return origlen-len;	
+	return true;
 }
 
-unsigned int
-SegmentedColorGenerator::decodeColors(const char buf[], unsigned int len) {
-	unsigned int origlen=len;
-	unsigned int used;
-	if(0==(used=decode(numColors,buf,len))) return 0;
-	len-=used; buf+=used;
+bool
+SegmentedColorGenerator::decodeColorsInc(const char*& buf, unsigned int& len) {
+	if(!decodeInc(numColors,buf,len)) return false;
 	for(unsigned int i=0; i<numColors; i++) {
-		if(0==(used=decode(colors[i].color.red,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=decode(colors[i].color.green,buf,len))) return 0;
-		len-=used; buf+=used;
-		if(0==(used=decode(colors[i].color.blue,buf,len))) return 0;
-		len-=used; buf+=used;
+		if(!decodeInc(colors[i].color.red,buf,len)) return false;
+		if(!decodeInc(colors[i].color.green,buf,len)) return false;
+		if(!decodeInc(colors[i].color.blue,buf,len)) return false;
 	}
-	return origlen-len;	
+	return true;
 }
 
 void
@@ -223,12 +204,17 @@
 
 unsigned char *
 SegmentedColorGenerator::createImageCache(unsigned int layer, unsigned int /*chan*/) const {
-	return new unsigned char[widths[layer]*heights[layer]];
+	// notice the +1 !!!
+	// this is because CMVision is a little naughty and writes an unused, terminator flag at the one-past-end of each row
+	// if we didn't add one, this last byte would be beyond the end of the array
+	return new unsigned char[widths[layer]*heights[layer]+1];
 }
 
 void
 SegmentedColorGenerator::calcImage(unsigned int layer, unsigned int chan) {
-	PROFSECTION("SegmentedColorGenerator::calcImage(...)",state->mainProfile);
+	if(tmaps.size()==0)
+		throw NoThresholdException();
+	PROFSECTION("SegmentedColorGenerator::calcImage(...)",*mainProfiler);
 	CMVision::image_yuv<const cmap_t> img;
 	img.buf_y=src->getImage(layer,srcYChan);
 	img.buf_u=src->getImage(layer,srcUChan);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/SegmentedColorGenerator.h ./Vision/SegmentedColorGenerator.h
--- ../Tekkotsu_2.4.1/Vision/SegmentedColorGenerator.h	2005-06-01 01:47:58.000000000 -0400
+++ ./Vision/SegmentedColorGenerator.h	2006-09-22 18:31:44.000000000 -0400
@@ -37,7 +37,7 @@
  *
  *  Uses the CMVision library for main processing
  *
- *  The format used for serialization is: (code is in SaveBuffer())
+ *  The format used for serialization is: (code is in saveBuffer())
  *  - <@c FilterBankGenerator: superclass header> <i>(First saves the superclass's info)</i>
  *  - <@c string: "SegColorImage"> <i>(remember a 'string' is len+str+0; so this is the literal "\015\0\0\0SegColorImage\0"; also remember "\015" is octal for 13)</i>
  *  - <<tt>char[</tt>width<tt>*</tt>height<tt>]</tt>: image data> <i>(one byte per sample)</i>
@@ -52,10 +52,10 @@
  */
 class SegmentedColorGenerator : public FilterBankGenerator {
 public:
-	typedef uchar cmap_t; //!< type to use for color indexes
+	typedef CMVision::uchar cmap_t; //!< type to use for color indexes
 	typedef CMVision::color_class_state color_class_state; //!< use CMVision's color structure
 	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
 	SegmentedColorGenerator(unsigned int mysid, FilterBankGenerator* fbg, EventBase::EventTypeID_t tid);
 	//! constructor, you can pass which channels to use as Y, U, & V channels
@@ -73,7 +73,7 @@
 
 	//! loads color information from a file, returns false if failed, true otherwise
 	virtual bool loadColorInfo(const std::string& col_file);
-	
+
 	//! returns the number of different colors available
 	virtual unsigned int getNumColors() const { return numColors; }
 
@@ -83,67 +83,75 @@
 	//! gives direct access to the color information
 	virtual color_class_state * getColors() { return colors; }
 
-	//! returns index of color corresponding to a string (uses a fast hash lookup)
-	unsigned int getColorIndex(const char * name) const { 
+	//! returns index of color corresponding to a string (uses a fast hash lookup), or -1U if not found
+	unsigned int getColorIndex(const char * name) const {
 		hashmap::const_iterator i;
 		i=colorNames.find(name);
 		return (i==colorNames.end())?-1U:i->second;
 	}
-	
-	//! returns index of color corresponding to a string (uses a fast hash lookup)
+
+	//! returns index of color corresponding to a string (uses a fast hash lookup), or -1U if not found
 	unsigned int getColorIndex(const std::string& name) const { return getColorIndex(name.c_str()); }
 
-	//! returns index of color corresponding to a specific rgb color
+	//! returns index of color corresponding to a specific rgb color, or -1U if not found
 	unsigned int getColorIndex(const rgb color) const {
 		for(unsigned int index = 0; index < getNumColors(); index++)
 			if(getColorRGB((int)index) == color)
 				return index;
-		return 0;
+		return -1U;
 	}
 
 
-	//! returns rgb struct (from colors.h) correspondingto an int index.
-	rgb getColorRGB(const int index) const {
-		return(getColors()[index].color);
+	//! returns rgb struct (from colors.h) corresponding to an int index.  Returns black if index is invalid.
+	rgb getColorRGB(const unsigned int index) const {
+		return (index>=numColors ? rgb() : getColors()[index].color);
 	}
 
-	//! returns rgb struct (from colors.h) corresponding to a string.
+	//! returns rgb struct (from colors.h) corresponding to a string.  Returns black if index is invalid.
 	rgb getColorRGB(const char * name) const {
-		return(getColorRGB(getColorIndex(name)));
+		return getColorRGB(getColorIndex(name));
 	}
 
-	//! returns rgb struct (from colors.h) corresponding to a string.
-	rgb getColorRGB(const std::string& name) const { 
-		return getColorRGB(name.c_str()); 
+	//! returns rgb struct (from colors.h) corresponding to a string.  Returns black if index is invalid.
+	rgb getColorRGB(const std::string& name) const {
+		return getColorRGB(name.c_str());
 	}
 
 
 	virtual unsigned int getBinSize() const;
-	virtual unsigned int LoadBuffer(const char buf[], unsigned int len);
-	virtual unsigned int SaveBuffer(char buf[], unsigned int len) const;
-	virtual unsigned int encodeColors(char buf[], unsigned int len) const; //!< in case you want to only save the color info but not the image (this is binary - *not* the same format as what's read in loadColorInfo)
-	virtual unsigned int decodeColors(const char buf[], unsigned int len); //!< in case you want to only load the color info but not the image (this is binary - *not* the same format as what's read in loadColorInfo)
-	
+	virtual unsigned int loadBuffer(const char buf[], unsigned int len);
+	virtual unsigned int saveBuffer(char buf[], unsigned int len) const;
+	virtual bool encodeColorsInc(char*& buf, unsigned int& len) const; //!< in case you want to only save the color info but not the image (this is binary - *not* the same format as what's read in loadColorInfo)
+	virtual bool decodeColorsInc(const char*& buf, unsigned int& len); //!< in case you want to only load the color info but not the image (this is binary - *not* the same format as what's read in loadColorInfo)
+
 
 protected:
+	//! thrown if no threshold maps are available
+	class NoThresholdException : public std::exception {
+	public:
+		//! returns descriptive error string
+		virtual const char * what() const throw() { return "SegmentedColorGenerator::calcImage(): can't segment image without any loaded threshold maps"; }
+	};
+
 	static const unsigned int BITS_Y = 4; //!< bits of discretization for Y channel in the threshold map
 	static const unsigned int BITS_U = 6; //!< bits of discretization for U channel in the threshold map
 	static const unsigned int BITS_V = 6; //!< bits of discretization for V channel in the threshold map
-  static const unsigned int NUM_Y = 1 << BITS_Y; //!< levels of discretization for Y channel in the threshold map
-  static const unsigned int NUM_U = 1 << BITS_U; //!< levels of discretization for U channel in the threshold map
-  static const unsigned int NUM_V = 1 << BITS_V; //!< levels of discretization for V channel in the threshold map
+	static const unsigned int NUM_Y = 1 << BITS_Y; //!< levels of discretization for Y channel in the threshold map
+	static const unsigned int NUM_U = 1 << BITS_U; //!< levels of discretization for U channel in the threshold map
+	static const unsigned int NUM_V = 1 << BITS_V; //!< levels of discretization for V channel in the threshold map
 	static const unsigned int MAX_COLORS = 20; //!< maximum number of different colors that can be segmented
-	
+
 	//! ignores @a nChannels - the number of channels is always the number of loaded threshold maps
 	virtual void setNumImages(unsigned int nLayers, unsigned int nChannels);
 	virtual void setDimensions(); //!< sets stride parameter to width (as set by FilterBankGenerator::setDimensions())
+	//! creates the image cache width[layer]*height[layer] + 1 -- why plus one?  Because CMVision temporarily scribbles one-past end of each row
 	virtual unsigned char * createImageCache(unsigned int layer, unsigned int chan) const;
 	virtual void calcImage(unsigned int layer, unsigned int chan);
 
 	unsigned int srcYChan; //!< the channel of the source's Y channel
 	unsigned int srcUChan; //!< the channel of the source's U channel
 	unsigned int srcVChan; //!< the channel of the source's V channel
-	
+
 	std::vector<cmap_t*> tmaps; //!< list of threshold maps so you can segment the same source different ways
 	std::vector<std::string> tmapNames; //!< filename of each tmap;
 
@@ -156,7 +164,7 @@
 	const SegmentedColorGenerator& operator=(const SegmentedColorGenerator& fbk); //!< don't call
 };
 
-/*! @file 
+/*! @file
  * @brief Describes SegmentedColorGenerator, which generates FilterBankEvents indexed color images based on a color threshold file
  * @author alokl (Creator)
  * @author ejt (reorganized)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/cmv_threshold.h ./Vision/cmv_threshold.h
--- ../Tekkotsu_2.4.1/Vision/cmv_threshold.h	2005-06-04 19:23:31.000000000 -0400
+++ ./Vision/cmv_threshold.h	2006-07-02 14:50:56.000000000 -0400
@@ -119,7 +119,6 @@
 
     int rowidx=0;
     for(col=0; col<width; col++) {
-      rowidx+=img.col_stride;
       py = row_y[rowidx] >> rshift_y;
       pu = row_u[rowidx] >> rshift_u;
       pv = row_v[rowidx] >> rshift_v;
@@ -139,6 +138,7 @@
         printf("py=%u pu=%u pv=%u tmap_idx=%d tmap val=%u\n",py,pu,pv,tmap_idx,tmap[tmap_idx]);
       }
       */
+      rowidx+=img.col_stride;
     }
   }
 
@@ -295,7 +295,9 @@
   FILE *in;
   char buf[256];
   int ny,nu,nv;
+//  int by,bu,bv;
   int size,read;
+  bool invertUV;
 
   in = fopen(filename,"r");
   if(!in) return(false);
@@ -305,17 +307,45 @@
   buf[4] = 0;
   if(strcmp(buf,"TMAP")) goto error;
 
-  // read type (ignore for now)
+  // read type
   if(!fgets(buf,256,in)) goto error;
+  if(strcmp(buf,"YUV8\n")==0)
+    invertUV=true;
+  else if(strcmp(buf,"YUV'8\n")==0)
+    invertUV=false;
+  else goto error;
 
   // read size
   if(!fgets(buf,256,in)) goto error;
   ny = nu = nv = 0;
   sscanf(buf,"%d %d %d",&ny,&nu,&nv);
-  if(num_y!=ny || num_u!=nu || num_v!=nv) goto error;
+  if(invertUV) {
+    if(num_y!=ny || num_u!=nv || num_v!=nu) goto error;
+  } else {
+    if(num_y!=ny || num_u!=nu || num_v!=nv) goto error;
+  }
+  /*//for(by=1; (num_y>>by)!=0; by++) {}
+  for(bu=1; (num_u>>bu)!=0; bu++) {}
+  for(bv=1; (num_v>>bv)!=0; bv++) {}
+  by=bu+bv;
+  bu=bv;
+  bv=0;*/
 
   size = num_y * num_u * num_v;
-  read = fread(tmap,sizeof(tmap_t),size,in);
+  if(!invertUV) {
+    read = fread(tmap,sizeof(tmap_t),size,in);
+  } else {
+    read=0;
+    for(int yi=0; yi<num_y; yi++) {
+      for(int vi=0; vi<num_v; vi++) {
+        for(int ui=0; ui<num_u; ui++) {
+          if(fread(tmap+ui*num_v+vi,sizeof(tmap_t),1,in)!=1) goto error;
+        }
+      }
+      tmap+=num_u*num_v;
+      read+=num_u*num_v;
+    }
+  }
 
   fclose(in);
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/cmv_types.h ./Vision/cmv_types.h
--- ../Tekkotsu_2.4.1/Vision/cmv_types.h	2005-06-04 19:23:31.000000000 -0400
+++ ./Vision/cmv_types.h	2006-01-17 15:10:03.000000000 -0500
@@ -19,7 +19,7 @@
 
 namespace CMVision{
 
-typedef unsigned char uchar;
+  //typedef unsigned char uchar;
 
 // uncomment if your compiler supports the "restrict" keyword
 // #define restrict __restrict__
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Vision/colors.h ./Vision/colors.h
--- ../Tekkotsu_2.4.1/Vision/colors.h	2005-03-10 18:18:07.000000000 -0500
+++ ./Vision/colors.h	2006-01-17 15:10:03.000000000 -0500
@@ -18,13 +18,14 @@
 #define RGB_COLOR_NAMES
 
 //==== Color Classes =================================================//
-
-typedef unsigned char uchar;
+namespace CMVision{
+  typedef unsigned char uchar;
+}
 
 #ifndef YUV_STRUCT
 #define YUV_STRUCT
 struct yuv{
-  uchar y,u,v;
+  CMVision::uchar y,u,v;
 };
 
 /* Depricated
@@ -51,26 +52,26 @@
 #ifndef YUYV_STRUCT
 #define YUYV_STRUCT
 struct yuyv{
-  uchar y1,u,y2,v;
+  CMVision::uchar y1,u,y2,v;
 };
 #endif
 
 struct uyvy{
 #ifndef UYVY_STRUCT
 #define UYVY_STRUCT
-  uchar u,y1,v,y2;
+  CMVision::uchar u,y1,v,y2;
 };
 #endif
 
 #ifndef RGB_STRUCT
 #define RGB_STRUCT
 struct rgb{
-  uchar red,green,blue;
+  CMVision::uchar red,green,blue;
 
   rgb() : red(0), green(0), blue(0) {};
 
   rgb(int r, int g, int b)
-    : red((uchar)r), green((uchar)g), blue((uchar)b)
+    : red((CMVision::uchar)r), green((CMVision::uchar)g), blue((CMVision::uchar)b)
   { };
 			 
 
@@ -89,14 +90,14 @@
 #ifndef RGBA_STRUCT
 #define RGBA_STRUCT
 struct rgba{
-  uchar r,g,b,a;
+  CMVision::uchar r,g,b,a;
 };
 #endif
 
 #ifndef ARGB_STRUCT
 #define ARGB_STRUCT
 struct argb{
-  uchar a,r,g,b;
+  CMVision::uchar a,r,g,b;
 };
 #endif
 
@@ -156,6 +157,6 @@
 /*   const rgb Gray(200,200,200); */
 /*   const rgb Skin(150,100,  0); */
 }
-#endif
 
 #endif
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Wireless/LGmixin.cc ./Wireless/LGmixin.cc
--- ../Tekkotsu_2.4.1/Wireless/LGmixin.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Wireless/LGmixin.cc	2006-04-26 17:46:59.000000000 -0400
@@ -0,0 +1,132 @@
+#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;
+Socket* LGmixin::LGsock = NULL;
+LGmixin* LGmixin::theOne = NULL;
+
+LGmixin::LGmixin() {
+  if ( instanceCount++ > 0 )
+    return;
+  if (theOne != NULL) {
+      cerr << "LGmixin statics already constructed!?!?!" << endl;
+      return;
+    }
+    theOne=this;
+
+    LGsock = wireless->socket(SocketNS::SOCK_STREAM, 1024, LGbufferSize);
+    wireless->setDaemon(LGsock, false);
+    wireless->listen(LGsock, LGport);
+}
+
+LGmixin::~LGmixin() {
+  if ( --instanceCount > 0 )
+    return;
+  if (theOne == NULL) {
+    cerr << "LGmixin statics already destructed!?!?!" << endl;
+    return;
+  }
+  wireless->close(LGsock->sock);
+  theOne = NULL;
+}
+
+void LGmixin::uploadFile(const std::string &filename, bool display, bool isImage) {
+  if ( !wireless->isConnected(LGsock->sock) ) {
+    cerr << "LookingGlass not connected." << endl;
+    return;
+  }
+
+  int in_file = open(filename.c_str(), O_RDONLY);
+  if ( in_file < 0 ) {
+    cerr << "Error: Unable to open file\n";
+    return;
+  }
+  struct stat s;
+  stat(filename.c_str(),&s);
+  const std::string remoteFilename = filename.substr(filename.rfind('/')+1);
+  LGsock->printf("UPLOAD_BINARY %s %u\n", remoteFilename.c_str(), (unsigned int)s.st_size);
+  
+  while(1){
+    char *buffer = (char*)LGsock->getWriteBuffer(s.st_size);
+    if ( buffer==NULL ) {
+      cerr << "NULL buffer in LG file upload" << endl;
+      break;
+    }
+    int read_size = read(in_file, buffer, s.st_size);
+    if( read_size == 0 )
+      break;
+    
+    if ( read_size < 0 ){
+      cerr << "Error: Read error " << read_size << endl;
+      break;
+    }
+    LGsock->write(read_size);
+  }
+  
+  if(display)
+    if ( isImage )
+      displayImageFile(remoteFilename);
+    else
+      displayHtmlFile(remoteFilename);
+
+  close(in_file);
+}
+
+void LGmixin::displayHtmlFile(const std::string &remoteFilename) {
+  LGsock->printf("DISPLAY LookingGlass_Temp_File\n"); // work-around because renderer can't display same file twice
+  LGsock->printf("DISPLAY %s\n",remoteFilename.c_str());
+}
+
+void LGmixin::displayImageFile(const std::string &remoteFilename) {
+  LGsock->printf((string("UPLOAD_HTML %s.html\n") +
+		 string("<html><body><table width=100%% height=100%%><tr><td align=center valign=middle>") +
+		  string("<img src=\"%s\"></td></tr></table></body>\n</html>\n")).c_str(),
+		 remoteFilename.c_str(), remoteFilename.c_str());
+  displayHtmlFile(remoteFilename+".html");
+}
+
+void LGmixin::displayHtmlText(const std::string &text) {
+  unsigned int const msgSize = text.size();
+  string const tempfilename = "temp9999";
+  LGsock->printf("UPLOAD_BINARY %s %u\n", tempfilename.c_str(), msgSize);
+  char *buffer = (char*)LGsock->getWriteBuffer(msgSize);
+  memcpy(buffer,text.c_str(),msgSize);
+  LGsock->write(msgSize);
+  displayHtmlFile(tempfilename);
+}
+
+void LGmixin::sendCommand(const std::string &command) {
+  LGsock->printf("%s\n", command.c_str());
+}
+
+void LGmixin::uploadCameraImage(const std::string &remoteFilename) {
+    JPEGGenerator *jpeg = ProjectInterface::defColorJPEGGenerator;  
+    // call to getImage must come before call to getImageSize
+    char *image = (char*)jpeg->getImage(ProjectInterface::fullLayer, 0);
+    int const imgSize = jpeg->getImageSize(ProjectInterface::fullLayer, 0);
+    LGsock->printf("UPLOAD_BINARY %s %u\n", remoteFilename.c_str(), imgSize);
+    char *buffer = (char*)LGsock->getWriteBuffer(imgSize);
+    if ( buffer==NULL ) {
+      cerr << "NULL buffer in LG camera upload" << endl;
+      return;
+    }
+    memcpy(buffer,image,imgSize);
+    LGsock->write(imgSize);
+}
+
+void LGmixin::uploadSketch(const DualCoding::Sketch<DualCoding::uchar> &/*sketch*/,
+			   const std::string &/*remoteFilename*/) {
+  // this function has not been written yet
+}
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Wireless/LGmixin.h ./Wireless/LGmixin.h
--- ../Tekkotsu_2.4.1/Wireless/LGmixin.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Wireless/LGmixin.h	2006-09-22 12:59:26.000000000 -0400
@@ -0,0 +1,58 @@
+//-*-c++-*-
+#ifndef INCLUDED_LGmixin_h_
+#define INCLUDED_LGmixin_h_
+
+#include "Wireless/Wireless.h"
+
+namespace DualCoding {
+  typedef unsigned char uchar;
+  template <typename T> class Sketch;
+}
+
+//! Mix-in for the BehaviorBase or StateNode class to give access to Looking Glass variables.
+class LGmixin {
+ protected:
+  static unsigned int instanceCount; //!< count of LGmixin instances -- when this hits zero, close the socket
+  static Socket *LGsock; //!< socket to talk to Looking Glass server
+
+ public:
+  //! Constructor
+  LGmixin();
+
+  //! Destructor
+  virtual ~LGmixin();
+
+  //! Upload a file from the AIBO to the Looking Glass client
+  static void uploadFile(const std::string &filename, bool display=false, bool isImage=false);
+
+  //! Display an HTML file on the Looking Glass
+  static void displayHtmlFile(const std::string &remoteFilename);
+
+  //! Display a single image file on the Looking Glass (creates a dummy HTML file)
+  static void displayImageFile(const std::string &remoteFilename);
+
+  //! Display HTML string on the Looking Glass (creates a dummy HTML file)
+  static void displayHtmlText(const std::string &text);
+
+  //! Upload current camera image to the Looking Glass client as a JPEG file
+  static void uploadCameraImage(const std::string &remoteFileName);
+
+  //! For debugging: send an arbitrary command string to the Looking Glass client
+  static void sendCommand(const std::string &command);
+
+  //! Upload a sketch as a PNG file to the Looking Glass client (not implemented yet) 
+  static void uploadSketch(const DualCoding::Sketch<DualCoding::uchar> &sketch, const std::string &remoteFilename);
+
+ private:
+  //! used so static member functions can access non-static members
+  static LGmixin* theOne;
+
+  LGmixin (const LGmixin&);	 //!< never call this
+  LGmixin& operator=(const LGmixin&); //!< never call this
+
+  static const unsigned int LGbufferSize = 80000; //!< maximum send buffer size
+  static const unsigned int LGport = 10100; //!< port number to listen on
+
+};
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Wireless/Socket.cc ./Wireless/Socket.cc
--- ../Tekkotsu_2.4.1/Wireless/Socket.cc	2005-08-02 18:24:29.000000000 -0400
+++ ./Wireless/Socket.cc	2006-07-03 21:36:46.000000000 -0400
@@ -11,6 +11,7 @@
 #  include <fcntl.h>
 #endif
 #include "Shared/Config.h"
+#include "Shared/MarkScope.h"
 #include <unistd.h>
 
 Socket* sout=NULL;
@@ -44,23 +45,41 @@
 Socket::getWriteBuffer(int bytesreq)
 {
 #ifndef PLATFORM_APERIOS
-  wireless->getLock().lock();
+  MarkScope l(wireless->getLock());
 #endif
+	byte* buf=NULL;
   if (sendBufSize-writeSize>=bytesreq
       && state==CONNECTION_CONNECTED)
-    return writeData+writeSize;
-  if (state!=CONNECTION_CONNECTED) {
+    buf=writeData+writeSize;
+  else if (state!=CONNECTION_CONNECTED) {
 		if(forwardSock!=NULL)
-			return forwardSock->getWriteBuffer(bytesreq);
-		if(textForward)
-			return (byte*)(textForwardBuf=new char[bytesreq]);
+			buf=forwardSock->getWriteBuffer(bytesreq);
+		else if(textForward)
+			buf=(byte*)(textForwardBuf=new char[bytesreq]);
   }
-	return NULL;
+#ifndef PLATFORM_APERIOS
+	// the lock is about to expire as we leave, but if buf is
+	// valid, we want to retain the lock until write() is called
+	if(buf!=NULL)
+		wireless->getLock().useResource(Resource::emptyData);
+#endif
+	return buf;
 }
 
 void
 Socket::write(int size)
 {
+#ifndef PLATFORM_APERIOS
+#  ifdef DEBUG
+	//we should be coming in with a lock from getWriteBuffer...
+	if(ThreadNS::Lock * lock=dynamic_cast<ThreadNS::Lock*>(&wireless->getLock())) {
+		if(lock->getLockLevel()==0) {
+			serr->printf("Socket: Attempted write() without previously successful getWriteBuffer()\n");
+			return;
+		}
+	}
+#  endif
+#endif
   writeSize+=size;
 	if(textForwardBuf) {
 		::write(STDOUT_FILENO,textForwardBuf,size);
@@ -69,7 +88,7 @@
 	} else
 		flush();
 #ifndef PLATFORM_APERIOS
-  wireless->getLock().unlock();
+  wireless->getLock().releaseResource(Resource::emptyData);
 #endif
 }
 
@@ -90,14 +109,16 @@
 Socket::init()
 {
 #ifndef PLATFORM_APERIOS
-  ThreadNS::Lock(wireless->getLock());
+  MarkScope l(wireless->getLock());
 #endif
   sendSize=0;
   writeSize=0;
   peer_addr=peer_port=-1;
 #ifndef PLATFORM_APERIOS
 	if(endpoint!=-1)
-		::close(endpoint);
+		if(::close(endpoint)==-1)
+			perror("Wireless::close(): close");
+	state = CONNECTION_CLOSED;
 	endpoint = ::socket ( AF_INET,trType,0 );
 	if(endpoint==-1) {
 		perror("Socket::init(): socket()");
@@ -112,6 +133,10 @@
 		if ( ::setsockopt ( endpoint, SOL_SOCKET, SO_BROADCAST, ( const char* ) &on, sizeof ( on ) ) == -1 ) {
 			perror("Socket::init(): SO_BROADCAST setsockopt");
 		}
+		const int sndbuf=(1<<16)-28;
+		if ( ::setsockopt ( endpoint, SOL_SOCKET, SO_SNDBUF, ( const char* ) &sndbuf, sizeof ( sndbuf ) ) == -1 ) {
+			perror("Socket::init(): SO_SNDBUF setsockopt");
+		}
 	}
 	if( ::fcntl(endpoint,F_SETFL,O_NONBLOCK) ==-1 ) {
 		perror("Socket::init(): fcntl");
@@ -131,7 +156,7 @@
 Socket::flush()
 {
 #ifndef PLATFORM_APERIOS
-  ThreadNS::Lock(wireless->getLock());
+  MarkScope l(wireless->getLock());
 #endif
   if (state!=CONNECTION_CONNECTED) {
 		if(forwardSock!=NULL)
@@ -197,7 +222,7 @@
 			return vfprintf(stdout, fmt, al);
   } else {
 #ifndef PLATFORM_APERIOS
-		ThreadNS::Lock(wireless->getLock());
+		MarkScope l(wireless->getLock());
 #endif
 		int ret=vsnprintf((char *)(writeData+writeSize), sendBufSize-writeSize, fmt, al);
 		writeSize+=ret;
@@ -217,7 +242,7 @@
 			return ::write(STDOUT_FILENO,buf,size);
 	} else {
 #ifndef PLATFORM_APERIOS
-		ThreadNS::Lock(wireless->getLock());
+		MarkScope l(wireless->getLock());
 #endif
 		byte *destbuf=getWriteBuffer(size);
 		if (destbuf==NULL) return -1;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Wireless/Socket.h ./Wireless/Socket.h
--- ../Tekkotsu_2.4.1/Wireless/Socket.h	2005-08-07 00:11:04.000000000 -0400
+++ ./Wireless/Socket.h	2006-10-03 18:32:49.000000000 -0400
@@ -1,6 +1,6 @@
 //-*-c++-*-
-#ifndef Socket_h_DEFINED
-#define Socket_h_DEFINED
+#ifndef INCLUDED_Socket_h_
+#define INCLUDED_Socket_h_
 
 #ifdef PLATFORM_APERIOS
 #  include <ant.h>
@@ -62,11 +62,8 @@
 //! Tekkotsu wireless Socket class
 /*! 
  * For more information on using wireless, please read the following tutorials:
- * - <a href="../AiboMon.html">TekkotsuMon</a>
+ * - <a href="../TekkotsuMon.html">TekkotsuMon</a>
  * - <a href="../Wireless.html">TCP/IP</a>
- * - <a href="../RemoteProcess.html">Remote Processing OPENR</a>
- * Tekkotsu Wireless and Remote Processing OPENR provide different
- * interfaces to comparable wireless functionality.
  *
  * The networking interface needs more documentation.  It also needs a
  * cleanup.  In the mean time, take a look at the TekkotsuMon objects
@@ -133,6 +130,11 @@
    * @return pointer to the buffer the previous call to blocking read wrote into or NULL if no data was read
    */
   byte* getReadBuffer();
+	
+	unsigned int getMaxSendSize() const { return sendBufSize; } //!< returns the maximum buffer size for a send
+	unsigned int getMaxReceiveSize() const { return recvBufSize; } //!< returns the maximum buffer size for a receive
+	unsigned int getAvailableSendSize() const { return sendBufSize-writeSize; } //!< returns the maximum *currently available* buffer size for a send
+	unsigned int getAvailableReceiveSize() const { return recvBufSize; } //!< returns the maximum *currently available* buffer size for a receive
 
   //! initialize socket member variables. This is different from the constructor since sockets are reused
   void init(); 
@@ -145,9 +147,13 @@
    * @return 0 on success
    */
   int setFlushType(FlushType_t fType);
+  //! returns flush mode
+  FlushType_t getFlushType() const { return flType; }
 	
   //! can choose between different transports; will reset the socket
   int setTransport(TransportType_t tr);
+  //! returns the transport in use
+  TransportType_t getTransport() const { return trType; }
 
 	//!causes this socket to forward output to stdout if it is not connected, call setForward(NULL) to unset
   void setTextForward() { textForward=true; forwardSock=NULL; }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Wireless/Wireless.cc ./Wireless/Wireless.cc
--- ../Tekkotsu_2.4.1/Wireless/Wireless.cc	2005-08-16 14:37:05.000000000 -0400
+++ ./Wireless/Wireless.cc	2006-06-26 12:24:17.000000000 -0400
@@ -191,7 +191,7 @@
 
 	if ( sockets[sock]->trType == SOCK_STREAM )
 		{
-			TCPEndpointListenMsg * listenMsg = ( TCPEndpointListenMsg * ) msg;
+			TCPEndpointListenMsg * listenMsg = ( TCPEndpointListenMsg * ) antEnvMsg::Receive( msg );
 
 			if ( listenMsg->error != TCP_SUCCESS )
 				{
@@ -227,7 +227,7 @@
 
 	if ( sockets[sock]->trType == SOCK_STREAM )
 		{
-			TCPEndpointConnectMsg * connectMsg = ( TCPEndpointConnectMsg * ) msg;
+			TCPEndpointConnectMsg * connectMsg = ( TCPEndpointConnectMsg * ) antEnvMsg::Receive( msg );
 			if ( connectMsg->error != TCP_SUCCESS )
 				{
 					sockets[sock]->state = CONNECTION_ERROR;
@@ -253,7 +253,7 @@
 Wireless::BindCont(void *msg)
 {
 try {
-	UDPEndpointBindMsg* bindMsg = (UDPEndpointBindMsg*)msg;
+	UDPEndpointBindMsg* bindMsg = (UDPEndpointBindMsg*) antEnvMsg::Receive( msg );
 	int sock = (int)bindMsg->continuation;
 
 	if (bindMsg->error != UDP_SUCCESS) {
@@ -316,7 +316,7 @@
 
 	if ( sockets[sock]->trType == SOCK_STREAM )
 		{
-			TCPEndpointSendMsg * sendMsg = ( TCPEndpointSendMsg * ) msg;
+			TCPEndpointSendMsg * sendMsg = ( TCPEndpointSendMsg * ) antEnvMsg::Receive( msg );
 			sockets[sock]->tx = false;
 			if ( sendMsg->error != TCP_SUCCESS )
 				{
@@ -328,7 +328,7 @@
 
 	else if ( sockets[sock]->trType == SOCK_DGRAM )
 		{
-			UDPEndpointSendMsg * sendMsg = ( UDPEndpointSendMsg * ) msg;
+			UDPEndpointSendMsg * sendMsg = ( UDPEndpointSendMsg * ) antEnvMsg::Receive( msg );
 			sockets[sock]->tx = false;
 			if ( sendMsg->error != UDP_SUCCESS )
 				{
@@ -445,7 +445,7 @@
 
 	if ( sockets[sock]->trType == SOCK_STREAM )
 		{
-			TCPEndpointReceiveMsg * receiveMsg = ( TCPEndpointReceiveMsg * ) msg;
+			TCPEndpointReceiveMsg * receiveMsg = ( TCPEndpointReceiveMsg * ) antEnvMsg::Receive( msg );
 			if ( receiveMsg->error != TCP_SUCCESS )
 				{
 					sockets[sock]->state = CONNECTION_ERROR;
@@ -569,7 +569,7 @@
 Wireless::CloseCont(void* msg)
 {
 try {
-	antEnvMsg * closeMsg = ( antEnvMsg * ) msg;
+	antEnvMsg * closeMsg = ( antEnvMsg * ) antEnvMsg::Receive( msg );
 	int sock = ( int )( closeMsg->continuation );
 	if ( sockets[sock] == NULL )
 		return;
@@ -614,12 +614,13 @@
 #  include <unistd.h>
 #  include <iostream>
 #  include <errno.h>
+#  include "Shared/MarkScope.h"
 
 using namespace std;
 
 
 Wireless::Wireless ()
-: interruptChk(-1), interruptCtl(-1), rfds(), wfds(), efds(), fdsMax(0), freeSockets(), usedSockets()
+	: callbackLock(NULL), interruptChk(-1), interruptCtl(-1), rfds(), wfds(), efds(), fdsMax(0), freeSockets(), usedSockets()
 {
 	sockets[0]=new DummySocket(0);
 	for (int sock = 1; sock < WIRELESS_MAX_SOCKETS; sock++) {
@@ -642,7 +643,7 @@
 
 Wireless::~Wireless ()
 {
-	ThreadNS::Lock l(getLock());
+	MarkScope l(getLock());
 	::close(interruptChk);
 	::close(interruptCtl);
 	interruptChk=interruptCtl=-1;
@@ -655,6 +656,7 @@
 		freeSockets.insert(freeSockets.end(),usedSockets.begin(),usedSockets.end());
 		usedSockets.clear();
 	}
+	delete sockets[0]; // DummySocket
 }
 
 void Wireless::setReceiver(int sock, int (*rcvcbckfn) (char*, int) ) {
@@ -662,16 +664,13 @@
 }
 
 void Wireless::close(int sock) {
-	ThreadNS::Lock l(getLock());
+	MarkScope l(getLock());
 	if ( sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL)
 		return;
 	sockets[sock]->flush();
 	sockets[sock]->peer_port = sockets[sock]->peer_addr = -1;
 	if(sockets[sock]->daemon) {
-		if(::close(sockets[sock]->endpoint)==-1)
-			perror("Wireless::close(): close");
-		sockets[sock]->endpoint=-1;
-		sockets[sock]->state = CONNECTION_CLOSED;
+		sockets[sock]->init();
 		listen(sock,sockets[sock]->server_port);
 	} else {
 		bool found=false;
@@ -687,14 +686,14 @@
 			return;
 		}
 		Socket * s=sockets[sock];
-		sockets[sock] = NULL;
+		sockets[sock] = NULL; //we don't delete the socket here -- wakeup() will cause pollProcess to do that
 		wakeup(s); //avoid select giving error about bad FD
 		freeSockets.push_back( sock );
 	}
 }
 
 int Wireless::connect(int sock, const char* ipaddr, int port) {
-	ThreadNS::Lock l(getLock());
+	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 )
 		return -1;
@@ -739,7 +738,7 @@
 }
 
 int Wireless::listen(int sock, int port) {
-  ThreadNS::Lock l(getLock());
+  MarkScope l(getLock());
   if ( port <= 0 || port >= 65535 || sock <= 0 || sock >= WIRELESS_MAX_SOCKETS
        || sockets[sock] == NULL || sockets[sock]->state != CONNECTION_CLOSED )
 		return -1;
@@ -775,7 +774,7 @@
 	return socket(ttype, WIRELESS_DEF_RECV_SIZE, WIRELESS_DEF_SEND_SIZE);
 }
 Socket* Wireless::socket(TransportType_t ttype, int recvsize, int sendsize) {
-	ThreadNS::Lock l(getLock());
+	MarkScope l(getLock());
 	if (freeSockets.empty()
 			|| (recvsize + sendsize) <= 256) return sockets[0];
 	int sock_num=freeSockets.front();
@@ -823,7 +822,7 @@
 void
 Wireless::send(int sock)
 {
-	ThreadNS::Lock l(getLock());
+	MarkScope l(getLock());
 	if ( sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL
 	    || sockets[sock]->state != CONNECTION_CONNECTED || sockets[sock]->sendSize <= 0 )
 		return;
@@ -832,9 +831,14 @@
 	int s=sockets[sock]->endpoint;
 	int sent=::send(s,sockets[sock]->sendData+sockets[sock]->sentSize,sockets[sock]->sendSize-sockets[sock]->sentSize,0);
 	if(sent==-1) {
-		perror("Wireless::pollProcess(): send");
-		sockets[sock]->tx = false;
-		sockets[sock]->sendSize = sockets[sock]->sentSize = 0;
+		if(errno==ECONNREFUSED) {
+			close(sock);
+		} else {
+			perror("Wireless::send(): send");
+			cerr << "Wireless::send() data size was " << sockets[sock]->sendSize-sockets[sock]->sentSize << endl;
+			sockets[sock]->tx = false;
+			sockets[sock]->sendSize = sockets[sock]->sentSize = 0;
+		}
 	} else {
 		sockets[sock]->sentSize+=sent;
 		if(sockets[sock]->sentSize==sockets[sock]->sendSize) {
@@ -853,7 +857,7 @@
 void
 Wireless::blockingSend(int sock)
 {
-	ThreadNS::Lock l(getLock());
+	MarkScope l(getLock());
 	if ( sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL
 	    || sockets[sock]->state != CONNECTION_CONNECTED || sockets[sock]->sendSize <= 0 )
 		return;
@@ -894,7 +898,7 @@
 	FD_SET(interruptChk, &rfds);
 
 	fdsMax=interruptChk;
-	ThreadNS::Lock l(getLock());
+	MarkScope l(getLock());
 	//cout << "pollSetup " << usedSockets.size() << endl;
 	for(list<int>::const_iterator it=usedSockets.begin(); it!=usedSockets.end(); ++it) {
 		if(sockets[*it]==NULL) {
@@ -925,7 +929,8 @@
 }
 
 void Wireless::pollProcess() {
-	ThreadNS::Lock l(getLock());
+	MarkScope cl(getCallbackLock()); //note how this will go out of scope and release the lock if an exception occurs... sexy!
+	MarkScope l(getLock());
 	if(FD_ISSET(interruptChk,&rfds)) {
 		//wakeup sent to handle non-blocking write
 		int res=1;
@@ -961,7 +966,8 @@
 					socklen_t addrlen=sizeof(m_addr);
 					int n=accept(s,(sockaddr*)&m_addr,&addrlen);
 					if(n==-1) {
-						perror("Wireless::pollProcess(): accept");
+						if(errno!=EAGAIN) //EAGAIN indicates we were woken due to some other issue, like a previous close completing
+							perror("Wireless::pollProcess(): accept");
 						continue;
 					}
 					sockets[*it]->peer_addr=ntohl(m_addr.sin_addr.s_addr);
@@ -1013,14 +1019,14 @@
 						sockets[*it]->recvSize = 0;
 					}
 				}
-			} else 	if(sockets[*it]->state==CONNECTION_CONNECTED || sockets[*it]->state==CONNECTION_CLOSING) {
+			} else if(sockets[*it]->state==CONNECTION_CONNECTED || sockets[*it]->state==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
-						if(errno==ECONNREFUSED) {
-							cerr << "connection refused: endpoint=" << s << " sock=" << *it << " Socket=" << sockets[*it] << endl;
+						if(errno==ECONNREFUSED || errno==ECONNRESET) {
+							//cerr << "connection refused: endpoint=" << s << " sock=" << *it << " Socket=" << sockets[*it] << endl;
 							list<int>::const_iterator tmp=it;
-							//a UDP server could come in here
+							//a UDP server could come in here if the client closes down (i.e. packet is refused)
 							if(!sockets[*it]->daemon) //don't decrement if the socket is going to stay open
 								--it;
 							close(*tmp);
@@ -1106,17 +1112,27 @@
 	::write(interruptCtl,&del,sizeof(del)); 
 }
 
-ThreadNS::Lock& Wireless::getLock() {
+Resource& Wireless::getLock() {
 	static ThreadNS::Lock lock;
 	return lock;
 }
 
+void Wireless::setCallbackLock(Resource& l) {
+	MarkScope pcl(getCallbackLock()); //put a lock on previous callback until we've switched
+	callbackLock=&l;
+}
+
+void Wireless::clearCallbackLock() {
+	callbackLock=NULL;
+}
+
 #endif
 
 /*! @file
  * @brief Interacts with the system to provide networking services
  * @author alokl (Creator)
  * @author Erik Berglund and Bryan Johnson (UDP support)
+ * @author ejt simulator support
  * 
  * @verbinclude CMPack_license.txt
  *
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/Wireless/Wireless.h ./Wireless/Wireless.h
--- ../Tekkotsu_2.4.1/Wireless/Wireless.h	2005-08-07 00:11:04.000000000 -0400
+++ ./Wireless/Wireless.h	2006-09-22 12:59:26.000000000 -0400
@@ -1,6 +1,6 @@
 //-*-c++-*-
-#ifndef Wireless_h_DEFINED
-#define Wireless_h_DEFINED
+#ifndef INCLUDED_Wireless_h_
+#define INCLUDED_Wireless_h_
 
 #ifdef PLATFORM_APERIOS
 #  include <OPENR/OObject.h>
@@ -8,10 +8,9 @@
 #  include <OPENR/OObserver.h>
 #  include <ant.h>
 #else
-namespace ThreadNS {
-	class Lock;
-}
-typedef unsigned int uint32;
+#  include "IPC/Thread.h"
+#  include "Shared/Resource.h"
+typedef unsigned long uint32;
 #endif
 #include "Socket.h"
 #include "DummySocket.h"
@@ -91,6 +90,10 @@
   bool isConnected(int sock) {
     return sockets[sock]==NULL ? false : sockets[sock]->state==CONNECTION_CONNECTED;
   }
+  bool isError(int sock) {
+    return sockets[sock]==NULL ? false : sockets[sock]->state==CONNECTION_ERROR;
+  }
+
   bool isReady(int sock) { return !sockets[sock]->tx; }
   bool hasData(int sock) { return !sockets[sock]->rx; }
   //@}
@@ -143,11 +146,14 @@
   //@}
 
 #else
-	void pollSetup(); //!< on non-aperios, set up structures to be checked in pollTest() (may want to protect this with a mutex lock)
+	void pollSetup(); //!< on non-aperios, set up structures to be checked in pollTest()
 	bool pollTest(struct timeval* tv); //!< on non-aperios, check to see any network communication has occurred
-	void pollProcess(); //!< on non-aperios, process callbacks and state changes as signaled in pollTest() (may want to protect this with a mutex lock)
+	void pollProcess(); //!< on non-aperios, process callbacks and state changes as signaled in pollTest()
 	void wakeup(Socket * del=NULL); //!< writes @a del on #interruptCtl, breaking out of a pending pollTest() and thus giving an opportunity to change the contents of the FD sets being used;
-	
+
+	void setCallbackLock(Resource& l); //!< sets #callbackLock
+	void clearCallbackLock(); //!< resets #callbackLock to a self-defined lock, which you can request from getCallbackLock() (there's always a callbackLock, the only question is it internally or externally instantiated)
+	Resource& getCallbackLock() const { static ThreadNS::Lock cl; return callbackLock==NULL ? cl : *callbackLock; } //!< returns #callbackLock
 #endif
 
 protected:
@@ -160,13 +166,14 @@
   antStackRef ipstackRef;
   OID myOID;
 #else
-  static ThreadNS::Lock& getLock(); //! returns the lock to use during wireless operations
-  int interruptChk;
-  int interruptCtl;
-  fd_set rfds;
-  fd_set wfds;
-  fd_set efds;
-  int fdsMax;
+  static Resource& getLock(); //!< returns the lock to use during @e all wireless operations (not just callbacks, this is more general)
+  Resource* callbackLock; //!< this lock will be aquired during any callbacks which might occur during pollProcess()
+  int interruptChk; //!< a socket, connected to #interruptCtl, which allows pollTest() to be interrupted if new sockets need to be polled
+  int interruptCtl; //!< a socket, connected to #interruptChk, which allows pollTest() to be interrupted if new sockets need to be polled
+  fd_set rfds; //!< a set of file descriptors which should be polled for readable data; set up by pollSetup(), watched (blocking) by pollTest(), and processed by pollProcess()
+  fd_set wfds; //!< a set of file descriptors which should be polled for write-complete; set up by pollSetup(), watched (blocking) by pollTest(), and processed by pollProcess()
+  fd_set efds; //!< a set of file descriptors which should be polled for errors; set up by pollSetup(), watched (blocking) by pollTest(), and processed by pollProcess()
+  int fdsMax; //!< maximum file descriptor value in the #rfds, #wfds, #efds fd_set's
 #endif
   Socket* sockets[WIRELESS_MAX_SOCKETS];
   std::list<int> freeSockets;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/EntryPoint.cc ./aperios/EntryPoint.cc
--- ../Tekkotsu_2.4.1/aperios/EntryPoint.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./aperios/EntryPoint.cc	2006-08-22 18:23:05.000000000 -0400
@@ -0,0 +1,76 @@
+#include "EntryPoint.h"
+
+void EntryPoint::setPool(WorldStatePool* wspool) {
+	if(wspool==pool)
+		return;
+	if(pool!=NULL) {
+		for(std::list<Data*>::reverse_iterator cit=data.rbegin(); cit!=data.rend(); ++cit)
+			pool->doReleaseResource(**cit);
+	}
+	pool=wspool;
+	if(pool!=NULL) {
+		for(std::list<Data*>::iterator cit=data.begin(); cit!=data.end(); ++cit)
+			if(*cit!=NULL)
+				pool->doUseResource(**cit);
+	}
+}
+
+void EntryPoint::useResource(Data& d) {
+	data.push_back(&d);
+	if(data.size()==1 || epFrame==NULL) {
+		epFrame=ProcessID::getMapFrame();
+		if(epFrame!=NULL) { // check that setMap has been called
+#ifdef DEBUG_STACKTRACE
+			epFrame->debug=0;
+#endif
+			getCurrentStackFrame(epFrame);
+			while(unrollStackFrame(epFrame,epFrame)) {}
+		}
+	}
+	if(pool!=NULL) {
+		pool->doUseResource(*data.back());
+	}/* else if(pool==NULL)
+		cout << ProcessID::getIDStr() << " pool is NULL" << endl; */
+}
+
+void EntryPoint::releaseResource(Data& d) {
+	ASSERTRET(data.size()>0,"EntryPoint::releaseResource underflow");
+	ASSERT(data.back()==&d,"Warning: data changed between resource usage and release");
+	if(WorldStateWrite * wsw=dynamic_cast<WorldStateWrite*>(&d)) {
+		if(wsw->getComplete() && state!=NULL && state!=wsw->src && wsw->src!=NULL) {
+			/*for(unsigned int i=0; i<NumPIDJoints; i++) {
+			pids[i][0]=lastState->pids[i][0];
+			pids[i][1]=lastState->pids[i][1];
+			pids[i][2]=lastState->pids[i][2];
+			}*/
+			memcpy(state->pids,wsw->src->pids,sizeof(state->pids)); //pids is probably big enough it's better to use memcpy (?)
+			state->vel_x=wsw->src->vel_x;
+			state->vel_y=wsw->src->vel_y;
+			state->vel_a=wsw->src->vel_a;
+			state->vel_time=wsw->src->vel_time;
+		}
+	}
+	if(pool!=NULL) {
+		pool->doReleaseResource(*data.back());
+	}/* else if(pool==NULL)
+		cout << ProcessID::getIDStr() << " pool is NULL" << endl; */
+	if(data.size()==1) {
+#ifdef DEBUG_STACKTRACE
+		//if(epFrame!=NULL)
+		//memset(epFrame,0,sizeof(StackFrame));
+#endif
+		epFrame=NULL;
+	}
+	data.pop_back();
+}
+
+/*! @file
+* @brief 
+* @author Ethan Tira-Thompson (ejt) (Creator)
+*
+* $Author: ejt $
+* $Name: HEAD $
+* $Revision: 1.1 $
+* $State: Exp $
+* $Date: 2006/10/04 04:21:12 $
+*/
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/EntryPoint.h ./aperios/EntryPoint.h
--- ../Tekkotsu_2.4.1/aperios/EntryPoint.h	1969-12-31 19:00:00.000000000 -0500
+++ ./aperios/EntryPoint.h	2006-08-22 18:23:05.000000000 -0400
@@ -0,0 +1,61 @@
+//-*-c++-*-
+#ifndef INCLUDED_EntryPoint_h_
+#define INCLUDED_EntryPoint_h_
+
+#include "Shared/Resource.h"
+#include "Shared/WorldStatePool.h"
+#include "Shared/debuget.h"
+#include <list>
+#include <typeinfo>
+
+//! manages a thread lock to serialize behavior computation and mark whether ::state is being read or written
+class EntryPoint : public Resource {
+public:
+	//! pass this to MarkScope when using an EntryPoint over a section which will read ::state
+	class WorldStateRead : public WorldStatePool::ReadRequest {
+	public:
+		//! constructor, hardcoded to use global ::state and non-blocking pool access
+		WorldStateRead() : WorldStatePool::ReadRequest(state,false) {}
+	};
+	
+	//! pass this to MarkScope when using an EntryPoint over a section which will update ::state
+	class WorldStateWrite : public WorldStatePool::WriteRequest {
+	public:
+		//! constructor, hardcoded to use global ::state and blocking pool access
+		explicit WorldStateWrite(unsigned int frame_number) : WorldStatePool::WriteRequest(state,true,frame_number) {}
+	};
+	
+	//! constructor, need to specify the WorldStatePool (presumably it's in a shared memory region...)
+	explicit EntryPoint() : Resource(), pool(NULL), epFrame(NULL), data() {}
+	
+	//! sets the WorldStatePool to use
+	void setPool(WorldStatePool* wspool);
+	
+	//! an EmptyData implies a WorldStateRead should be passed on to the pool, requesting a write requires a WorldStateWrite to be passed
+	virtual void useResource(Data& d);
+	//! an EmptyData implies a WorldStateRead should be passed on to the pool, requesting a write requires a WorldStateWrite to be passed
+	virtual void releaseResource(Data& d);
+	
+protected:
+	WorldStatePool* pool; //!< pool which manages which WorldStates are being updated while old copies can still be read
+	stacktrace::StackFrame * epFrame; //!< stores root stack frame so ProcessID::getID can tell processes apart through virtual calls on shared memory regions
+	std::list<Data*> data; //!< data supplied when resource was marked used
+	
+private:
+	EntryPoint(const EntryPoint&); //!< not implemented
+	EntryPoint operator=(const EntryPoint&); //!< not implemented
+};
+
+
+/*! @file
+* @brief 
+* @author Ethan Tira-Thompson (ejt) (Creator)
+*
+* $Author: ejt $
+* $Name: HEAD $
+* $Revision: 1.1 $
+* $State: Exp $
+* $Date: 2006/10/04 04:21:12 $
+*/
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/MMCombo/MMCombo.cc ./aperios/MMCombo/MMCombo.cc
--- ../Tekkotsu_2.4.1/aperios/MMCombo/MMCombo.cc	2005-08-16 14:27:58.000000000 -0400
+++ ./aperios/MMCombo/MMCombo.cc	2006-09-19 16:10:33.000000000 -0400
@@ -1,11 +1,11 @@
 #include "MMCombo.h"
-#include "Shared/WorldState.h"
+#include "Shared/WorldStatePool.h"
 #include "Shared/Profiler.h"
 #include "Shared/debuget.h"
 #include "Shared/Config.h"
 #include "IPC/SharedObject.h"
-#include "IPC/ProcessID.h"
 #include "Events/EventRouter.h"
+#include "Events/EventTranslator.h"
 #include "Behaviors/BehaviorBase.h"
 #include "Motion/MotionManager.h"
 #include "Motion/Kinematics.h"
@@ -34,9 +34,9 @@
 using namespace std;
 
 MMCombo::MMCombo()
-	: OObject(), motmanMemRgn(NULL), worldStateMemRgn(NULL),
-		soundManagerMemRgn(NULL),
-		runLevel(0), num_open(0), etrans(NULL), isStopped(true)
+	: 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)
 {
 try {
 	for(unsigned int i=0; i<NumOutputs; i++) {
@@ -70,20 +70,27 @@
 	NEW_ALL_SUBJECT_AND_OBSERVER;
 	REGISTER_ALL_ENTRY;
 	SET_ALL_READY_AND_NOTIFY_ENTRY;
-		
+	
 	// make sure the library doesn't drop data "for" us on this reliable communication channel
-	observer[obsReceiveWorldState]->SetBufCtrlParam(0,1,1);
+	observer[obsReceiveWorldStatePool]->SetBufCtrlParam(0,1,1);
 	observer[obsReceiveMotionManager]->SetBufCtrlParam(0,1,1);
 	observer[obsReceiveSoundManager]->SetBufCtrlParam(0,1,1);
+	observer[obsReceiveProcessMap]->SetBufCtrlParam(0,1,1);
+	observer[obsEventTranslatorComm]->SetBufCtrlParam(0,1,20); //allows up to 20 messages to be sent in a burst before dropping any
 	observer[obsMotionManagerComm]->SetBufCtrlParam(0,1,MotionManager::MAX_MOTIONS+1);
+	observer[obsReceiveMotionProfiler]->SetBufCtrlParam(0,1,1);
+	observer[obsReceiveSoundProfiler]->SetBufCtrlParam(0,1,2);
 	//+1 to MAX_MOTIONS so we can get a delete message after we've filled up
 
-	cout << objectName << ": sbjRegisterWorldState==" << sbjRegisterWorldState << " selector==" << subject[sbjRegisterWorldState]->GetID().GetSelector() << '\n'
-			 << objectName << ": obsReceiveWorldState==" << obsReceiveWorldState << " selector==" << observer[obsReceiveWorldState]->GetID().GetSelector() << '\n'
+	cout << objectName << ": sbjRegisterWorldStatePool==" << sbjRegisterWorldStatePool << " selector==" << subject[sbjRegisterWorldStatePool]->GetID().GetSelector() << '\n'
+			 << objectName << ": obsReceiveWorldStatePool==" << obsReceiveWorldStatePool << " selector==" << observer[obsReceiveWorldStatePool]->GetID().GetSelector() << '\n'
 			 << objectName << ": sbjRegisterMotionManager==" << sbjRegisterMotionManager << " selector==" << subject[sbjRegisterMotionManager]->GetID().GetSelector() << '\n'
 			 << objectName << ": obsReceiveMotionManager==" << obsReceiveMotionManager << " selector==" << observer[obsReceiveMotionManager]->GetID().GetSelector() << '\n'
 			 << objectName << ": obsEventTranslatorComm==" << obsEventTranslatorComm << " selector==" << observer[obsEventTranslatorComm]->GetID().GetSelector() << '\n'
 			 << objectName << ": sbjEventTranslatorComm==" << sbjEventTranslatorComm << " selector==" << observer[sbjEventTranslatorComm]->GetID().GetSelector() << '\n'
+			 << objectName << ": obsReceiveMotionProfiler==" << obsReceiveMotionProfiler << " selector==" << observer[obsReceiveMotionProfiler]->GetID().GetSelector() << '\n'
+			 << objectName << ": obsReceiveSoundProfiler==" << obsReceiveSoundProfiler << " selector==" << observer[obsReceiveSoundProfiler]->GetID().GetSelector() << '\n'
+			 << objectName << ": sbjRegisterProfiler==" << sbjRegisterProfiler << " selector==" << observer[sbjRegisterProfiler]->GetID().GetSelector() << '\n'
 			 << objectName << ": sbjMoveJoint==" << sbjMoveJoint << " selector==" << subject[sbjMoveJoint]->GetID().GetSelector() << '\n'
 			 << objectName << ": obsSensorFrame==" << obsSensorFrame << " selector==" << observer[obsSensorFrame]->GetID().GetSelector() << '\n'
 			 << objectName << ": obsImage==" << obsImage << " selector==" << observer[obsImage]->GetID().GetSelector() << '\n'
@@ -91,14 +98,24 @@
 			 << objectName << ": sbjMotionManagerComm==" << sbjMotionManagerComm << " selector==" << subject[sbjMotionManagerComm]->GetID().GetSelector() << '\n'
 			 << objectName << ": obsMotionManagerComm==" << obsMotionManagerComm << " selector==" << observer[obsMotionManagerComm]->GetID().GetSelector() << '\n'
 			 << objectName << ": obsReceiveSoundManager==" << obsReceiveSoundManager << " selector==" << observer[obsReceiveSoundManager]->GetID().GetSelector() << '\n'
+			 << objectName << ": sbjRegisterProcessMap==" << sbjRegisterProcessMap << " selector==" << subject[sbjRegisterProcessMap]->GetID().GetSelector() << '\n'
+			 << objectName << ": obsReceiveProcessMap==" << obsReceiveProcessMap << " selector==" << observer[obsReceiveProcessMap]->GetID().GetSelector() << '\n'
 			 << objectName << ": sbjSoundManagerComm==" << sbjSoundManagerComm << " selector==" << subject[sbjSoundManagerComm]->GetID().GetSelector() << '\n'
 			 << flush;
 
-	if(strcmp(objectName,"MainObj")==0)
+	if(strcmp(objectName,"MainObj")==0) {
 		ProcessID::setID(ProcessID::MainProcess);
-	else if(strcmp(objectName,"MotoObj")==0)
-		ProcessID::setID(ProcessID::MotionProcess);
 		
+		//processMapMemRgn -> ProcessID::setMap() setup
+		processMapMemRgn = InitRegion(sizeof(stacktrace::StackFrame)*ProcessID::NumProcesses);
+		memset(processMapMemRgn->Base(),0,sizeof(stacktrace::StackFrame)*ProcessID::NumProcesses);
+		ProcessID::setMap(reinterpret_cast<stacktrace::StackFrame*>(processMapMemRgn->Base()));
+	} else if(strcmp(objectName,"MotoObj")==0)
+		ProcessID::setID(ProcessID::MotionProcess);
+
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
+	
+	
 	//Read config file
 	config=new Config("/ms/config/tekkotsu.cfg");
 
@@ -121,43 +138,51 @@
 			return oFAIL;
 		}
 		
-    //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);
-
-		//worldStateMemRgn -> state setup
-		worldStateMemRgn = InitRegion(sizeof(WorldState));
-		state=new ((WorldState*)worldStateMemRgn->Base()) WorldState;
+		//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);
+		
+		//worldStatePoolMemRgn -> state setup
+		worldStatePoolMemRgn = InitRegion(sizeof(WorldStatePool));
+		wspool=new ((WorldStatePool*)worldStatePoolMemRgn->Base()) WorldStatePool;
+		wspool->InitAccess();
+		entryPt.setPool(wspool);
+		
+		mainProfiler = new mainProfiler_t;
 
 		etrans=new NoOpEventTranslator(*erouter);
 		MotionManager::setTranslator(etrans);
 	}
 	if(strcmp(objectName,"MotoObj")==0) {
 		SetupOutputs(IsFastOutput);
-    OPENR::SetMotorPower(opowerON);
+		OPENR::SetMotorPower(opowerON);
 		OPENR::EnableJointGain(oprimitiveID_UNDEF); //oprimitiveID_UNDEF means enable all
 
-    //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);
-    wireless->setDaemon(sout);
-    wireless->setDaemon(serr);
+		//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);
+		wireless->setDaemon(sout);
+		wireless->setDaemon(serr);
 		serr->setFlushType(SocketNS::FLUSH_BLOCKING);
-    sout->setTextForward();
-    serr->setForward(sout);
+		sout->setTextForward();
+		serr->setForward(sout);
 		
 		//motmanMemRgn -> motman setup
 		motmanMemRgn = InitRegion(sizeof(MotionManager));
-		motman = new (motmanMemRgn->Base()) MotionManager();
+		motman = new (motmanMemRgn->Base()) MotionManager;
 		motman->InitAccess(subject[sbjMotionManagerComm]);
-
+		
+		//motionProfilerMemRgn -> motionProfiler setup
+		motionProfilerMemRgn = InitRegion(sizeof(motionProfiler_t));
+		motionProfiler = new (motionProfilerMemRgn->Base()) motionProfiler_t;
+		
 		etrans=new IPCEventTranslator(*subject[sbjEventTranslatorComm]);
 		MotionManager::setTranslator(etrans);
 		//MotionCommands enqueue directly, so there shouldn't be any riff-raff to catch
@@ -167,7 +192,7 @@
 				erouter->addTrapper(etrans,static_cast<EventBase::EventGeneratorID_t>(i));
 	}
 	kine = new Kinematics();
-
+	
 	cout << objectName << "::DoInit()-DONE" << endl;
 	return oSUCCESS;
 
@@ -184,6 +209,7 @@
 OStatus
 MMCombo::DoStart(const OSystemEvent&)
 {
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 try {
 	cout << objectName << "::DoStart() " << endl;
 
@@ -207,7 +233,9 @@
 	ENABLE_ALL_SUBJECT;
 	ASSERT_READY_TO_ALL_OBSERVER;
 
-	addRunLevel();
+	if(strcmp(objectName,"MainObj")==0) {
+		addRunLevel();
+	}
 	
 	cout << objectName << "::DoStart()-DONE" << endl;
 	return oSUCCESS;
@@ -225,12 +253,14 @@
 OStatus
 MMCombo::DoStop(const OSystemEvent&)
 {
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 try {
 	cout << objectName << "::DoStop()..." << endl;
 	if(strcmp(objectName,"MainObj")==0) {
 		ProjectInterface::startupBehavior().DoStop();
 		wireless->close(sout);
 		wireless->close(serr);
+		motman->RemoveAccess();
 	}
 	DISABLE_ALL_SUBJECT;
 	DEASSERT_READY_TO_ALL_OBSERVER;
@@ -251,6 +281,7 @@
 OStatus
 MMCombo::DoDestroy(const OSystemEvent&)
 {
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 try {
 	cout << objectName << "::DoDestroy()..." << endl;
 	delete etrans;
@@ -258,12 +289,32 @@
 	MotionManager::setTranslator(NULL);
 	if(strcmp(objectName,"MainObj")==0) {
 		delete erouter;
-		motmanMemRgn->RemoveReference();
+		if(motmanMemRgn!=NULL) {
+			motmanMemRgn->RemoveReference();
+			motmanMemRgn=NULL;
+		}
+		if(motionProfilerMemRgn!=NULL) {
+			motionProfilerMemRgn->RemoveReference();
+			motionProfilerMemRgn=NULL;
+		}
+		delete mainProfiler;
 	}
 	if(strcmp(objectName,"MotoObj")==0) {
-		worldStateMemRgn->RemoveReference();
+		if(worldStatePoolMemRgn!=NULL) {
+			worldStatePoolMemRgn->RemoveReference();
+			worldStatePoolMemRgn=NULL;
+			entryPt.setPool(NULL);
+		}
+		if(processMapMemRgn!=NULL) {
+			processMapMemRgn->RemoveReference();
+			processMapMemRgn=NULL;
+		}
 	}
-	soundManagerMemRgn->RemoveReference();
+	if(soundManagerMemRgn!=NULL) {
+		soundManagerMemRgn->RemoveReference();
+		soundManagerMemRgn=NULL;
+	}
+	
 	DELETE_ALL_SUBJECT_AND_OBSERVER;
 	cout << objectName << "::DoDestroy()-DONE" << endl;
 	return oSUCCESS;
@@ -282,30 +333,45 @@
  *  processing the previous message - we only want to do this the first time
  *  otherwise we infinite loop. */
 void
-MMCombo::ReadyRegisterWorldState(const OReadyEvent&){
+MMCombo::ReadyRegisterWorldStatePool(const OReadyEvent&){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	static bool is_init=true;
 	if(is_init) {
 		is_init=false;
-		cout << objectName << " Registering WorldState" << endl;
+		cout << objectName << " Registering WorldStatePool" << endl;
 		if(strcmp(objectName,"MainObj")==0) {
-			subject[sbjRegisterWorldState]->SetData(worldStateMemRgn);
-			subject[sbjRegisterWorldState]->NotifyObservers();
+			subject[sbjRegisterWorldStatePool]->SetData(worldStatePoolMemRgn);
+			subject[sbjRegisterWorldStatePool]->NotifyObservers();
 		}
 	}
 }
 
 void
-MMCombo::GotWorldState(const ONotifyEvent& event){
-	cout << objectName << "-GOTWORLDSTATE..." << flush;
-	//	PROFSECTION("GotMemRegion()",state->mainProfile);
+MMCombo::GotWorldStatePool(const ONotifyEvent& event){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
+try {
+	cout << objectName << "-GOTWORLDSTATEPOOL..." << flush;
+	//	PROFSECTION("GotMemRegion()",*mainProfiler);
 	if(strcmp(objectName,"MotoObj")==0) {
-		ASSERT(event.NumOfData()==1,"Too many WorldStates");
-		worldStateMemRgn = event.RCData(0);
-		worldStateMemRgn->AddReference();
-		state = reinterpret_cast<WorldState*>(worldStateMemRgn->Base());
+		ASSERT(event.NumOfData()==1,"Too many WorldStatePools");
+		worldStatePoolMemRgn = event.RCData(0);
+		worldStatePoolMemRgn->AddReference();
+		wspool = reinterpret_cast<WorldStatePool*>(worldStatePoolMemRgn->Base());
+		wspool->InitAccess();
+		if(ProcessID::getMapFrame()!=NULL) // must have process map first
+			entryPt.setPool(wspool);
 	}
-  observer[obsReceiveWorldState]->AssertReady();
+	observer[obsReceiveWorldStatePool]->AssertReady();
 	cout << "done" << endl;
+} catch(const std::exception& ex) {
+  observer[obsSensorFrame]->AssertReady();
+	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during GotWorldStatePool",&ex))
+		throw;
+} catch(...) {
+  observer[obsSensorFrame]->AssertReady();
+	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during GotWorldStatePool",NULL))
+		throw;
+}
 }
 
 		
@@ -314,6 +380,7 @@
  *  otherwise we infinite loop. */
 void
 MMCombo::ReadyRegisterMotionManager(const OReadyEvent&){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	static bool is_init=true;
 	if(is_init) {
 		is_init=false;
@@ -327,8 +394,9 @@
 
 void
 MMCombo::GotMotionManager(const ONotifyEvent& event){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	cout << objectName << "-GOTMOTIONMANAGER..." << flush;
-	//	PROFSECTION("GotMemRegion()",state->mainProfile);
+	//	PROFSECTION("GotMemRegion()",*mainProfiler);
 	if(strcmp(objectName,"MainObj")==0) {
 		ASSERT(event.NumOfData()==1,"Too many MotionManagers");
 		motmanMemRgn = event.RCData(0);
@@ -346,20 +414,53 @@
 
 void
 MMCombo::GotInterProcessEvent(const ONotifyEvent& event){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	EventBase* evt=NULL;
 try {
 	//cout << objectName << "-GOTInterProcessEvent " << event.NumOfData() << "..." << flush;
 	//cout << TimeET() << endl;
-	//	PROFSECTION("GotMemRegion()",state->mainProfile);
+	//	PROFSECTION("GotMemRegion()",*mainProfiler);
 	if(etrans==NULL)
 		return;
+	static unsigned int lastSensorTime=-1U;
+	static unsigned int lastSensorFrame=-1U;
 	for(int i=0; i<event.NumOfData(); i++) {
 		RCRegion * msg = event.RCData(i);
 		evt=etrans->decodeEvent(msg->Base(),msg->Size());
+		if(evt->getGeneratorID()==EventBase::sensorEGID) {
+			// sensor events are dropped if there's a backlog
+			// so if we get one of these, update the timestamp info
+			if(lastSensorTime==-1U) {
+				addRunLevel();
+				lastSensorTime=0;
+			}
+			if(state->frameNumber==lastSensorFrame) { //already saw this one
+				delete evt;
+				evt=NULL;
+			} else {
+				evt->setTimeStamp(get_time());
+				evt->setDuration(evt->getTimeStamp()-lastSensorTime);
+				lastSensorTime=evt->getTimeStamp();
+				//if(state->frameNumber-lastSensorFrame!=NumFrames && lastSensorFrame!=-1U)
+				//cout << ProcessID::getIDStr() << " dropped " << (state->frameNumber-lastSensorFrame-NumFrames)/NumFrames << " sensor frames" << endl;
+				lastSensorFrame=state->frameNumber;
+			}
+		}
 		if(evt!=NULL)
-			erouter->postEvent(evt);
+			erouter->postEvent(*evt);
+		delete evt;
 	}
-  observer[obsEventTranslatorComm]->AssertReady();
+	if(state->frameNumber>lastSensorFrame && lastSensorTime!=-1U) {
+		// 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);
+		lastSensorTime=t;
+		//if(state->frameNumber-lastSensorFrame!=NumFrames && lastSensorFrame!=-1U)
+		//cout << ProcessID::getIDStr() << " dropped " << (state->frameNumber-lastSensorFrame-NumFrames)/NumFrames << " sensor frames" << endl;
+		lastSensorFrame=state->frameNumber;
+	}
+	observer[obsEventTranslatorComm]->AssertReady();
 	//cout << "done" << endl;
 
 } catch(const std::exception& ex) {
@@ -381,7 +482,54 @@
 
 		
 void
+MMCombo::ReadyRegisterProfiler(const OReadyEvent&){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
+	static bool is_init=true;
+	if(is_init) {
+		is_init=false;
+		if(strcmp(objectName,"MotoObj")==0) {
+			cout << objectName << " Registering Motion Profiler" << endl;
+			subject[sbjRegisterProfiler]->SetData(motionProfilerMemRgn);
+			subject[sbjRegisterProfiler]->NotifyObservers();
+		}
+	}
+}
+
+void
+MMCombo::GotMotionProfiler(const ONotifyEvent& event){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
+	cout << objectName << "-GOTMOTIONPROFILER..." << flush;
+	//	PROFSECTION("GotMemRegion()",*mainProfiler);
+	if(strcmp(objectName,"MainObj")==0) {
+		ASSERT(event.NumOfData()==1,"Too many Profilers");
+		motionProfilerMemRgn = event.RCData(0);
+		motionProfilerMemRgn->AddReference();
+		motionProfiler = reinterpret_cast<motionProfiler_t*>(motionProfilerMemRgn->Base());
+		addRunLevel();
+	}
+	observer[obsReceiveMotionProfiler]->AssertReady();
+	cout << "done" << endl;
+}
+void
+MMCombo::GotSoundProfiler(const ONotifyEvent& event){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
+	cout << objectName << "-GOTSOUNDPROFILER..." << flush;
+	//	PROFSECTION("GotMemRegion()",*mainProfiler);
+	if(strcmp(objectName,"MainObj")==0) {
+		ASSERT(event.NumOfData()==1,"Too many Profilers");
+		soundProfilerMemRgn = event.RCData(0);
+		soundProfilerMemRgn->AddReference();
+		soundProfiler = reinterpret_cast<soundProfiler_t*>(soundProfilerMemRgn->Base());
+		addRunLevel();
+	}
+	observer[obsReceiveSoundProfiler]->AssertReady();
+	cout << "done" << endl;
+}
+
+
+void
 MMCombo::ReadySendJoints(const OReadyEvent& sysevent) {
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 try {
 
 	if(isStopped) {
@@ -392,15 +540,13 @@
 	static unsigned int id=-1U;
 	Profiler::Timer timer;
 	if(ProcessID::getID()==ProcessID::MotionProcess) {
-		if(state) {
-			if(id==-1U)
-				id=state->motionProfile.getNewID("ReadySendJoints()");
-			timer.setID(id,&state->motionProfile.prof);
-		}
+		if(id==-1U)
+			id=motionProfiler->getNewID("ReadySendJoints()");
+		timer.setID(id,&motionProfiler->prof);
 	}	else if(ProcessID::getID()==ProcessID::MainProcess) {
 		if(id==-1U)
-			id=state->mainProfile.getNewID("ReadySendJoints()");
-		timer.setID(id,&state->mainProfile.prof);
+			id=mainProfiler->getNewID("ReadySendJoints()");
+		timer.setID(id,&mainProfiler->prof);
 	}
 
 	if(num_open==0) //If we don't have any joints to open, leave now. (i.e. MainObj on a 220, has no ears)
@@ -551,6 +697,7 @@
 
 void
 MMCombo::GotSensorFrame(const ONotifyEvent& event){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 try {
 	erouter->processTimers();
 } catch(const std::exception& ex) {
@@ -568,38 +715,86 @@
 		return;
 	}
 
-	PROFSECTION("GotSensorFrame()",state->mainProfile);
+	static unsigned int id=-1U;
+	Profiler::Timer timer;
+	if(ProcessID::getID()==ProcessID::MotionProcess) {
+		if(id==-1U)
+			id=motionProfiler->getNewID("GotSensorFrame()");
+		timer.setID(id,&motionProfiler->prof);
+	}	else if(ProcessID::getID()==ProcessID::MainProcess) {
+		if(id==-1U)
+			id=mainProfiler->getNewID("GotSensorFrame()");
+		timer.setID(id,&mainProfiler->prof);
+	}
+	TimeET t;
 
-  OSensorFrameVectorData* rawsensor = reinterpret_cast<OSensorFrameVectorData*>(event.RCData(0)->Base());
-	state->read(rawsensor[0],erouter);
+	OSensorFrameVectorData* rawsensor = reinterpret_cast<OSensorFrameVectorData*>(event.RCData(0)->Base());
+	static unsigned int lastFrameNumber=-1U;
 	static unsigned int throwaway=1; //i thought the first few sensor updates might be flakey, but now i think not.  But a good way to delay startup.
+	bool wasLastThrowAway=false;
 	if(throwaway!=0) {
-		throwaway--;
-		if(throwaway==0) {
-			//seed the random number generator with time value and sensor noise
-			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];
-				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);
+		if(--throwaway==0)
+			wasLastThrowAway=true;
+	}
+	//cout << objectName << " got sensors " << rawsensor[0].GetInfo(0)->frameNumber << " at " << t << endl;
+	if(wspool==NULL) {
+		if(wasLastThrowAway)
+			throwaway++; //postpone until wspool comes through
+		observer[obsSensorFrame]->AssertReady();
+		//cout << "burning throwaway, left: " << throwaway << endl;
+		return;
+	}
+	WorldStatePool::UpdateInfo * info=wspool->isUnread(rawsensor[0],lastFrameNumber);
+	if(info==NULL) {
+		//cout << objectName << " done checking sensors " << rawsensor[0].GetInfo(0)->frameNumber << " at " << TimeET() << " (" << (t.Age()*1000) << "ms)" << endl;
+	} else {
+		EntryPoint::WorldStateWrite wsw(info->frameNumber); MarkScope epw(entryPt,wsw);
+		if(state==NULL) {
+			observer[obsSensorFrame]->AssertReady();
+			cout << objectName << " had error updating sensors " << info->frameNumber << endl;
+			return;
+		}
+		//cout << objectName << " writing " << wsw.frame << " state=" << state << "(" << wsw.bufUsed << ") source=" << wsw.src << "("<<wsw.srcRequest.bufUsed<<") status="<<wsw.getStatus() << " complete="<<wsw.getComplete() << endl;
+		if(!wsw.getComplete()) {
+			// could already be complete if both processes were trying to get the write lock at the same time
+			// and the first in filled everything by itself (i.e. no feedback required, or the one with feedback was there first)
+			ASSERT(info->msg==&rawsensor[0],"message changed");
+			ASSERT(wsw.bufUsed==info->intendedBuf,"read() not using expected state buffer");
+			if(erouter!=NULL)
+				state->read(rawsensor[0],wsw.src,erouter);
+			wsw.setComplete(true);
+			//cout << objectName << " fr=" << info->frameNumber << " set status="<<wsw.getStatus() << " complete=" << wsw.getComplete() << endl;
+		}	
+		//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);
 			}
-			addRunLevel();
+			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;
 	}
-  observer[obsSensorFrame]->AssertReady();
+	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);
+	}
+		
+	observer[obsSensorFrame]->AssertReady();
 	//	if(state && state->buttons[RFrPawOffset])
 	//	cout << "done" << endl;
 
@@ -616,6 +811,7 @@
 
 void
 MMCombo::GotImage(const ONotifyEvent& event){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	if(isStopped) {
 		//cout << "BAH!GotImage" << endl;
 		return;
@@ -631,14 +827,14 @@
 		throw;
 }
 try {
-	PROFSECTION("GotImage()",state->mainProfile);
+	PROFSECTION("GotImage()",*mainProfiler);
   
 	WMvari(int, frame_counter, 0);
 	++frame_counter;
 	
-	erouter->postEvent(new DataEvent<const OFbkImageVectorData*>(reinterpret_cast<const OFbkImageVectorData*>(event.Data(0)),EventBase::visOFbkEGID,0,EventBase::activateETID));
-	erouter->postEvent(new DataEvent<const OFbkImageVectorData*>(reinterpret_cast<const OFbkImageVectorData*>(event.Data(0)),EventBase::visOFbkEGID,0,EventBase::statusETID));
-	erouter->postEvent(new DataEvent<const OFbkImageVectorData*>(reinterpret_cast<const OFbkImageVectorData*>(event.Data(0)),EventBase::visOFbkEGID,0,EventBase::deactivateETID));
+	erouter->postEvent(DataEvent<const OFbkImageVectorData*>(reinterpret_cast<const OFbkImageVectorData*>(event.Data(0)),EventBase::visOFbkEGID,0,EventBase::activateETID));
+	erouter->postEvent(DataEvent<const OFbkImageVectorData*>(reinterpret_cast<const OFbkImageVectorData*>(event.Data(0)),EventBase::visOFbkEGID,0,EventBase::statusETID));
+	erouter->postEvent(DataEvent<const OFbkImageVectorData*>(reinterpret_cast<const OFbkImageVectorData*>(event.Data(0)),EventBase::visOFbkEGID,0,EventBase::deactivateETID));
 	
   observer[obsImage]->AssertReady();
 
@@ -664,16 +860,17 @@
 
 void
 MMCombo::GotAudio(const ONotifyEvent& event){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 try {
 	if(isStopped) {
 		//cout << "BAH!GotAudio" << endl;
 		return;
 	}
 
-	PROFSECTION("GotAudio()",state->mainProfile);
+	PROFSECTION("GotAudio()",*mainProfiler);
 
 	for (int i = 0; i < event.NumOfData(); i++) {
-		erouter->postEvent(new DataEvent<const OSoundVectorData*>(reinterpret_cast<const OSoundVectorData*>(event.Data(i)),EventBase::micOSndEGID,0,EventBase::statusETID));
+		erouter->postEvent(DataEvent<const OSoundVectorData*>(reinterpret_cast<const OSoundVectorData*>(event.Data(i)),EventBase::micOSndEGID,0,EventBase::statusETID));
 		try {
 			erouter->processTimers();
 		} catch(const std::exception& ex) {
@@ -700,6 +897,7 @@
 
 void
 MMCombo::GotPowerEvent(void * msg){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	if(isStopped) {
 		//cout << "BAH!GotPowerEvent" << endl;
 		return;
@@ -716,7 +914,7 @@
 try {
 
 	//	cout << "POWER..."<<flush;
-	PROFSECTION("PowerEvent()",state->mainProfile);
+	PROFSECTION("PowerEvent()",*mainProfiler);
 
 	static bool first=true;
 	if(first) {
@@ -747,6 +945,7 @@
 
 void
 MMCombo::GotMotionMsg(const ONotifyEvent& event){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	if(isStopped) {
 		//cout << "BAH!GotMotionMsg" << endl;
 		return;
@@ -763,16 +962,61 @@
 
 void
 MMCombo::GotSoundManager(const ONotifyEvent& event) {
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	cout << objectName << "-GOTSOUNDMANAGER..." << flush;
-	//	PROFSECTION("GotMemRegion()",state->mainProfile);
+	//	PROFSECTION("GotMemRegion()",*mainProfiler);
 	ASSERT(event.NumOfData()==1,"Too many SoundManagers");
 	soundManagerMemRgn = event.RCData(0);
 	soundManagerMemRgn->AddReference();
 	sndman = reinterpret_cast<SoundManager*>(soundManagerMemRgn->Base());
-  observer[obsReceiveSoundManager]->AssertReady();
+	observer[obsReceiveSoundManager]->AssertReady();
 	sndman->InitAccess(subject[sbjSoundManagerComm]);
-	addRunLevel();
+	if(strcmp(objectName,"MainObj")==0) {
+		addRunLevel();
+	}
+	cout << "done" << endl;
+}
+
+void
+MMCombo::ReadyRegisterProcessMap(const OReadyEvent&){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
+	static bool is_init=true;
+	if(is_init) {
+		is_init=false;
+		cout << objectName << " Registering Process Map" << endl;
+		if(strcmp(objectName,"MainObj")==0) {
+			subject[sbjRegisterProcessMap]->SetData(processMapMemRgn);
+			subject[sbjRegisterProcessMap]->NotifyObservers();
+		}
+	}
+}
+
+void
+MMCombo::GotProcessMap(const ONotifyEvent& event){
+try {
+	cout << objectName << "-GOTPROCESSMAP..." << flush;
+	//	PROFSECTION("GotMemRegion()",*mainProfiler);
+	if(strcmp(objectName,"MotoObj")==0) {
+		ASSERT(event.NumOfData()==1,"Too many ProcessMaps");
+		processMapMemRgn = event.RCData(0);
+		processMapMemRgn->AddReference();
+		ProcessID::setMap(reinterpret_cast<stacktrace::StackFrame*>(processMapMemRgn->Base()));
+		//doesn't handle setting map within entry point, have to do that part first
+		EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
+		if(wspool!=NULL) // if we were waiting on initializing the pool, do so now
+			entryPt.setPool(wspool);
+	}
+	observer[obsReceiveProcessMap]->AssertReady();
 	cout << "done" << endl;
+} catch(const std::exception& ex) {
+  observer[obsSensorFrame]->AssertReady();
+	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during GotProcessMap",&ex))
+		throw;
+} catch(...) {
+  observer[obsSensorFrame]->AssertReady();
+	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during GotProcessMap",NULL))
+		throw;
+}
 }
 
 void
@@ -894,7 +1138,8 @@
 MMCombo::InitRegion(unsigned int size) {
 	unsigned int pagesize=4096;
 	sError err=GetPageSize(&pagesize);
-	ASSERT(err==sSUCCESS,"Error "<<err<<" getting page size");
+	if(err!=sSUCCESS)
+		cerr << "Error "<<err<<" getting page size " << pagesize << endl;
 	unsigned int pages=(size+pagesize-1)/pagesize;
 	return new RCRegion(pages*pagesize);
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/MMCombo/MMCombo.h ./aperios/MMCombo/MMCombo.h
--- ../Tekkotsu_2.4.1/aperios/MMCombo/MMCombo.h	2005-06-29 18:06:33.000000000 -0400
+++ ./aperios/MMCombo/MMCombo.h	2006-08-22 18:23:06.000000000 -0400
@@ -3,15 +3,20 @@
 #define INCLUDED_MMCombo_h_
 
 #include "Shared/debuget.h"
+#include "Shared/MarkScope.h"
 #include "Shared/RobotInfo.h"
 #include "Wireless/Wireless.h"
-#include "Events/EventTranslator.h"
+#include "IPC/ProcessID.h"
+#include "aperios/EntryPoint.h"
 
 #include <OPENR/OObject.h>
 #include <OPENR/OSubject.h>
 #include <OPENR/OObserver.h>
 #include "aperios/MMCombo/def.h"
 
+class EventTranslator;
+class WorldStatePool;
+
 //! Contains code for both MainObj and MotoObj processes
 /*! Why go to all this trouble?  Virtual functions and polymorphism!  Instead
  *  of writing my own object typing and serialization system, I would rather
@@ -40,11 +45,14 @@
 	virtual OStatus DoStop   (const OSystemEvent&);      //!< next to last call, stop sending and receiving messages
 	virtual OStatus DoDestroy(const OSystemEvent&);      //!< last call (before destructor), clean up memory here
 	
-	void ReadyRegisterWorldState(const OReadyEvent&);    //!< main only, send out the state global
-	void GotWorldState(const ONotifyEvent& event);       //!< motion only, called when state global is received
+	void ReadyRegisterWorldStatePool(const OReadyEvent&);    //!< main only, send out the state global
+	void GotWorldStatePool(const ONotifyEvent& event);       //!< motion only, called when state global is received
 	void ReadyRegisterMotionManager(const OReadyEvent&); //!< motion only, send out motman global
 	void GotMotionManager(const ONotifyEvent& event);    //!< main only, called when motman global is received
 	void GotInterProcessEvent(const ONotifyEvent& event);//!< main only, called when another process sends an event
+	void ReadyRegisterProfiler(const OReadyEvent&); //!< motion only, send out motion's profiler
+	void GotMotionProfiler(const ONotifyEvent& event);    //!< main only, called when Motion's profiler is received
+	void GotSoundProfiler(const ONotifyEvent& event);    //!< main only, called when SoundPlay's profiler is received
 	
 	void ReadySendJoints(const OReadyEvent& event);      //!< motion only (until main does ears again, then both) calls SendJoints, if DoStart has already been called
 	void GotSensorFrame(const ONotifyEvent& event);      //!< main only, called when new sensor information is available
@@ -56,12 +64,15 @@
 	
 	void GotSoundManager(const ONotifyEvent& event);     //!< both, called when the sndman global is received
 
-	void ListenCont (void* msg) { wireless->ListenCont(msg); }  //!< main only, called when //ALTODO
-	void BindCont   (void* msg) { wireless->BindCont(msg); }    //!< main only, called when //ALTODO
-	void ConnectCont(void* msg) { wireless->ConnectCont(msg); } //!< main only, called when //ALTODO
-	void SendCont   (void* msg) { wireless->SendCont(msg); }    //!< main only, called when //ALTODO
-	void ReceiveCont(void* msg) { wireless->ReceiveCont(msg); } //!< main only, called when //ALTODO
-	void CloseCont  (void* msg) { wireless->CloseCont(msg); }   //!< main only, called when //ALTODO
+	void ReadyRegisterProcessMap(const OReadyEvent&);    //!< main only, send out the process map
+	void GotProcessMap(const ONotifyEvent& event);       //!< motion only, called when process map is received	
+	
+	void ListenCont (void* msg) { EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr); wireless->ListenCont(msg); }  //!< main only, called when //ALTODO
+	void BindCont   (void* msg) { EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr); wireless->BindCont(msg); }    //!< main only, called when //ALTODO
+	void ConnectCont(void* msg) { EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr); wireless->ConnectCont(msg); } //!< main only, called when //ALTODO
+	void SendCont   (void* msg) { EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr); wireless->SendCont(msg); }    //!< main only, called when //ALTODO
+	void ReceiveCont(void* msg) { EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr); wireless->ReceiveCont(msg); } //!< main only, called when //ALTODO
+	void CloseCont  (void* msg) { EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr); wireless->CloseCont(msg); }   //!< main only, called when //ALTODO
 
 protected:
 	void OpenPrimitives();                               //!< both, called from SetupOutputs() (mostly for motion, but main does ears), uses #open to tell which to open
@@ -69,8 +80,11 @@
 	RCRegion* InitRegion(unsigned int size);             //!< both, called to set up a shared memory region of a given size
 
 	RCRegion * motmanMemRgn;     //!< Motion creates, Main receives
-	RCRegion * worldStateMemRgn; //!< Main creates, Motion receives
+	RCRegion * motionProfilerMemRgn; //!< Motion creates, Main receives
+	RCRegion * soundProfilerMemRgn; //!< Sound creates, Main receives
+	RCRegion * worldStatePoolMemRgn; //!< Main creates, Motion receives
 	RCRegion * soundManagerMemRgn; //!< SoundPlay creates, Main & Motion receives
+	RCRegion * processMapMemRgn; //!< Main creates, Motion receives
 
 	OPrimitiveID primIDs[NumOutputs];    //!< both, Main ears only, Motion the rest
 	static const unsigned int NUM_COMMAND_VECTOR=2; //!< both, for double buffering
@@ -79,13 +93,16 @@
 	float  ledActivation[NumLEDs]; //!< Motion, used for partial LED activation
 
 	unsigned int runLevel;           //!< Main, incremented until all sections are ready
-	static const unsigned int readyLevel=5; //!< Main, runLevel at which StartBehavior is created. (1st power event, 1st sensor event, motman init, sndman init, MainObj::DoStart())
+	static const unsigned int readyLevel=7; //!< Main, runLevel at which StartBehavior is created. (1st power event, 1st sensor event, motman init, motion profiler, sndman init, MainObj::DoStart())
 	void addRunLevel();              //!< Main, checks runLevel and creates StartBehavior when ready
 
 	bool open[NumOutputs];    //!< both, holds information regarding which outputs are open in ("controlled by") this process
 	unsigned int num_open;  //!< both, count of how many are open
 
 	EventTranslator * etrans; //!< both, allows events to be sent between processes (from other processes besides these two too)
+	
+	WorldStatePool * wspool; //!< WorldStatePool allows efficient updating of sensor data, avoids sensor deprivation of other processes if Main process blocks
+	EntryPoint entryPt; //!< should be used with MarkScope to wrap each entry point from the system, handles marking root stack frame and getting current WorldState
 
 	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
 
@@ -118,7 +135,6 @@
 	}
 
 private:
-//	WorldStateSerializer* wstateserializer;
 	MMCombo(const MMCombo&); //!< should never be called...
 	MMCombo& operator=(const MMCombo&); //!< should never be called...
 };
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/MMCombo/stub.cfg ./aperios/MMCombo/stub.cfg
--- ../Tekkotsu_2.4.1/aperios/MMCombo/stub.cfg	2005-06-29 18:06:33.000000000 -0400
+++ ./aperios/MMCombo/stub.cfg	2006-08-22 18:23:06.000000000 -0400
@@ -1,12 +1,15 @@
 ObjectName : MMCombo
-NumOfSubject   : 6
-NumOfObserver  : 8
-Service : "MMCombo.RegisterWorldState.WorldState.S"          , null, ReadyRegisterWorldState()
-Service : "MMCombo.ReceiveWorldState.WorldState.O"           , null, GotWorldState()
+NumOfSubject   : 8
+NumOfObserver  : 11
+Service : "MMCombo.RegisterWorldStatePool.WorldStatePool.S"          , null, ReadyRegisterWorldStatePool()
+Service : "MMCombo.ReceiveWorldStatePool.WorldStatePool.O"           , null, GotWorldStatePool()
 Service : "MMCombo.RegisterMotionManager.MotionManager.S"    , null, ReadyRegisterMotionManager()
 Service : "MMCombo.ReceiveMotionManager.MotionManager.O"     , null, GotMotionManager()
 Service : "MMCombo.EventTranslatorComm.EventBase.S"          , null, null
 Service : "MMCombo.EventTranslatorComm.EventBase.O"          , null, GotInterProcessEvent()
+Service : "MMCombo.RegisterProfiler.Profiler.S"    , null, ReadyRegisterProfiler()
+Service : "MMCombo.ReceiveMotionProfiler.Profiler.O"     , null, GotMotionProfiler()
+Service : "MMCombo.ReceiveSoundProfiler.Profiler.O"     , null, GotSoundProfiler()
 Service : "MMCombo.MoveJoint.OCommandVectorData.S"           , null, ReadySendJoints()
 Service : "MMCombo.SensorFrame.OSensorFrameVectorData.O"     , null, GotSensorFrame()
 Service : "MMCombo.Image.OFbkImageVectorData.O"              , null, GotImage()
@@ -15,6 +18,8 @@
 Service : "MMCombo.MotionManagerComm.MotionManagerMsg.O"     , null, GotMotionMsg()
 Service : "MMCombo.ReceiveSoundManager.SoundManager.O"       , null, GotSoundManager()
 Service : "MMCombo.SoundManagerComm.SoundManagerMsg.S"       , null, null
+Service : "MMCombo.RegisterProcessMap.StackFrames.S"          , null, ReadyRegisterProcessMap()
+Service : "MMCombo.ReceiveProcessMap.StackFrames.O"           , null, GotProcessMap()
 
 Extra : GotPowerEvent()
 Extra : ListenCont()
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/Makefile.aperios ./aperios/Makefile.aperios
--- ../Tekkotsu_2.4.1/aperios/Makefile.aperios	2005-06-01 01:47:59.000000000 -0400
+++ ./aperios/Makefile.aperios	2006-08-22 18:23:05.000000000 -0400
@@ -20,25 +21,31 @@
 		echo >> $@ ; \
 	done;
 
+$(TK_BD)/%Stub.d : $(TK_BD)/aperios/aperios.d
+
+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
 #not a big loss, just turn it off for these files
-$(TK_BD)/aperios/MMCombo/MMCombo.o $(TK_BD)/aperios/MMCombo/MMComboStub.o: %.o:
+$(TK_BD)/aperios/MMCombo/MMCombo.o $(TK_BD)/aperios/MMCombo/MMComboStub.o $(TK_BD)/aperios/SndPlay/SndPlayStub.o $(TK_BD)/aperios/TinyFTPD/TinyFTPDStub.o: %.o: | $(TOOLS_BUILT_FLAG)
 	@mkdir -p $(dir $@)
 	@src=$(patsubst %.o,%$(SRCSUFFIX),$(patsubst $(TK_BD)/%,%,$@)); \
-	echo "Compiling $$src... (no -O2)"; \
-	$(CXX) $(filter-out -O2,$(CXXFLAGS)) -o $@ -c $$src > $*.log 2>&1; \
+	echo "Compiling $$src... (no -O*)"; \
+	$(CXX) $(filter-out -O%,$(CXXFLAGS)) -o $@ -c $$src > $*.log 2>&1; \
 	retval=$$?; \
 	cat $*.log | $(FILTERSYSWARN) | $(COLORFILT) | $(TEKKOTSU_LOGVIEW); \
 	test $$retval -eq 0; \
 
-$(TK_BD)/aperios/TinyFTPD/%.o:
+$(TK_BD)/aperios/TinyFTPD/%.o: | $(TOOLS_BUILT_FLAG)
 	@mkdir -p $(dir $@)
 	@src=$(patsubst %.o,%$(SRCSUFFIX),$(patsubst $(TK_BD)/%,%,$@)); \
-	echo "Compiling $$src... (filter-out -Weffc++ -DOPENR_DEBUG)"; \
+	echo "Compiling $$src... (no -Weffc++, -DOPENR_DEBUG)"; \
 	$(CXX) $(filter-out -Weffc++ -DOPENR_DEBUG,$(CXXFLAGS)) -o $@ -c $$src > $(TK_BD)/aperios/TinyFTPD/$*.log 2>&1; \
 	retval=$$?; \
 	cat $(TK_BD)/aperios/TinyFTPD/$*.log | $(FILTERSYSWARN) | $(COLORFILT) | $(TEKKOTSU_LOGVIEW); \
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/SndPlay/SndPlay.cc ./aperios/SndPlay/SndPlay.cc
--- ../Tekkotsu_2.4.1/aperios/SndPlay/SndPlay.cc	2005-06-29 18:06:37.000000000 -0400
+++ ./aperios/SndPlay/SndPlay.cc	2006-09-18 14:08:02.000000000 -0400
@@ -23,9 +23,11 @@
 #include "Shared/Config.h"
 #include "Shared/debuget.h"
 #include "Events/EventRouter.h"
+#include "Shared/Profiler.h"
+#include "Shared/MarkScope.h"
 
 SndPlay::SndPlay()
-	: active(0), soundManagerMemRgn(NULL), etrans(NULL), speakerID(oprimitiveID_UNDEF)
+	: active(0), soundManagerMemRgn(NULL), processMapMemRgn(NULL), soundProfilerMemRgn(NULL), etrans(NULL), entryPt(), speakerID(oprimitiveID_UNDEF)
 {
 	for (unsigned int i = 0; i < SOUND_NUM_BUFFER; i++)
 		region[i] = 0;
@@ -43,6 +45,7 @@
 	REGISTER_ALL_ENTRY;
 	SET_ALL_READY_AND_NOTIFY_ENTRY;
 
+	observer[obsReceiveProcessMap]->SetBufCtrlParam(0,1,1);
 	observer[obsSoundManagerComm]->SetBufCtrlParam(0,1,SoundManager::MAX_SND+1);
 	//+1 to MAX_SND so that we can still get a delete message after we've filled up
 
@@ -54,14 +57,23 @@
 
 	erouter = new EventRouter;
 	etrans=new IPCEventTranslator(*subject[sbjEventTranslatorComm]);
+	// only expect to be handling audioEGID, but just in case,
+	// subscribe to everything except erouterEGID
+	for(unsigned int i=0; i<EventBase::numEGIDs; i++)
+		if(i!=EventBase::erouterEGID)
+			erouter->addTrapper(etrans,static_cast<EventBase::EventGeneratorID_t>(i));
 
 	//soundManagerMemRgn -> sndman setup
 	soundManagerMemRgn = InitRegion(sizeof(SoundManager));
-	sndman=new ((SoundManager*)soundManagerMemRgn->Base()) SoundManager;
+	sndman=new (soundManagerMemRgn->Base()) SoundManager;
 	sndman->InitAccess(subject[sbjSoundManagerComm]);
 	for(unsigned int i=0; i<config->sound.preload.size(); i++)
-		sndman->LoadFile(config->sound.preload[i]);
-
+		sndman->loadFile(config->sound.preload[i]);
+	
+	//soundProfilerMemRgn -> soundProfiler setup
+	soundProfilerMemRgn = InitRegion(sizeof(soundProfiler_t));
+	soundProfiler=new (soundProfilerMemRgn->Base()) soundProfiler_t;
+	
 	OpenSpeaker();
 	NewSoundVectorData();
 	SetPowerAndVolume();
@@ -71,6 +83,7 @@
 OStatus
 SndPlay::DoStart(const OSystemEvent&)
 {
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
   //OSYSDEBUG(("SndPlay::DoStart()\n"));
 
 	ENABLE_ALL_SUBJECT;
@@ -81,9 +94,10 @@
 OStatus
 SndPlay::DoStop(const OSystemEvent&)
 {
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	//OSYSDEBUG(("SndPlay::DoStop()\n"));
 
-	sndman->StopPlay();
+	sndman->stopPlay();
 
 	DISABLE_ALL_SUBJECT;
 	DEASSERT_READY_TO_ALL_OBSERVER;
@@ -94,11 +108,16 @@
 OStatus
 SndPlay::DoDestroy(const OSystemEvent&)
 {
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	for(unsigned int i=0; i<config->sound.preload.size(); i++)
-		sndman->ReleaseFile(config->sound.preload[i]);
+		sndman->releaseFile(config->sound.preload[i]);
 	delete etrans;
 	etrans=NULL;
 	delete erouter;
+	if(processMapMemRgn!=NULL) {
+		processMapMemRgn->RemoveReference();
+		processMapMemRgn=NULL;
+	}
 	DELETE_ALL_SUBJECT_AND_OBSERVER;
 	return oSUCCESS;
 }
@@ -106,12 +125,14 @@
 void
 SndPlay::ReadySendSound(const OReadyEvent&)
 {
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	//	OSYSDEBUG(("SndPlay::Ready()\n"));
 	doSendSound();
 }
 
 void
 SndPlay::ReadyRegisterSoundManager(const OReadyEvent&) {
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	static bool is_init=true;
 	if(is_init) {
 		is_init=false;
@@ -122,10 +143,23 @@
 }
 
 void
+SndPlay::ReadyRegisterProfiler(const OReadyEvent&) {
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
+	static bool is_init=true;
+	if(is_init) {
+		is_init=false;
+		cout << objectName << " Registering soundProfiler" << endl;
+		subject[sbjRegisterProfiler]->SetData(soundProfilerMemRgn);
+		subject[sbjRegisterProfiler]->NotifyObservers();
+	}
+}
+
+void
 SndPlay::GotSoundMsg(const ONotifyEvent& event) {
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
 	//	OSYSDEBUG(("SndPlay::GotSoundMsg()\n"));
 	sndman->ReceivedMsg(event);
-	unsigned int curact=sndman->GetNumPlaying();
+	unsigned int curact=sndman->getNumPlaying();
 	//	std::cout << "got-active=" << active << " cur=" << curact << std::endl;
 	if(active==0 && curact>0) {
 		active=curact;
@@ -135,11 +169,25 @@
 }
 
 void
+SndPlay::GotProcessMap(const ONotifyEvent& event){
+	EntryPoint::WorldStateRead wsr; MarkScope ep(entryPt,wsr);
+	//cout << objectName << "-GOTPROCESSMAP..." << flush;
+	//	PROFSECTION("GotMemRegion()",soundProfiler);
+	ASSERT(event.NumOfData()==1,"Too many ProcessMaps");
+	processMapMemRgn = event.RCData(0);
+	processMapMemRgn->AddReference();
+	ProcessID::setMap(reinterpret_cast<stacktrace::StackFrame*>(processMapMemRgn->Base()));
+	observer[obsReceiveProcessMap]->AssertReady();
+	//cout << "done" << endl;
+}
+
+void
 SndPlay::doSendSound() {
+	PROFSECTION("doSendSound()",*soundProfiler);
 	//	std::cout << "do-active=" << active << std::endl;
 	static unsigned int bufInUse=0;
 
-	active=sndman->GetNumPlaying();
+	active=sndman->getNumPlaying();
 	if(active==0) { //if we don't have any active channels, don't send a buffer
 		if(bufInUse>0)
 			bufInUse--;
@@ -229,7 +277,8 @@
 SndPlay::InitRegion(unsigned int size) {
 	unsigned int pagesize=4096;
 	sError err=GetPageSize(&pagesize);
-	ASSERT(err==sSUCCESS,"Error "<<err<<" getting page size");
+	if(err!=sSUCCESS)
+		std::cerr << "Error "<<err<<" getting page size " << pagesize << std::endl;
 	unsigned int pages=(size+pagesize-1)/pagesize;
 	return new RCRegion(pages*pagesize);
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/SndPlay/SndPlay.h ./aperios/SndPlay/SndPlay.h
--- ../Tekkotsu_2.4.1/aperios/SndPlay/SndPlay.h	2005-06-29 18:06:37.000000000 -0400
+++ ./aperios/SndPlay/SndPlay.h	2006-08-22 18:23:06.000000000 -0400
@@ -1,10 +1,11 @@
 #ifndef INCLUDED_SndPlay_h_
 #define INCLUDED_SndPlay_h_
 
+#include "aperios/EntryPoint.h"
 #include <OPENR/OObject.h>
 #include <OPENR/OSubject.h>
 #include <OPENR/OObserver.h>
-#include "aperios/MMCombo/def.h"
+#include "aperios/SndPlay/def.h"
 
 #include "Events/EventTranslator.h"
 
@@ -37,8 +38,10 @@
 
 	void ReadySendSound(const OReadyEvent& event);            //!< called by system when it's ready for another sound buffer
 	void ReadyRegisterSoundManager(const OReadyEvent& event); //!< called by system when observers are ready to receive the SoundManager
+	void ReadyRegisterProfiler(const OReadyEvent&); //!< send out sound's profiler
 
 	void GotSoundMsg(const ONotifyEvent& event); //!< called by system when SoundManager has sent itself a message on a different process (either to add or remove sounds from memory)
+	void GotProcessMap(const ONotifyEvent& event); //!< called when process map is received from Main
 
 	OSubject*  subject[numOfSubject];   //!< array of subject IDs, used to identify outgoing data
 	OObserver* observer[numOfObserver]; //!< array of observer IDs, used to identify what's ready
@@ -56,7 +59,11 @@
 	unsigned int active; //!< number of active sound channels - if it's 0, we'll purposely starve system of sound buffers
 
 	RCRegion*      soundManagerMemRgn; //!< SndPlay creates, Main & Motion receive - Shared region used by SoundManager
+	RCRegion*      processMapMemRgn; //!< Main creates, SndPlay receives
+	RCRegion*      soundProfilerMemRgn; //!< Sound creates, Main receives
+	
 	EventTranslator * etrans; //!< will be given all events created by SoundManager to be forwarded to Main
+	EntryPoint entryPt; //!< should be used with MarkScope to wrap each entry point from the system, handles marking root stack frame
 
 	OPrimitiveID   speakerID;  //!< ID returned to system after opening SPEAKER_LOCATOR
 	RCRegion*      region[SOUND_NUM_BUFFER]; //!< holds references to shared regions holding sound clips
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/SndPlay/stub.cfg ./aperios/SndPlay/stub.cfg
--- ../Tekkotsu_2.4.1/aperios/SndPlay/stub.cfg	2005-06-29 18:06:37.000000000 -0400
+++ ./aperios/SndPlay/stub.cfg	2006-07-13 13:25:50.000000000 -0400
@@ -1,8 +1,10 @@
 ObjectName : SndPlay
-NumOfOSubject   : 4
-NumOfOObserver  : 1
+NumOfOSubject   : 5
+NumOfOObserver  : 2
 Service : "SndPlay.Speaker.OSoundVectorData.S", null, ReadySendSound()
 Service : "SndPlay.RegisterSoundManager.SoundManager.S", null, ReadyRegisterSoundManager()
 Service : "SndPlay.SoundManagerComm.SoundManagerMsg.O", null, GotSoundMsg()
 Service : "SndPlay.SoundManagerComm.SoundManagerMsg.S", null, null
 Service : "SndPlay.EventTranslatorComm.EventBase.S" , null, null
+Service : "SndPlay.ReceiveProcessMap.StackFrames.O"           , null, GotProcessMap()
+Service : "SndPlay.RegisterProfiler.Profiler.S"    , null, ReadyRegisterProfiler()
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/TinyFTPD/FtpMethod.cc ./aperios/TinyFTPD/FtpMethod.cc
--- ../Tekkotsu_2.4.1/aperios/TinyFTPD/FtpMethod.cc	2005-06-01 01:47:59.000000000 -0400
+++ ./aperios/TinyFTPD/FtpMethod.cc	2005-10-25 17:37:56.000000000 -0400
@@ -17,6 +17,7 @@
 #include <stdlib.h>
 #include "FtpDTP.h"
 #include <stdio.h>
+#include <errno.h>
 
 Port 
 FtpDTP::SetIP(IPAddress ip)
@@ -313,7 +314,7 @@
         stat(tmp, &statbuf); //CHANGE_ET unused variable 'ret'
         if (listLong) {
             sprintf((char *)connection.sendData,
-                    "%c%c%c%c%c%c%c%c%c%c %x %s %s %-d %s %d %d %s\r\n",
+                    "%c%c%c%c%c%c%c%c%c%c %x %s %s %-lu %s %d %d %s\r\n",
                     (statbuf.st_mode & S_IFMT) == S_IFDIR ? 'd' : '-',
                     (statbuf.st_mode & S_IRUSR) ? 'r' : '-',
                     (statbuf.st_mode & S_IWUSR) ? 'w' : '-',
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/TinyFTPD/TCPConnection.h ./aperios/TinyFTPD/TCPConnection.h
--- ../Tekkotsu_2.4.1/aperios/TinyFTPD/TCPConnection.h	2005-06-01 01:47:59.000000000 -0400
+++ ./aperios/TinyFTPD/TCPConnection.h	2006-03-24 12:13:39.000000000 -0500
@@ -12,7 +12,7 @@
 #ifndef TCPConnection_h_DEFINED
 #define TCPConnection_h_DEFINED
 
-#include <ant.h>
+#include <MCOOP/ant.h>
 
 enum ConnectionState {
     CONNECTION_CLOSED,
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/TinyFTPD/TinyFTPD.cc ./aperios/TinyFTPD/TinyFTPD.cc
--- ../Tekkotsu_2.4.1/aperios/TinyFTPD/TinyFTPD.cc	2005-06-01 01:47:59.000000000 -0400
+++ ./aperios/TinyFTPD/TinyFTPD.cc	2006-05-09 13:27:28.000000000 -0400
@@ -15,7 +15,7 @@
 #include <TCPEndpointMsg.h>
 #include "TinyFTPD.h"
 
-TinyFTPD::TinyFTPD() : passwd()
+TinyFTPD::TinyFTPD() : OObject(), ipstackRef(), passwd()
 {
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/aperios/include/jmorecfg.h ./aperios/include/jmorecfg.h
--- ../Tekkotsu_2.4.1/aperios/include/jmorecfg.h	2005-06-01 01:48:00.000000000 -0400
+++ ./aperios/include/jmorecfg.h	2005-11-11 16:07:48.000000000 -0500
@@ -227,10 +227,10 @@
 typedef int boolean;
 #endif
 #ifndef FALSE			/* in case these macros already exist */
-#define FALSE	0		/* values of boolean */
+#define FALSE	false		/* values of boolean */
 #endif
 #ifndef TRUE
-#define TRUE	1
+#define TRUE	true
 #endif
 
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/common.h ./common.h
--- ../Tekkotsu_2.4.1/common.h	2005-07-01 15:45:42.000000000 -0400
+++ ./common.h	2006-09-21 19:02:30.000000000 -0400
@@ -1,47 +1,53 @@
 /* This is a file lists the most depended-upon header files used by
- * the project.  It is automatically generated by tools/genCommonHeader.
+ * the project.  It is automatically generated by:
+ *   tools/genCommonHeader -t .35 -p \(Shared/newmat\|Motion/roboop\)/.*
  * When compiling for PLATFORM_LOCAL, this header will be precompiled. 
- * It was created at Sat Mar 12 13:19:45 EST 2005 and checked into 
- * CVS at $Date: 2006/10/04 04:21:12 $ */
+ * It was created at Thu Sep 21 18:50:36 EDT 2006 and checked into 
+ * CVS at $Date: 2006/10/04 04:21:12 $ */
 
 #ifdef __cplusplus //lets us blindly apply to C files as well
 
 #ifdef PLATFORM_LOCAL
 #ifdef TGT_ERS210
-#include "Shared/get_time.h" //75
-#include "Shared/LoadSave.h" //75
-#include "Events/EventBase.h" //74
-#include "Shared/ReferenceCounter.h" //64
-#include "Events/EventTrapper.h" //64
-#include "Shared/CommonInfo.h" //59
-#include "Shared/RobotInfo.h" //58
-#include "Shared/ERS210Info.h" //58
-#include "Shared/debuget.h" //56
-#include "Events/EventListener.h" //56
-#include "IPC/SemaphoreManager.h" //54
-#include "IPC/ProcessID.h" //54
-#include "IPC/ListMemBuf.h" //54
-#include "IPC/MutexLock.h" //53
-#include "Wireless/Socket.h" //52
-#include "Events/EventRouter.h" //52
-#include "IPC/LockScope.h" //48
-#include "IPC/RCRegion.h" //47
-#include "IPC/MessageQueue.h" //45
-#include "Motion/OutputCmd.h" //43
-#include "Events/EventTranslator.h" //43
-#include "Shared/TimeET.h" //42
-#include "Shared/Config.h" //42
-#include "IPC/SharedObject.h" //42
-#include "Shared/mathutils.h" //41
-#include "Shared/Profiler.h" //41
-#include "Motion/MotionManagerMsg.h" //41
-#include "Motion/MotionCommand.h" //41
-#include "Motion/OutputPID.h" //40
-#include "Motion/MotionManager.h" //40
-#include "Behaviors/BehaviorBase.h" //40
-#include "Shared/newmat/newmat.h" //forced (pattern match)
-#include "Shared/newmat/myexcept.h" //forced (pattern match)
-#include "Shared/newmat/include.h" //forced (pattern match)
+#include "Shared/attributes.h" //143
+#include "Shared/LoadSave.h" //141
+#include "Shared/XMLLoadSave.h" //139
+#include "Shared/Resource.h" //132
+#include "IPC/Thread.h" //131
+#include "Shared/get_time.h" //129
+#include "Events/EventBase.h" //127
+#include "Shared/ReferenceCounter.h" //123
+#include "Shared/RobotInfo.h" //118
+#include "Shared/CommonInfo.h" //118
+#include "Wireless/Socket.h" //117
+#include "Shared/ERS210Info.h" //117
+#include "Shared/debuget.h" //114
+#include "Events/EventListener.h" //108
+#include "Behaviors/BehaviorBase.h" //90
+#include "Wireless/Wireless.h" //88
+#include "Wireless/DummySocket.h" //88
+#include "Shared/newmat/newmat.h" //82
+#include "Shared/newmat/myexcept.h" //82
+#include "Shared/newmat/include.h" //82
+#include "Shared/Config.h" //81
+#include "IPC/ProcessID.h" //81
+#include "Shared/plistBase.h" //80
+#include "Shared/Cloneable.h" //80
+#include "Shared/plistPrimitives.h" //79
+#include "IPC/ListMemBuf.h" //79
+#include "Shared/plistCollections.h" //78
+#include "IPC/SemaphoreManager.h" //78
+#include "IPC/MutexLock.h" //78
+#include "Shared/plist.h" //77
+#include "Events/EventTrapper.h" //77
+#include "Vision/colors.h" //74
+#include "IPC/RCRegion.h" //74
+#include "Motion/Kinematics.h" //73
+#include "Events/EventRouter.h" //73
+#include "Shared/ProjectInterface.h" //69
+#include "Shared/WorldState.h" //66
+#include "Motion/OutputCmd.h" //66
+#include "IPC/SharedObject.h" //64
 #include "Shared/newmat/newmatio.h" //forced (pattern match)
 #include "Shared/newmat/newmatap.h" //forced (pattern match)
 #include "Motion/roboop/utils.h" //forced (pattern match)
@@ -49,40 +55,45 @@
 #include "Motion/roboop/config.h" //forced (pattern match)
 #endif //TGT_ERS210
 #ifdef TGT_ERS220
-#include "Shared/get_time.h" //75
-#include "Shared/LoadSave.h" //75
-#include "Events/EventBase.h" //74
-#include "Shared/ReferenceCounter.h" //64
-#include "Events/EventTrapper.h" //64
-#include "Shared/CommonInfo.h" //59
-#include "Shared/RobotInfo.h" //58
-#include "Shared/ERS220Info.h" //58
-#include "Shared/debuget.h" //56
-#include "Events/EventListener.h" //56
-#include "IPC/SemaphoreManager.h" //54
-#include "IPC/ProcessID.h" //54
-#include "IPC/ListMemBuf.h" //54
-#include "IPC/MutexLock.h" //53
-#include "Wireless/Socket.h" //52
-#include "Events/EventRouter.h" //52
-#include "IPC/LockScope.h" //48
-#include "IPC/RCRegion.h" //47
-#include "IPC/MessageQueue.h" //45
-#include "Motion/OutputCmd.h" //43
-#include "Events/EventTranslator.h" //43
-#include "Shared/TimeET.h" //42
-#include "Shared/Config.h" //42
-#include "IPC/SharedObject.h" //42
-#include "Shared/mathutils.h" //41
-#include "Shared/Profiler.h" //41
-#include "Motion/MotionManagerMsg.h" //41
-#include "Motion/MotionCommand.h" //41
-#include "Motion/OutputPID.h" //40
-#include "Motion/MotionManager.h" //40
-#include "Behaviors/BehaviorBase.h" //40
-#include "Shared/newmat/newmat.h" //forced (pattern match)
-#include "Shared/newmat/myexcept.h" //forced (pattern match)
-#include "Shared/newmat/include.h" //forced (pattern match)
+#include "Shared/attributes.h" //143
+#include "Shared/LoadSave.h" //141
+#include "Shared/XMLLoadSave.h" //139
+#include "Shared/Resource.h" //132
+#include "IPC/Thread.h" //131
+#include "Shared/get_time.h" //129
+#include "Events/EventBase.h" //127
+#include "Shared/ReferenceCounter.h" //123
+#include "Shared/RobotInfo.h" //118
+#include "Shared/CommonInfo.h" //118
+#include "Wireless/Socket.h" //117
+#include "Shared/ERS220Info.h" //117
+#include "Shared/debuget.h" //114
+#include "Events/EventListener.h" //108
+#include "Behaviors/BehaviorBase.h" //90
+#include "Wireless/Wireless.h" //88
+#include "Wireless/DummySocket.h" //88
+#include "Shared/newmat/newmat.h" //82
+#include "Shared/newmat/myexcept.h" //82
+#include "Shared/newmat/include.h" //82
+#include "Shared/Config.h" //81
+#include "IPC/ProcessID.h" //81
+#include "Shared/plistBase.h" //80
+#include "Shared/Cloneable.h" //80
+#include "Shared/plistPrimitives.h" //79
+#include "IPC/ListMemBuf.h" //79
+#include "Shared/plistCollections.h" //78
+#include "IPC/SemaphoreManager.h" //78
+#include "IPC/MutexLock.h" //78
+#include "Shared/plist.h" //77
+#include "Events/EventTrapper.h" //77
+#include "Vision/colors.h" //74
+#include "IPC/RCRegion.h" //74
+#include "Motion/Kinematics.h" //73
+#include "Events/EventRouter.h" //73
+#include "Shared/ProjectInterface.h" //69
+#include "Shared/WorldState.h" //66
+#include "Motion/OutputCmd.h" //66
+#include "IPC/SharedObject.h" //64
 #include "Shared/newmat/newmatio.h" //forced (pattern match)
 #include "Shared/newmat/newmatap.h" //forced (pattern match)
 #include "Motion/roboop/utils.h" //forced (pattern match)
@@ -90,40 +101,45 @@
 #include "Motion/roboop/config.h" //forced (pattern match)
 #endif //TGT_ERS220
 #ifdef TGT_ERS2xx
-#include "Shared/get_time.h" //75
-#include "Shared/LoadSave.h" //75
-#include "Events/EventBase.h" //74
-#include "Shared/ReferenceCounter.h" //64
-#include "Events/EventTrapper.h" //64
-#include "Shared/CommonInfo.h" //59
-#include "Shared/RobotInfo.h" //58
-#include "Shared/ERS2xxInfo.h" //58
-#include "Shared/debuget.h" //56
-#include "Events/EventListener.h" //56
-#include "IPC/SemaphoreManager.h" //54
-#include "IPC/ProcessID.h" //54
-#include "IPC/ListMemBuf.h" //54
-#include "IPC/MutexLock.h" //53
-#include "Wireless/Socket.h" //52
-#include "Events/EventRouter.h" //52
-#include "IPC/LockScope.h" //48
-#include "IPC/RCRegion.h" //47
-#include "IPC/MessageQueue.h" //45
-#include "Motion/OutputCmd.h" //43
-#include "Events/EventTranslator.h" //43
-#include "Shared/TimeET.h" //42
-#include "Shared/Config.h" //42
-#include "IPC/SharedObject.h" //42
-#include "Shared/mathutils.h" //41
-#include "Shared/Profiler.h" //41
-#include "Motion/MotionManagerMsg.h" //41
-#include "Motion/MotionCommand.h" //41
-#include "Motion/OutputPID.h" //40
-#include "Motion/MotionManager.h" //40
-#include "Behaviors/BehaviorBase.h" //40
-#include "Shared/newmat/newmat.h" //forced (pattern match)
-#include "Shared/newmat/myexcept.h" //forced (pattern match)
-#include "Shared/newmat/include.h" //forced (pattern match)
+#include "Shared/attributes.h" //143
+#include "Shared/LoadSave.h" //141
+#include "Shared/XMLLoadSave.h" //139
+#include "Shared/Resource.h" //132
+#include "IPC/Thread.h" //131
+#include "Shared/get_time.h" //129
+#include "Events/EventBase.h" //127
+#include "Shared/ReferenceCounter.h" //123
+#include "Shared/RobotInfo.h" //118
+#include "Shared/CommonInfo.h" //118
+#include "Wireless/Socket.h" //117
+#include "Shared/ERS2xxInfo.h" //117
+#include "Shared/debuget.h" //114
+#include "Events/EventListener.h" //108
+#include "Behaviors/BehaviorBase.h" //90
+#include "Wireless/Wireless.h" //88
+#include "Wireless/DummySocket.h" //88
+#include "Shared/newmat/newmat.h" //82
+#include "Shared/newmat/myexcept.h" //82
+#include "Shared/newmat/include.h" //82
+#include "Shared/Config.h" //81
+#include "IPC/ProcessID.h" //81
+#include "Shared/plistBase.h" //80
+#include "Shared/Cloneable.h" //80
+#include "Shared/plistPrimitives.h" //79
+#include "IPC/ListMemBuf.h" //79
+#include "Shared/plistCollections.h" //78
+#include "IPC/SemaphoreManager.h" //78
+#include "IPC/MutexLock.h" //78
+#include "Shared/plist.h" //77
+#include "Events/EventTrapper.h" //77
+#include "Vision/colors.h" //74
+#include "IPC/RCRegion.h" //74
+#include "Motion/Kinematics.h" //73
+#include "Events/EventRouter.h" //73
+#include "Shared/ProjectInterface.h" //69
+#include "Shared/WorldState.h" //66
+#include "Motion/OutputCmd.h" //66
+#include "IPC/SharedObject.h" //64
 #include "Shared/newmat/newmatio.h" //forced (pattern match)
 #include "Shared/newmat/newmatap.h" //forced (pattern match)
 #include "Motion/roboop/utils.h" //forced (pattern match)
@@ -131,40 +147,45 @@
 #include "Motion/roboop/config.h" //forced (pattern match)
 #endif //TGT_ERS2xx
 #ifdef TGT_ERS7
-#include "Shared/get_time.h" //75
-#include "Shared/LoadSave.h" //75
-#include "Events/EventBase.h" //74
-#include "Shared/ReferenceCounter.h" //64
-#include "Events/EventTrapper.h" //64
-#include "Shared/ERS7Info.h" //59
-#include "Shared/CommonInfo.h" //59
-#include "Shared/RobotInfo.h" //58
-#include "Shared/debuget.h" //56
-#include "Events/EventListener.h" //56
-#include "IPC/SemaphoreManager.h" //54
-#include "IPC/ProcessID.h" //54
-#include "IPC/ListMemBuf.h" //54
-#include "IPC/MutexLock.h" //53
-#include "Wireless/Socket.h" //52
-#include "Events/EventRouter.h" //52
-#include "IPC/LockScope.h" //48
-#include "IPC/RCRegion.h" //47
-#include "IPC/MessageQueue.h" //45
-#include "Motion/OutputCmd.h" //43
-#include "Events/EventTranslator.h" //43
-#include "Shared/TimeET.h" //42
-#include "Shared/Config.h" //42
-#include "IPC/SharedObject.h" //42
-#include "Shared/mathutils.h" //41
-#include "Shared/Profiler.h" //41
-#include "Motion/MotionManagerMsg.h" //41
-#include "Motion/MotionCommand.h" //41
-#include "Motion/OutputPID.h" //40
-#include "Motion/MotionManager.h" //40
-#include "Behaviors/BehaviorBase.h" //40
-#include "Shared/newmat/newmat.h" //forced (pattern match)
-#include "Shared/newmat/myexcept.h" //forced (pattern match)
-#include "Shared/newmat/include.h" //forced (pattern match)
+#include "Shared/attributes.h" //144
+#include "Shared/LoadSave.h" //142
+#include "Shared/XMLLoadSave.h" //140
+#include "Shared/Resource.h" //132
+#include "IPC/Thread.h" //131
+#include "Shared/get_time.h" //130
+#include "Events/EventBase.h" //128
+#include "Shared/ReferenceCounter.h" //124
+#include "Shared/RobotInfo.h" //118
+#include "Shared/ERS7Info.h" //118
+#include "Shared/CommonInfo.h" //118
+#include "Wireless/Socket.h" //117
+#include "Shared/debuget.h" //115
+#include "Events/EventListener.h" //109
+#include "Behaviors/BehaviorBase.h" //91
+#include "Wireless/Wireless.h" //88
+#include "Wireless/DummySocket.h" //88
+#include "Shared/newmat/newmat.h" //83
+#include "Shared/newmat/myexcept.h" //83
+#include "Shared/newmat/include.h" //83
+#include "Shared/Config.h" //81
+#include "IPC/ProcessID.h" //81
+#include "Shared/plistBase.h" //80
+#include "Shared/Cloneable.h" //80
+#include "Shared/plistPrimitives.h" //79
+#include "IPC/ListMemBuf.h" //79
+#include "Shared/plistCollections.h" //78
+#include "IPC/SemaphoreManager.h" //78
+#include "IPC/MutexLock.h" //78
+#include "Events/EventTrapper.h" //78
+#include "Shared/plist.h" //77
+#include "Vision/colors.h" //74
+#include "IPC/RCRegion.h" //74
+#include "Events/EventRouter.h" //74
+#include "Motion/Kinematics.h" //73
+#include "Shared/ProjectInterface.h" //69
+#include "Shared/WorldState.h" //66
+#include "Motion/OutputCmd.h" //66
+#include "IPC/SharedObject.h" //64
 #include "Shared/newmat/newmatio.h" //forced (pattern match)
 #include "Shared/newmat/newmatap.h" //forced (pattern match)
 #include "Motion/roboop/utils.h" //forced (pattern match)
@@ -175,31 +196,35 @@
 
 #ifdef PLATFORM_APERIOS
 #ifdef TGT_ERS210
-#include "Shared/get_time.h" //75
-#include "Shared/LoadSave.h" //75
-#include "Events/EventBase.h" //74
-#include "Events/EventTrapper.h" //64
-#include "Shared/CommonInfo.h" //59
-#include "Shared/RobotInfo.h" //58
-#include "Shared/ERS210Info.h" //58
-#include "Shared/debuget.h" //56
-#include "Events/EventListener.h" //55
-#include "Wireless/Socket.h" //52
-#include "Events/EventRouter.h" //52
-#include "IPC/ProcessID.h" //49
-#include "IPC/MutexLock.h" //48
-#include "Shared/Config.h" //44
-#include "IPC/RCRegion.h" //44
-#include "IPC/LockScope.h" //44
-#include "IPC/ListMemBuf.h" //43
-#include "Events/EventTranslator.h" //43
-#include "Shared/ReferenceCounter.h" //42
-#include "Motion/OutputCmd.h" //41
-#include "Shared/TimeET.h" //40
-#include "Behaviors/BehaviorBase.h" //40
-#include "Shared/newmat/newmat.h" //forced (pattern match)
-#include "Shared/newmat/myexcept.h" //forced (pattern match)
-#include "Shared/newmat/include.h" //forced (pattern match)
+#include "Shared/attributes.h" //127
+#include "Shared/LoadSave.h" //126
+#include "Shared/XMLLoadSave.h" //125
+#include "Shared/get_time.h" //121
+#include "Events/EventBase.h" //120
+#include "Shared/CommonInfo.h" //115
+#include "Shared/RobotInfo.h" //114
+#include "Shared/ERS210Info.h" //114
+#include "Wireless/Socket.h" //111
+#include "Shared/debuget.h" //101
+#include "Events/EventListener.h" //99
+#include "Shared/ReferenceCounter.h" //86
+#include "Behaviors/BehaviorBase.h" //84
+#include "Wireless/Wireless.h" //83
+#include "Wireless/DummySocket.h" //83
+#include "Shared/Config.h" //80
+#include "Shared/newmat/newmat.h" //79
+#include "Shared/newmat/myexcept.h" //79
+#include "Shared/newmat/include.h" //79
+#include "Motion/Kinematics.h" //71
+#include "Shared/StackTrace.h" //70
+#include "IPC/ProcessID.h" //69
+#include "Events/EventTrapper.h" //68
+#include "Events/EventRouter.h" //67
+#include "Shared/Resource.h" //65
+#include "Shared/WorldState.h" //64
+#include "Vision/colors.h" //63
+#include "Motion/OutputCmd.h" //63
+#include "IPC/MutexLock.h" //63
 #include "Shared/newmat/newmatio.h" //forced (pattern match)
 #include "Shared/newmat/newmatap.h" //forced (pattern match)
 #include "Motion/roboop/utils.h" //forced (pattern match)
@@ -207,31 +232,35 @@
 #include "Motion/roboop/config.h" //forced (pattern match)
 #endif //TGT_ERS210
 #ifdef TGT_ERS220
-#include "Shared/get_time.h" //75
-#include "Shared/LoadSave.h" //75
-#include "Events/EventBase.h" //74
-#include "Events/EventTrapper.h" //64
-#include "Shared/CommonInfo.h" //59
-#include "Shared/RobotInfo.h" //58
-#include "Shared/ERS220Info.h" //58
-#include "Shared/debuget.h" //56
-#include "Events/EventListener.h" //55
-#include "Wireless/Socket.h" //52
-#include "Events/EventRouter.h" //52
-#include "IPC/ProcessID.h" //49
-#include "IPC/MutexLock.h" //48
-#include "Shared/Config.h" //44
-#include "IPC/RCRegion.h" //44
-#include "IPC/LockScope.h" //44
-#include "IPC/ListMemBuf.h" //43
-#include "Events/EventTranslator.h" //43
-#include "Shared/ReferenceCounter.h" //42
-#include "Motion/OutputCmd.h" //41
-#include "Shared/TimeET.h" //40
-#include "Behaviors/BehaviorBase.h" //40
-#include "Shared/newmat/newmat.h" //forced (pattern match)
-#include "Shared/newmat/myexcept.h" //forced (pattern match)
-#include "Shared/newmat/include.h" //forced (pattern match)
+#include "Shared/attributes.h" //127
+#include "Shared/LoadSave.h" //126
+#include "Shared/XMLLoadSave.h" //125
+#include "Shared/get_time.h" //121
+#include "Events/EventBase.h" //120
+#include "Shared/CommonInfo.h" //115
+#include "Shared/RobotInfo.h" //114
+#include "Shared/ERS220Info.h" //114
+#include "Wireless/Socket.h" //111
+#include "Shared/debuget.h" //101
+#include "Events/EventListener.h" //99
+#include "Shared/ReferenceCounter.h" //86
+#include "Behaviors/BehaviorBase.h" //84
+#include "Wireless/Wireless.h" //83
+#include "Wireless/DummySocket.h" //83
+#include "Shared/Config.h" //80
+#include "Shared/newmat/newmat.h" //79
+#include "Shared/newmat/myexcept.h" //79
+#include "Shared/newmat/include.h" //79
+#include "Motion/Kinematics.h" //71
+#include "Shared/StackTrace.h" //70
+#include "IPC/ProcessID.h" //69
+#include "Events/EventTrapper.h" //68
+#include "Events/EventRouter.h" //67
+#include "Shared/Resource.h" //65
+#include "Shared/WorldState.h" //64
+#include "Vision/colors.h" //63
+#include "Motion/OutputCmd.h" //63
+#include "IPC/MutexLock.h" //63
 #include "Shared/newmat/newmatio.h" //forced (pattern match)
 #include "Shared/newmat/newmatap.h" //forced (pattern match)
 #include "Motion/roboop/utils.h" //forced (pattern match)
@@ -239,31 +268,35 @@
 #include "Motion/roboop/config.h" //forced (pattern match)
 #endif //TGT_ERS220
 #ifdef TGT_ERS2xx
-#include "Shared/get_time.h" //75
-#include "Shared/LoadSave.h" //75
-#include "Events/EventBase.h" //74
-#include "Events/EventTrapper.h" //64
-#include "Shared/CommonInfo.h" //59
-#include "Shared/RobotInfo.h" //58
-#include "Shared/ERS2xxInfo.h" //58
-#include "Shared/debuget.h" //56
-#include "Events/EventListener.h" //55
-#include "Wireless/Socket.h" //52
-#include "Events/EventRouter.h" //52
-#include "IPC/ProcessID.h" //49
-#include "IPC/MutexLock.h" //48
-#include "Shared/Config.h" //44
-#include "IPC/RCRegion.h" //44
-#include "IPC/LockScope.h" //44
-#include "IPC/ListMemBuf.h" //43
-#include "Events/EventTranslator.h" //43
-#include "Shared/ReferenceCounter.h" //42
-#include "Motion/OutputCmd.h" //41
-#include "Shared/TimeET.h" //40
-#include "Behaviors/BehaviorBase.h" //40
-#include "Shared/newmat/newmat.h" //forced (pattern match)
-#include "Shared/newmat/myexcept.h" //forced (pattern match)
-#include "Shared/newmat/include.h" //forced (pattern match)
+#include "Shared/attributes.h" //127
+#include "Shared/LoadSave.h" //126
+#include "Shared/XMLLoadSave.h" //125
+#include "Shared/get_time.h" //121
+#include "Events/EventBase.h" //120
+#include "Shared/CommonInfo.h" //115
+#include "Shared/RobotInfo.h" //114
+#include "Shared/ERS2xxInfo.h" //114
+#include "Wireless/Socket.h" //111
+#include "Shared/debuget.h" //101
+#include "Events/EventListener.h" //99
+#include "Shared/ReferenceCounter.h" //86
+#include "Behaviors/BehaviorBase.h" //84
+#include "Wireless/Wireless.h" //83
+#include "Wireless/DummySocket.h" //83
+#include "Shared/Config.h" //80
+#include "Shared/newmat/newmat.h" //79
+#include "Shared/newmat/myexcept.h" //79
+#include "Shared/newmat/include.h" //79
+#include "Motion/Kinematics.h" //71
+#include "Shared/StackTrace.h" //70
+#include "IPC/ProcessID.h" //69
+#include "Events/EventTrapper.h" //68
+#include "Events/EventRouter.h" //67
+#include "Shared/Resource.h" //65
+#include "Shared/WorldState.h" //64
+#include "Vision/colors.h" //63
+#include "Motion/OutputCmd.h" //63
+#include "IPC/MutexLock.h" //63
 #include "Shared/newmat/newmatio.h" //forced (pattern match)
 #include "Shared/newmat/newmatap.h" //forced (pattern match)
 #include "Motion/roboop/utils.h" //forced (pattern match)
@@ -271,31 +304,35 @@
 #include "Motion/roboop/config.h" //forced (pattern match)
 #endif //TGT_ERS2xx
 #ifdef TGT_ERS7
-#include "Shared/get_time.h" //75
-#include "Shared/LoadSave.h" //75
-#include "Events/EventBase.h" //74
-#include "Events/EventTrapper.h" //64
-#include "Shared/ERS7Info.h" //59
-#include "Shared/CommonInfo.h" //59
-#include "Shared/RobotInfo.h" //58
-#include "Shared/debuget.h" //56
-#include "Events/EventListener.h" //55
-#include "Wireless/Socket.h" //52
-#include "Events/EventRouter.h" //52
-#include "IPC/ProcessID.h" //49
-#include "IPC/MutexLock.h" //48
-#include "Shared/Config.h" //44
-#include "IPC/RCRegion.h" //44
-#include "IPC/LockScope.h" //44
-#include "IPC/ListMemBuf.h" //43
-#include "Events/EventTranslator.h" //43
-#include "Shared/ReferenceCounter.h" //42
-#include "Motion/OutputCmd.h" //41
-#include "Shared/TimeET.h" //40
-#include "Behaviors/BehaviorBase.h" //40
-#include "Shared/newmat/newmat.h" //forced (pattern match)
-#include "Shared/newmat/myexcept.h" //forced (pattern match)
-#include "Shared/newmat/include.h" //forced (pattern match)
+#include "Shared/attributes.h" //127
+#include "Shared/LoadSave.h" //126
+#include "Shared/XMLLoadSave.h" //125
+#include "Shared/get_time.h" //121
+#include "Events/EventBase.h" //120
+#include "Shared/ERS7Info.h" //115
+#include "Shared/CommonInfo.h" //115
+#include "Shared/RobotInfo.h" //114
+#include "Wireless/Socket.h" //111
+#include "Shared/debuget.h" //101
+#include "Events/EventListener.h" //99
+#include "Shared/ReferenceCounter.h" //86
+#include "Behaviors/BehaviorBase.h" //84
+#include "Wireless/Wireless.h" //83
+#include "Wireless/DummySocket.h" //83
+#include "Shared/Config.h" //80
+#include "Shared/newmat/newmat.h" //79
+#include "Shared/newmat/myexcept.h" //79
+#include "Shared/newmat/include.h" //79
+#include "Motion/Kinematics.h" //71
+#include "Shared/StackTrace.h" //70
+#include "IPC/ProcessID.h" //69
+#include "Events/EventTrapper.h" //68
+#include "Events/EventRouter.h" //67
+#include "Shared/Resource.h" //65
+#include "Shared/WorldState.h" //64
+#include "Vision/colors.h" //63
+#include "Motion/OutputCmd.h" //63
+#include "IPC/MutexLock.h" //63
 #include "Shared/newmat/newmatio.h" //forced (pattern match)
 #include "Shared/newmat/newmatap.h" //forced (pattern match)
 #include "Motion/roboop/utils.h" //forced (pattern match)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/QuickReference/Makefile ./docs/QuickReference/Makefile
--- ../Tekkotsu_2.4.1/docs/QuickReference/Makefile	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/QuickReference/Makefile	2006-02-08 02:33:21.000000000 -0500
@@ -0,0 +1,30 @@
+TEKKOTSU_ROOT:=../..
+
+EVENT_GENERATOR_SRC:=$(TEKKOTSU_ROOT)/Events/EventBase.h
+VERSION_NUMBER_SRC:=$(TEKKOTSU_ROOT)/docs/doxygencfg
+MODELS:=ERS7 ERS210 ERS220
+
+all: $(addsuffix .pdf,$(addprefix TekkotsuQuickReference-,$(MODELS)))
+.PHONY: all clean
+
+TekkotsuQuickReference-%.pdf : TekkotsuQuickReference.tex EventGenerators.tex VersionNumber.tex
+	@MODEL=`echo $* | sed 's/\([A-Z]\)\([0-9]\)/\1-\2/g'`; \
+	echo "\newcommand{\model}{$$MODEL}" > ModelSpecific.tex; \
+	echo "\newcommand{\condensedmodel}{$*}" >> ModelSpecific.tex; \
+	echo "\newcommand{\release}{\input{VersionNumber}}" >> ModelSpecific.tex;
+	pdflatex -interaction errorstopmode $< < /dev/null
+	mv $(basename $<).pdf $@
+
+# The first part of this sed script extracts the EventGeneratorID_t enumeration
+# and formats it as a latex list.  That output is then put through a second sed
+# script which sanitizes special characters such as '_'.
+EventGenerators.tex : $(EVENT_GENERATOR_SRC)
+	sed -n '/enum EventGeneratorID_t/,/numEGIDs/s@	*\([a-zA-Z]*EGID\)\(=0\)\{0,1\},.*//!< *\(.*\)@{\\tt \1}, @p' $< | sed 's/_/\\_/g' > $@
+
+VersionNumber.tex : $(VERSION_NUMBER_SRC)
+	sed -n 's@PROJECT_NUMBER.*=[ 	]*\([0-9.]*\)@\1@p' $(VERSION_NUMBER_SRC) > $@
+
+clean:
+	rm -f *~ *.aux *.log *.out
+
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/QuickReference/TekkotsuQuickReference.tex ./docs/QuickReference/TekkotsuQuickReference.tex
--- ../Tekkotsu_2.4.1/docs/QuickReference/TekkotsuQuickReference.tex	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/QuickReference/TekkotsuQuickReference.tex	2006-09-29 08:52:11.000000000 -0400
@@ -0,0 +1,440 @@
+\documentclass[10pt]{article}
+\usepackage{amssymb}
+\usepackage{ifthen}
+\usepackage{multicol}
+\usepackage{url}
+\ifx\pdfoutput\undefined
+\usepackage[hypertex]{hyperref}
+%\usepackage[ps2pdf,bookmarks=true]{hyperref}
+\else
+\usepackage[pdftex,hypertexnames=false]{hyperref}
+\fi
+\ifx\pdfoutput\undefined
+\usepackage{graphicx}
+\else
+\usepackage[pdftex]{graphicx}
+\fi
+
+\usepackage{pslatex}
+
+\hypersetup{
+  pdfauthor   = {Ethan Tira-Thompson},
+  pdftitle    = {Tekkotsu Quick Reference}
+}
+%  pdfkeywords = {},
+%  pdfsubject  = {Seminar Title, SS/WS 20xx RWTH Aachen University},
+%  pdfcreator  = {LaTeX with hyperref package},
+%  pdfproducer = {dvips + ps2pdf}
+
+\topmargin -.5in
+\oddsidemargin -.25in
+\evensidemargin -.25in
+\textwidth 7in
+\textheight 10in
+\headsep 0pt
+\headheight 0pt
+\topskip 0pt
+\footskip .25in
+
+\pagestyle{empty}
+\parskip 7.2pt
+%\renewcommand{\baselinestretch}{1.5}
+\parindent 0pt
+\setlength{\fboxsep}{8pt}
+\setlength{\columnsep}{.25in}
+
+%\setlength{\floatsep}{0in}
+%\setlength{\textfloatsep}{0in}
+%\setlength{\intextsep}{0in}
+%\setlength{\dbltextfloatsep}{0in}
+%\setlength{\dblfloatsep}{0in}
+%\setlength{\abovedisplayskip}{0in}
+%\setlength{\topsep}{0in}
+\setlength{\partopsep}{-.2in}
+%\setlength{\parskip}{0in}
+
+%\renewcommand{\ttdefault}{cmtt}
+
+\input{ModelSpecific}
+
+\renewcommand{\labelitemi}{{\tiny $\blacklozenge$}}
+\newlength{\QRsubindent}
+
+\newenvironment{keylist}
+	{\begin{list}{}{
+		\flushleft
+		\providecommand{\keyliststyle}{\tt}
+		\renewcommand{\makelabel}[1]{\labelitemi\ {\keyliststyle ##1} - }
+		\setlength{\QRsubindent}{6pt}
+		\setlength{\itemsep}{2pt}
+		\setlength{\parsep}{0pt}
+		\setlength{\labelsep}{0pt}
+		\setlength{\leftmargin}{12pt}
+		\setlength{\labelwidth}{9pt}
+		\setlength{\parindent}{0pt}
+		\setlength{\listparindent}{0pt}}}
+	{\end{list}}
+
+\newenvironment{keyenum}
+	{\begin{list}{}{
+		\flushleft
+		\providecommand{\keyliststyle}{\tt}
+		\renewcommand{\makelabel}[1]{\labelitemi\ {\keyliststyle ##1} - }
+		\setlength{\QRsubindent}{6pt}
+		\setlength{\itemsep}{2pt}
+		\setlength{\parsep}{0pt}
+		\setlength{\labelsep}{0pt}
+		\setlength{\leftmargin}{12pt}
+		\setlength{\labelwidth}{9pt}
+		\setlength{\parindent}{0pt}
+		\setlength{\listparindent}{0pt}}}
+	{\end{list}}
+
+\newenvironment{QRitemize}
+	{\begin{list}{}{
+		\flushleft
+		\providecommand{\itemstyle}{\tt}
+		\renewcommand{\makelabel}[1]{\labelitemi\ {\itemstyle ##1}}
+		\setlength{\QRsubindent}{6pt}
+		\setlength{\itemsep}{2pt}
+		\setlength{\parsep}{0pt}
+		\setlength{\labelsep}{0pt}
+		\setlength{\leftmargin}{12pt}
+		\setlength{\labelwidth}{9pt}
+		\setlength{\parindent}{0pt}
+		\setlength{\listparindent}{0pt}}}
+	{\end{list}}
+
+\makeatletter
+\renewcommand{\section}[1]{\@startsection%
+	{section}{1}{-10pt}{6pt}{0pt}{\Large\bf\hspace{6pt}\rule[.2\lineheight]{24pt}{2pt}\hspace{-30pt}}%
+	{\hspace{28pt}#1}%
+}
+\renewcommand{\subsection}[1]{\@startsection{subsection}{2}{0pt}{3pt}{0.01pt}{\large\bf}{#1}}
+\renewcommand{\subsubsection}[1]{\@startsection{subsubsection}{3}{0pt}{0pt}{0.01pt}{\bf}{#1}}
+\makeatother
+
+\newenvironment{QRsection}[1]
+	{\section{#1}\hspace{6pt}\rule[.2\lineheight]{72pt}{2pt}}
+	{}
+
+\newenvironment{QRsubsection}[1]
+	{\subsection{#1}}
+	{}
+
+\title{Tekkotsu Quick Reference}
+\date{\model, Tekkotsu \release}
+\author{Ethan Tira-Thompson}
+
+\renewcommand{\maketitle}{\begin{center}%
+\large{\huge Tekkotsu Quick Reference} \vspace{6pt} \\%
+\model, Tekkotsu \release \vspace{6pt} \\%
+Ethan Tira-Thompson \vspace{12pt}%
+\end{center}
+}
+
+\begin{document}         
+% Start your text
+
+
+\raggedcolumns
+\begin{multicols}{2}[\maketitle]
+\raggedcolumns
+
+
+\begin{QRsection}{Building}
+\begin{QRsubsection}{Environment Variables}
+Values can be set in {\tt project/Environment.conf}, a shell environment variable, or the {\tt make} command line.
+Each configuration method overrides values from prior methods.
+
+\begin{keylist}
+\item[OPENRSDK\_\,ROOT] Location of OPEN-R SDK installation {\footnotesize (default {\tt /usr/local/OPEN\_\,R\_SDK})}
+\item[TEKKOTSU\_\,ROOT] Location of Tekkotsu installation {\footnotesize (default {\tt /usr/local/Tekkotsu})}
+\item[MEMSTICK\_\,ROOT] Location of memory stick mount point {\footnotesize (default tries to autodetect -- Mac OS X users should get something in {\tt /Volumes/}..., Cygwin users will want something like {\tt /cygdrive/e}, Linux defaults to {\tt /mnt/memstick})}
+\item[TEKKOTSU\_TARGET\_\,PLATFORM] Can be set to either {\tt PLATFORM\_APERIOS} {\footnotesize (the Aibo's OS, default)} or {\tt PLATFORM\_\,LOCAL} {\footnotesize (host machine's OS, local execution)}.
+\item[TEKKOTSU\_TARGET\_\,MODEL] Can be set to one of the supported robot models: {\tt TGT\_\,ERS210}, {\tt TGT\_\,ERS220}, {\tt TGT\_\,ERS2xx} {\footnotesize (dual boot either 210 or 220)}, {\tt TGT\_\,ERS7} {\footnotesize (default)}.
+\item[TEKKOTSU\_ALWAYS\_BUILD] If any non-empty string (default), update {\tt libtekkotsu.a} prior to each project build.  Turn off if {\tt TEKKOTSU\_ROOT} is in a read-only location, such as a shared directory in a computer lab.
+\end{keylist}
+See also additional options and documentation in {\tt project/Environment.conf}
+\end{QRsubsection}
+
+
+\begin{QRsubsection}{Build Targets}
+The following targets are available as targets to the {\tt make} command, from within a project directory:
+
+\begin{keylist}
+\item[all] Builds source into binary executables.
+\item[newstick] Erases memory stick, copies fresh system files
+\item[install] Builds {\tt all}, copies project's {\tt ms} directory to memory stick (may require previous {\tt make newstick})
+\item[update] Builds {\tt all}, selectively copies newer files from {\tt ms} to memory stick (requires rsync)
+\item[sim] Builds the project for local simulation, equivalent to {\tt all} with {\tt TEKKOTSU\_TARGET\_PLATFORM} set to {\tt PLATFORM\_LOCAL}
+\item[clean, cleanProj, cleanDeps] Erases all, just project, or dependancy (.d) build files
+\end{keylist}
+
+The following targets are available to {\tt make} from within the main Tekkotsu directory:
+
+\begin{keylist}
+\item[all] Updates {[build/.../]\tt libtekkotsu.a} for each supported platform 
+\item[compile] Updates {[build/.../]\tt libtekkotsu.a} for only the current platform (see {\tt TEKKOTSU\_TARGET\_PLATFORM})
+\end{keylist}
+
+\end{QRsubsection}
+\end{QRsection}
+
+
+
+
+\columnbreak
+\begin{QRsection}{Execution}
+\begin{QRsubsection}{Console}
+You can view text output from code running on the AIBO by using a telnet connection.  You can filter the output you wish to receive by selecting a port number below.  Any output sent to a port which is unconnected will be redirected to the one listed below it.
+
+\begin{keylist}
+\item[10002] Output from Main process's {\tt serr} (e.g. {\tt serr->printf(...)}).  Theoretically "blocking", but some output can still be lost in the system network buffers during a crash.  Input from client is ignored.
+\item[10001] Output from Main process's {\tt sout}.  Non-blocking for fast thoroughput, but will lose most recent data sent if crash occurs.  Input is interpreted as ControllerGUI commands if no GUI is connected, otherwise each line of input is broadcast as a TextMsgEvent.
+\item[59000] The system output console, catches all output from the operating system itself, {\tt cout}, {\tt cerr} or basic {\tt printf}.  Non-blocking, buffered output, {\em blocking input} (don't use {\tt cin}).
+\end{keylist}
+\end{QRsubsection}
+
+
+\begin{QRsubsection}{Controller}
+You can send these commands to port 10001 (assuming tekkotsu.cfg's main.consoleMode default setting), the GUI port 10020 (if GUI not connected), or the GUI's scripts or ``Send Input'' field.  All commands start with `{\tt !}'.  The input field will prefix non-commands with {\tt !input}.  Use quotes around multi-word arguments.
+
+\begin{keylist}
+\item[!reset] return to the root menu
+\item[!next] hilight the next menu item
+\item[!prev] hilight the previous menu item
+\item[!select {\rm[{\em item}]}] trigger activate of currently hilighted menu items, unless {\em item} is specified, in which case Controller will search from the root for an entry of the same name and trigger it if found
+\item[!cancel] move up/back a menu level
+\item[!msg {\rm\em text}] broadcasts {\em text} as a TextMsgEvent
+\item[!root {\rm {\em item} [{\em subitem} ...]}] triggers indicated items to drill down from root to a specified subitem.  Doesn't change current menu location unless final item is a menu itself.
+\item[!hilight {\rm [{\em n1} [{\em n2} ...]]}] Selects listed item indicies, can select multiple at once
+\item[!input {\rm\em text}] Passes {\em text} as input to the currently hilighted item(s), can be used to move directly to a submenu, specify a filename to save data into, set a corresponding variable, etc., depending on the context.
+\item[!set {\rm\em section.key}={\rm\em value}] sets a configuration variable, overriding the default found in {\tt tekkotsu.cfg} for remainder of the current session only
+\end{keylist}
+\end{QRsubsection}
+\end{QRsection}
+
+
+
+
+
+\begin{QRsection}{Model Specification}
+Each supported robot model is specified by an ``Info'' header file in {\tt Shared}, e.g. {\tt Shared/\condensedmodel Info.h}, which defines the constants shown in this section.  These files can also alias symbols found on other models to aid in portability between models.  {\tt Shared/RobotInfo.h} should be used to automatically include the proper header for the current target model and bring its constants into the global namespace.
+
+\begin{QRsubsection}{Output Offsets}
+``Outputs'' (i.e. Joints, LEDs) are refered to by index (``offset'') value.
+These values are formed by specifying a {\em section} offset, plus a {\em specific} offset.  Sections are typically general across robot models, whereas the specifics are model-dependent (but can be aliased to provide compatability).
+
+For most joints, the positive direction is ``up'', and the 0 position yields a forward looking, fully extended standing posture.
+
+\begin{QRitemize}{\small
+\item \{{\tt L},{\tt R}\}\{{\tt Fr},{\tt Bk}\}{\tt LegOffset} - {\tt NumLegs} combinations, each with {\tt JointsPerLeg} items \\
+{\footnotesize
+\hspace*{\QRsubindent}{\tt + RotatorOffset}: positive moves ``out'', away from body \\
+\hspace*{\QRsubindent}{\tt + ElevatorOffset}: positive moves up, away from body \\
+\hspace*{\QRsubindent}{\tt + KneeOffset}: positive bends knee (slight negative possible)
+}
+
+\item {\tt HeadOffset} - {\tt NumHeadJoints} items \\
+{\footnotesize
+\hspace*{\QRsubindent}{\tt + TiltOffset}: positive looks up \\
+\hspace*{\QRsubindent}{\tt + PanOffset}: positive looks left \\
+\ifthenelse{\equal{\model}{ERS-7}}{
+	\hspace*{\QRsubindent}{\tt + NodOffset}: positive looks up
+}{
+	\hspace*{\QRsubindent}{\tt + RollOffset}: positive rotates view counter-clockwise
+}
+}
+
+\ifthenelse{\equal{\model}{ERS-220}}{}{\item {\tt TailOffset} - {\tt NumTailJoints} items \\
+{\footnotesize
+\hspace*{\QRsubindent}{\tt + TiltOffset}: positive raises the joint \ifthenelse{\equal{\model}{ERS-7}}{(lowers the tail itself)}{} \\
+\hspace*{\QRsubindent}{\tt + PanOffset}: positive points the tail to the Aibo's right
+}}
+
+\ifthenelse{\equal{\model}{ERS-220}}{}{\item {\tt MouthOffset} - {\tt NumMouthJoints} items (no specific)}
+
+\item LEDs: these are all direct offsets, and do not need to be added to anything else \\
+\ifthenelse{\equal{\model}{ERS-7}}{
+\begin{QRitemize}
+\footnotesize
+\item {\tt HeadColorLEDOffset}, {\tt HeadWhiteLEDOffset}, {\tt ModeRedLEDOffset}, {\tt ModeGreenLEDOffset}, {\tt ModeBlueLEDOffset}, {\tt WirelessLEDOffset}, {\tt FrBackColorLEDOffset} (blue), {\tt FrBackWhiteLEDOffset}, {\tt MdBackColorLEDOffset} (orange), {\tt MdBackWhiteLEDOffset}, {\tt RrBackColorLEDOffset} (red), {\tt RrBackWhiteLEDOffset} \\
+\item {\tt FaceLEDPanelOffset} - 14 items, individually unnamed.  See Sony's model documentation for panel diagram. \\
+\item {\tt LEDABModeOffset} - this is a ``virtual'' LED, which changes how the AIBO interprets certain face panel LEDs \\
+\end{QRitemize}
+}{}
+\ifthenelse{\equal{\model}{ERS-210}}{
+\begin{QRitemize}
+\footnotesize
+\item Face LEDs: {\tt BotLLEDOffset}, {\tt BotRLEDOffset} - red/sad, {\tt MidLLEDOffset}, {\tt MidRLEDOffset} - green/happy, {\tt TopLLEDOffset}, {\tt TopRLEDOffset} - red/angry \\
+\item {\tt TopBrLEDOffset} - the green bar LED near the top of the face \\
+\item Tail LEDs: {\tt TlRedLEDOffset}, {\tt TlBluLEDOffset} \\
+\end{QRitemize}
+}{}
+\ifthenelse{\equal{\model}{ERS-220}}{
+\begin{QRitemize}
+\footnotesize
+\item {\tt FaceFrontLeftLEDOffset}, {\tt FaceFrontRightLEDOffset}, {\tt FaceCenterLeftLEDOffset}, {\tt FaceCenterRightLEDOffset} - blue, {\tt FaceBackLeftLEDOffset}, {\tt FaceBackRightLEDOffset} - red
+\item {\tt ModeLEDOffset} - mode indicator (back of the head - orange)
+\item {\tt BackLeft1LEDOffset}, {\tt BackLeft2LEDOffset}, {\tt BackLeft3LEDOffset}, {\tt BackRight3LEDOffset}, {\tt BackRight2LEDOffset}, {\tt BackRight1LEDOffset}
+\item {\tt TailLeftLEDOffset} (blue), {\tt TailCenterLEDOffset} (red), {\tt TailRightLEDOffset} (blue)
+\item {\tt FaceFrontALEDOffset} (blue), {\tt FaceFrontBLEDOffset} (blue), {\tt FaceFrontCLEDOffset} (red)
+\item {\tt RetractableHeadLEDOffset} - retractable head light
+\end{QRitemize}
+}{}
+\ifthenelse{\equal{\model}{ERS-2xx}}{
+Available LEDs depend on actual model running the code -- sensible mapping is done of LEDs from the other model.
+ERS-210:
+\begin{QRitemize}
+\footnotesize
+\item Face LEDs: {\tt BotLLEDOffset}, {\tt BotRLEDOffset} - red/sad, {\tt MidLLEDOffset}, {\tt MidRLEDOffset} - green/happy, {\tt TopLLEDOffset}, {\tt TopRLEDOffset} - red/angry \\
+\item {\tt TopBrLEDOffset} - the green bar LED near the top of the face \\
+\item Tail LEDs: {\tt TlRedLEDOffset}, {\tt TlBluLEDOffset} \\
+\end{QRitemize}
+ERS-220:
+\begin{QRitemize}
+\footnotesize
+\item {\tt FaceFrontLeftLEDOffset}, {\tt FaceFrontRightLEDOffset}, {\tt FaceCenterLeftLEDOffset}, {\tt FaceCenterRightLEDOffset} - blue, {\tt FaceBackLeftLEDOffset}, {\tt FaceBackRightLEDOffset} - red
+\item {\tt ModeLEDOffset} - mode indicator (back of the head - orange)
+\item {\tt BackLeft1LEDOffset}, {\tt BackLeft2LEDOffset}, {\tt BackLeft3LEDOffset}, {\tt BackRight3LEDOffset}, {\tt BackRight2LEDOffset}, {\tt BackRight1LEDOffset}
+\item {\tt TailLeftLEDOffset} (blue), {\tt TailCenterLEDOffset} (red), {\tt TailRightLEDOffset} (blue)
+\item {\tt FaceFrontALEDOffset} (blue), {\tt FaceFrontBLEDOffset} (blue), {\tt FaceFrontCLEDOffset} (red)
+\item {\tt RetractableHeadLEDOffset} - retractable head light
+\end{QRitemize}
+}{}
+
+\ifthenelse{\equal{\model}{ERS-220}}{}{\item {\tt EarOffset} - {\tt NumEarJoints} items}
+}\end{QRitemize}
+
+It happens that these joints can also be grouped by the {\em type} of joint, so there are additionally a few other offsets that can be used in order to loop across a group of joints:
+
+\begin{keylist}\small
+\item[PIDJointOffset] {\tt NumPIDJoints} items, servos using PID control \\
+\item[LegOffset] {\tt NumLegJoints} items, a subset of PID servos corresponding to the leg joints \\
+\item[LEDOffset] {\tt NumLEDs} items \\
+\item[BinJointOffset] {\tt NumBinJoints} items, solenoids, such as the ears (if any) which flip between two positions\\
+\item[NumOutputs] total number of outputs available
+\end{keylist}
+
+LEDs are often handled in groups to display patterns.  Some functions take an {\tt LEDBitMask\_t} parameter, which allows you to specify a set of LEDs in a single parameter.  
+For any given LED offset {\em foo}{\tt LEDOffset}, the corresponding bitmask constant is {\em foo}{\tt LEDMask}.  Alternatively, you could calculate the bitmask of {\em foo} by {\tt 1<<({\rm\em foo}-LEDOffset)}.
+
+\end{QRsubsection}
+
+\begin{QRsubsection}{Reference Frames}
+Every PID joint has an associated reference frame, with the {\em z} axis along the axis of rotation.  You can use the Output Offsets previously listed to refer to these reference frames.  However, there are a few additional reference frames you may wish to refer, which do not correspond to any particular joint:
+
+\begin{keylist}\small
+\item[BaseFrameOffset] body center, {\em x} forward, {\em y} Aibo's left, {\em z} up
+\item[PawFrameOffset] {\tt NumLegs} items, in the usual {\tt LegOrder\_t}, defines the reference frame of the passive ankle joint
+\item[CameraFrameOffset] The coordinate system used for vision, origin in the center of the image, {\em x} right, {\em y} down, {\em z} into the scene
+\ifthenelse{\equal{\model}{ERS-7}}{
+\item[NearIRFrameOffset, FarIRFrameOffset, ChestIRFrameOffset] {\em z} axis aligned with each IR beam
+}{
+\item[IRFrameOffset] {\em z} axis aligned with the IR beam
+}
+\end{keylist}
+\end{QRsubsection}
+
+\begin{QRsubsection}{Buttons}
+Primarily used with WorldState, i.e. {\tt state->buttons[{\rm\em x}]}.
+\ifthenelse{\equal{\model}{ERS-220}}{
+The antenna buttons (marked with a *) are ``pressure'' sensitive, but jump between threshold values (not a continuous response).
+}{
+Buttons marked with a * are ``pressure'' sensitive (range 0-1), the rest are boolean.
+}
+\ifthenelse{\equal{\model}{ERS-2xx}}{Buttons marked with a {\dag} are 220-specific.}{}
+
+\ifthenelse{\equal{\model}{ERS-210}}{
+\begin{tabular}{ll}
+\multicolumn{2}{l}{\small{\tt LFrPawOffset \ RFrPawOffset \ LBkPawOffset \ RBkPawOffset}} \\
+\small{\tt HeadFrButOffset}* & \small{\tt HeadBkButOffset}* \\
+\small{\tt ChinButOffset} & \small{\tt BackButOffset} %
+}{%
+\begin{tabular}{lll}
+}%
+\ifthenelse{\equal{\model}{ERS-7}}{%
+\small{\tt LFrPawOffset} & \small{\tt ChinButOffset} & \small{\tt FrontBackButOffset}*\\
+\small{\tt RFrPawOffset} & \small{\tt HeadButOffset}* & \small{\tt MiddleBackButOffset}*\\
+\small{\tt LBkPawOffset} & \small{\tt WirelessSwOffset} & \small{\tt RearBackButOffset}*\\
+\small{\tt RBkPawOffset} && %
+}{}%
+\ifthenelse{\equal{\model}{ERS-220}}{%
+\small{\tt LFrPawOffset} & \small{\tt ChinButOffset} & \small{\tt BackButOffset}\\
+\small{\tt RFrPawOffset} & \small{\tt HeadFrButOffset}* & \small{\tt TailLeftButOffset}\\
+\small{\tt LBkPawOffset} & \small{\tt HeadBkButOffset}* & \small{\tt TailCenterButOffset}\\
+\small{\tt RBkPawOffset} & & \small{\tt TailRightButOffset}%
+}{}%
+\ifthenelse{\equal{\model}{ERS-2xx}}{%
+\small{\tt LFrPawOffset} & \small{\tt ChinButOffset} & \small{\tt BackButOffset}\\
+\small{\tt RFrPawOffset} & \small{\tt HeadFrButOffset}* & \small{\tt TailLeftButOffset}\dag\\
+\small{\tt LBkPawOffset} & \small{\tt HeadBkButOffset}* & \small{\tt TailCenterButOffset}\dag\\
+\small{\tt RBkPawOffset} & & \small{\tt TailRightButOffset}\dag%
+}{}%
+\end{tabular}
+\end{QRsubsection}
+
+\vspace{-.5\lineheight}
+\begin{QRsubsection}{Sensors}
+Primarily used with WorldState, i.e. {\tt state->sensors[{\rm\em x}]}
+
+\begin{tabular}{lll}
+\ifthenelse{\equal{\model}{ERS-7}}{%
+\small{\tt NearIRDistOffset} & \small{\tt BAccelOffset} & \small{\tt PowerRemainOffset} \\
+\small{\tt FarIRDistOffset} & \small{\tt LAccelOffset} & \small{\tt PowerThermoOffset} \\
+\small{\tt ChestIRDistOffset} & \small{\tt DAccelOffset} &\small{\tt PowerCapacityOffset} \\
+& & \small{\tt PowerVoltageOffset}, \\
+& & \small{\tt PowerCurrentOffset} %
+}{}%
+\ifthenelse{\equal{\model}{ERS-210}}{%
+\small{\tt BAccelOffset} & \small{\tt IRDistOffset} & \small{\tt PowerCapacityOffset} \\
+\small{\tt LAccelOffset} & \small{\tt PowerRemainOffset} & \small{\tt PowerVoltageOffset} \\
+\small{\tt DAccelOffset} & \small{\tt PowerThermoOffset} &\small{\tt PowerCurrentOffset} %
+}{}%
+\ifthenelse{\equal{\model}{ERS-220}}{%
+\small{\tt BAccelOffset} & \small{\tt IRDistOffset} & \small{\tt PowerCapacityOffset} \\
+\small{\tt LAccelOffset} & \small{\tt PowerRemainOffset} & \small{\tt PowerVoltageOffset} \\
+\small{\tt DAccelOffset} & \small{\tt PowerThermoOffset} &\small{\tt PowerCurrentOffset} %
+}{}%
+\ifthenelse{\equal{\model}{ERS-2xx}}{%
+\small{\tt BAccelOffset} & \small{\tt IRDistOffset} & \small{\tt PowerCapacityOffset} \\
+\small{\tt LAccelOffset} & \small{\tt PowerRemainOffset} & \small{\tt PowerVoltageOffset} \\
+\small{\tt DAccelOffset} & \small{\tt PowerThermoOffset} &\small{\tt PowerCurrentOffset} %
+}{}%
+\end{tabular}
+\end{QRsubsection}
+
+
+\ifthenelse{\equal{\model}{ERS-7}}{
+\vspace{-1.5\lineheight}
+}{
+\vspace{-.5\lineheight}
+}
+\begin{QRsubsection}{Limits}
+{\tt outputRanges} defines the range of values available for each output.  {\tt MaxOutputSpeed} defines the maximum recommended speed for each output (0 indicates no limit, e.g LEDs).
+%{\tt outputRanges[NumOutputs][{\rm\{}MinRange,MaxRange{\rm\}}]} defines the range of values available for each output.  {\tt MaxOutputSpeed[NumOutputs]} defines the maximum recommended speed for each output (0 indicates no limit, e.g LEDs).
+\end{QRsubsection}
+\end{QRsection}
+
+
+
+\vspace{.5\lineheight}
+\begin{QRsection}{Development}
+\begin{QRsubsection}{Events}
+These constants are defined by the {\tt EventBase::EventGeneratorID\_t} enumeration.
+For more information about the events sent by each generator, see {\tt EventBase} documentation.  Each of these constants will need to be prefixed with {\tt EventBase::}.
+\vspace{-1\lineheight}
+\setlength{\columnsep}{30pt}
+\flushbottom
+\begin{multicols}{3}\small
+\input{EventGenerators}
+\end{multicols}
+\vspace{-1\lineheight}
+The value and meaning of the event's `source' field is defined by its generator, but the `type' field is restricted to one of {\tt activateETID}, {\tt statusETID}, or {\tt deactivateETID}.
+\end{QRsubsection}
+\end{QRsection}
+
+\end{multicols}
+% Stop your text
+\end{document}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/VisionQuickReference/Makefile ./docs/VisionQuickReference/Makefile
--- ../Tekkotsu_2.4.1/docs/VisionQuickReference/Makefile	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/VisionQuickReference/Makefile	2006-01-26 22:41:37.000000000 -0500
@@ -0,0 +1,31 @@
+TEKKOTSU_ROOT:=../..
+
+VERSION_NUMBER_SRC:=$(TEKKOTSU_ROOT)/docs/doxygencfg
+MODELS:=ERS7
+
+all: $(addsuffix .pdf,$(addprefix VisionQuickReference-,$(MODELS)))
+.PHONY: all clean
+
+VisionQuickReference-%.pdf : VisionQuickReference.tex VersionNumber.tex vision.pdf
+	@MODEL=`echo $* | sed 's/\([A-Z]\)\([0-9]\)/\1-\2/g'`; \
+	echo "\newcommand{\model}{$$MODEL}" > ModelSpecific.tex; \
+	echo "\newcommand{\condensedmodel}{$*}" >> ModelSpecific.tex; \
+	echo "\newcommand{\release}{\input{VersionNumber}}" >> ModelSpecific.tex;
+	pdflatex -interaction errorstopmode $< < /dev/null
+	mv $(basename $<).pdf $@
+
+VersionNumber.tex : $(VERSION_NUMBER_SRC)
+	sed -n 's@PROJECT_NUMBER.*=[ 	]*\([0-9.]*\)@\1@p' $(VERSION_NUMBER_SRC) > $@
+
+ifeq ($(findstring Darwin,$(shell uname)),)
+vision.pdf: vision.dot
+	dot -Tps2 $^ | ps2pdf - $@
+else
+vision.pdf: vision.dot
+	dot -Tepdf $^ > $@
+endif
+
+clean:
+	rm -f *~ *.aux *.log *.out vision.pdf
+
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/VisionQuickReference/VisionQuickReference.tex ./docs/VisionQuickReference/VisionQuickReference.tex
--- ../Tekkotsu_2.4.1/docs/VisionQuickReference/VisionQuickReference.tex	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/VisionQuickReference/VisionQuickReference.tex	2006-01-26 22:41:38.000000000 -0500
@@ -0,0 +1,212 @@
+\documentclass[10pt]{article}
+\usepackage{amssymb}
+\usepackage{ifthen}
+\usepackage{multicol}
+\usepackage{url}
+\ifx\pdfoutput\undefined
+\usepackage[hypertex]{hyperref}
+%\usepackage[ps2pdf,bookmarks=true]{hyperref}
+\else
+\usepackage[pdftex,hypertexnames=false]{hyperref}
+\fi
+\ifx\pdfoutput\undefined
+\usepackage{graphicx}
+\else
+\usepackage[pdftex]{graphicx}
+\fi
+
+\usepackage{pslatex}
+
+\hypersetup{
+  pdfauthor   = {Ethan Tira-Thompson},
+  pdftitle    = {Tekkotsu Quick Reference}
+}
+%  pdfkeywords = {},
+%  pdfsubject  = {Seminar Title, SS/WS 20xx RWTH Aachen University},
+%  pdfcreator  = {LaTeX with hyperref package},
+%  pdfproducer = {dvips + ps2pdf}
+
+\topmargin -.5in
+\oddsidemargin -.25in
+\evensidemargin -.25in
+\textwidth 7in
+\textheight 10in
+\headsep 0pt
+\headheight 0pt
+\topskip 0pt
+\footskip .25in
+
+\pagestyle{empty}
+\parskip 7.2pt
+%\renewcommand{\baselinestretch}{1.5}
+\parindent 0pt
+\setlength{\fboxsep}{8pt}
+\setlength{\columnsep}{.25in}
+
+%\setlength{\floatsep}{0in}
+%\setlength{\textfloatsep}{0in}
+%\setlength{\intextsep}{0in}
+%\setlength{\dbltextfloatsep}{0in}
+%\setlength{\dblfloatsep}{0in}
+%\setlength{\abovedisplayskip}{0in}
+%\setlength{\topsep}{0in}
+\setlength{\partopsep}{-.2in}
+%\setlength{\parskip}{0in}
+
+%\renewcommand{\ttdefault}{cmtt}
+
+\input{ModelSpecific}
+
+\renewcommand{\labelitemi}{{\tiny $\blacklozenge$}}
+\newlength{\QRsubindent}
+
+\newenvironment{keylist}
+	{\begin{list}{}{
+		\flushleft
+		\providecommand{\keyliststyle}{\tt}
+		\renewcommand{\makelabel}[1]{\labelitemi\ {\keyliststyle ##1} - }
+		\setlength{\QRsubindent}{6pt}
+		\setlength{\itemsep}{2pt}
+		\setlength{\parsep}{0pt}
+		\setlength{\labelsep}{0pt}
+		\setlength{\leftmargin}{12pt}
+		\setlength{\labelwidth}{9pt}
+		\setlength{\parindent}{0pt}
+		\setlength{\listparindent}{0pt}}}
+	{\end{list}}
+
+\newenvironment{keyenum}
+	{\begin{list}{}{
+		\flushleft
+		\providecommand{\keyliststyle}{\tt}
+		\renewcommand{\makelabel}[1]{\labelitemi\ {\keyliststyle ##1} - }
+		\setlength{\QRsubindent}{6pt}
+		\setlength{\itemsep}{2pt}
+		\setlength{\parsep}{0pt}
+		\setlength{\labelsep}{0pt}
+		\setlength{\leftmargin}{12pt}
+		\setlength{\labelwidth}{9pt}
+		\setlength{\parindent}{0pt}
+		\setlength{\listparindent}{0pt}}}
+	{\end{list}}
+
+\newenvironment{QRitemize}
+	{\begin{list}{}{
+		\flushleft
+		\providecommand{\itemstyle}{\tt}
+		\renewcommand{\makelabel}[1]{\labelitemi\ {\itemstyle ##1}}
+		\setlength{\QRsubindent}{6pt}
+		\setlength{\itemsep}{2pt}
+		\setlength{\parsep}{0pt}
+		\setlength{\labelsep}{0pt}
+		\setlength{\leftmargin}{12pt}
+		\setlength{\labelwidth}{9pt}
+		\setlength{\parindent}{0pt}
+		\setlength{\listparindent}{0pt}}}
+	{\end{list}}
+
+\makeatletter
+\renewcommand{\section}[1]{\@startsection%
+	{section}{1}{-10pt}{6pt}{0pt}{\Large\bf\hspace{6pt}\rule[.2\lineheight]{24pt}{2pt}\hspace{-30pt}}%
+	{\hspace{28pt}#1}%
+}
+\renewcommand{\subsection}[1]{\@startsection{subsection}{2}{0pt}{3pt}{0.01pt}{\large\bf}{#1}}
+\renewcommand{\subsubsection}[1]{\@startsection{subsubsection}{3}{0pt}{0pt}{0.01pt}{\bf}{#1}}
+\makeatother
+
+\newenvironment{QRsection}[1]
+	{\section{#1}\hspace{6pt}\rule[.2\lineheight]{72pt}{2pt}}
+	{}
+
+\newenvironment{QRsubsection}[1]
+	{\subsection{#1}}
+	{}
+
+\title{Tekkotsu Quick Reference}
+\date{\model, Tekkotsu \release}
+\author{Ethan Tira-Thompson}
+
+\renewcommand{\maketitle}{\begin{center}%
+\large{\huge Tekkotsu Quick Reference} \vspace{6pt} \\%
+\model, Tekkotsu \release \vspace{6pt} \\%
+Ethan Tira-Thompson \vspace{12pt}%
+\end{center}
+}
+
+\begin{document}         
+% Start your text
+
+
+\raggedcolumns
+\begin{multicols}{2}[\maketitle]
+\raggedcolumns
+
+
+\begin{QRsection}{Vision Pipeline}
+
+The vision system is organized into pipeline stages.  Each stage uses the event system to notify following stages when new results are available.  This provides behaviors access to all intermediary results and allows branches in the pipeline to avoid recomputation.  Also, results are lazily evaluated, so only minimal computations are performed.
+
+Each stage provides the current image at a number of resolution {\em layers}, and most stages provide several different {\em channels} of related information.  (e.g. the raw camera generator has several color channels, and the segmented color generator can apply a different threshold settings per channel.)
+
+\begin{QRsubsection}{Included Stages}
+\begin{center}
+\includegraphics*[width=3in]{vision}
+\end{center}
+
+Generator IDs:
+\begin{keyenum}\small
+\item[visRawCamera\{EGID,SID\}] original camera frame
+\item[visInterleave\{EGID,SID\}] reorders memory layout to interleave by pixel
+\item[visJPEGEGID] two different sources:
+\begin{keylist}
+\item[visGrayscaleJPEGSID] color channels individually compressed
+\item[visColorJPEGSID] combines color channels into a single compressed channel 
+\end{keylist}
+\item[visSegment\{EGID,SID\}] produces color segmented images
+\item[visRLE\{EGID,SID\}] Run-Length encoded images
+\item[visRegion\{EGID,SID\}] Gathers region statistics
+\item[BallDetectionGenerator] A very general detector, finds largest blob which meets simple size and density criteria.
+\end{keyenum}
+\end{QRsubsection}
+
+\begin{QRsubsection}{Image Channels}
+The `raw' stages provide 6 channels for each image, defined in {\tt RawCameraGenerator}:
+\begin{keylist}\small
+\item[CHAN\_Y] Y (intensity) channel
+\item[CHAN\_U] Cr (approx. pink-red-yellow) channel
+\item[CHAN\_V] Cb (approx. blue-green-yellow) channel
+\item[CHAN\_Y\_DY] vertical derivative of Y channel (aka `LH')
+\item[CHAN\_Y\_DX] horizontal derivative of Y channel (aka `HL')
+\item[CHAN\_Y\_DXDY] vert. and horiz. derivatives of Y channel (aka `HH')
+\end{keylist}
+
+The Color JPEG stage provides a single channel, containing a color JPEG image.
+
+The `segmented' stages provide a separate channel for each of the threshold files specified in {\tt tekkotsu.cfg}.
+\end{QRsubsection}
+
+\begin{QRsubsection}{Resolution Layers}
+\begin{keylist}\small
+\item[doubleLayer]    416 x 320 (involves computation recombining the Y derivatives -- but only simple upsampling for the color channels)
+\item[fullLayer]     208 x 160 (*)
+\item[halfLayer]     104 x 80 (*)
+\item[quarterLayer]  52 x 40 (*)
+\item[eighthLayer]    26 x 20
+\item[sixteenthLayer] 13 x 10
+\end{keylist}
+* these layers are directly provided by the hardware.  Smaller layers are provided by adjusting the increment parameter.
+\end{QRsubsection}
+
+\begin{QRsubsection}{Extending the Pipeline}
+{\tt Shared/ProjectInterface.h} specifies constants for global access to each of the pipeline stages.  Your project's {\tt StartupBehavior\_SetupVision.cc} defines the values used for each of the stages, allowing you to add new stages or replace those provided by the framework.
+\end{QRsubsection}
+
+\begin{QRsubsection}{Image Access}
+Each stage sends {\tt FilterBankEvent}s when new results are available.  From this event, or directly on a pipeline stage, {\tt getImage(}{\em layer}{\tt ,}{\em channel}{\tt )} returns a pointer to the base of the image.  {\tt getWidth(}{\em layer}{\tt )}, {\tt getHeight(}{\em layer}{\tt )} return the layer's dimensions.  {\tt getStride(}{\em layer}{\tt )} will return the vertical increment, {\tt getIncrement(}{\em layer}{\tt )} returns the horizontal increment.  (Different stages may store pixels in different types of interleaving)
+\end{QRsubsection}
+\end{QRsection}
+
+\end{multicols}
+
+% Stop your text
+\end{document}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/VisionQuickReference/vision.dot ./docs/VisionQuickReference/vision.dot
--- ../Tekkotsu_2.4.1/docs/VisionQuickReference/vision.dot	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/VisionQuickReference/vision.dot	2006-01-26 22:41:39.000000000 -0500
@@ -0,0 +1,13 @@
+digraph vision {
+	graph [ ranksep=".3", rankdir=LR, ordering=out ] ;
+	raw [ label="Raw\nImage" ] ;
+	inter [ label="Interleaved" ] ;
+	color [ label="Color\nJPEG" ] ;
+	gray [ label="Gray\nJPEG" ] ;
+	seg [ label="Segmented" ] ;
+	ball [ label="\"Ball\"\nDetection" ] ;
+	
+	raw -> gray ;
+	raw -> inter -> color ;
+	raw -> seg -> RLE -> Regions -> ball ;
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/benchmarks/profilerun_ERS210A_3.0.txt ./docs/benchmarks/profilerun_ERS210A_3.0.txt
--- ../Tekkotsu_2.4.1/docs/benchmarks/profilerun_ERS210A_3.0.txt	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/benchmarks/profilerun_ERS210A_3.0.txt	2006-09-28 18:07:02.000000000 -0400
@@ -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.601371 to 302.168316
+ReadySendJoints():
+        2196 calls
+        0.501699 ms avg
+        0.382626 ms exp.avg
+        0.002823 ms avg child time (0.500000%)
+        128.243160 ms avg inter (7.797687 fps)
+        127.816780 ms exp.avg (7.823699 fps)
+        Exec: 0 0 1752 442 0 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 
+        Inter: 0 0 1 2 0 0 0 0 0 0 1775 415 0 0 0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+GotAudio():
+        8770 calls
+        1.452230 ms avg
+        1.588324 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        32.079751 ms avg inter (31.172312 fps)
+        31.765759 ms exp.avg (31.480438 fps)
+        Exec: 0 0 1561 6975 234 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 3 7019 1744 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+PowerEvent():
+        28 calls
+        25.999857 ms avg
+        9.176179 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        9507.409464 ms avg inter (0.105181 fps)
+        11222.237305 ms exp.avg (0.089109 fps)
+        Exec: 0 1 25 1 0 0 0 0 0 0 0 0 0 0 0 0 1 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 1 0 0 0 0 11 0 0 0 2 0 2 0 3 0 8 
+GotImage():
+        6995 calls
+        10.231059 ms avg
+        10.102356 ms exp.avg
+        8.278227 ms avg child time (80.900000%)
+        40.127059 ms avg inter (24.920839 fps)
+        39.834362 ms exp.avg (25.103954 fps)
+        Exec: 0 0 0 8 0 5222 1765 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 2 0 495 6496 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+BallDetection::processEvent():
+        6992 calls
+        8.281850 ms avg
+        8.298972 ms exp.avg
+        7.460258 ms avg child time (90.000000%)
+        40.058718 ms avg inter (24.963355 fps)
+        39.874828 ms exp.avg (25.078478 fps)
+        Exec: 3 1 1 0 0 6720 267 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 4 0 0 0 0 1 422 6564 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(...):
+        6987 calls
+        7.465592 ms avg
+        7.413508 ms exp.avg
+        5.035603 ms avg child time (67.400000%)
+        40.098317 ms avg inter (24.938702 fps)
+        39.838959 ms exp.avg (25.101057 fps)
+        Exec: 0 0 0 0 308 6610 69 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 425 6561 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(...):
+        6987 calls
+        5.035603 ms avg
+        4.955937 ms exp.avg
+        3.180999 ms avg child time (63.100000%)
+        40.099044 ms avg inter (24.938250 fps)
+        39.860821 ms exp.avg (25.087290 fps)
+        Exec: 0 0 0 0 5068 1918 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 0 0 0 0 0 426 6560 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(...):
+        6987 calls
+        3.180999 ms avg
+        3.186928 ms exp.avg
+        0.071209 ms avg child time (2.200000%)
+        40.095975 ms avg inter (24.940159 fps)
+        39.861107 ms exp.avg (25.087112 fps)
+        Exec: 0 0 0 0 6981 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 0 0 426 6560 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(...):
+        20961 calls
+        0.023736 ms avg
+        0.007952 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        13.355915 ms avg inter (74.873191 fps)
+        11.085652 ms exp.avg (90.206688 fps)
+        Exec: 13352 6979 576 54 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 13001 884 89 0 0 0 427 6559 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: 19.987377 to 302.180477
+ReadySendJoints():
+        8786 calls
+        2.196028 ms avg
+        2.123986 ms exp.avg
+        0.000587 ms avg child time (0.000000%)
+        32.048916 ms avg inter (31.202303 fps)
+        31.944227 ms exp.avg (31.304562 fps)
+        Exec: 0 0 0 5320 3449 3 0 0 0 13 1 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 1 2 2 8759 6 14 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+GotSensorFrame():
+        8796 calls
+        2.142896 ms avg
+        2.200585 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        32.006505 ms avg inter (31.243649 fps)
+        31.908367 ms exp.avg (31.339743 fps)
+        Exec: 0 0 0 6265 2527 2 0 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 
+        Inter: 0 0 0 2 6 10 9 8747 7 8 6 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, 
+
+~~~ Sound: ~~~
+Profiling information since: 19.579342 to 302.184884
+doSendSound():
+        50 calls
+        1.139560 ms avg
+        1.494666 ms exp.avg
+        0.031040 ms avg child time (2.700000%)
+        5634.143620 ms avg inter (0.177489 fps)
+        35649.140625 ms exp.avg (0.028051 fps)
+        Exec: 2 1 12 30 5 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 0 0 1 0 1 41 3 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_2.4.1/docs/benchmarks/profilerun_ERS7_2.4.txt ./docs/benchmarks/profilerun_ERS7_2.4.txt
--- ../Tekkotsu_2.4.1/docs/benchmarks/profilerun_ERS7_2.4.txt	2005-08-09 23:35:14.000000000 -0400
+++ ./docs/benchmarks/profilerun_ERS7_2.4.txt	2006-09-28 18:07:02.000000000 -0400
@@ -1,5 +1,5 @@
 Setup:
-  Default build for ERS-2xx (TGT_ERS2xx)
+  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)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/benchmarks/profilerun_ERS7_3.0.txt ./docs/benchmarks/profilerun_ERS7_3.0.txt
--- ../Tekkotsu_2.4.1/docs/benchmarks/profilerun_ERS7_3.0.txt	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/benchmarks/profilerun_ERS7_3.0.txt	2006-09-28 18:07:02.000000000 -0400
@@ -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: 17.018763 to 298.058755
+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():
+        8756 calls
+        0.128307 ms avg
+        0.127381 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        32.017760 ms avg inter (31.232666 fps)
+        32.020893 ms exp.avg (31.229610 fps)
+        Exec: 0 4148 4607 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 
+        Inter: 0 0 0 1 0 1 0 8750 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():
+        8397 calls
+        5.166750 ms avg
+        5.118693 ms exp.avg
+        4.348183 ms avg child time (84.100000%)
+        33.390237 ms avg inter (29.948874 fps)
+        33.542843 ms exp.avg (29.812620 fps)
+        Exec: 0 7 20 0 6167 2202 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 0 1 0 1 1 6956 1435 0 0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+PowerEvent():
+        20 calls
+        12.926850 ms avg
+        11.779295 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        13350.264700 ms avg inter (0.074905 fps)
+        12971.545898 ms exp.avg (0.077092 fps)
+        Exec: 0 18 1 0 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 1 0 0 0 0 0 0 1 0 1 16 
+BallDetection::processEvent():
+        8375 calls
+        4.359631 ms avg
+        4.237320 ms exp.avg
+        4.092209 ms avg child time (93.800000%)
+        33.335123 ms avg inter (29.998389 fps)
+        33.515694 ms exp.avg (29.836767 fps)
+        Exec: 4 0 1 0 6263 2107 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 2 1 6937 1430 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(...):
+        8370 calls
+        4.094652 ms avg
+        3.987980 ms exp.avg
+        2.735832 ms avg child time (66.800000%)
+        33.354581 ms avg inter (29.980890 fps)
+        33.516983 ms exp.avg (29.835619 fps)
+        Exec: 0 0 0 0 6273 2097 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 1 6937 1430 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(...):
+        8370 calls
+        2.735832 ms avg
+        2.642987 ms exp.avg
+        2.018154 ms avg child time (73.700000%)
+        33.354494 ms avg inter (29.980968 fps)
+        33.521011 ms exp.avg (29.832035 fps)
+        Exec: 0 0 0 0 8365 5 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 1 6937 1430 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(...):
+        8370 calls
+        2.018154 ms avg
+        1.927372 ms exp.avg
+        0.018810 ms avg child time (0.900000%)
+        33.354653 ms avg inter (29.980825 fps)
+        33.521385 ms exp.avg (29.831703 fps)
+        Exec: 0 0 0 6283 2085 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 
+        Inter: 0 0 0 0 0 1 1 6937 1430 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(...):
+        25110 calls
+        0.006270 ms avg
+        0.003734 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        11.116241 ms avg inter (89.958465 fps)
+        9.354381 ms exp.avg (106.901787 fps)
+        Exec: 22170 2805 134 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 
+        Inter: 8038 8337 364 1 0 1 1 6937 1430 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: 17.404824 to 298.061958
+ReadySendJoints():
+        8745 calls
+        1.099006 ms avg
+        0.936845 ms exp.avg
+        0.000356 ms avg child time (0.000000%)
+        32.070014 ms avg inter (31.181776 fps)
+        31.942242 ms exp.avg (31.306507 fps)
+        Exec: 0 0 17 8694 16 2 1 0 0 15 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 1 0 1 8724 3 14 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+GotSensorFrame():
+        8756 calls
+        0.811839 ms avg
+        0.814478 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        32.017589 ms avg inter (31.232833 fps)
+        31.944380 ms exp.avg (31.304411 fps)
+        Exec: 0 0 198 8553 5 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 8 8 6 7 8709 2 4 11 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, 
+
+~~~ Sound: ~~~
+Profiling information since: 17.017888 to 298.062724
+doSendSound():
+        50 calls
+        0.588880 ms avg
+        0.873355 ms exp.avg
+        0.025740 ms avg child time (4.300000%)
+        5609.940660 ms avg inter (0.178255 fps)
+        35496.847656 ms exp.avg (0.028172 fps)
+        Exec: 3 2 27 17 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 
+        Inter: 0 1 0 1 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_2.4.1/docs/builddocs ./docs/builddocs
--- ../Tekkotsu_2.4.1/docs/builddocs	2005-08-11 16:59:51.000000000 -0400
+++ ./docs/builddocs	2006-02-01 16:08:58.000000000 -0500
@@ -15,7 +15,7 @@
 searchengine="SEARCHENGINE = NO";
 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";
+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";
 
 while [ $# -gt 0 ] ; do
 	case $1 in
@@ -46,6 +46,7 @@
 echo $searchengine >> doxygenbuildcfg;
 echo "GENERATE_TAGFILE = generated/tekkotsu.tag" >> doxygenbuildcfg
 echo "TAGFILES += generated/roboop.tag=roboop generated/newmat.tag=newmat" >> doxygenbuildcfg
+#generated/dualcoding.tag=dualcoding
 
 cancelupdate=0;
 if [ $update -ne 0 -a ! -d "$target" ] ; then
@@ -55,9 +56,8 @@
 
 if [ $update -eq 0 -o $clean -ne 0 ] ; then
 	printf "Cleaning previous build of \`\`$target''...";
-	rm -rf ${target}/*.html;
-	rm -rf ${target}/*.png;
-	rm -rf ${target}/*;
+	rm -rf ${target};
+	rm -rf generated/*.tag;
 	printf "done\n";
 	if [ $update -ne 0 ] ; then
 		update=0;
@@ -71,9 +71,16 @@
 printf "Building documentation for \`\`$input'' ...";
 mv doxygenbuildcfg doxygenbuildcfg.tmp;
 touch doxygenbuildcfg;
+if [ -f "generated/tekkotsu.tag" ] ; then
+echo "TAGFILES += generated/tekkotsu.tag=.." >> 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
 mv doxygenbuildcfg.tmp doxygenbuildcfg
 doxygen doxygencfg ;
 printf "done\n";
@@ -84,7 +91,7 @@
 	printf "done\n";
 fi;
 
-if [ $update -eq 0 ] ; then
+#if [ $update -eq 0 ] ; then
 	printf "Copying additional documentation..."
 	for x in ${src}/docs/html/* ; do
 		printf "${x}, "
@@ -104,16 +111,16 @@
 	cp -f "$src"/docs/html/.htaccess $target ;
 #	rm -rf $target/CVS ;
 	printf "done\n"
-else
-	if [ $tree -eq 0 ] ; then
-		printf "Replacing generated index.html with docs/html/index.html..."
-		cp -f "$src"/docs/html/index.html $target ;
-	else
-		printf "Replacing generated main.html with docs/html/index.html..."
-		cp -f "$src"/docs/html/index.html $target/main.html ;
-	fi;
-	printf "done\n"
-fi;
+#else
+#	if [ $tree -eq 0 ] ; then
+#		printf "Replacing generated index.html with docs/html/index.html..."
+#		cp -f "$src"/docs/html/index.html $target ;
+#	else
+#		printf "Replacing generated main.html with docs/html/index.html..."
+#		cp -f "$src"/docs/html/index.html $target/main.html ;
+#	fi;
+#	printf "done\n"
+#fi;
 
 if [ $tree -ne 0 ] ; then
 	printf "Adding favicon tag to index.html..."
@@ -122,4 +129,4 @@
 	printf "done\n"
 fi;
 
-exit 0;
\ No newline at end of file
+exit 0;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/doxygencfg ./docs/doxygencfg
--- ../Tekkotsu_2.4.1/docs/doxygencfg	2005-08-16 14:57:19.000000000 -0400
+++ ./docs/doxygencfg	2006-10-03 23:16:57.000000000 -0400
@@ -1,4 +1,4 @@
-# Doxyfile 1.4.4
+# Doxyfile 1.4.7
 
 # This file describes the settings to be used by the documentation system
 # doxygen (www.doxygen.org) for a project
@@ -23,7 +23,7 @@
 # This could be handy for archiving the generated documentation or 
 # if some version control system is used.
 
-PROJECT_NUMBER         = 2.4.1
+PROJECT_NUMBER         = 3.0
 
 # The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) 
 # base path where the generated documentation will be put. 
@@ -163,13 +163,6 @@
 
 INHERIT_DOCS           = YES
 
-# 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 
-# all members of a group must be documented explicitly.
-
-DISTRIBUTE_GROUP_DOC   = YES
-
 # If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce 
 # a new page for each member. If set to NO, the documentation of a member will 
 # be part of the file/class/namespace that contains it.
@@ -197,13 +190,29 @@
 
 OPTIMIZE_OUTPUT_FOR_C  = NO
 
-# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java sources 
-# only. Doxygen will then generate output that is more tailored for Java. 
+# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java 
+# sources only. Doxygen will then generate output that is more tailored for Java. 
 # For instance, namespaces will be presented as packages, qualified scopes 
 # will look different, etc.
 
 OPTIMIZE_OUTPUT_JAVA   = NO
 
+# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want to 
+# include (a tag file for) the STL sources as input, then you should 
+# set this tag to YES in order to let doxygen match functions declarations and 
+# definitions whose arguments contain STL classes (e.g. func(std::string); v.s. 
+# func(std::string) {}). This also make the inheritance and collaboration 
+# diagrams that involve STL classes more complete and accurate.
+
+BUILTIN_STL_SUPPORT    = YES
+
+# 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 
+# all members of a group must be documented explicitly.
+
+DISTRIBUTE_GROUP_DOC   = YES
+
 # Set the SUBGROUPING tag to YES (the default) to allow class member groups of 
 # the same type (for instance a group of public functions) to be put as a 
 # subgroup of that type (e.g. under the Public Functions section). Set it to 
@@ -380,7 +389,7 @@
 
 # If the sources in your project are distributed over multiple directories 
 # then setting the SHOW_DIRECTORIES tag to YES will show the directory hierarchy 
-# in the documentation. The default is YES.
+# in the documentation. The default is NO.
 
 SHOW_DIRECTORIES       = YES
 
@@ -389,10 +398,10 @@
 # version control system). Doxygen will invoke the program by executing (via 
 # popen()) the command <command> <input-file>, where <command> is the value of 
 # the FILE_VERSION_FILTER tag, and <input-file> is the name of an input file 
-# provided by doxygen. Whatever the progam writes to standard output 
+# provided by doxygen. Whatever the program writes to standard output 
 # is used as the file version. See the manual for examples.
 
-FILE_VERSION_FILTER    = 
+FILE_VERSION_FILTER    = "/bin/sh ../tools/versionFilter"
 
 #---------------------------------------------------------------------------
 # configuration options related to warning and progress messages
@@ -462,7 +471,7 @@
 # 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
+# *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.py
 
 FILE_PATTERNS          = 
 
@@ -497,7 +506,8 @@
                          */Motion/roboop/* \
                          */project/* \
                          */local/* \
-                         */aperios/*
+                         */aperios/* \
+                         */Behaviors/Demos/*
 
 # The EXAMPLE_PATH tag can be used to specify one or more files or 
 # directories that contain example code fragments that are included (see 
@@ -584,6 +594,13 @@
 
 REFERENCES_RELATION    = NO
 
+# If the REFERENCES_LINK_SOURCE tag is set to YES (the default)
+# and SOURCE_BROWSER tag is set to YES, then the hyperlinks from
+# functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will
+# link to the source code.  Otherwise they will link to the documentstion.
+
+REFERENCES_LINK_SOURCE = YES
+
 # If the USE_HTAGS tag is set to YES then the references to source code 
 # will point to the HTML generated by the htags(1) tool instead of doxygen 
 # built-in source browser. The htags tool is part of GNU's global source 
@@ -733,7 +750,7 @@
 # used to set the initial width (in pixels) of the frame in which the tree 
 # is shown.
 
-TREEVIEW_WIDTH         = 210
+TREEVIEW_WIDTH         = 200
 
 #---------------------------------------------------------------------------
 # configuration options related to the LaTeX output
@@ -980,7 +997,7 @@
 
 # If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES 
 # then the macro expansion is limited to the macros specified with the 
-# PREDEFINED and EXPAND_AS_PREDEFINED tags.
+# PREDEFINED and EXPAND_AS_DEFINED tags.
 
 EXPAND_ONLY_PREDEF     = YES
 
@@ -1010,16 +1027,22 @@
 # undefined via #undef or recursively expanded use the := operator 
 # instead of the = operator.
 
-PREDEFINED             = DEBUG \
+PREDEFINED             = __cplusplus \
+                         DEBUG \
                          PLATFORM_APERIOS \
-                         TGT_ERS7
+                         TGT_ERS7 \
+                         __DOXYGEN__
 
 # If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then 
 # this tag can be used to specify a list of macro names that should be expanded. 
 # The macro definition that is found in the sources will be used. 
 # Use the PREDEFINED tag if you want to use a different macro definition.
 
-EXPAND_AS_DEFINED      = 
+EXPAND_AS_DEFINED      = PLIST_CLONE_ABS \
+                         PLIST_CLONE_DEF \
+                         PLIST_CLONE_IMP \
+                         PLIST_CLONE_IMPT \
+                         PLIST_OBJECT_SPECIALIZATION
 
 # 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 
@@ -1152,6 +1175,14 @@
 
 CALL_GRAPH             = NO
 
+# If the CALLER_GRAPH 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 
+# functions only using the \callergraph command.
+
+CALLER_GRAPH           = NO
+
 # If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen 
 # will graphical hierarchy of all classes instead of a textual one.
 
@@ -1222,7 +1253,7 @@
 # makes dot run faster, but since only newer versions of dot (>1.8.10) 
 # support this, this feature is disabled by default.
 
-DOT_MULTI_TARGETS      = NO
+DOT_MULTI_TARGETS      = YES
 
 # If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will 
 # generate a legend page explaining the meaning of the various boxes and 
@@ -1234,7 +1265,7 @@
 # remove the intermediate dot files that are used to generate 
 # the various graphs.
 
-DOT_CLEANUP            = YES
+DOT_CLEANUP            = NO
 
 #---------------------------------------------------------------------------
 # Configuration::additions related to the search engine   
@@ -1246,6 +1277,7 @@
 #builddocs will set this in doxygenbuildcfg
 #SEARCHENGINE           = YES
 
+
 #---------------------------------------------------------------------------
 # Custom inclusions - doxygenbuildcfg is created by the builddocs script
 #---------------------------------------------------------------------------
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/doxygenfoot.html ./docs/doxygenfoot.html
--- ../Tekkotsu_2.4.1/docs/doxygenfoot.html	2004-02-09 20:47:08.000000000 -0500
+++ ./docs/doxygenfoot.html	2006-02-01 16:08:59.000000000 -0500
@@ -33,12 +33,12 @@
 						navigator.appVersion.charAt(0) == "2") {NS2Ch=1}
 						if (NS2Ch == 0) {
 						r="size="+s+"&colors="+c+"&referer="+f+"&java="+j+"&stamp="+(new Date()).getTime()+""
-						pr("<IMG BORDER=0 width=16 height=16 align=\"middle\" SRC=\"http://aibo2.boltz.cs.cmu.edu/head.gif?"+r+"\">")}
+						pr("<IMG BORDER=0 width=16 height=16 align=\"middle\" SRC=\"http://aibo4.boltz.cs.cmu.edu/head.gif?"+r+"\">")}
 						//-->
 					</script> 
 					
 					<noscript>
-						<img src="http://aibo2.boltz.cs.cmu.edu/head.gif" border="0" width=16 height=16 align="middle">
+						<img src="http://aibo4.boltz.cs.cmu.edu/head.gif" border="0" width=16 height=16 align="middle">
 					</noscript>
 				</td>
 			</tr>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/doxygenhead.html ./docs/doxygenhead.html
--- ../Tekkotsu_2.4.1/docs/doxygenhead.html	2005-08-12 14:51:53.000000000 -0400
+++ ./docs/doxygenhead.html	2006-09-16 12:09:27.000000000 -0400
@@ -4,6 +4,7 @@
 		<meta http-equiv="Content-Type" content="text/html;charset=iso-8859-1">
 		<title>$title</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">
 		<link type="text/css" rel="stylesheet" href="doxygen-override.css">
@@ -17,7 +18,7 @@
 					 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>
+					<!-- #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);"><br></td>
@@ -33,7 +34,7 @@
 				</tr>
 			</tbody>
 		</table>
-<table style="text-align: left; margin-left: auto; margin-right: auto; width: 750px;" border="0" cellspacing="2" cellpadding="2">
+<table style="text-align: left; margin-left: auto; margin-right: auto; width: 725px;" border="0" cellspacing="2" cellpadding="2">
   <tbody>
     <tr>
-      <td style="vertical-align: top;">
\ No newline at end of file
+      <td style="vertical-align: top;">
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/dualcoding.doxycfg ./docs/dualcoding.doxycfg
--- ../Tekkotsu_2.4.1/docs/dualcoding.doxycfg	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/dualcoding.doxycfg	2006-02-21 12:58:41.000000000 -0500
@@ -0,0 +1,18 @@
+@INCLUDE = doxygencfg
+
+PROJECT_NAME = DualCoding
+PROJECT_NUMBER = 3.0 beta
+INPUT = ../DualCoding
+EXCLUDE =
+EXCLUDE_PATTERNS =
+OUTPUT_DIRECTORY = generated/html
+EXTRACT_ALL = YES
+ALWAYS_DETAILED_SEC = NO
+GENERATE_TREEVIEW = YES
+HTML_OUTPUT = dualcoding
+HIDE_SCOPE_NAMES = YES
+SEARCHENGINE = YES
+GENERATE_TAGFILE = generated/dualcoding.tag
+HTML_HEADER = exthead.html
+HTML_FOOTER = dualcodingfoot.html
+PREDEFINED += use_namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/dualcodingfoot.html ./docs/dualcodingfoot.html
--- ../Tekkotsu_2.4.1/docs/dualcodingfoot.html	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/dualcodingfoot.html	2006-02-01 16:08:59.000000000 -0500
@@ -0,0 +1,48 @@
+</td></tr></tbody></table>
+
+  <br>
+	<table cellpadding="2" cellspacing="2" border="0" style="text-align: left; width: 100%; color: rgb(0, 0, 0);">
+		<tbody>
+			<tr>
+				<td style="vertical-align: top;"><small>
+						<b>$projectname $projectnumber<br></b>
+					</small>
+				</td>
+				<td style="vertical-align: top; text-align: right; font-style: italic;">
+					<small>
+						Generated $datetime by <a href="http://www.doxygen.org/">Doxygen</a> $doxygenversion
+					</small>
+					<script type="text/javascript" language="javascript">
+						<!--
+						s="na";c="na";j="na";f=""+escape(document.referrer)
+						//-->
+					</script>
+					<script type="text/javascript" language="javascript1.2">
+						<!--
+						s=screen.width;v=navigator.appName
+						if (v != "Netscape") {c=screen.colorDepth}
+						else {c=screen.pixelDepth}
+						j=navigator.javaEnabled()
+						//-->
+					</script>
+					<script type="text/javascript" language="javascript">
+						<!--
+						function pr(n) {document.write(n,"\n");}
+						NS2Ch=0
+						if (navigator.appName == "Netscape" &&
+						navigator.appVersion.charAt(0) == "2") {NS2Ch=1}
+						if (NS2Ch == 0) {
+						r="size="+s+"&colors="+c+"&referer="+f+"&java="+j+"&stamp="+(new Date()).getTime()+""
+						pr("<IMG BORDER=0 width=16 height=16 align=\"middle\" SRC=\"http://aibo4.boltz.cs.cmu.edu/head.gif?"+r+"\">")}
+						//-->
+					</script> 
+					
+					<noscript>
+						<img src="http://aibo4.boltz.cs.cmu.edu/head.gif" border="0" width=16 height=16 align="middle">
+					</noscript>
+				</td>
+			</tr>
+		</tbody>
+	</table>
+</body>
+</html>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/exthead.html ./docs/exthead.html
--- ../Tekkotsu_2.4.1/docs/exthead.html	2004-11-24 16:30:39.000000000 -0500
+++ ./docs/exthead.html	2006-03-03 10:33:05.000000000 -0500
@@ -3,7 +3,11 @@
 	<head>
 		<meta http-equiv="Content-Type" content="text/html;charset=iso-8859-1">
 		<title>$title</title>
-		<link href="doxygen.css" rel="stylesheet" type="text/css">
+		<link href="../doxygen.css" rel="stylesheet" type="text/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">
+		<link type="text/css" rel="stylesheet" href="../doxygen-override.css">
 		<link rel="home" href="../index.html">
 		<link rel="up" href="../index.html">
 		<link rel="SHORTCUT ICON" href="favicon.ico">
Binary files ../Tekkotsu_2.4.1/docs/html/ERS7-LED-Modes.png and ./docs/html/ERS7-LED-Modes.png differ
Binary files ../Tekkotsu_2.4.1/docs/html/MotionSequenceGraph1.png and ./docs/html/MotionSequenceGraph1.png differ
Binary files ../Tekkotsu_2.4.1/docs/html/MotionSequenceGraph2-head.png and ./docs/html/MotionSequenceGraph2-head.png differ
Binary files ../Tekkotsu_2.4.1/docs/html/MotionSequenceGraph2-tail.png and ./docs/html/MotionSequenceGraph2-tail.png differ
Binary files ../Tekkotsu_2.4.1/docs/html/NumberLEDs-ERS7.jpg and ./docs/html/NumberLEDs-ERS7.jpg differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/html/doxygen.css ./docs/html/doxygen.css
--- ../Tekkotsu_2.4.1/docs/html/doxygen.css	2005-07-19 19:35:27.000000000 -0400
+++ ./docs/html/doxygen.css	2006-03-28 19:37:17.000000000 -0500
@@ -1,16 +1,3 @@
-/*
-H1 {
-	text-align: center;
-	font-family: Arial, Helvetica, sans-serif;
-}
-H2 {
-	font-family: Geneva, Arial, Helvetica, sans-serif;
-	font-size: 20px;
-}
-P {
-	width: 620px;
-}
-*/
 CAPTION { font-weight: bold }
 DIV.qindex {
 	background-color: #eeeeff;
@@ -25,9 +12,6 @@
     margin-right: auto; 
 	font-size: smaller;
 }
-TABLE.qindex {
-	font-size: 100%;
-}
 DIV.nav {
 	width: 100%;
 	background-color: #eeeeff;
@@ -37,6 +21,17 @@
 	padding: 2px;
 	line-height: 140%;
 }
+DIV.navtab {
+       background-color: #e8eef2;
+       border: 1px solid #84b0c7;
+       text-align: center;
+       margin: 2px;
+       margin-right: 15px;
+       padding: 2px;
+}
+TD.navtab {
+       font-size: 70%;
+}
 A.qindex {
        text-decoration: none;
        font-weight: bold;
@@ -49,7 +44,6 @@
 }
 A.qindex:hover {
 	text-decoration: none;
-	background-color: #ddddff;
 }
 A.qindexHL {
 	text-decoration: none;
@@ -57,12 +51,9 @@
 	background-color: #6666cc;
 	color: #ffffff;
 	border: 1px double #9295C2;
-	padding-left: .55ex;
-	padding-right: .55ex;
 }
 A.qindexHL:hover {
 	text-decoration: none;
-	background-color: #6666cc;
 	color: #ffffff;
 }
 A.qindexHL:visited { text-decoration: none; background-color: #6666cc; color: #ffffff }
@@ -72,11 +63,10 @@
 A.code:visited { text-decoration: none; font-weight: normal; color: #0000FF}
 A.codeRef:link { font-weight: normal; color: #0000FF}
 A.codeRef:visited { font-weight: normal; color: #0000FF}
-/*A:hover { text-decoration: none; background-color: #f2f2ff }*/
 DL.el { margin-left: -1cm }
 .fragment {
-       font-family: monospace;
-       font-size: 9pt;
+       font-family: monospace, fixed;
+       font-size: 95%;
 }
 PRE.fragment {
 	border: 1px solid #CCCCCC;
@@ -91,11 +81,14 @@
 	padding-bottom: 4px;
 }
 DIV.ah { background-color: black; font-weight: bold; color: #ffffff; margin-bottom: 3px; margin-top: 3px }
-TD.md { background-color: #f2f2ff; font-weight: bold; }
-TD.mdname1 { background-color: #f2f2ff; font-weight: bold; color: #602020; }
-TD.mdname { background-color: #f2f2ff; font-weight: bold; color: #602020; }
-DIV.groupHeader { margin-left: 16px; margin-top: 12px; margin-bottom: 6px; font-weight: bold }
-DIV.groupText { margin-left: 16px; font-style: italic; font-size: smaller }
+
+DIV.groupHeader {
+       margin-left: 16px;
+       margin-top: 12px;
+       margin-bottom: 6px;
+       font-weight: bold;
+}
+DIV.groupText { margin-left: 16px; font-style: italic; font-size: 90% }
 BODY {
 	background: white;
 	color: black;
@@ -103,7 +96,7 @@
 	margin-left: 20px;
 }
 TD.indexkey {
-	background-color: #eeeeff;
+	background-color: #e8eef2;
 	font-weight: bold;
 	padding-right  : 10px;
 	padding-top    : 2px;
@@ -116,7 +109,7 @@
 	border: 1px solid #CCCCCC;
 }
 TD.indexvalue {
-	background-color: #eeeeff;
+	background-color: #e8eef2;
 	font-style: italic;
 	padding-right  : 10px;
 	padding-top    : 2px;
@@ -141,20 +134,11 @@
 SPAN.preprocessor  { color: #806020 }
 SPAN.stringliteral { color: #002080 }
 SPAN.charliteral   { color: #008080 }
-.mdTable {
-	border: 1px solid #808080;
-	background-color: #f2f2ff;
-	border-bottom-style: none;
-}
-.mdRow {
-	padding: 8px 20px;
-}
 .mdescLeft {
        padding: 0px 8px 4px 8px;
-	font-size: smaller;
+	font-size: 80%;
 	font-style: italic;
 	background-color: #F4F4F4;
-	padding-left: 8px;
 	border-top: 1px none #E0E0E0;
 	border-right: 1px solid #E0E0E0;
 	border-bottom: 1px solid #D0D0D0;
@@ -163,7 +147,7 @@
 }
 .mdescRight {
        padding: 0px 8px 4px 8px;
-	font-size: smaller;
+	font-size: 80%;
 	font-style: italic;
 	background-color: #F4F4F4;
 	border-top: 1px none #E0E0E0;
@@ -188,7 +172,7 @@
 	border-bottom-style: none;
 	border-left-style: none;
 	background-color: #F4F4F4;
-	font-size: 14px;
+	font-size: 80%;
 }
 .memItemRight {
 	padding: 1px 8px 0px 8px;
@@ -206,7 +190,7 @@
 	border-bottom-style: none;
 	border-left-style: none;
 	background-color: #F4F4F4;
-	font-size: 14px;
+	font-size: 80%;
 }
 .memTemplItemLeft {
 	padding: 1px 0px 0px 8px;
@@ -224,7 +208,7 @@
 	border-bottom-style: none;
 	border-left-style: none;
 	background-color: #F4F4F4;
-	font-size: 14px;
+	font-size: 80%;
 }
 .memTemplItemRight {
 	padding: 1px 8px 0px 8px;
@@ -242,8 +226,8 @@
 	border-bottom-style: none;
 	border-left-style: none;
 	background-color: #F4F4F4;
-	font-size: 14px;
-	}
+	font-size: 80%;
+}
 .memTemplParams {
 	padding: 1px 0px 0px 8px;
 	margin: 4px;
@@ -260,7 +244,8 @@
 	border-bottom-style: none;
 	border-left-style: none;
 	background-color: #F4F4F4;
-	font-size: 14px;
+       color: #606060;
+	font-size: 80%;
 }
 .search     { color: #003399;
               font-weight: bold;
@@ -272,7 +257,86 @@
 INPUT.search { font-size: 75%;
                color: #000080;
                font-weight: normal;
-               background-color: #eeeeff;
+               background-color: #e8eef2;
 }
 TD.tiny      { font-size: 75%;
 }
+a {
+	color: #1A41A8;
+}
+a:visited {
+	color: #2A3798;
+}
+.dirtab { padding: 4px;
+          border-collapse: collapse;
+          border: 1px solid #84b0c7;
+}
+TH.dirtab { background: #e8eef2;
+            font-weight: bold;
+}
+HR { height: 1px;
+     border: none;
+     border-top: 1px solid black;
+}
+
+/* Style for detailed member documentation */
+.memtemplate {
+  font-size: 80%;
+  color: #606060;
+  font-weight: normal;
+} 
+.memnav { 
+  background-color: #e8eef2;
+  border: 1px solid #84b0c7;
+  text-align: center;
+  margin: 2px;
+  margin-right: 15px;
+  padding: 2px;
+}
+.memitem {
+  padding: 4px;
+  background-color: #eef3f5;
+  border-width: 1px;
+  border-style: solid;
+  border-color: #dedeee;
+  -moz-border-radius: 8px 8px 8px 8px;
+}
+.memname {
+  white-space: nowrap;
+  font-weight: bold;
+}
+.memdoc{
+  padding-left: 10px;
+}
+.memproto {
+  background-color: #d5e1e8;
+  width: 100%;
+  border-width: 1px;
+  border-style: solid;
+  border-color: #84b0c7;
+  font-weight: bold;
+  -moz-border-radius: 8px 8px 8px 8px;
+}
+.paramkey {
+  text-align: right;
+}
+.paramtype {
+  white-space: nowrap;
+}
+.paramname {
+  color: #602020;
+  font-style: italic;
+}
+/* End Styling for detailed member documentation */
+
+/* for the tree view */
+.ftvtree {
+	font-family: sans-serif;
+	margin:0.5em;
+}
+.directory { font-size: 9pt; font-weight: bold; }
+.directory h3 { margin: 0px; margin-top: 1em; font-size: 11pt; }
+.directory > h3 { margin-top: 0; }
+.directory p { margin: 0px; white-space: nowrap; }
+.directory div { display: none; margin: 0px; }
+.directory img { vertical-align: -30%; }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/html/index.html ./docs/html/index.html
--- ../Tekkotsu_2.4.1/docs/html/index.html	2005-08-12 14:52:52.000000000 -0400
+++ ./docs/html/index.html	2006-10-03 23:01:52.000000000 -0400
@@ -5,6 +5,7 @@
   <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">
 	<link type="text/css" rel="stylesheet" href="doxygen-override.css">
@@ -16,7 +17,7 @@
   <tbody>
     <tr>
 <!-- #Homepage# --> <td style="vertical-align: top;"><a
- href="../index.html" target="_top">Homepage</a></td>
+ href="../index.html" target="_top">Tekkotsu Homepage</a></td>
 <!-- #Bar# --> <td
  style="vertical-align: top; background-color: rgb(0, 0, 0);"><br>
       </td>
@@ -51,23 +52,38 @@
   </tbody>
 </table>
 <table
- style="text-align: left; width: 620px; margin-left: auto; margin-right: auto; height: 100%;"
- border="0" cellpadding="2" cellspacing="2">
+ style="text-align: left;" align="center" width=725 border="0" cellpadding="2" cellspacing="2">
+  <tbody>
+    <tr>
+      <td style="vertical-align: top;">
+<div class="tabs">
+  <ul>
+    <li id="current"><a href="main.html"><span>Main&nbsp;Page</span></a></li>
+    <li><a href="namespaces.html"><span>Namespaces</span></a></li>
+    <li><a href="classes.html"><span>Classes</span></a></li>
+    <li><a href="files.html"><span>Files</span></a></li>
+    <li><a href="dirs.html"><span>Directories</span></a></li>
+    <li><a href="pages.html"><span>Related&nbsp;Pages</span></a></li>
+    <li>
+      <form action="http://cvs.tekkotsu.org/search.php" method="get">
+        <table cellspacing="0" cellpadding="0" border="0">
+          <tr>
+            <td><label>&nbsp;<u>S</u>earch&nbsp;for&nbsp;</label></td>
+            <td><input type="text" name="query" value="" size="20" accesskey="s"/></td>
+          </tr>
+        </table>
+      </form>
+    </li>
+  </ul></div>
+      </td>
+    </tr>
+  </tbody>
+</table>
+<table
+ style="text-align: left;" align="center" width=620 border="0" cellpadding="2" cellspacing="2" width=620>
   <tbody>
     <tr>
       <td style="vertical-align: top;">
-<div class="qindex">  <form class="search" action="http://cvs.tekkotsu.org/search.php" method="get" name="doxyform">
-<table border=0 class="qindex"><tr><td width="20%" align="center"><a class="qindexHL" href="main.html">Main&nbsp;Page</a></td>
-<td width="0px" bgcolor="000000"></td>
-<td valign="top" width="20%" align="left"><b>Classes: </b><center><a class="qindex" href="annotated.html">List</a>, <a class="qindex" href="classes.html">Index</a>, <a class="qindex" href="hierarchy.html">Hierarchy</a>, <a class="qindex" href="functions.html">Members</a></center></td>
-<td width="0px" bgcolor="000000"></td>
-<td valign="top" width="20%" align="left"><b>Namespaces: </b><center><a class="qindex" href="namespaces.html">List</a>, <a class="qindex" href="namespacemembers.html">Members</a></center></td>
-<td width="0px" bgcolor="000000"></td>
-<td valign="top" width="20%" align="left"><b>Files: </b><center><a class="qindex" href="files.html">List</a>, <a class="qindex" href="dirs.html">Directories</a>, <a class="qindex" href="globals.html">Members</a></center></td>
-<td width="0px" bgcolor="000000"></td>
-<td valign="top" width="20%" align="center"><a class="qindex" href="pages.html">Other&nbsp;Pages</a><hr><span class="search"><u>S</u>earch&nbsp;<input value="0" name="page" type="hidden"><input class="search" type="text" name="query" value="" size="10" accesskey="s"/></span></td>
-</tr></table></form>
-</div>
 <center>
 <h1>Tekkotsu Reference Documentation</h1>
 </center>
@@ -79,7 +95,15 @@
       <p>If you want a more general overview
 of what this software does and how the pieces fit together, you may
 want
-to visit the <a target="_top" href="../Overview.html">overview</a>.</p>
+to visit the <a target="_top" href="../Overview.html">overview</a>.  Don't forget there are also <a href="development.html">tutorials</a> available.</p>
+<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="newmat/index.html" target="_top">newmat</a></li>
+        <li><a href="roboop/index.html" target="_top">ROBOOP</a></li>
+      </ul>
+<br>
+<div style="margin-left:20px;"><b>Tekkotsu Documentation:</b></div>
       <ul>
         <li><a href="classes.html">Alphabetical Index</a> - Lists all
 classes and structs<br>
@@ -88,17 +112,13 @@
 description of each class and struct<br>
         </li>
         <li><a href="namespacemembers.html">Namespace Members</a> -
-Lists the global constants which are organized into namespaces</li>
+Lists the global constants, organized by namespaces</li>
         <li><a href="globals.html">File Members</a> - Lists all of the
 global
 variables and macros which aren't in namespaces<br>
         </li>
         <li><a href="pages.html">Related Pages</a> - Links to the <a
  href="todo.html">todo</a> and <a href="bug.html">bug</a> lists.</li>
-        <li>Local documentation of the included <a
- href="newmat/index.html" target="_top">newmat</a> and <a
- href="roboop/index.html" target="_top">ROBOOP</a> libraries<br>
-        </li>
         <li>You can also search the framework:<br>
           <form action="http://cvs.tekkotsu.org/search.php" method="get"
  name="doxyform"><input value="0" name="page" type="hidden"><input
@@ -107,22 +127,43 @@
  height="16" type="image" width="74"></form>
         </li>
       </ul>
-      <p>These documents will give you
-nitty-gritty details on the individual functions, classes, and data
-structures. &nbsp;It is collated from comments embedded in the source
-code by <a href="http://www.doxygen.org/">doxygen</a>.&nbsp; Expect a
-few rough edges, this started life as an internal resource.&nbsp; It's
-not that we don't know proper grammar, it's just that we'd rather be
-writing code. ;-)&nbsp; If something is unclear, please feel free to <a
- href="Credits.html#contact">drop us a
-line</a>!<br>
       </p>
+      <h3>Popular Destinations:</h3>
+      <center>
+      <table border="0" cellpadding="0" cellspacing="0" style="line-height:1.5em; text-align:center;"><tr>
+      	<td width="20%"><a href="classBehaviorBase.html">BehaviorBase</a></td>
+      	<td width="20%"><a href="classEventBase.html">EventBase</a></td>
+      	<td width="20%"><a href="classEventRouter.html">EventRouter</a></td>
+      	<td width="20%"><a href="classLoadSave.html">LoadSave</a></td>
+      </tr><tr>
+      	<td><a href="classMotionManager.html">MotionManager</a></td>
+      	<td><a href="classMotionCommand.html">MotionCommand</a></td>
+      	<td><a href="classWorldState.html">WorldState</a></td>
+      	<td><a href="classSoundManager.html">SoundManager</a></td>
+      </tr><tr>
+      	<td><a href="classLedEngine.html">LedEngine</a></td>
+      	<td><a href="classPostureEngine.html">PostureEngine</a></td>
+      	<td><a href="classMotionSequenceEngine.html">MotionSequenceEngine</a></td>
+      	<td><a href="classWalkMC.html">WalkMC</a></td>
+      </tr><tr>
+      	<td><a href="namespaceERS7Info.html">ERS7Info</a></td>
+      	<td><a href="namespaceProjectInterface.html">ProjectInterface</a></td>
+      	<td><a href="classSocket.html">Socket</a></td>
+      	<td><a href="classWireless.html">Wireless</a></td>
+      </tr></table>
+      </center>
       <h3>Documentation Download:</h3>
       <p>If you would like to obtain a local
 copy of the reference materials, you may download a tarball of this site:<br>
       <ul>
         <li><a href="../media/Tekkotsu_doc_<!--#echo var="current_version" -->.tar.gz">HTML</a>
 (v<!--#echo var="current_version" -->, <!--#fsize virtual="../media/Tekkotsu_doc_${current_version}.tar.gz" -->B)</li>
+<li>Quick Reference Sheets (PDF):
+<ul>
+<li><a href="../media/TekkotsuQuickReference_ERS7_<!--#echo var="current_version" -->.pdf">ERS-7</a></li>
+<li><a href="../media/TekkotsuQuickReference_ERS210_<!--#echo var="current_version" -->.pdf">ERS-210</a></li>
+<li><a href="../media/TekkotsuQuickReference_ERS220_<!--#echo var="current_version" -->.pdf">ERS-220</a></li>
+</ul></li>
       </ul>
       </p>
       <p>If you're using the most recent
@@ -138,18 +179,8 @@
  target="_top">newmat</a> matrix library
 and the <a href="http://www.cours.polymtl.ca/roboop/" target="_top">ROBOOP</a>
 kinematics library. We mirror their own doxygen documentation on our
-site so that our documentation can link to it.
-      </p>
-      <p>You can directly access these
-libraries' documentation with these links:
-      <ul>
-        <li><a href="newmat/index.html" target="_top">newmat</a>
-Documentation
-        </li>
-        <li><a href="roboop/index.html" target="_top">ROBOOP</a>
-Documentation
-        </li>
-      </ul>
+site so that our documentation can link to it.  You can directly access these
+libraries' documentation with the Library Sub-Documentation links given above.
       </p>
       <p>In addition, we provide precompiled copies of several other libraries for the AIBO platform.
 You may wish to make use of their references as well:
@@ -217,10 +248,10 @@
 navigator.appVersion.charAt(0) == "2") {NS2Ch=1}
 if (NS2Ch == 0) {
 r="size="+s+"&colors="+c+"&referer="+f+"&java="+j+"&stamp="+(new Date()).getTime()+""
-pr("<IMG BORDER=0 width=16 height=16 align=\"middle\" SRC=\"http://aibo2.boltz.cs.cmu.edu/head.gif?"+r+"\">")}
+pr("<IMG BORDER=0 width=16 height=16 align=\"middle\" SRC=\"http://aibo4.boltz.cs.cmu.edu/head.gif?"+r+"\">")}
 //-->
 </script>
-<noscript><img src="http://aibo2.boltz.cs.cmu.edu/head.gif" border="0"
+<noscript><img src="http://aibo4.boltz.cs.cmu.edu/head.gif" border="0"
 width=16 height=16 align="middle">
 </noscript>
 </span></small></div>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/newmatfoot.html ./docs/newmatfoot.html
--- ../Tekkotsu_2.4.1/docs/newmatfoot.html	2004-07-20 13:57:01.000000000 -0400
+++ ./docs/newmatfoot.html	2006-02-01 16:08:59.000000000 -0500
@@ -33,12 +33,12 @@
 						navigator.appVersion.charAt(0) == "2") {NS2Ch=1}
 						if (NS2Ch == 0) {
 						r="size="+s+"&colors="+c+"&referer="+f+"&java="+j+"&stamp="+(new Date()).getTime()+""
-						pr("<IMG BORDER=0 width=16 height=16 align=\"middle\" SRC=\"http://aibo2.boltz.cs.cmu.edu/head.gif?"+r+"\">")}
+						pr("<IMG BORDER=0 width=16 height=16 align=\"middle\" SRC=\"http://aibo4.boltz.cs.cmu.edu/head.gif?"+r+"\">")}
 						//-->
 					</script> 
 					
 					<noscript>
-						<img src="http://aibo2.boltz.cs.cmu.edu/head.gif" border="0" width=16 height=16 align="middle">
+						<img src="http://aibo4.boltz.cs.cmu.edu/head.gif" border="0" width=16 height=16 align="middle">
 					</noscript>
 				</td>
 			</tr>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/docs/roboopfoot.html ./docs/roboopfoot.html
--- ../Tekkotsu_2.4.1/docs/roboopfoot.html	2004-07-20 13:57:01.000000000 -0400
+++ ./docs/roboopfoot.html	2006-02-01 16:08:59.000000000 -0500
@@ -33,12 +33,12 @@
 						navigator.appVersion.charAt(0) == "2") {NS2Ch=1}
 						if (NS2Ch == 0) {
 						r="size="+s+"&colors="+c+"&referer="+f+"&java="+j+"&stamp="+(new Date()).getTime()+""
-						pr("<IMG BORDER=0 width=16 height=16 align=\"middle\" SRC=\"http://aibo2.boltz.cs.cmu.edu/head.gif?"+r+"\">")}
+						pr("<IMG BORDER=0 width=16 height=16 align=\"middle\" SRC=\"http://aibo4.boltz.cs.cmu.edu/head.gif?"+r+"\">")}
 						//-->
 					</script> 
 					
 					<noscript>
-						<img src="http://aibo2.boltz.cs.cmu.edu/head.gif" border="0" width=16 height=16 align="middle">
+						<img src="http://aibo4.boltz.cs.cmu.edu/head.gif" border="0" width=16 height=16 align="middle">
 					</noscript>
 				</td>
 			</tr>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/EntryPoint.h ./local/EntryPoint.h
--- ../Tekkotsu_2.4.1/local/EntryPoint.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/EntryPoint.h	2006-09-28 16:42:51.000000000 -0400
@@ -0,0 +1,75 @@
+//-*-c++-*-
+#ifndef INCLUDED_EntryPoint_h_
+#define INCLUDED_EntryPoint_h_
+
+#include "IPC/Thread.h"
+#include "Shared/Resource.h"
+#include "Shared/WorldStatePool.h"
+
+//! manages a thread lock to serialize behavior computation and mark whether ::state is being read or written
+class EntryPoint : public Resource {
+public:
+	//! pass this to MarkScope when using an EntryPoint over a section which will read ::state
+	class WorldStateRead : public WorldStatePool::ReadRequest {
+	public:
+		//! constructor, hardcoded to use global ::state and non-blocking pool access
+		WorldStateRead() : WorldStatePool::ReadRequest(state,false) {}
+	};
+	WorldStateRead defaultRead; //!< this instance will be used if an empty Data is passed to useResource (only safe to do because we get #lock first, so two threads won't be using the same data at the same time)
+	
+	//! pass this to MarkScope when using an EntryPoint over a section which will update ::state
+	class WorldStateWrite : public WorldStatePool::WriteRequest {
+	public:
+		//! constructor, hardcoded to use global ::state and blocking pool access
+		explicit WorldStateWrite(unsigned int frame_number) : WorldStatePool::WriteRequest(state,true,frame_number) {} 
+	};
+	
+	//! constructor, need to specify the WorldStatePool (presumably it's in a shared memory region...)
+	explicit EntryPoint(WorldStatePool& wspool) : Resource(), defaultRead(), pool(wspool), lock() {}
+	
+	//! an EmptyData implies a WorldStateRead should be passed on to the pool, requesting a write requires a WorldStateWrite to be passed
+	virtual void useResource(Data& d) {
+		static_cast<Resource&>(lock).useResource(emptyData); //important to get lock first to make sure using shared defaultRead is safe in multi-threaded env.
+		pool.useResource(typeid(d)==typeid(Data) ? defaultRead : d);
+	}
+	//! an EmptyData implies a WorldStateRead should be passed on to the pool, requesting a write requires a WorldStateWrite to be passed
+	virtual void releaseResource(Data& d) {
+		if(WorldStateWrite * wsw=dynamic_cast<WorldStateWrite*>(&d)) {
+			if(wsw->getComplete() && state!=wsw->src) {
+				/*for(unsigned int i=0; i<NumPIDJoints; i++) {
+				pids[i][0]=lastState->pids[i][0];
+				pids[i][1]=lastState->pids[i][1];
+				pids[i][2]=lastState->pids[i][2];
+				}*/
+				memcpy(state->pids,wsw->src->pids,sizeof(state->pids)); //pids is probably big enough it's better to use memcpy (?)
+				state->vel_x=wsw->src->vel_x;
+				state->vel_y=wsw->src->vel_y;
+				state->vel_a=wsw->src->vel_a;
+				state->vel_time=wsw->src->vel_time;
+			}
+		}
+		pool.releaseResource(typeid(d)==typeid(Data) ? defaultRead : d);
+		static_cast<Resource&>(lock).releaseResource(emptyData); //important to release lock last to make sure using shared defaultRead is safe in multi-threaded env.
+	}
+	
+	//! this can be useful when planning to write, get the threadlock to do some initial setup before grabbing an entry from the pool
+	ThreadNS::Lock& getLock() { return lock; }
+	
+protected:
+	WorldStatePool& pool; //!< pool which manages which WorldStates are being updated while old copies can still be read
+	ThreadNS::Lock lock; //!< only one behavior runs at a time
+};
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/LoadFileThread.cc ./local/LoadFileThread.cc
--- ../Tekkotsu_2.4.1/local/LoadFileThread.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/LoadFileThread.cc	2006-09-28 16:42:51.000000000 -0400
@@ -0,0 +1,643 @@
+#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: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/LoadFileThread.h ./local/LoadFileThread.h
--- ../Tekkotsu_2.4.1/local/LoadFileThread.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/LoadFileThread.h	2006-09-28 16:42:51.000000000 -0400
@@ -0,0 +1,222 @@
+//-*-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: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/LoadImageThread.cc ./local/LoadImageThread.cc
--- ../Tekkotsu_2.4.1/local/LoadImageThread.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/LoadImageThread.cc	2006-09-28 16:42:51.000000000 -0400
@@ -0,0 +1,261 @@
+#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: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/LoadImageThread.h ./local/LoadImageThread.h
--- ../Tekkotsu_2.4.1/local/LoadImageThread.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/LoadImageThread.h	2006-09-28 16:42:51.000000000 -0400
@@ -0,0 +1,41 @@
+//-*-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: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/Makefile.local ./local/Makefile.local
--- ../Tekkotsu_2.4.1/local/Makefile.local	2005-06-01 01:48:06.000000000 -0400
+++ ./local/Makefile.local	2006-09-28 16:42:51.000000000 -0400
@@ -9,6 +9,8 @@
 
 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))
 
 ifeq ($(shell uname | grep -ci cygwin),0)
   PLATFORM_FLAGS:=$(PLATFORM_FLAGS) -DHAVE_READDIR_R
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/minisim.h ./local/minisim.h
--- ../Tekkotsu_2.4.1/local/minisim.h	2005-08-01 19:18:00.000000000 -0400
+++ ./local/minisim.h	2006-07-13 13:25:50.000000000 -0400
@@ -12,7 +12,7 @@
 
 #ifdef TK_ENABLE_WIRELESS
 #  include "Wireless/Wireless.h"
-#  include "IPC/Thread.h"
+#  define TK_ENABLE_THREADING
 #endif
 #ifdef TK_ENABLE_SOUTSERR
 #  include "Wireless/Socket.h"
@@ -24,6 +24,10 @@
 #  include "Motion/Kinematics.h"
 #endif
 
+#ifdef TK_ENABLE_THREADING
+#  include "IPC/Thread.h"
+#endif
+
 #define TK_cstr(s) TK_str(s)
 #define TK_str(s) #s
 
@@ -32,6 +36,15 @@
 #ifdef TK_ENABLE_WIRELESS
 	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
@@ -39,6 +52,10 @@
 			wireless->pollSetup(); // reinitialize for next test
 			return 0; //no sleep time because pollTest blocks
 		}
+		virtual void stop() {
+			Thread::stop();
+			wireless->wakeup();
+		}
 	} wireless_thread;
 #endif
 	
@@ -54,6 +71,9 @@
 		erouter=new EventRouter;
 #endif
 		
+#ifdef TK_ENABLE_THREADING
+		Thread::initMainThread();
+#endif
 #ifdef TK_ENABLE_WIRELESS
 		wireless = new Wireless();
 #endif
@@ -119,7 +139,6 @@
 	void destruct() {
 #ifdef TK_ENABLE_WIRELESS
 		wireless_thread.stop();
-		wireless->wakeup();
 		wireless_thread.join();
 #endif
 		
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/LoadFileThread.cc ./local/sim/LoadFileThread.cc
--- ../Tekkotsu_2.4.1/local/sim/LoadFileThread.cc	2005-08-04 17:32:16.000000000 -0400
+++ ./local/sim/LoadFileThread.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,307 +0,0 @@
-#include "LoadFileThread.h"
-#include "Shared/get_time.h"
-#include <sys/stat.h>
-#include <regex.h>
-#include <dirent.h>
-
-LoadFileThread::~LoadFileThread() {
-	Thread::Lock 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();
-	}
-}
-
-void LoadFileThread::loadFileList(bool clearCurrent/*=true*/) {
-	Thread::Lock l(lock);
-	struct stat sb;
-	if(stat(src.c_str(),&sb)) {
-		std::cerr << "Could not open source " << src << std::endl;
-		return;
-	}
-	if(clearCurrent)
-		files.clear();
-	isIndexed=false;
-	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
-			//loadFileListFromIndex();
-		} else {
-			char msg[128];
-			regerror(match,&re,msg,128);
-			std::cerr << "Regex error on '" << src << "': " << msg << std::endl;
-		}
-	}
-	setFrame(0);
-}
-
-void LoadFileThread::setFrame(unsigned int f) {
-	Thread::Lock 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) {
-	Thread::Lock l(lock);
-	files[(unsigned int)calcLoopTime()]=file;
-}
-
-void LoadFileThread::loadFileListFromDirectory() {
-	Thread::Lock 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;
-	}
-	float tinc=1000.f/framerate;
-	float time=calcLoopTime();
-	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
-	while(res!=NULL) {
-		int match=regexec(&re,res->d_name,0,NULL,0);
-		if(match==0) {
-			files[static_cast<unsigned int>(time)]=(src+"/")+res->d_name;
-			//std::cout << "Enqueuing " << res->d_name << std::endl;
-			time+=tinc;
-		} 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);
-}
-
-/*
-void LoadFileThread::loadFileListFromIndex() {
-	isIndexed=true;
-	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;
-	}
-	// todo read index file
-	regfree(&re);
-}
-*/
-
-bool LoadFileThread::incrementCurfile(float loopTime, int& curTime) {
-	if(++curfile == files.end()) {
-		if(!loop) {
-			if(verbose)
-				std::cout << "Out of data from '" << src << "' -- set 'loop' to true, or use 'restart' command to manually loop" << std::endl;
-			return false;
-		} else {
-			if(verbose)
-				std::cout << "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;
-}
-
-void LoadFileThread::getNextData(RCRegion*& data, unsigned int& t) {
-	if(files.size()==0 || curfile==files.end())
-		return;
-	if(startTimeOffset!=timeOffset)
-		resetTimeOffset(startTimeOffset);
-
-	//skip old data -- current time is already past these frames, no point in loading them
-	unsigned int realt=get_time();
-	int curt=realt-timeOffset;
-	float loopTime=calcLoopTime();
-	if(curt>(int)(loopTime)) {
-		if(!loop) {
-			if(verbose)
-				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)
-			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;
-		startTimeOffset+=massLoopTimeI+loopRemainderI;
-		resetTimeOffset(startTimeOffset);
-		curt=realt-timeOffset;
-		curfile=files.begin();
-	}
-	while(static_cast<int>(curfile->first)<curt)
-		if(!incrementCurfile(loopTime,curt))
-			return;
-
-	if(verbose)
-		std::cout << "Loading frame from " << curfile->second << " dt="<<curfile->first << " scheduled:" << (curfile->first+timeOffset) << std::endl;
-	msgbuf_t::iterator it;
-	for(it=sent.begin();it!=sent.end(); ++it)
-		if((*it)->NumberOfReference()==1)
-			break;
-	if(it!=sent.end()) {
-		if(!loadFile(curfile->second, *it)) {
-			std::cerr << "Bad load on " << curfile->second << std::endl;
-			++curfile;
-			return;
-		}
-		data=*it;
-		sent.erase(it);
-	} else {
-		if(!loadFile(curfile->second, data)) {
-			std::cerr << "Bad load on " << curfile->second << std::endl;
-			++curfile;
-			return;
-		}
-	}
-	t=curfile->first+timeOffset;
-	incrementCurfile(loopTime,curt);
-}
-
-unsigned int LoadFileThread::runloop() {
-	Thread::Lock l(lock);
-	if(unsigned int read=msgr.pollStatus())
-		fireMessagesRead(read);
-	unsigned int curt=get_time();
-	if(timestamps.size()>0 && curt>=timestamps.front()) {
-		if(verbose)
-			std::cout << "Sending frame " << timestamps.front() << " at " << curt << std::endl;
-		msgr.sendMessage(loaded.front());
-		sent.push_back(loaded.front());
-		loaded.pop_front();
-		timestamps.pop_front();
-	}
-	if(loaded.size()<NUM_PRELOAD) {
-		RCRegion* rcr=NULL;
-		unsigned int t=-1U;
-		getNextData(rcr,t);
-		if(t==-1U) {
-			//out of data, skip a frame and then check again in case we get reset
-			return (1000000/(unsigned int)framerate);
-		}
-		if(rcr==NULL) {
-			std::cerr << "Could not allocate new shared memory region or bad initial load" << std::endl;
-			return (1000000/(unsigned int)framerate);
-		}
-		if(timestamps.size()==0 || t>timestamps.back()) {
-			loaded.push_back(rcr);
-			timestamps.push_back(t);
-		} else {
-			std::cerr << "ERROR: LoadFileThread received old data from getNextData" << std::endl;
-			sent.push_front(rcr);
-		}
-	}
-	return 1000;
-}
-
-void LoadFileThread::fireMessagesRead(unsigned int howmany) {
-	std::list<MessageQueueBase::StatusListener*>::iterator it=statusListeners.begin();
-	while(it!=statusListeners.end()) {
-		std::list<MessageQueueBase::StatusListener*>::iterator cur=it++; //increment early in case the listener changes subscription
-		(*cur)->messagesRead(msgr,howmany);
-	}
-}
-
-void LoadFileThread::resetTimeOffset(int t) {
-	while(loaded.size()>0) {
-		sent.push_front(loaded.front());
-		loaded.pop_front();
-	}
-	timestamps.clear();
-	if(timeOffset<t) {
-		//need to rewind curfile
-		curfile=files.begin(); //getNextData will fast forward to current time
-	}
-	timeOffset=t;
-}
-
-float LoadFileThread::calcLoopTime() {
-	if(files.size()==0)
-		return 0;
-	float tinc=1000.f/framerate;
-	if(isIndexed) {
-		files_t::iterator lastfile=files.end();
-		--lastfile;
-		unsigned int last=lastfile->first;
-		return last+tinc;
-	} else {
-		return files.size()*tinc;
-	}
-}
-
-
-/*! @file
- * @brief 
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/LoadFileThread.h ./local/sim/LoadFileThread.h
--- ../Tekkotsu_2.4.1/local/sim/LoadFileThread.h	2005-08-04 17:32:16.000000000 -0400
+++ ./local/sim/LoadFileThread.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,167 +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
-	 *
-	 *  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)
-	: Thread(), plist::Dictionary(),
-		src(source),
-		filenameFilter(filter),
-		framerate(fps),
-		startTimeOffset(0),
-		verbose(false),
-		loop(true),
-		sent(), loaded(), timestamps(), files(), curfile(files.begin()), msgr(messages),
-		timeOffset(0), lock(), loopRemainder(0), isIndexed(false), statusListeners()
-	{
-		addEntry("Source",src,"The directory from which data samples should be loaded, or a single specific file.\nIn the future, this could also be network addresses for teleoperation and remote processing.");
-		addEntry("FileFilter",filenameFilter,"If Source is a directory, only files matching the filter will be loaded from it.");
-		addEntry("Framerate",framerate,"The rate at which images should be loaded");
-		addEntry("StartTime",startTimeOffset,"The time at which the file list should start being processed");
-		addEntry("Verbose",verbose,"If true, input status information will be dumped on the console");
-		addEntry("Loop",loop,"If true, restart file list at the beginning when the end is reached; otherwise just stop loading data");
-		src.addPrimitiveListener(this);
-		verbose.addPrimitiveListener(this);
-	}
-	//! destructor
-	~LoadFileThread();
-	
-	//! source the path to either a directory to load files from, or a single specific data file
-	plist::Primitive<std::string> src;
-
-	//! a regular expression (POSIX.2 extended format) to select which files to load from @a source, if @a is a directory
-	plist::Primitive<std::string> filenameFilter;
-
-	//! frames per second to send -- only referenced when setting up #files during loadFileList -- later modifications won't resent the already loaded file list
-	plist::Primitive<float> framerate;
-
-	//! 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
-	plist::Primitive<int> startTimeOffset;
-
-	//! controls whether to give feedback messages on the console regarding progress
-	plist::Primitive<bool> verbose; 
-
-	//! controls whether to restart #curfile at the beginning of #files when it reaches the end
-	plist::Primitive<bool> loop; 
-
-
-	//! 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);
-	//! 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() { return timestamps.size()>0 ? timestamps.front() : -1U; }
-	
-	//! Request updates to StatusListener callbacks
-	virtual void addStatusListener(MessageQueueBase::StatusListener* l) {
-		if(l==NULL)
-			return;
-		statusListeners.push_back(l);
-	}
-	//! Unsubscribes a StatusListener from future updates
-	virtual void removeStatusListener(MessageQueueBase::StatusListener* l) {
-		std::list<MessageQueueBase::StatusListener*>::iterator it=find(statusListeners.begin(),statusListeners.end(),l);
-		if(it!=statusListeners.end())
-			statusListeners.erase(it);
-	}
-	
-	virtual void plistValueChanged(const plist::PrimitiveBase& pl) {
-		if(&pl==&src)
-			loadFileList();
-		else if(&pl==&verbose)
-			msgr.setReportDroppings(verbose);
-	}
-	
-protected:
-	//! removes our reference to a region created by loadFile()
-	virtual void freeRegion(RCRegion* rcr) { 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, should be provided by subclass
-	/*! @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 */
-	virtual bool loadFile(const std::string& file, RCRegion*& data)=0;
-	//! 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 */
-	virtual bool incrementCurfile(float loopTime, int& curTime);
-	
-	//! 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);
-	// ! NOT DONE -- load a list of files from an index file specified by #src
-	//virtual void loadFileListFromIndex();
-
-	//! monitor #msgr, send new messages when their timestamp indicates they are due, then load upcoming messages
-	virtual unsigned int runloop();
-
-	//! Notifies statusListeners that a message has been read by all MessageQueue receivers
-	virtual void fireMessagesRead(unsigned int howmany);
-
-	//! 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();
-
-	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 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
-
-	std::list<MessageQueueBase::StatusListener*> statusListeners; //!< MessageQueueBase::StatusListeners currently subscribed from addStatusListener()
-};
-
-/*! @file
- * @brief 
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/LoadImageThread.cc ./local/sim/LoadImageThread.cc
--- ../Tekkotsu_2.4.1/local/sim/LoadImageThread.cc	2005-06-13 14:00:04.000000000 -0400
+++ ./local/sim/LoadImageThread.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,85 +0,0 @@
-#include "LoadImageThread.h"
-
-extern "C" {
-#include <jpeglib.h>
-}
-#include "sim.h"
-#include "SimConfig.h"
-
-using namespace std;
-
-LoadImageThread::LoadImageThread(std::string source, std::string filter, float fps, MessageQueueBase& messages)
-: LoadFileThread(source,filter,fps,messages), cinfo(new jpeg_decompress_struct), jerr(new jpeg_error_mgr), frameIndex(0)
-{
-	cinfo->err = jpeg_std_error(jerr);
-	jpeg_create_decompress(cinfo);
-}
-
-LoadImageThread::~LoadImageThread() {
-	jpeg_destroy_decompress(cinfo);
-	delete cinfo;
-	delete jerr;
-}
-
-bool LoadImageThread::loadFile(const std::string& file, RCRegion*& data) {
-	FILE * infile= fopen(file.c_str(), "rb");
-	if (infile==NULL) {
-		cerr << "Could not open '" << file << "'" << endl;
-		return false;
-	}
-	jpeg_stdio_src(cinfo, infile);
-	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;
-	}
-	const unsigned int HEADER_SIZE=sizeof(unsigned int)*5;
-	unsigned int reqBufSize=sizeof(JSAMPLE)*cinfo->output_width*cinfo->output_height*cinfo->output_components+HEADER_SIZE;
-	if(data==NULL)
-		data=new RCRegion(reqBufSize);
-	else if(data->Size()<reqBufSize) {
-		//too small -- free it, we'll make another one the right size
-		freeRegion(data);
-		data=new RCRegion(reqBufSize);
-	}
-	reinterpret_cast<unsigned int*>(data->Base())[0]=cinfo->output_width;
-	reinterpret_cast<unsigned int*>(data->Base())[1]=cinfo->output_height;
-	reinterpret_cast<unsigned int*>(data->Base())[2]=cinfo->output_components;
-	reinterpret_cast<unsigned int*>(data->Base())[3]=frameIndex++;
-	reinterpret_cast<int*>(data->Base())[4]=*dynamic_cast<plist::Primitive<int>*>(sim::config.findEntry("Vision.Layer"));
-	unsigned int row_stride = cinfo->output_width * cinfo->output_components;
-	//JSAMPARRAY buffer = (*cinfo.mem->alloc_sarray)((j_common_ptr) &cinfo, JPOOL_IMAGE, row_stride, 1);
-	jpeg_start_decompress(cinfo);
-	unsigned int remain=cinfo->output_height;
-	JSAMPROW rows[remain];
-	rows[0]=reinterpret_cast<JSAMPROW>(data->Base()+HEADER_SIZE);
-	for(unsigned int i=1; i<remain; i++)
-		rows[i]=rows[i-1]+row_stride;
-	JSAMPROW* curpos=rows;
-	while (remain>0) {
-		unsigned int used=jpeg_read_scanlines(cinfo, curpos, remain);
-		curpos+=used;
-		remain-=used;
-	}
-	jpeg_finish_decompress(cinfo);
-	fclose(infile);
-	if(jerr->num_warnings>0) {
-		cerr << "Warning: Decompression of '" << file << "' had warnings" << endl;
-		jerr->num_warnings=0;
-	}
-	return true;
-}
-
-
-/*! @file
- * @brief 
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/LoadImageThread.h ./local/sim/LoadImageThread.h
--- ../Tekkotsu_2.4.1/local/sim/LoadImageThread.h	2005-06-01 01:48:07.000000000 -0400
+++ ./local/sim/LoadImageThread.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,36 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_LoadImageThread_h_
-#define INCLUDED_LoadImageThread_h_
-
-#include "LoadFileThread.h"
-
-//! description of LoadImageThread
-class LoadImageThread : public LoadFileThread {
-public:
-	LoadImageThread(std::string source, std::string filter, float fps, MessageQueueBase& messages);
-	~LoadImageThread();
-
-	virtual bool loadFile(const std::string& file, RCRegion*& data);
-	
-protected:
-	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
-	
-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: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/Main.cc ./local/sim/Main.cc
--- ../Tekkotsu_2.4.1/local/sim/Main.cc	2005-08-16 14:24:43.000000000 -0400
+++ ./local/sim/Main.cc	2006-09-26 17:44:30.000000000 -0400
@@ -2,16 +2,20 @@
 #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 "Vision/BufferedImageGenerator.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"
@@ -25,20 +29,29 @@
 	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))),
-	worldstate(ipc_setup->registerRegion(getWorldStateID(),sizeof(WorldState))),
-	visrecv(NULL), sensrecv(NULL), evtrecv(NULL), visionRead(true), sensorRead(true),
-	wireless_thread(), curimg(NULL)
+	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 (&(*worldstate)) WorldState;
-	state=&(*worldstate);
+	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);
@@ -65,19 +78,23 @@
 
 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);
+	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;
@@ -89,18 +106,30 @@
 
 void Main::run() {
 try {
-
-	ProjectInterface::startupBehavior().DoStart();
-
+	{
+		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();
-
-	ProjectInterface::startupBehavior().DoStop();
+	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))
@@ -114,15 +143,23 @@
 void Main::DoStop() {
 try {
 
-	events->close();
-
+	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->wakeup();
 	wireless_thread.join();
 	wireless->setDaemon(sout,false);
 	wireless->close(sout);
@@ -131,11 +168,6 @@
 	wireless->close(serr);
 	serr=NULL;
 	
-	motman->RemoveAccess();
-	
-	if(curimg!=NULL)
-		curimg->RemoveReference();
-
 	Process::DoStop();
 
 } catch(const std::exception& ex) {
@@ -147,107 +179,230 @@
 }
 }
 
-bool Main::canManuallyAdvance() {
+bool Main::gotCamera(RCRegion* msg) {
+	if(msg==NULL)
+		return true;
 	Main * main=dynamic_cast<Main*>(Process::getCurrent());
-	if(main==NULL) {
-		cerr << "WARNING: attempt to call Main::advanceVision() from outside Main process!" << endl;
-		return false;
+	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;
 	}
-	if(globals->timeScale >= 0) //ignore call if we're in realtime mode
-		return false;
-	if(globals->advanceOnAccess) //ignore call if we're advancing on access
-		return false;
+	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;
 }
 
-void Main::advanceVision() {
+bool Main::gotSensors(RCRegion* msg) {
 	Main * main=dynamic_cast<Main*>(Process::getCurrent());
-	if(main==NULL) {
-		cerr << "WARNING: attempt to call Main::advanceVision() from outside Main process!" << endl;
-		return;
-	}
-	if(globals->timeScale >= 0) //ignore call if we're in realtime mode
-		return;
-	if(globals->advanceOnAccess) //ignore call if we're advancing on access
-		return;
-	if(main->visionRead) //already marked this frame read
-		return;
-	main->visionRead=true;
-	main->visrecv->markRead();
-}
+	ASSERTRETVAL(main!=NULL,"gotSensors, but not within Main process!",true);
 
-void Main::advanceSensor() {
-	Main * main=dynamic_cast<Main*>(Process::getCurrent());
-	if(main==NULL) {
-		cerr << "WARNING: attempt to call Main::advanceSensor() from outside Main process!" << endl;
-		return;
+	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->timeScale >= 0) //ignore call if we're in realtime mode
-		return;
-	if(globals->advanceOnAccess) //ignore call if we're advancing on access
-		return;
-	if(main->sensorRead) //already marked this frame read
-		return;
-	main->sensorRead=true;
-	main->sensrecv->markRead();
+	if(globals->setNextTimer(erouter->getNextTimer()))
+		main->timerExec->reset();
+	return true;
 }
 
-
-bool Main::gotCamera(RCRegion* msg) {
-try {
+bool Main::gotEvent(RCRegion* msg) {
 	if(msg==NULL)
 		return true;
-	msg->AddReference();
 	Main * main=dynamic_cast<Main*>(Process::getCurrent());
-	if(main->curimg!=NULL)
-		main->curimg->RemoveReference();
-	main->curimg=msg;
-	BufferedImageGenerator::ImageSource img;
-	memcpy(&img,msg->Base(),sizeof(unsigned int)*4);
-	int l=reinterpret_cast<int*>(msg->Base())[4];
-	img.layer = (l<0)?ProjectInterface::defRawCameraGenerator->getNumLayers()+l:l;
-	bool isRealtime=(globals->timeScale >= 0);
-	main->visionRead=globals->advanceOnAccess; //not actually read until the BufferedImageGenerator is accessed, but it's read as far as advanceVision() is concerned
-	if(!isRealtime && main->visionRead)
-		img.receiver = main->visrecv;
-	img.img = reinterpret_cast<unsigned char*>(msg->Base()+sizeof(unsigned int)*5);
-	erouter->postEvent(new DataEvent<BufferedImageGenerator::ImageSource>(img,EventBase::visOFbkEGID,0,EventBase::activateETID));
-	erouter->postEvent(new DataEvent<BufferedImageGenerator::ImageSource>(img,EventBase::visOFbkEGID,0,EventBase::statusETID));
-	erouter->postEvent(new DataEvent<BufferedImageGenerator::ImageSource>(img,EventBase::visOFbkEGID,0,EventBase::deactivateETID));
-	return isRealtime;
-} 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;
-}
-return true;
+	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::gotEvent(RCRegion* msg) {
-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;
+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();
 	}
-	erouter->postEvent(evt);
-} catch(const std::exception& ex) {
-	std::string emsg("Occurred during inter-process event processing");
-	if(evt!=NULL)
-		emsg+=": "+evt->getName();
-	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();
-	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,emsg.c_str(),NULL))
-		throw;
-}
-return true;
+	return true;
 }
 
 /*! @file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/Main.h ./local/sim/Main.h
--- ../Tekkotsu_2.4.1/local/sim/Main.h	2005-07-06 18:53:10.000000000 -0400
+++ ./local/sim/Main.h	2006-09-28 16:42:52.000000000 -0400
@@ -8,8 +8,10 @@
 #include "SharedGlobals.h"
 #include "Motion/MotionManager.h"
 #include "Sound/SoundManager.h"
-#include "Shared/WorldState.h"
-class MessageReceiver;
+#include "Shared/WorldStatePool.h"
+#include "local/EntryPoint.h"
+#include "Vision/BufferedImageGenerator.h"
+#include "Shared/Profiler.h"
 
 class Main : public Process {
 public:
@@ -22,20 +24,11 @@
 	virtual void DoStop();
 	virtual void run();
 
-	//! Will return true if calls to advanceVision() and advanceSensor() will be heeded
-	static bool canManuallyAdvance();
-
-	//! Use this to request the next vision frame be sent
-	static void advanceVision();
-
-	//! Use this to request the next sensor frame be sent
-	static void advanceSensor();
-	
 	static const char* getClassName() { return "Main"; }
 	static ProcessID::ProcessID_t getID() { return ProcessID::MainProcess; }
 	
 	static const char * getEventsID() { return "MainEvents"; }
-	static const char * getWorldStateID() { return "WorldState"; }
+	static const char * getWorldStatePoolID() { return "WorldStatePool"; }
 	
 protected:
 	SharedObject<sim::SoundPlayQueue_t> sounds;
@@ -43,19 +36,34 @@
 	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<WorldState> worldstate;
-	MessageReceiver * visrecv;
-	MessageReceiver * sensrecv;
-	MessageReceiver * evtrecv;
+	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;
-	bool sensorRead;
 	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);
-	RCRegion * curimg;
+	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)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/Motion.cc ./local/sim/Motion.cc
--- ../Tekkotsu_2.4.1/local/sim/Motion.cc	2005-06-29 18:06:41.000000000 -0400
+++ ./local/sim/Motion.cc	2006-08-31 15:01:46.000000000 -0400
@@ -1,11 +1,14 @@
 #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"
@@ -17,17 +20,24 @@
 	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))),
-	worldstate(ipc_setup->registerRegion(Main::getWorldStateID(),sizeof(WorldState))),
-	etrans(NULL), mcrecv(NULL), wireless_thread()
+	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 (&(*motionmanager)) MotionManager;
+	new (&(*motionProf)) motionProfiler_t;
 	motman=&(*motionmanager);
-	motman->InitAccess(*motions);
+	motman->InitAccess(*motions,motionLock);
 	sndman=&(*soundmanager);
-	state=&(*worldstate);
+	state=NULL;
+	::motionProfiler=&(*motionProf);
 	
 	//Setup wireless
 	wireless = new Wireless();
@@ -72,27 +82,109 @@
 			erouter->addTrapper(etrans,static_cast<EventBase::EventGeneratorID_t>(i));
 	
 	wireless_thread.start();
-	mcrecv=new MessageReceiver(*motions,gotMC);
+	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() {
-	wireless_thread.stop();
-	wireless->wakeup();
-	wireless_thread.join();
+	wakeuprecv->finish();
+	statusrecv->finish();
+	sensrecv->finish();
 
-	mcrecv->finish();
-	delete mcrecv;
-	mcrecv=NULL;
+	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)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/Motion.h ./local/sim/Motion.h
--- ../Tekkotsu_2.4.1/local/sim/Motion.h	2005-06-29 18:06:41.000000000 -0400
+++ ./local/sim/Motion.h	2006-09-28 16:42:52.000000000 -0400
@@ -9,7 +9,10 @@
 #include "SharedGlobals.h"
 #include "Motion/MotionManager.h"
 #include "Sound/SoundManager.h"
-#include "Shared/WorldState.h"
+#include "Shared/WorldStatePool.h"
+#include "Shared/Profiler.h"
+#include "local/EntryPoint.h"
+#include <list>
 
 class Motion : public Process {
 public:
@@ -27,19 +30,32 @@
 	
 	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<WorldState> worldstate;
+	SharedObject<WorldStatePool> worldstatepool;
+	SharedObject<sim::MotionWakeup_t> motionWakeup;
+	SharedObject<motionProfiler_t> motionProf;
+	
 	IPCEventTranslator * etrans;
-	class MessageReceiver * mcrecv;
+	class MessageReceiver * sensrecv;
+	class MessageReceiver * statusrecv;
+	class MessageReceiver * wakeuprecv;
+	class MotionExecThread * motionExec;
 	WirelessThread wireless_thread;
 
-	static bool gotMC(RCRegion* msg) { motman->processMsg(msg); return true; }
+	EntryPoint motionLock;
+	
+	static bool gotSensors(RCRegion* msg);
+	static bool gotWakeup(RCRegion* msg);
+	unsigned int lastSensorSN;
 	
 private:
 	Motion(const Motion&); //!< don't call (copy constructor)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/MotionExecThread.cc ./local/sim/MotionExecThread.cc
--- ../Tekkotsu_2.4.1/local/sim/MotionExecThread.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/sim/MotionExecThread.cc	2006-09-28 16:42:52.000000000 -0400
@@ -0,0 +1,184 @@
+#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: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/MotionExecThread.h ./local/sim/MotionExecThread.h
--- ../Tekkotsu_2.4.1/local/sim/MotionExecThread.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/sim/MotionExecThread.h	2006-08-07 17:51:28.000000000 -0400
@@ -0,0 +1,76 @@
+//-*-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: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/Process.cc ./local/sim/Process.cc
--- ../Tekkotsu_2.4.1/local/sim/Process.cc	2005-06-15 14:54:26.000000000 -0400
+++ ./local/sim/Process.cc	2006-06-16 21:15:38.000000000 -0400
@@ -1,7 +1,13 @@
 #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;
 
@@ -21,6 +27,33 @@
 	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)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/Process.h ./local/sim/Process.h
--- ../Tekkotsu_2.4.1/local/sim/Process.h	2005-06-15 14:54:43.000000000 -0400
+++ ./local/sim/Process.h	2006-06-16 21:15:38.000000000 -0400
@@ -5,6 +5,8 @@
 #include "IPC/ProcessID.h"
 #include <string>
 
+class RCRegion;
+
 //! Represents a common interface for each process being run
 class Process {
 public:
@@ -16,6 +18,9 @@
 
 	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;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/SharedGlobals.cc ./local/sim/SharedGlobals.cc
--- ../Tekkotsu_2.4.1/local/sim/SharedGlobals.cc	2005-07-27 13:37:53.000000000 -0400
+++ ./local/sim/SharedGlobals.cc	2006-09-28 16:42:52.000000000 -0400
@@ -1,4 +1,5 @@
 #include "SharedGlobals.h"
+#include "Simulator.h"
 
 const char * const SharedGlobals::runlevel_names[SharedGlobals::NUM_RUNLEVELS] = {
 	"CREATED",
@@ -14,6 +15,7 @@
 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
@@ -34,9 +36,24 @@
 		}
 		//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)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/SharedGlobals.h ./local/sim/SharedGlobals.h
--- ../Tekkotsu_2.4.1/local/sim/SharedGlobals.h	2005-07-28 14:22:26.000000000 -0400
+++ ./local/sim/SharedGlobals.h	2006-09-28 16:42:52.000000000 -0400
@@ -13,9 +13,9 @@
 public:
 	//! constructor
 	SharedGlobals()
-		: simulatorTime(0), timeScale(1), advanceOnAccess(true), lock(),
-		bootTime(), timeOffset(0), lastTimeScale(1), autoPauseTime(-1U),
-		semgr(), running(semgr.getSemaphore())
+		: 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;
@@ -35,7 +35,7 @@
 		semgr.setValue(running,0);
 	}
 	//! test to see if the shutdown flag has been set (non-blocking)
-	bool isShutdown() {
+	bool isShutdown() const {
 		return semgr.testZero(running,false);
 	}
 	//! blocks until shutdown flag has been set
@@ -61,7 +61,12 @@
 	 *  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;
 	
@@ -79,29 +84,10 @@
 	 *  A value of zero halts time. */
 	plist::Primitive<double> timeScale;
 
-	//! If true, and #timeScale is negative, simulator will automatically advance simulatorTime after each data update is processed, allowing full-speed processing
-	/*! This functionality is actually achieved by having the receiver mark the
-	 *  message read when it is ready for another message.  If #advanceOnAccess is
-	 *  false, the receiver will not automatically mark the message read when it
-	 *  is accessed, and you will have to make a manual call within your code to
-	 *  signal completion.  For example, typically you will be doing this from
-	 *  Main process, which would look like this:
-	 *
-	 *  @code
-	 *  #include "local/sim/Main.h"
-	 *  
-	 *  Main::advanceVision(); //only legal if your code is
-	 *  Main::advanceSensor(); // actually running in Main!
-	 *  @endcode
-	 *
-	 *  This flag applies to both sensors and vision, but ignored when in realtime
-	 *  mode (0 or positive #timeScale, or loading from a realtime source, such as
-	 *  live telemetry)
-	 */
-	plist::Primitive<bool> advanceOnAccess;
-
 	//! sets #autoPauseTime
 	void setAutoPauseTime(unsigned int t) { autoPauseTime=t; }
+	//! returns #autoPauseTime
+	unsigned int getAutoPauseTime() const { return autoPauseTime; }
 	
 	//@}
 
@@ -130,6 +116,31 @@
 
 	//@}
 
+
+	//       **********************
+	//!@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;
 
@@ -142,12 +153,30 @@
 	//! 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; 
 
@@ -174,6 +203,7 @@
 
 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
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/SimConfig.cc ./local/sim/SimConfig.cc
--- ../Tekkotsu_2.4.1/local/sim/SimConfig.cc	2005-06-01 01:48:07.000000000 -0400
+++ ./local/sim/SimConfig.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,14 +0,0 @@
-#include "SimConfig.h"
-
-
-
-/*! @file
- * @brief 
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: HEAD $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/10/04 04:21:12 $
- */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/SimConfig.h ./local/sim/SimConfig.h
--- ../Tekkotsu_2.4.1/local/sim/SimConfig.h	2005-07-25 23:07:36.000000000 -0400
+++ ./local/sim/SimConfig.h	2006-09-28 16:42:52.000000000 -0400
@@ -5,26 +5,23 @@
 #include "Shared/plist.h"
 #include "SharedGlobals.h"
 
-//! description of SimConfig
+//! 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),
-		runTo(-1U),
 		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.)");
-		addEntry("RunToTime",runTo,"Time at which to automatically set Speed to 0, from either realtime or non-realtime mode");
 	}
 	
 	std::string cmdPrompt; //!< not persistently stored -- [re]set by main(...) on each run
 	plist::Primitive<unsigned int> initSimTime;
 	plist::NamedEnumeration<SharedGlobals::runlevel_t> tgtRunlevel;
-	plist::Primitive<unsigned int> runTo;
 
 	void setLastFile(const std::string& str) const {
 		lastfile=str;
@@ -32,13 +29,13 @@
 	const std::string& getLastFile() const {
 		return lastfile;
 	}
-	virtual	unsigned int LoadFile(const char* filename) {
+	virtual	unsigned int loadFile(const char* filename) {
 		lastfile=filename;
-		return Dictionary::LoadFile(filename);
+		return Dictionary::loadFile(filename);
 	}
-	virtual unsigned int SaveFile(const char* filename) const {
+	virtual unsigned int saveFile(const char* filename) const {
 		lastfile=filename;
-		return Dictionary::SaveFile(filename);
+		return Dictionary::saveFile(filename);
 	}
 	
 protected:
@@ -46,7 +43,7 @@
 };
 
 /*! @file
- * @brief 
+ * @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 $
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/Simulator.cc ./local/sim/Simulator.cc
--- ../Tekkotsu_2.4.1/local/sim/Simulator.cc	2005-08-03 02:37:41.000000000 -0400
+++ ./local/sim/Simulator.cc	2006-09-26 17:42:50.000000000 -0400
@@ -1,51 +1,102 @@
 #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()),
+: Process(getID(),getClassName()), frameCounter(),
 cameraQueue(ipc_setup->registerRegion(Simulator::getCameraQueueID(),sizeof(sim::CameraQueue_t))),
 sensorQueue(ipc_setup->registerRegion(Simulator::getSensorQueueID(),sizeof(sim::SensorQueue_t))),
-vision("images", ".*\\.jpg", 30, *cameraQueue),
-sensors("sensors", ".*\\.txt", 1000.f/NumFrames/FrameTime, *sensorQueue),
-visionLayer(-2)
+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);
-	sim::config.addEntry("Vision",vision);
-	vision.addEntry("Layer",visionLayer,"Controls at what resolution layer the image should be processed.\n0 and positive numbers indicate the resolution layer directly as it would be accessed by behaviors.\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.");
+	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]);
-		cmdSet(setarg);
+		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;
+		}
 	}
-	if(globals->timeScale<0) {
-		cameraQueue->setOverflowPolicy(MessageQueueBase::WAIT);
-		sensorQueue->setOverflowPolicy(MessageQueueBase::WAIT);
-	} else {
-		cameraQueue->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
-		sensorQueue->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
+	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;
 	}
-	globals->timeScale.addPrimitiveListener(this);
+	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);
 }
 
@@ -53,34 +104,50 @@
 	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;
 
-	vision.addStatusListener(this);
-	vision.addStatusListener(this);
-	vision.loadFileList();
-	vision.start();
-
-	processRunlevel(SharedGlobals::RUNNING);
+	resetSpeedMode();
+	if(globals->timeScale<0)
+		incrementTime();
 
-	vision.stop();
-	vision.removeStatusListener(this);
-	vision.removeStatusListener(this);
+	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();
-	cout << "So long buddy!" << endl;
 }
 
 void Simulator::plistValueChanged(const plist::PrimitiveBase& pl) {
 	if(&pl==&globals->timeScale) {
 		get_time(); // force SharedGlobals to notice the change and update its state
-		if(globals->timeScale<0) {
-			cameraQueue->setOverflowPolicy(MessageQueueBase::WAIT);
-			sensorQueue->setOverflowPolicy(MessageQueueBase::WAIT);
-			unsigned int next=std::min(vision.nextTimestamp(),sensors.nextTimestamp());
-			if(next!=-1U)
-				globals->simulatorTime=next;
-		} else {
-			cameraQueue->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
-			sensorQueue->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
+		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";
@@ -88,113 +155,329 @@
 }
 
 void Simulator::messagesRead(MessageQueueBase& mq, unsigned int /*n*/) {
+	MarkScope l(simLock);
 	if(globals->timeScale<0) {
-		if(&mq==&(*cameraQueue)) {
-			unsigned int next=vision.nextTimestamp();
-			if(next!=-1U)
-				globals->simulatorTime=next;
+		//clear corresponding bit in waitingSteps
+		 if(&mq==&(*cameraQueue)) {
+			//cout << "Camera read, ";
+			waitingSteps&=~(1<<STEP_CAMERA);
 		} else if(&mq==&(*sensorQueue)) {
-			unsigned int next=sensors.nextTimestamp();
-			if(next!=-1U)
-				globals->simulatorTime=next;
+			//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::processRunlevel(SharedGlobals::runlevel_t curLevel) {
+
+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;
-		cout << sim::config.cmdPrompt << flush;
-		getline(cin,line);
-		if(line=="shutdown" || line=="quit" || line=="exit" || !cin) {
-			sim::config.tgtRunlevel=SharedGlobals::DESTRUCTED;
-			break;
-		}
-		vector<string> args;
-		vector <unsigned int> offs;
-		if(!string_util::parseArgs(line,args,offs)) {
-			cerr << "Mismatched quotes" << endl;
+#ifndef DISABLE_READLINE
+		char* readin=readline(sim::config.cmdPrompt.c_str());
+		if(readin==NULL) {
+			cmdQuit(vector<string>());
 			continue;
 		}
-		if(args.size()==0)
+		line=readin;
+		free(readin);
+#else
+		cout << sim::config.cmdPrompt << flush;
+		getline(cin,line);
+		if(!cin) {
+			cmdQuit(vector<string>());
 			continue;
-		if(args[0]=="load") {
-			cmdLoad(args);
-		} else if(args[0]=="save") {
-			cmdSave(args);
-		} else if(args[0]=="runlevel") {
-			cmdRunlevel(args, curLevel);
-		} 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,curLevel,false);
-		} else if(args[0]=="runfor") {
-			cmdRun(args,curLevel,true);
-		} else if(args[0]=="run") {
-			cmdRun(args,curLevel);
-		} else if(args[0]=="pause") {
-			cmdPause(args,curLevel);
-		} else if(args[0]=="help") {
-			cmdHelp(args);
-		} else {
-			cout << "Unknown command '" << args[0] << "'" << endl;
 		}
+#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());
+			sim::config.loadFile(args[i].c_str());
 	else
-		sim::config.LoadFile(sim::config.getLastFile().c_str());
+		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());
+			sim::config.saveFile(args[i].c_str());
 	else
-		sim::config.SaveFile(sim::config.getLastFile().c_str());
+		sim::config.saveFile(sim::config.getLastFile().c_str());
 }
-void Simulator::cmdRunlevel(const std::vector<std::string>& args, SharedGlobals::runlevel_t curLevel) {
-	if(args.size()==1) {
+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;
-		return;
-	}
-	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;
-	} 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;
+	} 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();
 }
-void Simulator::cmdSet(const std::vector<std::string>& args) {
-	if(args.size()==1) {
+bool Simulator::cmdSet(const std::vector<std::string>& args) {
+	if(args.size()<=1) {
 		cout << sim::config << endl;
-		return;
+		return false;
 	}
 	string arg;
 	for(unsigned int i=1; i<args.size(); i++) {
@@ -203,23 +486,24 @@
 			arg+=" ";
 	}
 	if(arg.rfind("=")==string::npos) {
-		plist::ObjectBase* ob=sim::config.findEntry(arg);
+		plist::ObjectBase* ob=sim::config.getEntry(arg);
 		if(ob==NULL) {
 			cout << "'" << arg << "' is unknown" << endl;
-			return;
+			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.findEntry(key);
+		plist::ObjectBase* ob=sim::config.getEntry(key);
 		if(ob==NULL) {
 			cout << "'" << key << "' is unknown" << endl;
-			return;
+			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;
@@ -228,22 +512,44 @@
 			}
 		} else {
 			cout << "Cannot assign to a dictionary" << endl;
-			return;
+			return false;
 		}
 	}
+	return false; //exception occurred
 }
-void Simulator::cmdRun(const std::vector<std::string>& args, SharedGlobals::runlevel_t /*curLevel*/, bool isRelative) {
-	if(args.size()<=1)
+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*/, SharedGlobals::runlevel_t /*curLevel*/) {
-	globals->timeScale=1;
+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*/, SharedGlobals::runlevel_t /*curLevel*/) {
+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) {
@@ -259,27 +565,57 @@
 		syntax["runlevel"]+=ss.str();
 	}
 	syntax["runlevel"]+="]";
-	syntax["get_time"]+="";
-	syntax["set"]+="[var=value]";
-	syntax["runto"]+="time";
-	syntax["runfor"]+="time";
-	syntax["run"]+="";
-	syntax["pause"]+="";
+	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'.";
-	help["save"]="Save simulator configuration to file; if file unspecified, defaults to 'simulator.plist'.";
+	
+	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,\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\n"
-		"all available variables and their current values.  Type 'help set <variable>' to get\n"
-		"more information about a particular variable.";
-	help["runto"]="Will advance the simulator time to a the specified value and then set Speed to 0.";
-	help["runfor"]="Will advance the simulator time forward the specified number of milliseconds and then set Speed to 0.";
-	help["run"]="Equivalent to 'set Speed=1'";
-	help["pause"]="Equivalent to 'set Speed=0'";
+	
+	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;
@@ -297,7 +633,7 @@
 			cout << help[args[1]] << endl;
 		} else {
 			if(args[1]=="set") {
-				plist::ObjectBase* ob=sim::config.findEntry(args[2]);
+				plist::ObjectBase* ob=sim::config.getEntry(args[2]);
 				if(ob==NULL) {
 					cout << "'" << args[2] << "' is unknown" << endl;
 					return;
@@ -306,7 +642,7 @@
 				if(n==string::npos)
 					cout << sim::config.getComment(args[2]) << endl;
 				else {
-					ob=sim::config.findEntry(args[2].substr(0,n));
+					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
@@ -319,7 +655,222 @@
 		}
 	}
 }
-
+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 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/Simulator.h ./local/sim/Simulator.h
--- ../Tekkotsu_2.4.1/local/sim/Simulator.h	2005-08-03 02:37:42.000000000 -0400
+++ ./local/sim/Simulator.h	2006-09-28 16:42:52.000000000 -0400
@@ -5,11 +5,14 @@
 #include "Process.h"
 #include "sim.h"
 #include "IPC/SharedObject.h"
+#include "IPC/MessageQueueStatusThread.h"
 #include "SharedGlobals.h"
 #include "Shared/plist.h"
-#include "LoadImageThread.h"
+#include "Shared/debuget.h"
+#include "local/LoadImageThread.h"
+#include <set>
 
-class Simulator : public Process,  public plist::PrimitiveListener, public MessageQueueBase::StatusListener {
+class Simulator : public Process,  public plist::PrimitiveListener, public MessageQueueStatusThread::StatusListener {
 public:
 	//! constructor
 	Simulator();
@@ -25,27 +28,96 @@
 	
 	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:
-	void processRunlevel(SharedGlobals::runlevel_t curLevel);
+	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, SharedGlobals::runlevel_t curLevel);
-	void cmdSet(const std::vector<std::string>& args);
-	void cmdRun(const std::vector<std::string>& args, SharedGlobals::runlevel_t curLevel, bool isRelative);
-	void cmdRun(const std::vector<std::string>& args, SharedGlobals::runlevel_t curLevel);
-	void cmdPause(const std::vector<std::string>& args, SharedGlobals::runlevel_t curLevel);
+	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;
-	LoadImageThread sensors;
-	plist::Primitive<int> visionLayer;
+	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)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/SoundPlay.cc ./local/sim/SoundPlay.cc
--- ../Tekkotsu_2.4.1/local/sim/SoundPlay.cc	2005-06-29 18:06:41.000000000 -0400
+++ ./local/sim/SoundPlay.cc	2006-09-18 14:07:58.000000000 -0400
@@ -1,4 +1,5 @@
 #include "SoundPlay.h"
+#include "Simulator.h"
 #include "SharedGlobals.h"
 #include "Main.h"
 #include "IPC/RegionRegistry.h"
@@ -9,12 +10,16 @@
 	: 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))),
-		etrans(NULL), sndrecv(NULL)
+		soundProf(ipc_setup->registerRegion(getSoundProfilerID(),sizeof(soundProfiler_t))),
+		etrans(NULL), sndrecv(NULL), statusrecv(NULL)
 {
 	new (&(*requests)) sim::SoundPlayQueue_t;
-	new (&(*soundmanager)) SoundManager();
+	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
@@ -40,13 +45,19 @@
 			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;
-	sndman->StopPlay();
+	delete statusrecv;
+	statusrecv=NULL;
+	
+	sndman->stopPlay();
 	erouter->removeTrapper(etrans);
 	Process::DoStop();
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/SoundPlay.h ./local/sim/SoundPlay.h
--- ../Tekkotsu_2.4.1/local/sim/SoundPlay.h	2005-06-29 18:06:41.000000000 -0400
+++ ./local/sim/SoundPlay.h	2006-07-13 13:25:51.000000000 -0400
@@ -8,6 +8,7 @@
 #include "IPC/SharedObject.h"
 #include "SharedGlobals.h"
 #include "Sound/SoundManager.h"
+#include "Shared/Profiler.h"
 
 class SoundPlay : public Process {
 public:
@@ -24,13 +25,18 @@
 	
 	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:
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/TimerExecThread.cc ./local/sim/TimerExecThread.cc
--- ../Tekkotsu_2.4.1/local/sim/TimerExecThread.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/sim/TimerExecThread.cc	2006-07-11 18:40:25.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) && 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: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/TimerExecThread.h ./local/sim/TimerExecThread.h
--- ../Tekkotsu_2.4.1/local/sim/TimerExecThread.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/sim/TimerExecThread.h	2006-08-23 15:02:32.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: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/local/sim/sim.cc ./local/sim/sim.cc
--- ../Tekkotsu_2.4.1/local/sim/sim.cc	2005-08-04 17:30:07.000000000 -0400
+++ ./local/sim/sim.cc	2006-09-28 16:42:52.000000000 -0400
@@ -8,6 +8,8 @@
 #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>
@@ -19,18 +21,19 @@
 #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[]) {
@@ -38,125 +41,160 @@
 	//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();
 	
-	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;
+#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()
+	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(SIGTERM, handle_signal);
-	signal(SIGSEGV, handle_signal);
-	signal(SIGBUS, handle_signal);
-	signal(SIGPIPE, handle_signal);
+	signal(SIGILL, handle_signal);
 	signal(SIGABRT, handle_signal);
 	signal(SIGFPE, handle_signal);
-	signal(SIGHUP, 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.");
-	sim::config.addEntry("AdvanceOnAccess",globals->advanceOnAccess,"When running in non-realtime mode (see Speed), the simulator can either automatically advance to the next input after the previous input was accessed (if true), or wait until an explicit call to Main::advanceVision() (or manual change from the simulator command line) (if false)");
 	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("ms/config/tekkotsu.cfg");
+	::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];
-/*
-		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);
 	}
-
 }
-
+	
 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)) {
+		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]))
+			if(!sim::config.loadFile(argv[++i]))
 				return false;
 		} else if(strchr(argv[i],'=')!=NULL) {
-			assignments.push_back(argv[i]);
+			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;
@@ -165,26 +203,40 @@
 	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() {
-	config.removeEntry("TimeMultiplier");
 	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 << "Waiting for children to exit..." << endl;
-	int res=wait(NULL);
-	if(res<0 && errno!=ECHILD)
-		perror("wait");
+		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]++;
@@ -198,11 +250,11 @@
 		cout << "|  done" << endl;
 	globals->lock.unlock();
 	while(globals->level_count[level]!=globals->level_count[SharedGlobals::CREATED])
-		usleep(1000);
+		usleep(150*1000);
 	globals->lock.lock(ProcessID::getID());
 	globals->lock.unlock();
 }
-
+	
 template<class T>
 void sim::manage_process() {
 	//initialize the first runlevel
@@ -213,10 +265,10 @@
 	ASSERT(T::getID()==ProcessID::getID(),"Process ID set incorrectly!");
 	globals->lock.unlock();
 	while(globals->level_count[SharedGlobals::CONSTRUCTING]!=globals->level_count[SharedGlobals::CREATED])
-		usleep(500);
+		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();
@@ -226,50 +278,55 @@
 	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]++;
-	if(fork()) {
+	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.   */
 	
+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);
+	//	signal(sig, handle_signal);
 	/* mask any further signals while we're inside the handler. */
-//	sigfillset(&mask_set);
-//	sigprocmask(SIG_SETMASK, &mask_set, &old_set);
-	
+	//	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;
+	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;
@@ -279,7 +336,9 @@
 		return;
 	}
 	firstCall=false;
-
+	
+	stacktrace::displayCurrentStackTrace(15);
+	
 	cout << "*** ERROR " << Process::getName() << ": Engaging fault shutdown..." << endl;
 	if(globals!=NULL && !globals->hadFault()) {
 		if(!MutexLockBase::getSemaphoreManager()->hadFault())
@@ -303,7 +362,7 @@
 	cout << "*** ERROR " << Process::getName() << ": Exiting..." << endl;
 	exit(EXIT_FAILURE);
 }
-
+	
 void sim::handle_exit() {
 	static bool firstCall=true;
 	if(!firstCall) {
@@ -311,14 +370,14 @@
 		return;
 	}
 	firstCall=false;
-	cout << Process::getName() << ": Exiting..." << endl;
+	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" << endl;
-	cout << "*** ERROR " << Process::getName() << ": Engaging fault shutdown..." << endl;
+	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());
@@ -344,20 +403,20 @@
 	RCRegion::faultShutdown();
 	cout << "*** ERROR " << Process::getName() << ": Exiting..." << endl;
 }
-
+	
 unsigned int sim::measure_usleep_cost() {
-	usleep(5000); //to hopefully clear out the scheduler for the duration of our test
+	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(0);
+		usleep(1); // at least 1 to avoid being a no-op
 		TimeET elapsed(cur.Age());
 		if(elapsed<mintime)
 			mintime=elapsed;
 	}
-	usleep(5000); //to hopefully clear out the scheduler for the duration of our test
+	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
@@ -366,8 +425,18 @@
 		if(elapsed<minover)
 			minover=elapsed;
 	}
-	//subtract overhead
-	mintime-=minover;
-	cout << "usleep granularity is " << mintime.Value()*1.0e6 << "us" << endl;
+	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_2.4.1/local/sim/sim.h ./local/sim/sim.h
--- ../Tekkotsu_2.4.1/local/sim/sim.h	2005-08-01 19:18:00.000000000 -0400
+++ ./local/sim/sim.h	2006-10-03 19:11:37.000000000 -0400
@@ -8,6 +8,7 @@
 #include "IPC/SharedObject.h"
 #include "IPC/Thread.h"
 #include "Wireless/Wireless.h"
+#include "Shared/ProjectInterface.h"
 #include <vector>
 class SimConfig;
 
@@ -23,6 +24,10 @@
 	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;
@@ -34,6 +39,7 @@
 	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();
@@ -43,10 +49,20 @@
 	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
@@ -54,6 +70,10 @@
 		wireless->pollSetup(); // reinitialize for next test
 		return 0; //no sleep time because pollTest blocks
 	}
+	virtual void stop() {
+		Thread::stop();
+		wireless->wakeup();
+	}
 };
 
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/Environment.conf ./project/Environment.conf
--- ../Tekkotsu_2.4.1/project/Environment.conf	2005-08-12 12:25:16.000000000 -0400
+++ ./project/Environment.conf	2006-05-09 12:28:42.000000000 -0400
@@ -10,15 +10,19 @@
 TEKKOTSU_ROOT ?= /usr/local/Tekkotsu
 
 # Location where the memstick will be mounted
-# If you're using cygwin, you probably want something like
-# '/cygdrive/e' instead.
-# Mac OS users would want to use something like '/Volumes/xxx',
-# where 'xxx' is the name of the memory stick, often initially
-# 'Unlabeled' or 'Untitled'
 # You may wish to override this as an environment variable
 # instead of changing it here, as the former will allow you to run
 # tools/mntmem and tools/umntmem manually.
-MEMSTICK_ROOT ?= /mnt/memstick
+ifeq ($(findstring Darwin,$(shell uname)),Darwin)
+# For OS X users, the following script assumes the highest numbered
+# device is your memory stick.  Feel free to replace this with the actual
+# mount point (e.g. /Volumes/Untitled) if this doesn't work.
+MEMSTICK_ROOT ?= $(shell $(TEKKOTSU_ROOT)/tools/osx_find_memstick)
+else
+# Cygwin users will probably want /cygdrive/e, and anyone else
+# will need to check /etc/mtab (we'll assume /mnt/memstick)
+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
@@ -44,7 +48,7 @@
 
 # This will trigger the project's Makefile to always attempt to make
 # the framework as well.  This is useful if you are hacking the
-# framework itself, and thus want any changes made there to be 
+# framework itself, and thus want any changes made there to be
 # compiled automatically.
 # default: ON (non-empty string) - any non-empty string is ON
 TEKKOTSU_ALWAYS_BUILD ?= true
@@ -59,15 +63,20 @@
 # default: OFF (empty string) - any non-empty string is ON
 STRICT_MEMSTICK_IMAGE ?=
 
-# This will control the debug flags such as -g and -DDEBUG
-TEKKOTSU_DEBUG ?= ON
+# This will control the debug flags such as -g and -DDEBUG, disables optimization
+# default: ON (specify compiler flags) for platform local, OFF (empty string) for others
+TEKKOTSU_DEBUG ?= $(if $(findstring PLATFORM_LOCAL,$(TEKKOTSU_TARGET_PLATFORM)),-g -fno-inline -DDEBUG)
+
+# 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)
 
 # 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 ?= ( if which more > /dev/null ; then more $(if $(findstring Darwin,$(shell uname)),-R); else cat ; fi )
+TEKKOTSU_LOGVIEW ?= $(shell if which more > /dev/null ; then echo "more $(if $(findstring Darwin,$(shell uname)),-R)"; else echo "cat" ; fi )
 
 # These control the location that the temporary object files will
 # be stored.
@@ -95,7 +104,11 @@
   MKBINFLAGS=-p $(OPENRSDK_ROOT) -L$(TEKKOTSU_ROOT)/aperios/lib
   AR=$(OPENRSDK_ROOT)/bin/mipsel-linux-ar rcs
   AR2=touch
-  FILTERSYSWARN=$(TEKKOTSU_FILTERSYSWARN) $(OPEN_R_SDK)
+  ifeq ($(TEKKOTSU_FILTERSYSWARN),cat)
+    FILTERSYSWARN=$(TEKKOTSU_FILTERSYSWARN)
+  else
+    FILTERSYSWARN=$(TEKKOTSU_FILTERSYSWARN) $(OPENRSDK_ROOT)
+  endif
   STUBGEN=$(OPENRSDK_ROOT)/OPEN_R/bin/stubgen2
 else
   CC=gcc
@@ -104,7 +117,11 @@
   STRIP=strip
   AR=ar rcs
   AR2=touch
-  FILTERSYSWARN=$(TEKKOTSU_FILTERSYSWARN) /usr/include
+  ifeq ($(TEKKOTSU_FILTERSYSWARN),cat)
+    FILTERSYSWARN=$(TEKKOTSU_FILTERSYSWARN)
+  else
+    FILTERSYSWARN=$(TEKKOTSU_FILTERSYSWARN) /usr/.*/?include/
+  endif
 endif
 COLORFILT=$(TEKKOTSU_COLORFILT)
 
@@ -112,8 +129,11 @@
 # supported by the 3.4 branch of gcc, or 3.3 of the gcc from Apple
 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
 TEST_CXX_APPLE:=$(findstring Apple,$(shell $(CXX) --version))
-TEKKOTSU_PCH ?= $(shell if [ $(TEST_CXX_MAJOR) -ge 4 -o $(TEST_CXX_MAJOR) -ge 3 -a \( $(TEST_CXX_MINOR) -ge 4 -o -n "$(TEST_CXX_APPLE)" \) ] ; then echo "common.h"; fi)
+#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)
 
 #These will be the actual build directories used for the current target
 TK_LIB_BD:=$(TEKKOTSU_BUILDDIR)/$(TEKKOTSU_TARGET_PLATFORM)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/Make.xcodeproj/project.pbxproj ./project/Make.xcodeproj/project.pbxproj
--- ../Tekkotsu_2.4.1/project/Make.xcodeproj/project.pbxproj	2005-08-12 12:25:16.000000000 -0400
+++ ./project/Make.xcodeproj/project.pbxproj	2006-09-28 16:42:52.000000000 -0400
@@ -7,31 +7,143 @@
 	objects = {
 
 /* Begin PBXBuildFile section */
+		6900659F0A4EF58700E895F9 /* PNGGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6900659D0A4EF58700E895F9 /* PNGGenerator.cc */; };
+		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 */; };
 		691C805608255F6300E8E256 /* Base64.cc in Sources */ = {isa = PBXBuildFile; fileRef = 691C805508255F6300E8E256 /* Base64.cc */; };
 		691C805708255F6300E8E256 /* Base64.cc in Sources */ = {isa = PBXBuildFile; fileRef = 691C805508255F6300E8E256 /* Base64.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 */; };
-		692CD99607F9F05500604100 /* LoadFileThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692CD99407F9F05500604100 /* LoadFileThread.cc */; };
-		692CD99707F9F05500604100 /* LoadFileThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692CD99407F9F05500604100 /* LoadFileThread.cc */; };
-		692CD99807F9F05500604100 /* LoadFileThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692CD99407F9F05500604100 /* LoadFileThread.cc */; };
 		693D801408ABF46D00AC993E /* RegionCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D801208ABF46D00AC993E /* RegionCamBehavior.cc */; };
 		693D801508ABF46D00AC993E /* RegionCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D801208ABF46D00AC993E /* RegionCamBehavior.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 */; };
 		6942779207E164EA003DE3D9 /* Thread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942779007E164EA003DE3D9 /* Thread.cc */; };
+		69469FC809AA1D2100D1EC14 /* AgentData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F6C09AA1D2000D1EC14 /* AgentData.cc */; };
+		69469FC909AA1D2100D1EC14 /* BaseData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F6E09AA1D2000D1EC14 /* BaseData.cc */; };
+		69469FCA09AA1D2100D1EC14 /* BlobData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7009AA1D2000D1EC14 /* BlobData.cc */; };
+		69469FCB09AA1D2100D1EC14 /* BrickData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7209AA1D2000D1EC14 /* BrickData.cc */; };
+		69469FCD09AA1D2100D1EC14 /* EllipseData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7709AA1D2000D1EC14 /* EllipseData.cc */; };
+		69469FCE09AA1D2100D1EC14 /* EndPoint.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7909AA1D2000D1EC14 /* EndPoint.cc */; };
+		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 */; };
+		69469FDA09AA1D2100D1EC14 /* PolygonData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9209AA1D2000D1EC14 /* PolygonData.cc */; };
+		69469FDB09AA1D2100D1EC14 /* Region.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9409AA1D2000D1EC14 /* Region.cc */; };
+		69469FDC09AA1D2100D1EC14 /* ShapeAgent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9609AA1D2000D1EC14 /* ShapeAgent.cc */; };
+		69469FDD09AA1D2100D1EC14 /* ShapeBlob.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9809AA1D2000D1EC14 /* ShapeBlob.cc */; };
+		69469FDE09AA1D2100D1EC14 /* ShapeBrick.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9A09AA1D2000D1EC14 /* ShapeBrick.cc */; };
+		69469FDF09AA1D2100D1EC14 /* ShapeEllipse.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9C09AA1D2000D1EC14 /* ShapeEllipse.cc */; };
+		69469FE009AA1D2100D1EC14 /* ShapeFuns.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9E09AA1D2000D1EC14 /* ShapeFuns.cc */; };
+		69469FE109AA1D2100D1EC14 /* ShapeLine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA009AA1D2100D1EC14 /* ShapeLine.cc */; };
+		69469FE209AA1D2100D1EC14 /* ShapePoint.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA209AA1D2100D1EC14 /* ShapePoint.cc */; };
+		69469FE309AA1D2100D1EC14 /* ShapePolygon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA409AA1D2100D1EC14 /* ShapePolygon.cc */; };
+		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 */; };
+		69469FEB09AA1D2100D1EC14 /* SketchRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB609AA1D2100D1EC14 /* SketchRoot.cc */; };
+		69469FEC09AA1D2100D1EC14 /* SketchSpace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB809AA1D2100D1EC14 /* SketchSpace.cc */; };
+		69469FED09AA1D2100D1EC14 /* SphereData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBB09AA1D2100D1EC14 /* SphereData.cc */; };
+		69469FEE09AA1D2100D1EC14 /* susan.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBD09AA1D2100D1EC14 /* susan.cc */; };
+		69469FEF09AA1D2100D1EC14 /* ViewerConnection.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBF09AA1D2100D1EC14 /* ViewerConnection.cc */; };
+		69469FF009AA1D2100D1EC14 /* visops.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FC109AA1D2100D1EC14 /* visops.cc */; };
+		69469FF109AA1D2100D1EC14 /* VisualRoutinesBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FC309AA1D2100D1EC14 /* VisualRoutinesBehavior.cc */; };
+		69469FF309AA1D2100D1EC14 /* AgentData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F6C09AA1D2000D1EC14 /* AgentData.cc */; };
+		69469FF409AA1D2100D1EC14 /* BaseData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F6E09AA1D2000D1EC14 /* BaseData.cc */; };
+		69469FF509AA1D2100D1EC14 /* BlobData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7009AA1D2000D1EC14 /* BlobData.cc */; };
+		69469FF609AA1D2100D1EC14 /* BrickData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7209AA1D2000D1EC14 /* BrickData.cc */; };
+		69469FF809AA1D2100D1EC14 /* EllipseData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7709AA1D2000D1EC14 /* EllipseData.cc */; };
+		69469FF909AA1D2100D1EC14 /* EndPoint.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7909AA1D2000D1EC14 /* EndPoint.cc */; };
+		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 */; };
+		6946A00509AA1D2100D1EC14 /* PolygonData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9209AA1D2000D1EC14 /* PolygonData.cc */; };
+		6946A00609AA1D2100D1EC14 /* Region.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9409AA1D2000D1EC14 /* Region.cc */; };
+		6946A00709AA1D2100D1EC14 /* ShapeAgent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9609AA1D2000D1EC14 /* ShapeAgent.cc */; };
+		6946A00809AA1D2100D1EC14 /* ShapeBlob.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9809AA1D2000D1EC14 /* ShapeBlob.cc */; };
+		6946A00909AA1D2100D1EC14 /* ShapeBrick.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9A09AA1D2000D1EC14 /* ShapeBrick.cc */; };
+		6946A00A09AA1D2100D1EC14 /* ShapeEllipse.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9C09AA1D2000D1EC14 /* ShapeEllipse.cc */; };
+		6946A00B09AA1D2100D1EC14 /* ShapeFuns.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9E09AA1D2000D1EC14 /* ShapeFuns.cc */; };
+		6946A00C09AA1D2100D1EC14 /* ShapeLine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA009AA1D2100D1EC14 /* ShapeLine.cc */; };
+		6946A00D09AA1D2100D1EC14 /* ShapePoint.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA209AA1D2100D1EC14 /* ShapePoint.cc */; };
+		6946A00E09AA1D2100D1EC14 /* ShapePolygon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA409AA1D2100D1EC14 /* ShapePolygon.cc */; };
+		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 */; };
+		6946A01609AA1D2100D1EC14 /* SketchRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB609AA1D2100D1EC14 /* SketchRoot.cc */; };
+		6946A01709AA1D2200D1EC14 /* SketchSpace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB809AA1D2100D1EC14 /* SketchSpace.cc */; };
+		6946A01809AA1D2200D1EC14 /* SphereData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBB09AA1D2100D1EC14 /* SphereData.cc */; };
+		6946A01909AA1D2200D1EC14 /* susan.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBD09AA1D2100D1EC14 /* susan.cc */; };
+		6946A01A09AA1D2200D1EC14 /* ViewerConnection.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBF09AA1D2100D1EC14 /* ViewerConnection.cc */; };
+		6946A01B09AA1D2200D1EC14 /* visops.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FC109AA1D2100D1EC14 /* visops.cc */; };
+		6946A01C09AA1D2200D1EC14 /* VisualRoutinesBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FC309AA1D2100D1EC14 /* VisualRoutinesBehavior.cc */; };
+		6946A1A209AAE1C600D1EC14 /* VRmixin.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6946A1A109AAE1C600D1EC14 /* VRmixin.cc */; };
+		6946A1A309AAE1C600D1EC14 /* VRmixin.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6946A1A109AAE1C600D1EC14 /* VRmixin.cc */; };
+		6946A1A609AAE1D800D1EC14 /* VisualRoutinesStateNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6946A1A409AAE1D800D1EC14 /* VisualRoutinesStateNode.cc */; };
+		6946A1A709AAE1D800D1EC14 /* VisualRoutinesStateNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6946A1A409AAE1D800D1EC14 /* VisualRoutinesStateNode.cc */; };
 		694AB43707F48A860071A2AE /* libjpeg.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 694AB43507F48A860071A2AE /* libjpeg.dylib */; };
 		694AB43807F48A860071A2AE /* libpng12.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 694AB43607F48A860071A2AE /* libpng12.dylib */; };
 		694AB43907F48A860071A2AE /* libjpeg.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 694AB43507F48A860071A2AE /* libjpeg.dylib */; };
 		694AB43A07F48A860071A2AE /* libpng12.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 694AB43607F48A860071A2AE /* libpng12.dylib */; };
 		694AB43B07F48A860071A2AE /* libjpeg.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 694AB43507F48A860071A2AE /* libjpeg.dylib */; };
 		694AB43C07F48A860071A2AE /* libpng12.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 694AB43607F48A860071A2AE /* libpng12.dylib */; };
-		695967E207FF3DCF004FABFF /* LoadImageThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695967E007FF3DCF004FABFF /* LoadImageThread.cc */; };
-		695967E307FF3DCF004FABFF /* LoadImageThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695967E007FF3DCF004FABFF /* LoadImageThread.cc */; };
-		695967E407FF3DCF004FABFF /* LoadImageThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695967E007FF3DCF004FABFF /* LoadImageThread.cc */; };
+		694B2B200A0FC983002ABC4C /* SketchPoolRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694B2B1E0A0FC983002ABC4C /* SketchPoolRoot.cc */; };
+		694B36570A190FE2002ABC4C /* jpeg_mem_src.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694B36560A190FE2002ABC4C /* jpeg_mem_src.cc */; };
+		694B36580A190FE2002ABC4C /* jpeg_mem_src.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694B36560A190FE2002ABC4C /* jpeg_mem_src.cc */; };
+		694E67E60AC308290087EC83 /* PitchEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694E67E40AC308290087EC83 /* PitchEvent.cc */; };
+		694E67E70AC308290087EC83 /* PitchEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694E67E40AC308290087EC83 /* PitchEvent.cc */; };
+		694E68560AC33A120087EC83 /* PitchDetector.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694E684B0AC338CF0087EC83 /* PitchDetector.cc */; };
+		694E68570AC33A120087EC83 /* PitchDetector.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694E684B0AC338CF0087EC83 /* PitchDetector.cc */; };
+		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 */; };
 		695F1ACA0804A81800ACB3D7 /* BufferedImageGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695F1AC80804A81800ACB3D7 /* BufferedImageGenerator.cc */; };
 		695F1ACB0804A81800ACB3D7 /* BufferedImageGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695F1AC80804A81800ACB3D7 /* BufferedImageGenerator.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 */; };
+		6962F2F00A917E74002DDEC9 /* Aibo3DControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2EE0A917E74002DDEC9 /* Aibo3DControllerBehavior.cc */; };
+		6962F2FF0A917F41002DDEC9 /* LookoutRequests.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2FD0A917F40002DDEC9 /* LookoutRequests.cc */; };
+		6962F3000A917F41002DDEC9 /* LookoutRequests.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2FD0A917F40002DDEC9 /* LookoutRequests.cc */; };
+		6966753C0926558A00405769 /* MCNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6966753B0926558A00405769 /* MCNode.cc */; };
+		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 */; };
+		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 */; };
+		698A071E09575F41001A13D5 /* plistBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 698A071B09575F41001A13D5 /* plistBase.cc */; };
+		698A072909575F7D001A13D5 /* plistCollections.cc in Sources */ = {isa = PBXBuildFile; fileRef = 698A072709575F7D001A13D5 /* plistCollections.cc */; };
+		698A072A09575F7D001A13D5 /* plistCollections.cc in Sources */ = {isa = PBXBuildFile; fileRef = 698A072709575F7D001A13D5 /* plistCollections.cc */; };
 		6994F3D907D4D35F003A7628 /* SemaphoreManager.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3CF07D4D35F003A7628 /* SemaphoreManager.cc */; };
 		6994F3DA07D4D35F003A7628 /* ProcessID.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3D107D4D35F003A7628 /* ProcessID.cc */; };
 		6994F3DB07D4D35F003A7628 /* RCRegion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3D307D4D35F003A7628 /* RCRegion.cc */; };
@@ -47,11 +159,36 @@
 		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 */; };
+		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 */; };
+		69A7EF2809C9EA77003DDD18 /* plistPrimitives.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EF2709C9EA77003DDD18 /* plistPrimitives.cc */; };
+		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 */; };
+		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 */; };
+		69B3446E0A7152AC0021FBE6 /* ShapePyramid.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B3446B0A7152AC0021FBE6 /* ShapePyramid.cc */; };
+		69B344710A7152C30021FBE6 /* BrickOps.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B3446F0A7152C30021FBE6 /* BrickOps.cc */; };
+		69B344720A7152C30021FBE6 /* BrickOps.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B3446F0A7152C30021FBE6 /* BrickOps.cc */; };
 		69B4E446089409D900832D58 /* StareAtPawBehavior2.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B4E445089409D800832D58 /* StareAtPawBehavior2.cc */; };
 		69B4E447089409D900832D58 /* StareAtPawBehavior2.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B4E445089409D800832D58 /* StareAtPawBehavior2.cc */; };
 		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 */; };
+		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 */; };
+		69D5F82A09BBDF0C000602D2 /* MessageQueueStatusThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D5F82709BBDF0C000602D2 /* MessageQueueStatusThread.cc */; };
 		69E0A76407CBD4F9008493CA /* StartupBehavior_SetupBackgroundBehaviors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75907CBD4F9008493CA /* StartupBehavior_SetupBackgroundBehaviors.cc */; };
 		69E0A76507CBD4F9008493CA /* StartupBehavior_SetupFileAccess.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75A07CBD4F9008493CA /* StartupBehavior_SetupFileAccess.cc */; };
 		69E0A76607CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75B07CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc */; };
@@ -85,7 +222,6 @@
 		69E0A9CF07CBD6C1008493CA /* ChaseBallBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7C807CBD6C0008493CA /* ChaseBallBehavior.cc */; };
 		69E0A9D207CBD6C1008493CA /* DriveMeBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7CB07CBD6C0008493CA /* DriveMeBehavior.cc */; };
 		69E0A9D407CBD6C1008493CA /* ExploreMachine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7CD07CBD6C0008493CA /* ExploreMachine.cc */; };
-		69E0A9D607CBD6C1008493CA /* FlashIPAddrBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7CF07CBD6C0008493CA /* FlashIPAddrBehavior.cc */; };
 		69E0A9D807CBD6C1008493CA /* FollowHeadBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7D107CBD6C0008493CA /* FollowHeadBehavior.cc */; };
 		69E0A9E407CBD6C1008493CA /* PaceTargetsMachine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7DD07CBD6C0008493CA /* PaceTargetsMachine.cc */; };
 		69E0A9E907CBD6C1008493CA /* StareAtBallBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7E207CBD6C0008493CA /* StareAtBallBehavior.cc */; };
@@ -221,7 +357,6 @@
 		69E0ABBB07CBDE11008493CA /* ChaseBallBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7C807CBD6C0008493CA /* ChaseBallBehavior.cc */; };
 		69E0ABBC07CBDE11008493CA /* DriveMeBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7CB07CBD6C0008493CA /* DriveMeBehavior.cc */; };
 		69E0ABBD07CBDE11008493CA /* ExploreMachine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7CD07CBD6C0008493CA /* ExploreMachine.cc */; };
-		69E0ABBE07CBDE11008493CA /* FlashIPAddrBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7CF07CBD6C0008493CA /* FlashIPAddrBehavior.cc */; };
 		69E0ABBF07CBDE11008493CA /* FollowHeadBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7D107CBD6C0008493CA /* FollowHeadBehavior.cc */; };
 		69E0ABC007CBDE11008493CA /* PaceTargetsMachine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7DD07CBD6C0008493CA /* PaceTargetsMachine.cc */; };
 		69E0ABC107CBDE11008493CA /* StareAtBallBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7E207CBD6C0008493CA /* StareAtBallBehavior.cc */; };
@@ -347,8 +482,8 @@
 		69E666BD07F0CE51005F4FA9 /* plist.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E666BB07F0CE51005F4FA9 /* plist.cc */; };
 		69E6674907F1E23A005F4FA9 /* XMLLoadSave.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E6674707F1E23A005F4FA9 /* XMLLoadSave.cc */; };
 		69E6674A07F1E23A005F4FA9 /* XMLLoadSave.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E6674707F1E23A005F4FA9 /* XMLLoadSave.cc */; };
-		69E6696507F3398F005F4FA9 /* SimConfig.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E6696307F3398F005F4FA9 /* SimConfig.cc */; };
-		69E6696607F3398F005F4FA9 /* SimConfig.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E6696307F3398F005F4FA9 /* SimConfig.cc */; };
+		69E78D0309F6C114000385E9 /* StackTrace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E78D0109F6C114000385E9 /* StackTrace.cc */; };
+		69E78D0409F6C115000385E9 /* StackTrace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E78D0109F6C114000385E9 /* StackTrace.cc */; };
 		69EA8B9507EB57480047DA8D /* libiconv.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9207EB57480047DA8D /* libiconv.dylib */; };
 		69EA8B9607EB57480047DA8D /* libxml2.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9307EB57480047DA8D /* libxml2.dylib */; };
 		69EA8B9707EB57480047DA8D /* libz.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9407EB57480047DA8D /* libz.dylib */; };
@@ -358,6 +493,8 @@
 		69EA8B9B07EB57480047DA8D /* libiconv.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9207EB57480047DA8D /* libiconv.dylib */; };
 		69EA8B9C07EB57480047DA8D /* libxml2.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9307EB57480047DA8D /* libxml2.dylib */; };
 		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 */; };
 		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 */; };
@@ -366,94 +503,140 @@
 		69FA4904084C39230003A261 /* UPennWalkControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA4901084C39230003A261 /* UPennWalkControllerBehavior.cc */; };
 /* End PBXBuildFile section */
 
-/* Begin PBXBuildStyle section */
-		014CEA460018CE2711CA2923 /* Development */ = {
-			isa = PBXBuildStyle;
-			buildSettings = {
-				COPY_PHASE_STRIP = 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_WARN_ABOUT_MISSING_PROTOTYPES = 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 = NO;
-				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;
-				GENERATE_PROFILING_CODE = YES;
-				HEADER_SEARCH_PATHS = (
-					"$(TEKKOTSU_ROOT)",
-					/usr/include/libxml2,
-				);
-				OBJROOT = build;
-				PREBINDING = NO;
-				SYMROOT = "";
-				WARNING_CFLAGS = (
-					"-Wall",
-					"-W",
-					"-Wpointer-arith",
-					"-Wcast-qual",
-					"-Woverloaded-virtual",
-					"-Wdeprecated",
-				);
-			};
-			name = Development;
-		};
-		014CEA470018CE2711CA2923 /* Deployment */ = {
-			isa = PBXBuildStyle;
-			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)";
-				ZERO_LINK = NO;
-			};
-			name = Deployment;
-		};
-/* End PBXBuildStyle section */
-
 /* Begin PBXFileReference section */
 		0249A663FF388D9811CA2CEA /* libstdc++.a */ = {isa = PBXFileReference; lastKnownFileType = archive.ar; name = "libstdc++.a"; path = "/usr/lib/libstdc++.a"; sourceTree = "<absolute>"; };
-		690564F20819531A00613A0E /* minisim.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = minisim.h; path = /Users/ejt/todo/Tekkotsu/local/minisim.h; 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>"; };
 		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>"; };
+		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>"; };
-		692CD99407F9F05500604100 /* LoadFileThread.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = LoadFileThread.cc; sourceTree = "<group>"; };
-		692CD99507F9F05500604100 /* LoadFileThread.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = LoadFileThread.h; sourceTree = "<group>"; };
 		6934224207D408E600BB3331 /* sim.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = sim.h; sourceTree = "<group>"; };
+		693C86E7090EE6F00058EE92 /* MCNode.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = MCNode.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>"; };
 		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>"; };
+		69469F6D09AA1D2000D1EC14 /* AgentData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = AgentData.h; sourceTree = "<group>"; };
+		69469F6E09AA1D2000D1EC14 /* BaseData.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = BaseData.cc; sourceTree = "<group>"; };
+		69469F6F09AA1D2000D1EC14 /* BaseData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = BaseData.h; sourceTree = "<group>"; };
+		69469F7009AA1D2000D1EC14 /* BlobData.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = BlobData.cc; sourceTree = "<group>"; };
+		69469F7109AA1D2000D1EC14 /* BlobData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = BlobData.h; sourceTree = "<group>"; };
+		69469F7209AA1D2000D1EC14 /* BrickData.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = BrickData.cc; sourceTree = "<group>"; };
+		69469F7309AA1D2000D1EC14 /* BrickData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = BrickData.h; sourceTree = "<group>"; };
+		69469F7609AA1D2000D1EC14 /* DualCoding.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = DualCoding.h; sourceTree = "<group>"; };
+		69469F7709AA1D2000D1EC14 /* EllipseData.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = EllipseData.cc; sourceTree = "<group>"; };
+		69469F7809AA1D2000D1EC14 /* EllipseData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = EllipseData.h; sourceTree = "<group>"; };
+		69469F7909AA1D2000D1EC14 /* EndPoint.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = EndPoint.cc; sourceTree = "<group>"; };
+		69469F7A09AA1D2000D1EC14 /* EndPoint.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = EndPoint.h; sourceTree = "<group>"; };
+		69469F7B09AA1D2000D1EC14 /* LineData.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = LineData.cc; sourceTree = "<group>"; };
+		69469F7C09AA1D2000D1EC14 /* LineData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = LineData.h; sourceTree = "<group>"; };
+		69469F7F09AA1D2000D1EC14 /* Lookout.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Lookout.cc; sourceTree = "<group>"; };
+		69469F8009AA1D2000D1EC14 /* Lookout.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Lookout.h; sourceTree = "<group>"; };
+		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>"; };
+		69469F8E09AA1D2000D1EC14 /* Point.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Point.cc; sourceTree = "<group>"; };
+		69469F8F09AA1D2000D1EC14 /* Point.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Point.h; sourceTree = "<group>"; };
+		69469F9009AA1D2000D1EC14 /* PointData.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = PointData.cc; sourceTree = "<group>"; };
+		69469F9109AA1D2000D1EC14 /* PointData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = PointData.h; sourceTree = "<group>"; };
+		69469F9209AA1D2000D1EC14 /* PolygonData.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = PolygonData.cc; sourceTree = "<group>"; };
+		69469F9309AA1D2000D1EC14 /* PolygonData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = PolygonData.h; sourceTree = "<group>"; };
+		69469F9409AA1D2000D1EC14 /* Region.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Region.cc; sourceTree = "<group>"; };
+		69469F9509AA1D2000D1EC14 /* Region.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Region.h; sourceTree = "<group>"; };
+		69469F9609AA1D2000D1EC14 /* ShapeAgent.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeAgent.cc; sourceTree = "<group>"; };
+		69469F9709AA1D2000D1EC14 /* ShapeAgent.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeAgent.h; sourceTree = "<group>"; };
+		69469F9809AA1D2000D1EC14 /* ShapeBlob.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeBlob.cc; sourceTree = "<group>"; };
+		69469F9909AA1D2000D1EC14 /* ShapeBlob.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeBlob.h; sourceTree = "<group>"; };
+		69469F9A09AA1D2000D1EC14 /* ShapeBrick.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeBrick.cc; sourceTree = "<group>"; };
+		69469F9B09AA1D2000D1EC14 /* ShapeBrick.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeBrick.h; sourceTree = "<group>"; };
+		69469F9C09AA1D2000D1EC14 /* ShapeEllipse.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeEllipse.cc; sourceTree = "<group>"; };
+		69469F9D09AA1D2000D1EC14 /* ShapeEllipse.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeEllipse.h; sourceTree = "<group>"; };
+		69469F9E09AA1D2000D1EC14 /* ShapeFuns.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeFuns.cc; sourceTree = "<group>"; };
+		69469F9F09AA1D2000D1EC14 /* ShapeFuns.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeFuns.h; sourceTree = "<group>"; };
+		69469FA009AA1D2100D1EC14 /* ShapeLine.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeLine.cc; sourceTree = "<group>"; };
+		69469FA109AA1D2100D1EC14 /* ShapeLine.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeLine.h; sourceTree = "<group>"; };
+		69469FA209AA1D2100D1EC14 /* ShapePoint.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapePoint.cc; sourceTree = "<group>"; };
+		69469FA309AA1D2100D1EC14 /* ShapePoint.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapePoint.h; sourceTree = "<group>"; };
+		69469FA409AA1D2100D1EC14 /* ShapePolygon.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapePolygon.cc; sourceTree = "<group>"; };
+		69469FA509AA1D2100D1EC14 /* ShapePolygon.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapePolygon.h; sourceTree = "<group>"; };
+		69469FA609AA1D2100D1EC14 /* ShapeRoot.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeRoot.cc; sourceTree = "<group>"; };
+		69469FA709AA1D2100D1EC14 /* ShapeRoot.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeRoot.h; sourceTree = "<group>"; };
+		69469FA809AA1D2100D1EC14 /* ShapeSpace.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeSpace.cc; sourceTree = "<group>"; };
+		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>"; };
+		69469FB109AA1D2100D1EC14 /* SketchDataRoot.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SketchDataRoot.cc; sourceTree = "<group>"; };
+		69469FB209AA1D2100D1EC14 /* SketchDataRoot.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SketchDataRoot.h; sourceTree = "<group>"; };
+		69469FB309AA1D2100D1EC14 /* SketchIndices.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SketchIndices.cc; sourceTree = "<group>"; };
+		69469FB409AA1D2100D1EC14 /* SketchIndices.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SketchIndices.h; sourceTree = "<group>"; };
+		69469FB509AA1D2100D1EC14 /* SketchPool.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SketchPool.h; sourceTree = "<group>"; };
+		69469FB609AA1D2100D1EC14 /* SketchRoot.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SketchRoot.cc; sourceTree = "<group>"; };
+		69469FB709AA1D2100D1EC14 /* SketchRoot.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SketchRoot.h; sourceTree = "<group>"; };
+		69469FB809AA1D2100D1EC14 /* SketchSpace.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SketchSpace.cc; sourceTree = "<group>"; };
+		69469FB909AA1D2100D1EC14 /* SketchSpace.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SketchSpace.h; sourceTree = "<group>"; };
+		69469FBA09AA1D2100D1EC14 /* SketchTypes.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SketchTypes.h; sourceTree = "<group>"; };
+		69469FBB09AA1D2100D1EC14 /* SphereData.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SphereData.cc; sourceTree = "<group>"; };
+		69469FBC09AA1D2100D1EC14 /* SphereData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SphereData.h; sourceTree = "<group>"; };
+		69469FBD09AA1D2100D1EC14 /* susan.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = susan.cc; sourceTree = "<group>"; };
+		69469FBE09AA1D2100D1EC14 /* susan.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = susan.h; sourceTree = "<group>"; };
+		69469FBF09AA1D2100D1EC14 /* ViewerConnection.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ViewerConnection.cc; sourceTree = "<group>"; };
+		69469FC009AA1D2100D1EC14 /* ViewerConnection.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ViewerConnection.h; sourceTree = "<group>"; };
+		69469FC109AA1D2100D1EC14 /* visops.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = visops.cc; sourceTree = "<group>"; };
+		69469FC209AA1D2100D1EC14 /* visops.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = visops.h; sourceTree = "<group>"; };
+		69469FC309AA1D2100D1EC14 /* VisualRoutinesBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = VisualRoutinesBehavior.cc; sourceTree = "<group>"; };
+		69469FC409AA1D2100D1EC14 /* VisualRoutinesBehavior.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = VisualRoutinesBehavior.h; sourceTree = "<group>"; };
+		69469FC509AA1D2100D1EC14 /* VRmixin.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = VRmixin.h; sourceTree = "<group>"; };
+		6946A1A109AAE1C600D1EC14 /* VRmixin.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = VRmixin.cc; sourceTree = "<group>"; };
+		6946A1A409AAE1D800D1EC14 /* VisualRoutinesStateNode.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = VisualRoutinesStateNode.cc; sourceTree = "<group>"; };
+		6946A1A509AAE1D800D1EC14 /* VisualRoutinesStateNode.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = VisualRoutinesStateNode.h; sourceTree = "<group>"; };
 		694AB43507F48A860071A2AE /* libjpeg.dylib */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.dylib"; name = libjpeg.dylib; path = /usr/local/lib/libjpeg.dylib; sourceTree = "<absolute>"; };
 		694AB43607F48A860071A2AE /* libpng12.dylib */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.dylib"; name = libpng12.dylib; path = /usr/local/lib/libpng12.dylib; sourceTree = "<absolute>"; };
+		694B2B1E0A0FC983002ABC4C /* SketchPoolRoot.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SketchPoolRoot.cc; sourceTree = "<group>"; };
+		694B2B1F0A0FC983002ABC4C /* SketchPoolRoot.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SketchPoolRoot.h; sourceTree = "<group>"; };
+		694B36550A190FE2002ABC4C /* jpeg_mem_src.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = jpeg_mem_src.h; sourceTree = "<group>"; };
+		694B36560A190FE2002ABC4C /* jpeg_mem_src.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = jpeg_mem_src.cc; sourceTree = "<group>"; };
+		694E67E10AC308130087EC83 /* PitchDetector.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = PitchDetector.h; sourceTree = "<group>"; };
+		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>"; };
 		6952B61A07DBFDCC00E2565F /* SemaphoreManager.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SemaphoreManager.h; sourceTree = "<group>"; };
-		695967E007FF3DCF004FABFF /* LoadImageThread.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = LoadImageThread.cc; sourceTree = "<group>"; };
-		695967E107FF3DCF004FABFF /* LoadImageThread.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = LoadImageThread.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>"; };
 		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>"; };
+		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>"; };
+		6962F2EE0A917E74002DDEC9 /* Aibo3DControllerBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Aibo3DControllerBehavior.cc; sourceTree = "<group>"; };
+		6962F2FD0A917F40002DDEC9 /* LookoutRequests.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = LookoutRequests.cc; sourceTree = "<group>"; };
+		6962F2FE0A917F41002DDEC9 /* LookoutRequests.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = LookoutRequests.h; sourceTree = "<group>"; };
+		6966753B0926558A00405769 /* MCNode.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = MCNode.cc; sourceTree = "<group>"; };
 		696B01FB07D6906E000C1839 /* ms */ = {isa = PBXFileReference; lastKnownFileType = folder; path = ms; sourceTree = "<group>"; };
+		69750F030AC03FFE004FE3CF /* AutoGetupBehavior.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = AutoGetupBehavior.h; sourceTree = "<group>"; };
+		69750F040AC03FFE004FE3CF /* BatteryMonitorBehavior.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = BatteryMonitorBehavior.h; sourceTree = "<group>"; };
+		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>"; };
 		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>"; };
@@ -516,9 +699,21 @@
 		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>"; };
-		6985DA3408527479009FD05A /* tools */ = {isa = PBXFileReference; lastKnownFileType = folder; name = tools; path = ../tools; sourceTree = SOURCE_ROOT; };
+		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>"; };
+		6985DA3408527479009FD05A /* tools */ = {isa = PBXFileReference; lastKnownFileType = folder; path = tools; sourceTree = TEKKOTSU_ROOT; };
+		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>"; };
+		698A072709575F7D001A13D5 /* plistCollections.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plistCollections.cc; sourceTree = "<group>"; };
+		698A072809575F7D001A13D5 /* plistCollections.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plistCollections.h; sourceTree = "<group>"; };
+		698A072E09575F94001A13D5 /* plistPrimitives.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plistPrimitives.h; sourceTree = "<group>"; };
 		6994F3CA07D4D35F003A7628 /* ListMemBuf.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = ListMemBuf.h; sourceTree = "<group>"; };
-		6994F3CB07D4D35F003A7628 /* LockScope.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = LockScope.h; sourceTree = "<group>"; };
 		6994F3CC07D4D35F003A7628 /* MessageQueue.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = MessageQueue.h; sourceTree = "<group>"; };
 		6994F3CD07D4D35F003A7628 /* MessageReceiver.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = MessageReceiver.h; sourceTree = "<group>"; };
 		6994F3CE07D4D35F003A7628 /* MutexLock.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = MutexLock.h; sourceTree = "<group>"; };
@@ -553,7 +748,7 @@
 		6994F5AB07D68DF7003A7628 /* TinyFTPD.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = TinyFTPD.cc; sourceTree = "<group>"; };
 		6994F5AC07D68DF7003A7628 /* TinyFTPD.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = TinyFTPD.h; sourceTree = "<group>"; };
 		6994F5AD07D68DF7003A7628 /* TinyFTPD.ocf */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = text; path = TinyFTPD.ocf; sourceTree = "<group>"; };
-		6994F5B807D68E41003A7628 /* Makefile.local */ = {isa = PBXFileReference; explicitFileType = sourcecode.make; fileEncoding = 30; name = Makefile.local; path = /Users/ejt/todo/Tekkotsu/local/Makefile.local; sourceTree = "<absolute>"; };
+		6994F5B807D68E41003A7628 /* Makefile.local */ = {isa = PBXFileReference; explicitFileType = sourcecode.make; fileEncoding = 30; path = Makefile.local; sourceTree = "<group>"; };
 		6994F5C307D68EE4003A7628 /* Makefile.local */ = {isa = PBXFileReference; explicitFileType = sourcecode.make; fileEncoding = 30; name = Makefile.local; path = local/Makefile.local; sourceTree = "<group>"; };
 		6994F5CC07D68F2A003A7628 /* Makefile.aperios */ = {isa = PBXFileReference; explicitFileType = sourcecode.make; fileEncoding = 30; languageSpecificationIdentifier = make; path = Makefile.aperios; sourceTree = "<group>"; };
 		69970AC0083DB2760069D95C /* StewartPlatformBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = StewartPlatformBehavior.cc; sourceTree = "<group>"; };
@@ -565,8 +760,31 @@
 		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; };
+		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>"; };
+		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>"; };
+		69B3446C0A7152AC0021FBE6 /* ShapePyramid.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapePyramid.h; sourceTree = "<group>"; };
+		69B3446F0A7152C30021FBE6 /* BrickOps.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = BrickOps.cc; sourceTree = "<group>"; };
+		69B344700A7152C30021FBE6 /* BrickOps.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = BrickOps.h; sourceTree = "<group>"; };
 		69B4E445089409D800832D58 /* StareAtPawBehavior2.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = StareAtPawBehavior2.cc; sourceTree = "<group>"; };
+		69B8DDBD0AC44586003EC54A /* LookAtPointBehavior.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = LookAtPointBehavior.h; sourceTree = "<group>"; };
+		69B8DDC00AC44735003EC54A /* LGmixin.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = LGmixin.cc; sourceTree = "<group>"; };
+		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>"; };
+		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>"; };
 		69E0A75907CBD4F9008493CA /* StartupBehavior_SetupBackgroundBehaviors.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = StartupBehavior_SetupBackgroundBehaviors.cc; sourceTree = "<group>"; };
@@ -642,9 +860,7 @@
 		69E0A7C007CBD6C0008493CA /* AlanBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = AlanBehavior.h; sourceTree = "<group>"; };
 		69E0A7C107CBD6C0008493CA /* ASCIIVisionBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ASCIIVisionBehavior.cc; sourceTree = "<group>"; };
 		69E0A7C207CBD6C0008493CA /* ASCIIVisionBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = ASCIIVisionBehavior.h; sourceTree = "<group>"; };
-		69E0A7C307CBD6C0008493CA /* AutoGetupBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = AutoGetupBehavior.h; sourceTree = "<group>"; };
 		69E0A7C407CBD6C0008493CA /* BanditMachine.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = BanditMachine.h; sourceTree = "<group>"; };
-		69E0A7C507CBD6C0008493CA /* BatteryMonitorBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = BatteryMonitorBehavior.h; sourceTree = "<group>"; };
 		69E0A7C607CBD6C0008493CA /* CameraBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = CameraBehavior.cc; sourceTree = "<group>"; };
 		69E0A7C707CBD6C0008493CA /* CameraBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = CameraBehavior.h; sourceTree = "<group>"; };
 		69E0A7C807CBD6C0008493CA /* ChaseBallBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ChaseBallBehavior.cc; sourceTree = "<group>"; };
@@ -654,8 +870,6 @@
 		69E0A7CC07CBD6C0008493CA /* DriveMeBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = DriveMeBehavior.h; sourceTree = "<group>"; };
 		69E0A7CD07CBD6C0008493CA /* ExploreMachine.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ExploreMachine.cc; sourceTree = "<group>"; };
 		69E0A7CE07CBD6C0008493CA /* ExploreMachine.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = ExploreMachine.h; sourceTree = "<group>"; };
-		69E0A7CF07CBD6C0008493CA /* FlashIPAddrBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = FlashIPAddrBehavior.cc; sourceTree = "<group>"; };
-		69E0A7D007CBD6C0008493CA /* FlashIPAddrBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = FlashIPAddrBehavior.h; sourceTree = "<group>"; };
 		69E0A7D107CBD6C0008493CA /* FollowHeadBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = FollowHeadBehavior.cc; sourceTree = "<group>"; };
 		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>"; };
@@ -679,7 +893,6 @@
 		69E0A7E607CBD6C0008493CA /* ToggleHeadLightBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = ToggleHeadLightBehavior.h; sourceTree = "<group>"; };
 		69E0A7E707CBD6C0008493CA /* WallTestBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = WallTestBehavior.cc; sourceTree = "<group>"; };
 		69E0A7E807CBD6C0008493CA /* WallTestBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = WallTestBehavior.h; sourceTree = "<group>"; };
-		69E0A7E907CBD6C0008493CA /* WorldStateVelDaemon.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = WorldStateVelDaemon.h; sourceTree = "<group>"; };
 		69E0A7EB07CBD6C0008493CA /* Aibo3DControllerBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = Aibo3DControllerBehavior.h; sourceTree = "<group>"; };
 		69E0A7EC07CBD6C0008493CA /* EStopControllerBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = EStopControllerBehavior.cc; sourceTree = "<group>"; };
 		69E0A7ED07CBD6C0008493CA /* EStopControllerBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = EStopControllerBehavior.h; sourceTree = "<group>"; };
@@ -707,7 +920,6 @@
 		69E0A80407CBD6C0008493CA /* LedNode.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = LedNode.h; sourceTree = "<group>"; };
 		69E0A80507CBD6C0008493CA /* MotionSequenceNode.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = MotionSequenceNode.h; sourceTree = "<group>"; };
 		69E0A80607CBD6C0008493CA /* OutputNode.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = OutputNode.h; sourceTree = "<group>"; };
-		69E0A80707CBD6C0008493CA /* PlayMotionSequenceNode.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = PlayMotionSequenceNode.h; sourceTree = "<group>"; };
 		69E0A80807CBD6C0008493CA /* SoundNode.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SoundNode.h; sourceTree = "<group>"; };
 		69E0A80907CBD6C0008493CA /* TailWagNode.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = TailWagNode.h; sourceTree = "<group>"; };
 		69E0A80A07CBD6C0008493CA /* WalkNode.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = WalkNode.h; sourceTree = "<group>"; };
@@ -837,7 +1049,7 @@
 		69E0A8DE07CBD6C1008493CA /* jpeg_mem_dest.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = jpeg_mem_dest.cc; sourceTree = "<group>"; };
 		69E0A8DF07CBD6C1008493CA /* jpeg_mem_dest.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = jpeg_mem_dest.h; sourceTree = "<group>"; };
 		69E0A8F807CBD6C1008493CA /* LoadSave.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = LoadSave.cc; sourceTree = "<group>"; };
-		69E0A8F907CBD6C1008493CA /* LoadSave.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = LoadSave.h; sourceTree = "<group>"; };
+		69E0A8F907CBD6C1008493CA /* LoadSave.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 4; path = LoadSave.h; sourceTree = "<group>"; };
 		69E0A8FB07CBD6C1008493CA /* mathutils.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = mathutils.h; sourceTree = "<group>"; };
 		69E0A8FE07CBD6C1008493CA /* bandmat.cpp */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = bandmat.cpp; sourceTree = "<group>"; };
 		69E0A8FF07CBD6C1008493CA /* boolean.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = boolean.h; sourceTree = "<group>"; };
@@ -887,7 +1099,6 @@
 		69E0A96107CBD6C1008493CA /* RobotInfo.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = RobotInfo.h; sourceTree = "<group>"; };
 		69E0A96507CBD6C1008493CA /* string_util.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = string_util.cc; sourceTree = "<group>"; };
 		69E0A96607CBD6C1008493CA /* string_util.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = string_util.h; sourceTree = "<group>"; };
-		69E0A96707CBD6C1008493CA /* SystemUtility.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SystemUtility.h; sourceTree = "<group>"; };
 		69E0A96807CBD6C1008493CA /* TimeET.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = TimeET.cc; sourceTree = "<group>"; };
 		69E0A96907CBD6C1008493CA /* TimeET.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = TimeET.h; sourceTree = "<group>"; };
 		69E0A96A07CBD6C1008493CA /* Util.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = Util.h; sourceTree = "<group>"; };
@@ -942,12 +1153,19 @@
 		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>"; };
-		69E6696307F3398F005F4FA9 /* SimConfig.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = SimConfig.cc; 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>"; };
 		69EA8B9307EB57480047DA8D /* libxml2.dylib */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.dylib"; name = libxml2.dylib; path = /usr/lib/libxml2.dylib; sourceTree = "<absolute>"; };
 		69EA8B9407EB57480047DA8D /* libz.dylib */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.dylib"; name = libz.dylib; path = /usr/lib/libz.dylib; sourceTree = "<absolute>"; };
+		69EB5B2C0A41C8DE00415C6B /* ResourceAccessor.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ResourceAccessor.h; sourceTree = "<group>"; };
+		69EB5B530A41CCD700415C6B /* Resource.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = Resource.cc; sourceTree = "<group>"; };
+		69EB5B540A41CCD700415C6B /* MarkScope.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = MarkScope.h; sourceTree = "<group>"; };
 		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>"; };
+		69F6038C0A40800F0052ECA1 /* Resource.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 4; path = Resource.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>"; };
@@ -967,6 +1185,7 @@
 				69EA8B9D07EB57480047DA8D /* libz.dylib in Frameworks */,
 				694AB43707F48A860071A2AE /* libjpeg.dylib in Frameworks */,
 				694AB43807F48A860071A2AE /* libpng12.dylib in Frameworks */,
+				69A7EE7009C8F70C003DDD18 /* libreadline.dylib in Frameworks */,
 			);
 			runOnlyForDeploymentPostprocessing = 0;
 		};
@@ -982,6 +1201,7 @@
 				69EA8B9A07EB57480047DA8D /* libz.dylib in Frameworks */,
 				694AB43B07F48A860071A2AE /* libjpeg.dylib in Frameworks */,
 				694AB43C07F48A860071A2AE /* libpng12.dylib in Frameworks */,
+				69A7EE7209C8F70C003DDD18 /* libreadline.dylib in Frameworks */,
 			);
 			runOnlyForDeploymentPostprocessing = 0;
 		};
@@ -995,6 +1215,7 @@
 				69EA8B9707EB57480047DA8D /* libz.dylib in Frameworks */,
 				694AB43907F48A860071A2AE /* libjpeg.dylib in Frameworks */,
 				694AB43A07F48A860071A2AE /* libpng12.dylib in Frameworks */,
+				69A7EE7109C8F70C003DDD18 /* libreadline.dylib in Frameworks */,
 			);
 			runOnlyForDeploymentPostprocessing = 0;
 		};
@@ -1014,6 +1235,7 @@
 				69EA8B9307EB57480047DA8D /* libxml2.dylib */,
 				69EA8B9207EB57480047DA8D /* libiconv.dylib */,
 				69EA8B9407EB57480047DA8D /* libz.dylib */,
+				69A7EE6F09C8F70C003DDD18 /* libreadline.dylib */,
 			);
 			name = "External Frameworks and Libraries";
 			sourceTree = "<group>";
@@ -1023,11 +1245,11 @@
 			children = (
 				08FB7795FE84155DC02AAC07 /* Project Files */,
 				69E0A74A07CBBECE008493CA /* Tekkotsu Source */,
-				69E0A75107CBBF2D008493CA /* Sim Source */,
-				0249A662FF388D9811CA2CEA /* External Frameworks and Libraries */,
+				69E0A75107CBBF2D008493CA /* local */,
 				6985DA3408527479009FD05A /* tools */,
 				69761DB608562012007DB073 /* mon */,
 				69E0AD5D07CBDE11008493CA /* Products */,
+				0249A662FF388D9811CA2CEA /* External Frameworks and Libraries */,
 			);
 			name = sim;
 			sourceTree = "<group>";
@@ -1056,6 +1278,123 @@
 			name = "Project Files";
 			sourceTree = "<group>";
 		};
+		69469F6B09AA1D2000D1EC14 /* DualCoding */ = {
+			isa = PBXGroup;
+			children = (
+				69469F6C09AA1D2000D1EC14 /* AgentData.cc */,
+				69469F6D09AA1D2000D1EC14 /* AgentData.h */,
+				69469F6E09AA1D2000D1EC14 /* BaseData.cc */,
+				69469F6F09AA1D2000D1EC14 /* BaseData.h */,
+				69469F7009AA1D2000D1EC14 /* BlobData.cc */,
+				69469F7109AA1D2000D1EC14 /* BlobData.h */,
+				69469F7209AA1D2000D1EC14 /* BrickData.cc */,
+				69469F7309AA1D2000D1EC14 /* BrickData.h */,
+				69B3446F0A7152C30021FBE6 /* BrickOps.cc */,
+				69B344700A7152C30021FBE6 /* BrickOps.h */,
+				69469F7609AA1D2000D1EC14 /* DualCoding.h */,
+				69469F7709AA1D2000D1EC14 /* EllipseData.cc */,
+				69469F7809AA1D2000D1EC14 /* EllipseData.h */,
+				69469F7909AA1D2000D1EC14 /* EndPoint.cc */,
+				69469F7A09AA1D2000D1EC14 /* EndPoint.h */,
+				69469F7B09AA1D2000D1EC14 /* LineData.cc */,
+				69469F7C09AA1D2000D1EC14 /* LineData.h */,
+				69469F7F09AA1D2000D1EC14 /* Lookout.cc */,
+				69469F8009AA1D2000D1EC14 /* Lookout.h */,
+				6962F2FD0A917F40002DDEC9 /* LookoutRequests.cc */,
+				6962F2FE0A917F41002DDEC9 /* LookoutRequests.h */,
+				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 */,
+				69469F8A09AA1D2000D1EC14 /* ParticleShapes.cc */,
+				69469F8B09AA1D2000D1EC14 /* ParticleShapes.h */,
+				69469F8D09AA1D2000D1EC14 /* Pilot.h */,
+				69469F8E09AA1D2000D1EC14 /* Point.cc */,
+				69469F8F09AA1D2000D1EC14 /* Point.h */,
+				69469F9009AA1D2000D1EC14 /* PointData.cc */,
+				69469F9109AA1D2000D1EC14 /* PointData.h */,
+				69469F9209AA1D2000D1EC14 /* PolygonData.cc */,
+				69469F9309AA1D2000D1EC14 /* PolygonData.h */,
+				69B344670A7152900021FBE6 /* PyramidData.cc */,
+				69B344680A7152900021FBE6 /* PyramidData.h */,
+				69469F9409AA1D2000D1EC14 /* Region.cc */,
+				69469F9509AA1D2000D1EC14 /* Region.h */,
+				69469F9609AA1D2000D1EC14 /* ShapeAgent.cc */,
+				69469F9709AA1D2000D1EC14 /* ShapeAgent.h */,
+				69469F9809AA1D2000D1EC14 /* ShapeBlob.cc */,
+				69469F9909AA1D2000D1EC14 /* ShapeBlob.h */,
+				69469F9A09AA1D2000D1EC14 /* ShapeBrick.cc */,
+				69469F9B09AA1D2000D1EC14 /* ShapeBrick.h */,
+				69469F9C09AA1D2000D1EC14 /* ShapeEllipse.cc */,
+				69469F9D09AA1D2000D1EC14 /* ShapeEllipse.h */,
+				69469F9E09AA1D2000D1EC14 /* ShapeFuns.cc */,
+				69469F9F09AA1D2000D1EC14 /* ShapeFuns.h */,
+				69469FA009AA1D2100D1EC14 /* ShapeLine.cc */,
+				69469FA109AA1D2100D1EC14 /* ShapeLine.h */,
+				69469FA209AA1D2100D1EC14 /* ShapePoint.cc */,
+				69469FA309AA1D2100D1EC14 /* ShapePoint.h */,
+				69469FA409AA1D2100D1EC14 /* ShapePolygon.cc */,
+				69469FA509AA1D2100D1EC14 /* ShapePolygon.h */,
+				69B3446B0A7152AC0021FBE6 /* ShapePyramid.cc */,
+				69B3446C0A7152AC0021FBE6 /* ShapePyramid.h */,
+				69469FA609AA1D2100D1EC14 /* ShapeRoot.cc */,
+				69469FA709AA1D2100D1EC14 /* ShapeRoot.h */,
+				69469FA809AA1D2100D1EC14 /* ShapeSpace.cc */,
+				69469FA909AA1D2100D1EC14 /* ShapeSpace.h */,
+				69469FAA09AA1D2100D1EC14 /* ShapeSphere.cc */,
+				69469FAB09AA1D2100D1EC14 /* ShapeSphere.h */,
+				69469FAC09AA1D2100D1EC14 /* ShapeTypes.cc */,
+				69469FAD09AA1D2100D1EC14 /* ShapeTypes.h */,
+				69469FAE09AA1D2100D1EC14 /* Sketch.cc */,
+				69469FAF09AA1D2100D1EC14 /* Sketch.h */,
+				69469FB009AA1D2100D1EC14 /* SketchData.h */,
+				69469FB109AA1D2100D1EC14 /* SketchDataRoot.cc */,
+				69469FB209AA1D2100D1EC14 /* SketchDataRoot.h */,
+				69469FB309AA1D2100D1EC14 /* SketchIndices.cc */,
+				69469FB409AA1D2100D1EC14 /* SketchIndices.h */,
+				69469FB509AA1D2100D1EC14 /* SketchPool.h */,
+				694B2B1E0A0FC983002ABC4C /* SketchPoolRoot.cc */,
+				694B2B1F0A0FC983002ABC4C /* SketchPoolRoot.h */,
+				69469FB609AA1D2100D1EC14 /* SketchRoot.cc */,
+				69469FB709AA1D2100D1EC14 /* SketchRoot.h */,
+				69469FB809AA1D2100D1EC14 /* SketchSpace.cc */,
+				69469FB909AA1D2100D1EC14 /* SketchSpace.h */,
+				69469FBA09AA1D2100D1EC14 /* SketchTypes.h */,
+				69469FBB09AA1D2100D1EC14 /* SphereData.cc */,
+				69469FBC09AA1D2100D1EC14 /* SphereData.h */,
+				69469FBD09AA1D2100D1EC14 /* susan.cc */,
+				69469FBE09AA1D2100D1EC14 /* susan.h */,
+				69469FBF09AA1D2100D1EC14 /* ViewerConnection.cc */,
+				69469FC009AA1D2100D1EC14 /* ViewerConnection.h */,
+				69469FC109AA1D2100D1EC14 /* visops.cc */,
+				69469FC209AA1D2100D1EC14 /* visops.h */,
+				69469FC309AA1D2100D1EC14 /* VisualRoutinesBehavior.cc */,
+				69469FC409AA1D2100D1EC14 /* VisualRoutinesBehavior.h */,
+				6946A1A409AAE1D800D1EC14 /* VisualRoutinesStateNode.cc */,
+				6946A1A509AAE1D800D1EC14 /* VisualRoutinesStateNode.h */,
+				6946A1A109AAE1C600D1EC14 /* VRmixin.cc */,
+				69469FC509AA1D2100D1EC14 /* VRmixin.h */,
+			);
+			path = DualCoding;
+			sourceTree = "<group>";
+		};
+		69750F020AC03FFD004FE3CF /* Services */ = {
+			isa = PBXGroup;
+			children = (
+				69750F030AC03FFE004FE3CF /* AutoGetupBehavior.h */,
+				69750F040AC03FFE004FE3CF /* BatteryMonitorBehavior.h */,
+				69750F050AC03FFE004FE3CF /* FlashIPAddrBehavior.cc */,
+				69750F060AC03FFE004FE3CF /* FlashIPAddrBehavior.h */,
+				69750F070AC03FFE004FE3CF /* WorldStateVelDaemon.h */,
+			);
+			path = Services;
+			sourceTree = "<group>";
+		};
 		69761DB608562012007DB073 /* mon */ = {
 			isa = PBXGroup;
 			children = (
@@ -1130,19 +1469,23 @@
 			isa = PBXGroup;
 			children = (
 				6994F3CA07D4D35F003A7628 /* ListMemBuf.h */,
-				6994F3CB07D4D35F003A7628 /* LockScope.h */,
+				69D5F7BB09BB4DC9000602D2 /* MessageQueue.cc */,
 				6994F3CC07D4D35F003A7628 /* MessageQueue.h */,
+				69D5F82709BBDF0C000602D2 /* MessageQueueStatusThread.cc */,
+				69D5F82809BBDF0C000602D2 /* MessageQueueStatusThread.h */,
 				69AA7D690860898300185BA2 /* MessageReceiver.cc */,
 				6994F3CD07D4D35F003A7628 /* MessageReceiver.h */,
 				6994F3CE07D4D35F003A7628 /* MutexLock.h */,
 				6942757707E0DCDD003DE3D9 /* MutexLock.cc */,
-				6994F3CF07D4D35F003A7628 /* SemaphoreManager.cc */,
-				6952B61A07DBFDCC00E2565F /* SemaphoreManager.h */,
+				69A7EBE909C7162E003DDD18 /* PollThread.cc */,
+				69A7EBEA09C7162E003DDD18 /* PollThread.h */,
 				6994F3D107D4D35F003A7628 /* ProcessID.cc */,
 				6994F3D207D4D35F003A7628 /* ProcessID.h */,
 				6994F3D307D4D35F003A7628 /* RCRegion.cc */,
 				6994F3D407D4D35F003A7628 /* RCRegion.h */,
 				6994F3D507D4D35F003A7628 /* RegionRegistry.h */,
+				6994F3CF07D4D35F003A7628 /* SemaphoreManager.cc */,
+				6952B61A07DBFDCC00E2565F /* SemaphoreManager.h */,
 				6994F3D607D4D35F003A7628 /* SharedObject.cc */,
 				6994F3D707D4D35F003A7628 /* SharedObject.h */,
 				6942779007E164EA003DE3D9 /* Thread.cc */,
@@ -1155,6 +1498,8 @@
 			isa = PBXGroup;
 			children = (
 				6994F59607D68DF6003A7628 /* Makefile.aperios */,
+				69EE6BE00A951DC900DB7B88 /* EntryPoint.cc */,
+				69EE6BE10A951DC900DB7B88 /* EntryPoint.h */,
 				6994F59707D68DF6003A7628 /* MMCombo */,
 				6994F59C07D68DF6003A7628 /* SndPlay */,
 				6994F5A107D68DF7003A7628 /* TinyFTPD */,
@@ -1206,11 +1551,15 @@
 		6994F5B407D68E31003A7628 /* local */ = {
 			isa = PBXGroup;
 			children = (
-				690564F20819531A00613A0E /* minisim.h */,
 				6994F5B807D68E41003A7628 /* Makefile.local */,
+				6976B20E0ACC669F00BA657B /* EntryPoint.h */,
+				6976B20F0ACC669F00BA657B /* LoadFileThread.cc */,
+				6976B2100ACC669F00BA657B /* LoadFileThread.h */,
+				6976B2110ACC669F00BA657B /* LoadImageThread.cc */,
+				6976B2120ACC669F00BA657B /* LoadImageThread.h */,
+				690564F20819531A00613A0E /* minisim.h */,
 			);
-			name = local;
-			path = aperios;
+			path = local;
 			sourceTree = "<group>";
 		};
 		6994F5BF07D68ED9003A7628 /* local */ = {
@@ -1236,6 +1585,7 @@
 				6994F57D07D68D23003A7628 /* INSTALL */,
 				69E0AD8407CBED91008493CA /* Makefile */,
 				69E0A78B07CBD6BF008493CA /* Behaviors */,
+				69469F6B09AA1D2000D1EC14 /* DualCoding */,
 				69E0A81E07CBD6C0008493CA /* Events */,
 				6994F3C907D4D35F003A7628 /* IPC */,
 				69E0A83207CBD6C0008493CA /* Motion */,
@@ -1249,41 +1599,39 @@
 			name = "Tekkotsu Source";
 			sourceTree = TEKKOTSU_ROOT;
 		};
-		69E0A75107CBBF2D008493CA /* Sim Source */ = {
+		69E0A75107CBBF2D008493CA /* local */ = {
 			isa = PBXGroup;
 			children = (
-				69E0A75607CBD4A2008493CA /* Framework */,
+				69E0A75607CBD4A2008493CA /* sim */,
 			);
-			name = "Sim Source";
-			sourceTree = "<group>";
+			path = local;
+			sourceTree = TEKKOTSU_ROOT;
 		};
-		69E0A75607CBD4A2008493CA /* Framework */ = {
+		69E0A75607CBD4A2008493CA /* sim */ = {
 			isa = PBXGroup;
 			children = (
-				695967E007FF3DCF004FABFF /* LoadImageThread.cc */,
-				695967E107FF3DCF004FABFF /* LoadImageThread.h */,
-				692CD99407F9F05500604100 /* LoadFileThread.cc */,
-				692CD99507F9F05500604100 /* LoadFileThread.h */,
 				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 */,
-				69E6696307F3398F005F4FA9 /* SimConfig.cc */,
 				69E6696407F3398F005F4FA9 /* SimConfig.h */,
 				69E0A77807CBD52D008493CA /* Simulator.cc */,
 				69E0A77907CBD52D008493CA /* Simulator.h */,
 				69E0A77A07CBD52D008493CA /* SoundPlay.cc */,
 				69E0A77B07CBD52D008493CA /* SoundPlay.h */,
+				69A7EC7909C79817003DDD18 /* TimerExecThread.cc */,
+				69A7EC7A09C79817003DDD18 /* TimerExecThread.h */,
 			);
-			name = Framework;
-			path = local/sim;
-			sourceTree = TEKKOTSU_ROOT;
+			path = sim;
+			sourceTree = "<group>";
 		};
 		69E0A78B07CBD6BF008493CA /* Behaviors */ = {
 			isa = PBXGroup;
@@ -1297,6 +1645,7 @@
 				69E0A7BF07CBD6C0008493CA /* Demos */,
 				69E0A7EA07CBD6C0008493CA /* Mon */,
 				69E0A80107CBD6C0008493CA /* Nodes */,
+				69750F020AC03FFD004FE3CF /* Services */,
 				69E0A80E07CBD6C0008493CA /* StateNode.cc */,
 				69E0A80F07CBD6C0008493CA /* StateNode.h */,
 				69E0A81007CBD6C0008493CA /* Transition.cc */,
@@ -1345,6 +1694,7 @@
 				69E0A7B307CBD6C0008493CA /* SensorObserverControl.h */,
 				69E0A7B407CBD6C0008493CA /* ShutdownControl.cc */,
 				69E0A7B507CBD6C0008493CA /* ShutdownControl.h */,
+				69616DF90AA4EDED00E63351 /* SimulatorAdvanceFrameControl.h */,
 				69E0A7B607CBD6C0008493CA /* StringInputControl.cc */,
 				69E0A7B707CBD6C0008493CA /* StringInputControl.h */,
 				69E0A7B807CBD6C0008493CA /* ToggleControl.h */,
@@ -1364,20 +1714,18 @@
 				69E0A7C007CBD6C0008493CA /* AlanBehavior.h */,
 				69E0A7C107CBD6C0008493CA /* ASCIIVisionBehavior.cc */,
 				69E0A7C207CBD6C0008493CA /* ASCIIVisionBehavior.h */,
-				69E0A7C307CBD6C0008493CA /* AutoGetupBehavior.h */,
 				69E0A7C407CBD6C0008493CA /* BanditMachine.h */,
-				69E0A7C507CBD6C0008493CA /* BatteryMonitorBehavior.h */,
 				69E0A7C607CBD6C0008493CA /* CameraBehavior.cc */,
 				69E0A7C707CBD6C0008493CA /* CameraBehavior.h */,
 				69E0A7C807CBD6C0008493CA /* ChaseBallBehavior.cc */,
 				69E0A7C907CBD6C0008493CA /* ChaseBallBehavior.h */,
 				69E0A7CA07CBD6C0008493CA /* CrashTestBehavior.h */,
+				69B8DEC00AC4952D003EC54A /* DrawSkeletonBehavior.h */,
+				69B8DEC10AC4952D003EC54A /* DrawVisObjBoundBehavior.h */,
 				69E0A7CB07CBD6C0008493CA /* DriveMeBehavior.cc */,
 				69E0A7CC07CBD6C0008493CA /* DriveMeBehavior.h */,
 				69E0A7CD07CBD6C0008493CA /* ExploreMachine.cc */,
 				69E0A7CE07CBD6C0008493CA /* ExploreMachine.h */,
-				69E0A7CF07CBD6C0008493CA /* FlashIPAddrBehavior.cc */,
-				69E0A7D007CBD6C0008493CA /* FlashIPAddrBehavior.h */,
 				69E0A7D107CBD6C0008493CA /* FollowHeadBehavior.cc */,
 				69E0A7D207CBD6C0008493CA /* FollowHeadBehavior.h */,
 				69E0A7D307CBD6C0008493CA /* FreezeTestBehavior.h */,
@@ -1388,6 +1736,7 @@
 				69E0A7D807CBD6C0008493CA /* KinematicSampleBehavior.h */,
 				69E0A7D907CBD6C0008493CA /* KinematicSampleBehavior2.h */,
 				69970AC4083DB2C60069D95C /* LogTestMachine.h */,
+				69B8DDBD0AC44586003EC54A /* LookAtPointBehavior.h */,
 				69E0A7DA07CBD6C0008493CA /* LookForSoundBehavior.h */,
 				69E0A7DB07CBD6C0008493CA /* MCRepeater.h */,
 				69E0A7DC07CBD6C0008493CA /* MotionStressTestBehavior.h */,
@@ -1400,10 +1749,11 @@
 				69E0A7E307CBD6C0008493CA /* StareAtBallBehavior.h */,
 				69B4E445089409D800832D58 /* StareAtPawBehavior2.cc */,
 				69E0A7E507CBD6C0008493CA /* StareAtPawBehavior2.h */,
+				692964F60AA8CEEF00F47522 /* TestBehaviors.cc */,
+				692964F70AA8CEEF00F47522 /* TestBehaviors.h */,
 				69E0A7E607CBD6C0008493CA /* ToggleHeadLightBehavior.h */,
 				69E0A7E707CBD6C0008493CA /* WallTestBehavior.cc */,
 				69E0A7E807CBD6C0008493CA /* WallTestBehavior.h */,
-				69E0A7E907CBD6C0008493CA /* WorldStateVelDaemon.h */,
 			);
 			path = Demos;
 			sourceTree = "<group>";
@@ -1411,7 +1761,10 @@
 		69E0A7EA07CBD6C0008493CA /* Mon */ = {
 			isa = PBXGroup;
 			children = (
+				6962F2EE0A917E74002DDEC9 /* Aibo3DControllerBehavior.cc */,
 				69E0A7EB07CBD6C0008493CA /* Aibo3DControllerBehavior.h */,
+				69844A2A08CE5F7F00BCDD5C /* CameraStreamBehavior.cc */,
+				69844A2B08CE5F7F00BCDD5C /* CameraStreamBehavior.h */,
 				69A1995E080ED8A200540970 /* EchoBehavior.cc */,
 				69A19963080ED8AE00540970 /* EchoBehavior.h */,
 				69E0A7EC07CBD6C0008493CA /* EStopControllerBehavior.cc */,
@@ -1453,12 +1806,13 @@
 				69E0A80407CBD6C0008493CA /* LedNode.h */,
 				69E0A80507CBD6C0008493CA /* MotionSequenceNode.h */,
 				69E0A80607CBD6C0008493CA /* OutputNode.h */,
-				69E0A80707CBD6C0008493CA /* PlayMotionSequenceNode.h */,
 				69E0A80807CBD6C0008493CA /* SoundNode.h */,
 				69E0A80907CBD6C0008493CA /* TailWagNode.h */,
 				69E0A80A07CBD6C0008493CA /* WalkNode.h */,
 				69E0A80B07CBD6C0008493CA /* WalkToTargetNode.cc */,
 				69E0A80C07CBD6C0008493CA /* WalkToTargetNode.h */,
+				693C86E7090EE6F00058EE92 /* MCNode.h */,
+				6966753B0926558A00405769 /* MCNode.cc */,
 			);
 			path = Nodes;
 			sourceTree = "<group>";
@@ -1499,9 +1853,15 @@
 				69E0A82A07CBD6C0008493CA /* FilterBankEvent.h */,
 				69E0A82B07CBD6C0008493CA /* LocomotionEvent.cc */,
 				69E0A82C07CBD6C0008493CA /* LocomotionEvent.h */,
+				6962F2E90A917E33002DDEC9 /* LookoutEvents.cc */,
+				6962F2EA0A917E33002DDEC9 /* LookoutEvents.h */,
+				694E67E40AC308290087EC83 /* PitchEvent.cc */,
+				694E67E50AC308290087EC83 /* PitchEvent.h */,
 				69E0A82D07CBD6C0008493CA /* SegmentedColorFilterBankEvent.h */,
 				69E0A82E07CBD6C0008493CA /* TextMsgEvent.cc */,
 				69E0A82F07CBD6C0008493CA /* TextMsgEvent.h */,
+				6901D58D0AAF288500104815 /* TimerEvent.cc */,
+				6901D58E0AAF288500104815 /* TimerEvent.h */,
 				69E0A83007CBD6C0008493CA /* VisionObjectEvent.cc */,
 				69E0A83107CBD6C0008493CA /* VisionObjectEvent.h */,
 			);
@@ -1601,10 +1961,12 @@
 		69E0A89107CBD6C0008493CA /* Shared */ = {
 			isa = PBXGroup;
 			children = (
+				69A7EF6F09C9FE5B003DDD18 /* attributes.h */,
 				691C805508255F6300E8E256 /* Base64.cc */,
 				691C805C08255F6D00E8E256 /* Base64.h */,
 				69E0A89207CBD6C0008493CA /* Buffer.cc */,
 				69E0A89307CBD6C0008493CA /* Buffer.h */,
+				698A06D10955F0E4001A13D5 /* Cloneable.h */,
 				69E0A89407CBD6C0008493CA /* CommonInfo.h */,
 				69E0A89507CBD6C0008493CA /* Config.cc */,
 				69E0A89607CBD6C0008493CA /* Config.h */,
@@ -1619,20 +1981,31 @@
 				69E0A89F07CBD6C0008493CA /* jpeg-6b */,
 				69E0A8F807CBD6C1008493CA /* LoadSave.cc */,
 				69E0A8F907CBD6C1008493CA /* LoadSave.h */,
+				69EB5B540A41CCD700415C6B /* MarkScope.h */,
 				69E0A8FB07CBD6C1008493CA /* mathutils.h */,
 				69E0A8FD07CBD6C1008493CA /* newmat */,
 				69E0A95707CBD6C1008493CA /* ODataFormats.h */,
 				69E666BB07F0CE51005F4FA9 /* plist.cc */,
 				69E666B607F0CE3A005F4FA9 /* plist.h */,
+				698A071B09575F41001A13D5 /* plistBase.cc */,
+				698A071C09575F41001A13D5 /* plistBase.h */,
+				698A072709575F7D001A13D5 /* plistCollections.cc */,
+				698A072809575F7D001A13D5 /* plistCollections.h */,
+				69A7EF2709C9EA77003DDD18 /* plistPrimitives.cc */,
+				698A072E09575F94001A13D5 /* plistPrimitives.h */,
 				69E0A95A07CBD6C1008493CA /* Profiler.cc */,
 				69E0A95B07CBD6C1008493CA /* Profiler.h */,
 				69E0A95C07CBD6C1008493CA /* ProjectInterface.cc */,
 				69E0A95D07CBD6C1008493CA /* ProjectInterface.h */,
 				69E0A96007CBD6C1008493CA /* ReferenceCounter.h */,
+				69EB5B530A41CCD700415C6B /* Resource.cc */,
+				69F6038C0A40800F0052ECA1 /* Resource.h */,
+				69EB5B2C0A41C8DE00415C6B /* ResourceAccessor.h */,
 				69E0A96107CBD6C1008493CA /* RobotInfo.h */,
+				69E78D0109F6C114000385E9 /* StackTrace.cc */,
+				69E78D0209F6C114000385E9 /* StackTrace.h */,
 				69E0A96507CBD6C1008493CA /* string_util.cc */,
 				69E0A96607CBD6C1008493CA /* string_util.h */,
-				69E0A96707CBD6C1008493CA /* SystemUtility.h */,
 				69E0A96807CBD6C1008493CA /* TimeET.cc */,
 				69E0A96907CBD6C1008493CA /* TimeET.h */,
 				69E0A96A07CBD6C1008493CA /* Util.h */,
@@ -1640,6 +2013,8 @@
 				69E0A96C07CBD6C1008493CA /* WMclass.h */,
 				69E0A96D07CBD6C1008493CA /* WorldState.cc */,
 				69E0A96E07CBD6C1008493CA /* WorldState.h */,
+				6958D6890A5EE5AB00D46050 /* WorldStatePool.cc */,
+				6958D68A0A5EE5AB00D46050 /* WorldStatePool.h */,
 				69E6674707F1E23A005F4FA9 /* XMLLoadSave.cc */,
 				69E6674807F1E23A005F4FA9 /* XMLLoadSave.h */,
 			);
@@ -1651,6 +2026,8 @@
 			children = (
 				69E0A8DE07CBD6C1008493CA /* jpeg_mem_dest.cc */,
 				69E0A8DF07CBD6C1008493CA /* jpeg_mem_dest.h */,
+				694B36560A190FE2002ABC4C /* jpeg_mem_src.cc */,
+				694B36550A190FE2002ABC4C /* jpeg_mem_src.h */,
 				69A323C007E35646009D94E1 /* write_jpeg.cc */,
 				69A323C107E35646009D94E1 /* write_jpeg.h */,
 			);
@@ -1722,6 +2099,8 @@
 		69E0A96F07CBD6C1008493CA /* Sound */ = {
 			isa = PBXGroup;
 			children = (
+				694E684B0AC338CF0087EC83 /* PitchDetector.cc */,
+				694E67E10AC308130087EC83 /* PitchDetector.h */,
 				69E0A97007CBD6C1008493CA /* SoundManager.cc */,
 				69E0A97107CBD6C1008493CA /* SoundManager.h */,
 				69E0A97207CBD6C1008493CA /* SoundManagerMsg.h */,
@@ -1754,6 +2133,8 @@
 				69E0A98307CBD6C1008493CA /* JPEGGenerator.cc */,
 				69E0A98407CBD6C1008493CA /* JPEGGenerator.h */,
 				69E0A98507CBD6C1008493CA /* OFbkImage.h */,
+				6900659D0A4EF58700E895F9 /* PNGGenerator.cc */,
+				6900659E0A4EF58700E895F9 /* PNGGenerator.h */,
 				69E0A98607CBD6C1008493CA /* RawCameraGenerator.cc */,
 				69E0A98707CBD6C1008493CA /* RawCameraGenerator.h */,
 				69E0A98807CBD6C1008493CA /* RegionGenerator.cc */,
@@ -1770,6 +2151,8 @@
 			isa = PBXGroup;
 			children = (
 				69E0A98F07CBD6C1008493CA /* DummySocket.h */,
+				69B8DDC00AC44735003EC54A /* LGmixin.cc */,
+				69B8DDC10AC44735003EC54A /* LGmixin.h */,
 				69E0A99107CBD6C1008493CA /* Socket.cc */,
 				69E0A99207CBD6C1008493CA /* Socket.h */,
 				69E0A99307CBD6C1008493CA /* Wireless.cc */,
@@ -1793,23 +2176,10 @@
 /* Begin PBXLegacyTarget section */
 		693D800E08ABBB4200AC993E /* Aperios Build */ = {
 			isa = PBXLegacyTarget;
-			buildArgumentsString = "TEKKOTSU_ROOT=$(TEKKOTSU_ROOT) update";
+			buildArgumentsString = "TEKKOTSU_ROOT=$(TEKKOTSU_ROOT) -j2 $ACTION";
 			buildConfigurationList = 693D800F08ABBB6100AC993E /* Build configuration list for PBXLegacyTarget "Aperios Build" */;
 			buildPhases = (
 			);
-			buildSettings = {
-				OPTIMIZATION_CFLAGS = "";
-				OTHER_CFLAGS = "";
-				OTHER_LDFLAGS = "";
-				OTHER_REZFLAGS = "";
-				PRODUCT_NAME = "Aperios Build";
-				SECTORDER_FLAGS = "";
-				WARNING_CFLAGS = (
-					"-Wmost",
-					"-Wno-four-char-constants",
-					"-Wno-unknown-pragmas",
-				);
-			};
 			buildToolPath = /usr/bin/make;
 			buildWorkingDirectory = "";
 			dependencies = (
@@ -1830,11 +2200,6 @@
 			);
 			buildRules = (
 			);
-			buildSettings = {
-				INSTALL_PATH = "$(HOME)/bin";
-				OTHER_CPLUSPLUSFLAGS = "-DTGT_ERS210";
-				PRODUCT_NAME = "sim-ERS210";
-			};
 			dependencies = (
 			);
 			name = "sim (ERS-210)";
@@ -1852,11 +2217,6 @@
 			);
 			buildRules = (
 			);
-			buildSettings = {
-				INSTALL_PATH = /usr/local/bin;
-				OTHER_CPLUSPLUSFLAGS = "-DTGT_ERS7";
-				PRODUCT_NAME = "sim-ERS7";
-			};
 			dependencies = (
 			);
 			name = "sim (ERS-7) Light";
@@ -1873,11 +2233,6 @@
 			);
 			buildRules = (
 			);
-			buildSettings = {
-				INSTALL_PATH = "$(HOME)/bin";
-				OTHER_CPLUSPLUSFLAGS = "-DTGT_ERS7";
-				PRODUCT_NAME = "sim-ERS7";
-			};
 			dependencies = (
 			);
 			name = "sim (ERS-7)";
@@ -1892,21 +2247,15 @@
 		08FB7793FE84155DC02AAC07 /* Project object */ = {
 			isa = PBXProject;
 			buildConfigurationList = 69FD50360881E74900E825BA /* Build configuration list for PBXProject "Make" */;
-			buildSettings = {
-			};
-			buildStyles = (
-				014CEA460018CE2711CA2923 /* Development */,
-				014CEA470018CE2711CA2923 /* Deployment */,
-			);
 			hasScannedForEncodings = 1;
 			mainGroup = 08FB7794FE84155DC02AAC07 /* sim */;
 			productRefGroup = 69E0AD5D07CBDE11008493CA /* Products */;
 			projectDirPath = "";
 			targets = (
-				8DD76F620486A84900D96B5E /* sim (ERS-7) */,
+				693D800E08ABBB4200AC993E /* Aperios Build */,
 				69E0AFA707CBF79B008493CA /* sim (ERS-7) Light */,
+				8DD76F620486A84900D96B5E /* sim (ERS-7) */,
 				69E0AB9A07CBDE11008493CA /* sim (ERS-210) */,
-				693D800E08ABBB4200AC993E /* Aperios Build */,
 			);
 		};
 /* End PBXProject section */
@@ -1949,7 +2298,6 @@
 				69E0ABBB07CBDE11008493CA /* ChaseBallBehavior.cc in Sources */,
 				69E0ABBC07CBDE11008493CA /* DriveMeBehavior.cc in Sources */,
 				69E0ABBD07CBDE11008493CA /* ExploreMachine.cc in Sources */,
-				69E0ABBE07CBDE11008493CA /* FlashIPAddrBehavior.cc in Sources */,
 				69E0ABBF07CBDE11008493CA /* FollowHeadBehavior.cc in Sources */,
 				69E0ABC007CBDE11008493CA /* PaceTargetsMachine.cc in Sources */,
 				69E0ABC107CBDE11008493CA /* StareAtBallBehavior.cc in Sources */,
@@ -2062,10 +2410,7 @@
 				69A323C507E35665009D94E1 /* write_jpeg.cc in Sources */,
 				69E666BD07F0CE51005F4FA9 /* plist.cc in Sources */,
 				69E6674907F1E23A005F4FA9 /* XMLLoadSave.cc in Sources */,
-				69E6696507F3398F005F4FA9 /* SimConfig.cc in Sources */,
 				692CD63507F8C46B00604100 /* sim.cc in Sources */,
-				692CD99607F9F05500604100 /* LoadFileThread.cc in Sources */,
-				695967E407FF3DCF004FABFF /* LoadImageThread.cc in Sources */,
 				695F1ACB0804A81800ACB3D7 /* BufferedImageGenerator.cc in Sources */,
 				69A19960080ED8A200540970 /* EchoBehavior.cc in Sources */,
 				691C805708255F6300E8E256 /* Base64.cc in Sources */,
@@ -2076,6 +2421,76 @@
 				69AA7D6C0860898300185BA2 /* MessageReceiver.cc in Sources */,
 				69B4E447089409D900832D58 /* StareAtPawBehavior2.cc in Sources */,
 				693D801508ABF46D00AC993E /* RegionCamBehavior.cc in Sources */,
+				69844A2D08CE5F7F00BCDD5C /* CameraStreamBehavior.cc in Sources */,
+				6966753D0926558A00405769 /* MCNode.cc in Sources */,
+				698A071E09575F41001A13D5 /* plistBase.cc in Sources */,
+				698A072A09575F7D001A13D5 /* plistCollections.cc in Sources */,
+				69469FF309AA1D2100D1EC14 /* AgentData.cc in Sources */,
+				69469FF409AA1D2100D1EC14 /* BaseData.cc in Sources */,
+				69469FF509AA1D2100D1EC14 /* BlobData.cc in Sources */,
+				69469FF609AA1D2100D1EC14 /* BrickData.cc in Sources */,
+				69469FF809AA1D2100D1EC14 /* EllipseData.cc in Sources */,
+				69469FF909AA1D2100D1EC14 /* EndPoint.cc in Sources */,
+				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 */,
+				6946A00509AA1D2100D1EC14 /* PolygonData.cc in Sources */,
+				6946A00609AA1D2100D1EC14 /* Region.cc in Sources */,
+				6946A00709AA1D2100D1EC14 /* ShapeAgent.cc in Sources */,
+				6946A00809AA1D2100D1EC14 /* ShapeBlob.cc in Sources */,
+				6946A00909AA1D2100D1EC14 /* ShapeBrick.cc in Sources */,
+				6946A00A09AA1D2100D1EC14 /* ShapeEllipse.cc in Sources */,
+				6946A00B09AA1D2100D1EC14 /* ShapeFuns.cc in Sources */,
+				6946A00C09AA1D2100D1EC14 /* ShapeLine.cc in Sources */,
+				6946A00D09AA1D2100D1EC14 /* ShapePoint.cc in Sources */,
+				6946A00E09AA1D2100D1EC14 /* ShapePolygon.cc in Sources */,
+				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 */,
+				6946A01609AA1D2100D1EC14 /* SketchRoot.cc in Sources */,
+				6946A01709AA1D2200D1EC14 /* SketchSpace.cc in Sources */,
+				6946A01809AA1D2200D1EC14 /* SphereData.cc in Sources */,
+				6946A01909AA1D2200D1EC14 /* susan.cc in Sources */,
+				6946A01A09AA1D2200D1EC14 /* ViewerConnection.cc in Sources */,
+				6946A01B09AA1D2200D1EC14 /* visops.cc in Sources */,
+				6946A01C09AA1D2200D1EC14 /* VisualRoutinesBehavior.cc in Sources */,
+				6946A1A309AAE1C600D1EC14 /* VRmixin.cc in Sources */,
+				6946A1A709AAE1D800D1EC14 /* VisualRoutinesStateNode.cc in Sources */,
+				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 */,
+				69EB5B550A41CCD700415C6B /* Resource.cc in Sources */,
+				6900659F0A4EF58700E895F9 /* PNGGenerator.cc in Sources */,
+				6958D68C0A5EE5AB00D46050 /* WorldStatePool.cc in Sources */,
+				69B344690A7152900021FBE6 /* PyramidData.cc in Sources */,
+				69B3446D0A7152AC0021FBE6 /* ShapePyramid.cc in Sources */,
+				69B344710A7152C30021FBE6 /* BrickOps.cc in Sources */,
+				6962F2EB0A917E33002DDEC9 /* LookoutEvents.cc in Sources */,
+				6962F2EF0A917E74002DDEC9 /* Aibo3DControllerBehavior.cc in Sources */,
+				6962F2FF0A917F41002DDEC9 /* LookoutRequests.cc in Sources */,
+				692964F90AA8CEEF00F47522 /* TestBehaviors.cc in Sources */,
+				6901D58F0AAF288500104815 /* TimerEvent.cc in Sources */,
+				69750F080AC03FFE004FE3CF /* FlashIPAddrBehavior.cc in Sources */,
+				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 */,
 			);
 			runOnlyForDeploymentPostprocessing = 0;
 		};
@@ -2098,8 +2513,9 @@
 				69E0AFB707CBF862008493CA /* Simulator.cc in Sources */,
 				69E0AFB807CBF863008493CA /* SoundPlay.cc in Sources */,
 				692CD63707F8C46B00604100 /* sim.cc in Sources */,
-				692CD99707F9F05500604100 /* LoadFileThread.cc in Sources */,
-				695967E207FF3DCF004FABFF /* LoadImageThread.cc in Sources */,
+				69A7EC7D09C79818003DDD18 /* TimerExecThread.cc in Sources */,
+				69A7ED9D09C88623003DDD18 /* MotionExecThread.cc in Sources */,
+				694E68580AC33A130087EC83 /* PitchDetector.cc in Sources */,
 			);
 			runOnlyForDeploymentPostprocessing = 0;
 		};
@@ -2107,6 +2523,8 @@
 			isa = PBXSourcesBuildPhase;
 			buildActionMask = 2147483647;
 			files = (
+				698A071D09575F41001A13D5 /* plistBase.cc in Sources */,
+				698A072909575F7D001A13D5 /* plistCollections.cc in Sources */,
 				69E0A76407CBD4F9008493CA /* StartupBehavior_SetupBackgroundBehaviors.cc in Sources */,
 				69E0A76507CBD4F9008493CA /* StartupBehavior_SetupFileAccess.cc in Sources */,
 				69E0A76607CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc in Sources */,
@@ -2140,7 +2558,6 @@
 				69E0A9CF07CBD6C1008493CA /* ChaseBallBehavior.cc in Sources */,
 				69E0A9D207CBD6C1008493CA /* DriveMeBehavior.cc in Sources */,
 				69E0A9D407CBD6C1008493CA /* ExploreMachine.cc in Sources */,
-				69E0A9D607CBD6C1008493CA /* FlashIPAddrBehavior.cc in Sources */,
 				69E0A9D807CBD6C1008493CA /* FollowHeadBehavior.cc in Sources */,
 				69E0A9E407CBD6C1008493CA /* PaceTargetsMachine.cc in Sources */,
 				69E0A9E907CBD6C1008493CA /* StareAtBallBehavior.cc in Sources */,
@@ -2252,10 +2669,7 @@
 				69A323C207E3564F009D94E1 /* write_jpeg.cc in Sources */,
 				69E666BC07F0CE51005F4FA9 /* plist.cc in Sources */,
 				69E6674A07F1E23A005F4FA9 /* XMLLoadSave.cc in Sources */,
-				69E6696607F3398F005F4FA9 /* SimConfig.cc in Sources */,
 				692CD63607F8C46B00604100 /* sim.cc in Sources */,
-				692CD99807F9F05500604100 /* LoadFileThread.cc in Sources */,
-				695967E307FF3DCF004FABFF /* LoadImageThread.cc in Sources */,
 				695F1ACA0804A81800ACB3D7 /* BufferedImageGenerator.cc in Sources */,
 				69A1995F080ED8A200540970 /* EchoBehavior.cc in Sources */,
 				691C805608255F6300E8E256 /* Base64.cc in Sources */,
@@ -2267,27 +2681,97 @@
 				69B4E446089409D900832D58 /* StareAtPawBehavior2.cc in Sources */,
 				69B4E6D50895E34F00832D58 /* robot.cpp in Sources */,
 				693D801408ABF46D00AC993E /* RegionCamBehavior.cc in Sources */,
+				69844A2C08CE5F7F00BCDD5C /* CameraStreamBehavior.cc in Sources */,
+				6966753C0926558A00405769 /* MCNode.cc in Sources */,
+				69469FC809AA1D2100D1EC14 /* AgentData.cc in Sources */,
+				69469FC909AA1D2100D1EC14 /* BaseData.cc in Sources */,
+				69469FCA09AA1D2100D1EC14 /* BlobData.cc in Sources */,
+				69469FCB09AA1D2100D1EC14 /* BrickData.cc in Sources */,
+				69469FCD09AA1D2100D1EC14 /* EllipseData.cc in Sources */,
+				69469FCE09AA1D2100D1EC14 /* EndPoint.cc in Sources */,
+				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 */,
+				69469FDA09AA1D2100D1EC14 /* PolygonData.cc in Sources */,
+				69469FDB09AA1D2100D1EC14 /* Region.cc in Sources */,
+				69469FDC09AA1D2100D1EC14 /* ShapeAgent.cc in Sources */,
+				69469FDD09AA1D2100D1EC14 /* ShapeBlob.cc in Sources */,
+				69469FDE09AA1D2100D1EC14 /* ShapeBrick.cc in Sources */,
+				69469FDF09AA1D2100D1EC14 /* ShapeEllipse.cc in Sources */,
+				69469FE009AA1D2100D1EC14 /* ShapeFuns.cc in Sources */,
+				69469FE109AA1D2100D1EC14 /* ShapeLine.cc in Sources */,
+				69469FE209AA1D2100D1EC14 /* ShapePoint.cc in Sources */,
+				69469FE309AA1D2100D1EC14 /* ShapePolygon.cc in Sources */,
+				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 */,
+				69469FEB09AA1D2100D1EC14 /* SketchRoot.cc in Sources */,
+				69469FEC09AA1D2100D1EC14 /* SketchSpace.cc in Sources */,
+				69469FED09AA1D2100D1EC14 /* SphereData.cc in Sources */,
+				69469FEE09AA1D2100D1EC14 /* susan.cc in Sources */,
+				69469FEF09AA1D2100D1EC14 /* ViewerConnection.cc in Sources */,
+				69469FF009AA1D2100D1EC14 /* visops.cc in Sources */,
+				69469FF109AA1D2100D1EC14 /* VisualRoutinesBehavior.cc in Sources */,
+				6946A1A209AAE1C600D1EC14 /* VRmixin.cc in Sources */,
+				6946A1A609AAE1D800D1EC14 /* VisualRoutinesStateNode.cc in Sources */,
+				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 */,
+				694B36580A190FE2002ABC4C /* jpeg_mem_src.cc in Sources */,
+				69EB5B560A41CCD700415C6B /* Resource.cc in Sources */,
+				690065A00A4EF58800E895F9 /* PNGGenerator.cc in Sources */,
+				6958D68B0A5EE5AB00D46050 /* WorldStatePool.cc in Sources */,
+				69B3446A0A7152900021FBE6 /* PyramidData.cc in Sources */,
+				69B3446E0A7152AC0021FBE6 /* ShapePyramid.cc in Sources */,
+				69B344720A7152C30021FBE6 /* BrickOps.cc in Sources */,
+				6962F2EC0A917E33002DDEC9 /* LookoutEvents.cc in Sources */,
+				6962F2F00A917E74002DDEC9 /* Aibo3DControllerBehavior.cc in Sources */,
+				6962F3000A917F41002DDEC9 /* LookoutRequests.cc in Sources */,
+				692964F80AA8CEEF00F47522 /* TestBehaviors.cc in Sources */,
+				6901D5900AAF288600104815 /* TimerEvent.cc in Sources */,
+				69750F090AC03FFE004FE3CF /* FlashIPAddrBehavior.cc in Sources */,
+				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 */,
 			);
 			runOnlyForDeploymentPostprocessing = 0;
 		};
 /* End PBXSourcesBuildPhase section */
 
 /* Begin XCBuildConfiguration section */
-		693D801008ABBB6100AC993E /* Development */ = {
+		693D801008ABBB6100AC993E /* . */ = {
 			isa = XCBuildConfiguration;
 			buildSettings = {
-				MEMSTICK_ROOT = /Volumes/Untitled;
-				TEKKOTSU_ALWAYS_BUILD = true;
+				CXXFLAGS = "-fmessage-length=0";
 				TEKKOTSU_COLORFILT = cat;
+				TEKKOTSU_DEFTARGET = update;
+				TEKKOTSU_LOGVIEW = cat;
 			};
-			name = Development;
+			name = .;
 		};
 		693D801108ABBB6100AC993E /* Deployment */ = {
 			isa = XCBuildConfiguration;
 			buildSettings = {
 				COPY_PHASE_STRIP = YES;
 				GCC_GENERATE_DEBUGGING_SYMBOLS = NO;
-				OPTIMIZATION_CFLAGS = "";
+				OPTIMIZATION_CFLAGS = "-O0";
 				OTHER_CFLAGS = "";
 				OTHER_LDFLAGS = "";
 				OTHER_REZFLAGS = "";
@@ -2301,7 +2785,7 @@
 			};
 			name = Deployment;
 		};
-		69FD502B0881E74900E825BA /* Development */ = {
+		69FD502B0881E74900E825BA /* . */ = {
 			isa = XCBuildConfiguration;
 			buildSettings = {
 				COPY_PHASE_STRIP = NO;
@@ -2355,7 +2839,7 @@
 					"-Wdeprecated",
 				);
 			};
-			name = Development;
+			name = .;
 		};
 		69FD502C0881E74900E825BA /* Deployment */ = {
 			isa = XCBuildConfiguration;
@@ -2375,7 +2859,7 @@
 			};
 			name = Deployment;
 		};
-		69FD502F0881E74900E825BA /* Development */ = {
+		69FD502F0881E74900E825BA /* . */ = {
 			isa = XCBuildConfiguration;
 			buildSettings = {
 				COPY_PHASE_STRIP = NO;
@@ -2411,11 +2895,16 @@
 					/usr/include/libxml2,
 				);
 				INSTALL_PATH = /usr/local/bin;
+				LIBRARY_SEARCH_PATHS = (
+					"$(TEKKOTSU_BUILDDIR)/PLATFORM_LOCAL/TGT_ERS7",
+					"$(TEKKOTSU_BUILDDIR)/PLATFORM_LOCAL/Motion/roboop",
+					"$(TEKKOTSU_BUILDDIR)/PLATFORM_LOCAL/Shared/newmat",
+				);
 				OBJROOT = build;
 				OTHER_CPLUSPLUSFLAGS = "-DTGT_ERS7";
 				PREBINDING = NO;
 				PRODUCT_NAME = "sim-ERS7";
-				SYMROOT = "";
+				SYMROOT = .;
 				WARNING_CFLAGS = (
 					"-Wall",
 					"-W",
@@ -2425,7 +2914,7 @@
 					"-Wdeprecated",
 				);
 			};
-			name = Development;
+			name = .;
 		};
 		69FD50300881E74900E825BA /* Deployment */ = {
 			isa = XCBuildConfiguration;
@@ -2439,13 +2928,18 @@
 				GCC_WARN_UNINITIALIZED_AUTOS = YES;
 				HEADER_SEARCH_PATHS = "$(TEKKOTSU_ROOT)";
 				INSTALL_PATH = /usr/local/bin;
+				LIBRARY_SEARCH_PATHS = (
+					"$(TEKKOTSU_BUILDDIR)/PLATFORM_LOCAL/TGT_ERS7",
+					"$(TEKKOTSU_BUILDDIR)/PLATFORM_LOCAL/Motion/roboop",
+					"$(TEKKOTSU_BUILDDIR)/PLATFORM_LOCAL/Shared/newmat",
+				);
 				OTHER_CPLUSPLUSFLAGS = "-DTGT_ERS7";
 				PRODUCT_NAME = "sim-ERS7";
 				ZERO_LINK = NO;
 			};
 			name = Deployment;
 		};
-		69FD50330881E74900E825BA /* Development */ = {
+		69FD50330881E74900E825BA /* . */ = {
 			isa = XCBuildConfiguration;
 			buildSettings = {
 				COPY_PHASE_STRIP = NO;
@@ -2495,7 +2989,7 @@
 					"-Wdeprecated",
 				);
 			};
-			name = Development;
+			name = .;
 		};
 		69FD50340881E74900E825BA /* Deployment */ = {
 			isa = XCBuildConfiguration;
@@ -2515,17 +3009,19 @@
 			};
 			name = Deployment;
 		};
-		69FD50370881E74900E825BA /* Development */ = {
+		69FD50370881E74900E825BA /* . */ = {
 			isa = XCBuildConfiguration;
 			buildSettings = {
+				DEBUG_INFORMATION_FORMAT = dwarf;
 				DEPLOYMENT_LOCATION = YES;
 				DSTROOT = build;
 			};
-			name = Development;
+			name = .;
 		};
 		69FD50380881E74900E825BA /* Deployment */ = {
 			isa = XCBuildConfiguration;
 			buildSettings = {
+				DEBUG_INFORMATION_FORMAT = dwarf;
 			};
 			name = Deployment;
 		};
@@ -2535,46 +3031,47 @@
 		693D800F08ABBB6100AC993E /* Build configuration list for PBXLegacyTarget "Aperios Build" */ = {
 			isa = XCConfigurationList;
 			buildConfigurations = (
-				693D801008ABBB6100AC993E /* Development */,
+				693D801008ABBB6100AC993E /* . */,
 				693D801108ABBB6100AC993E /* Deployment */,
 			);
 			defaultConfigurationIsVisible = 0;
+			defaultConfigurationName = .;
 		};
 		69FD502A0881E74900E825BA /* Build configuration list for PBXNativeTarget "sim (ERS-7)" */ = {
 			isa = XCConfigurationList;
 			buildConfigurations = (
-				69FD502B0881E74900E825BA /* Development */,
+				69FD502B0881E74900E825BA /* . */,
 				69FD502C0881E74900E825BA /* Deployment */,
 			);
 			defaultConfigurationIsVisible = 0;
-			defaultConfigurationName = Development;
+			defaultConfigurationName = .;
 		};
 		69FD502E0881E74900E825BA /* Build configuration list for PBXNativeTarget "sim (ERS-7) Light" */ = {
 			isa = XCConfigurationList;
 			buildConfigurations = (
-				69FD502F0881E74900E825BA /* Development */,
+				69FD502F0881E74900E825BA /* . */,
 				69FD50300881E74900E825BA /* Deployment */,
 			);
 			defaultConfigurationIsVisible = 0;
-			defaultConfigurationName = Development;
+			defaultConfigurationName = .;
 		};
 		69FD50320881E74900E825BA /* Build configuration list for PBXNativeTarget "sim (ERS-210)" */ = {
 			isa = XCConfigurationList;
 			buildConfigurations = (
-				69FD50330881E74900E825BA /* Development */,
+				69FD50330881E74900E825BA /* . */,
 				69FD50340881E74900E825BA /* Deployment */,
 			);
 			defaultConfigurationIsVisible = 0;
-			defaultConfigurationName = Development;
+			defaultConfigurationName = .;
 		};
 		69FD50360881E74900E825BA /* Build configuration list for PBXProject "Make" */ = {
 			isa = XCConfigurationList;
 			buildConfigurations = (
-				69FD50370881E74900E825BA /* Development */,
+				69FD50370881E74900E825BA /* . */,
 				69FD50380881E74900E825BA /* Deployment */,
 			);
 			defaultConfigurationIsVisible = 0;
-			defaultConfigurationName = Development;
+			defaultConfigurationName = .;
 		};
 /* End XCConfigurationList section */
 	};
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/Makefile ./project/Makefile
--- ../Tekkotsu_2.4.1/project/Makefile	2005-07-06 18:53:29.000000000 -0400
+++ ./project/Makefile	2006-09-26 17:53:55.000000000 -0400
@@ -40,15 +40,14 @@
 	  $(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
+	  `$(TEKKOTSU_ROOT)/aperios/bin/xml2-config --libs` -ljpeg -lpng
 else
-  PLATFORM_FLAGS=`xml2-config --cflags`
-  LDFLAGS=`xml2-config --libs` $(if $(shell locate librt.a),-lrt) -ljpeg
+  PLATFORM_FLAGS=`xml2-config --cflags` -isystem /usr/include/libpng12
+  LDFLAGS=`xml2-config --libs` $(if $(shell locate librt.a),-lrt) -lreadline -lncurses -ljpeg -lpng12
 endif
 
-CXXFLAGS= \
-	$(if $(TEKKOTSU_DEBUG),-g -fno-inline -DDEBUG,) \
-	$(if $(TEKKOTSU_DEBUG),,-O2 -frename-registers -fomit-frame-pointer) \
+CXXFLAGS:= \
+	$(if $(TEKKOTSU_DEBUG),$(TEKKOTSU_DEBUG),$(TEKKOTSU_OPTIMIZE)) \
 	-pipe -ffast-math -fno-common \
 	-Wall -W -Wshadow -Wlarger-than-8192 -Wpointer-arith -Wcast-qual \
 	-Woverloaded-virtual -Weffc++ -Wdeprecated -Wnon-virtual-dtor \
@@ -56,10 +55,11 @@
 	-I$(TEKKOTSU_ROOT)/Shared/newmat \
 	-isystem $(TEKKOTSU_ROOT)/Shared/jpeg-6b \
 	-D$(TEKKOTSU_TARGET_PLATFORM)  -D$(TEKKOTSU_TARGET_MODEL) \
-	$(PLATFORM_FLAGS)
+	$(PLATFORM_FLAGS) $(CXXFLAGS)
 
 INCLUDE_PCH=$(if $(TEKKOTSU_PCH),-include $(TK_BD)/$(TEKKOTSU_PCH))
 
+TEKKOTSU_VERSION=Tekkotsu pre-3.0 CVS
 
 ###################################################
 ##              SOURCE CODE LIST                 ##
@@ -70,7 +70,7 @@
 # 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))
+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))
 
 # We can also link in third-party libraries
 USERLIBS:= $(TK_BD)/libtekkotsu.a \
@@ -84,14 +84,23 @@
 # Hopefully, you shouldn't have to change anything down here,
 # except one or two little things ;)
 
-.PHONY: all compile clean cleanDeps cleanProj reportTarget checkLibs testLibs buildLibs sim
+.PHONY: all compile clean cleanDeps cleanProj reportTarget checkLibs testEnv testLibs buildLibs sim
 
-sim all: reportTarget checkLibs compile
-ifeq ($(TEKKOTSU_TARGET_PLATFORM),PLATFORM_APERIOS)
-	@echo "Type: '$(MAKE) install' to copy all files to the memory stick";
-	@echo "  or: '$(MAKE) update' to copy only changed files";
-	@echo "  or: '$(TEKKOTSU_ROOT)/tools/{ftpinstall,ftpupdate} <ipaddr> ms' might also be useful";
+sim all update install ftpupdate: reportTarget testEnv checkLibs
+	@$(MAKE) TEKKOTSU_TARGET_PLATFORM=$(TEKKOTSU_TARGET_PLATFORM) compile-$@
+
+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
@@ -160,7 +169,12 @@
 
 endif
 
-ifeq ($(filter clean% docs,$(MAKECMDGOALS)),)
+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)
+endif
+
+ifeq ($(filter clean% docs newstick,$(MAKECMDGOALS)),)
 -include $(DEPENDS)
 ifeq ($(TEKKOTSU_TARGET_PLATFORM),PLATFORM_APERIOS)
 -include $(PROJ_BD)/aperios/aperios.d
@@ -180,8 +194,27 @@
 	$(CXX) $(CXXFLAGS) -MP -MG -MT "$@" -MT "$(@:.d=.o)" -MM "$$src" > $@
 
 reportTarget:
-	@echo " ** Targeting $(TEKKOTSU_TARGET_MODEL) for build on $(TEKKOTSU_TARGET_PLATFORM) ** ";
-	@echo " ** TEKKOTSU_DEBUG is $(if $(TEKKOTSU_DEBUG),ON ,OFF) ** ";
+	@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 \
@@ -191,12 +224,13 @@
 	@echo "ERROR: Seems to be a missing header file '$@'...";
 	@echo "       Someone probably forgot to check a file into CVS.";
 	@echo "       I'll try to find where it's being included from:";
+	@echo "       if this was a file you recently deleted, just make again after this completes. (will update dependency files)";
 	@find . -name "*.h" -exec grep -H "$(notdir $@)" \{\} \; ;
 	@find . -name "*.cc" -exec grep -H "$(notdir $@)" \{\} \; ;
 	@find $(TEKKOTSU_ROOT) -name "*.h" -exec grep -H "$(notdir $@)" \{\} \; ;
 	@find $(TEKKOTSU_ROOT) -name "*.cc" -exec grep -H "$(notdir $@)" \{\} \; ;
-	@echo "";
-	@echo "You might need to rebuild the dependancy files ('make cleanDeps') to get rid of this error.";
+	@find $(TK_BD) -name "*.d" -exec grep -qH "$(notdir $@)" \{\} \; -exec rm \{\} \; ;
+	@find $(PROJ_BD) -name "*.d" -exec grep -qH "$(notdir $@)" \{\} \; -exec rm \{\} \; ;
 	@exit 1
 
 #don't try to make random files via this implicit chain
@@ -244,6 +278,6 @@
 
 cleanDeps:
 	@echo "Cleaning all .d files from build directory..."
-	find $(PROJ_BD) -name "*.d" -exec rm \{\} \;
+	find $(PROJECT_BUILDDIR) -name "*.d" -exec rm \{\} \;
 	@echo "done."
 	$(if $(TEKKOTSU_ALWAYS_BUILD),$(MAKE) -C $(TEKKOTSU_ROOT) $@)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/StartupBehavior.cc ./project/StartupBehavior.cc
--- ../Tekkotsu_2.4.1/project/StartupBehavior.cc	2005-06-10 13:26:04.000000000 -0400
+++ ./project/StartupBehavior.cc	2006-09-18 14:08:09.000000000 -0400
@@ -81,7 +81,7 @@
 	wireless->setReceiver(sout, Controller::console_callback);
 	spawned.push_back(controller);
 	
-	sndman->PlayFile("roar.wav");
+	sndman->playFile("roar.wav");
 
 	//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)
@@ -105,6 +105,14 @@
 	for(unsigned int i=0; i<spawnedMC.size(); i++)
 		erouter->addListener(this,EventBase::motmanEGID,spawnedMC[i],EventBase::deactivateETID);
 	
+#ifdef PLATFORM_APERIOS
+	sout->printf("Remember, telnet to port 10001 for text entry (port 59000 is read only)\n");
+#else
+	sout->printf("All console output will be redirected to this terminal.\n");
+	sout->printf("Alternatively, telnet to port 10001 to isolate data from sout as a separate stream.\n");
+	sout->printf("If a prompt does not appear below, hit 'enter' or 'return' to refresh it.\n");
+#endif
+	
 	//if you didn't want to start off paused, you should throw an
 	//un-estop event.  This will make it clear to any background
 	//behaviors (namely WorldStateVelDaemon) that we're not in estop
@@ -196,7 +204,9 @@
 		startSubMenu();
 		{ 
 			addItem(new ShutdownControl());
+#ifdef PLATFORM_APERIOS
 			addItem(new RebootControl());
+#endif
 		}
 		endSubMenu();
 		addItem(new HelpControl(root,2));
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/StartupBehavior_SetupBackgroundBehaviors.cc ./project/StartupBehavior_SetupBackgroundBehaviors.cc
--- ../Tekkotsu_2.4.1/project/StartupBehavior_SetupBackgroundBehaviors.cc	2005-06-01 01:48:07.000000000 -0400
+++ ./project/StartupBehavior_SetupBackgroundBehaviors.cc	2006-09-21 17:26:08.000000000 -0400
@@ -3,31 +3,30 @@
 #include "Behaviors/Controls/ControlBase.h"
 #include "Behaviors/Controls/BehaviorSwitchControl.h"
 
-#include "Behaviors/Demos/FlashIPAddrBehavior.h"
+#include "Behaviors/Services/FlashIPAddrBehavior.h"
 #include "Behaviors/Demos/SimpleChaseBallBehavior.h"
 #include "Behaviors/Demos/StareAtBallBehavior.h"
-#include "Behaviors/Demos/AutoGetupBehavior.h"
-#include "Behaviors/Demos/BatteryMonitorBehavior.h"
+#include "Behaviors/Services/AutoGetupBehavior.h"
+#include "Behaviors/Services/BatteryMonitorBehavior.h"
 #include "Behaviors/Demos/HeadLevelBehavior.h"
 #include "Behaviors/Demos/ToggleHeadLightBehavior.h"
 #include "Behaviors/Demos/CrashTestBehavior.h"
 #include "Behaviors/Demos/FreezeTestBehavior.h"
 #include "Behaviors/Demos/RelaxBehavior.h"
-#include "Behaviors/Demos/WorldStateVelDaemon.h"
+#include "Behaviors/Services/WorldStateVelDaemon.h"
 #include "Behaviors/Demos/CameraBehavior.h"
 #include "Behaviors/Demos/MotionStressTestBehavior.h"
 #include "Behaviors/Demos/ASCIIVisionBehavior.h"
 #include "Behaviors/Nodes/TailWagNode.h"
+#include "Sound/PitchDetector.h"
 
-#include "Shared/WorldState.h"
-#include "Shared/ERS210Info.h"
+#include "Behaviors/Demos/TestBehaviors.h"
 
 ControlBase*
 StartupBehavior::SetupBackgroundBehaviors() {
 	addItem(new ControlBase("Background Behaviors","Background daemons and monitors"));
 	startSubMenu();
 	{ 
-		addItem((new BehaviorSwitchControl<FlashIPAddrBehavior>("Flash IP Address",false))->start());
 		addItem(new BehaviorSwitchControl<SimpleChaseBallBehavior>("Simple Chase Ball",false));
 		addItem(new BehaviorSwitchControl<StareAtBallBehavior>("Stare at Ball",false));
 		addItem(new BehaviorSwitchControl<HeadLevelBehavior>("Head Level",false));
@@ -43,14 +42,23 @@
 			addItem(new BehaviorSwitchControl<MotionStressTestBehavior>("Motion Stress Test",false));
 			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
+			addItem(new BehaviorSwitchControl<InstantMotionTestBehavior>("Instant MC Add/Remove",false));
+			addItem(new BehaviorSwitchControl<BusyLoopTestBehavior>("Busy Loop Behavior",false));
+			addItem(new BehaviorSwitchControl<BusyMCTestBehavior>("Busy Loop MC",false));
+			addItem(new BehaviorSwitchControl<SuicidalBehavior>("Suicidal Behavior",false));
+			addItem(new BehaviorSwitchControl<EchoTextBehavior>("Echo Text",false));
+			addItem(new BehaviorSwitchControl<SaveImagePyramidBehavior>("Save Image Pyramid",false));
 		}
 		endSubMenu();
 		addItem(new ControlBase("System Daemons","Provide some common sensor or event processing"));
 		startSubMenu();
 		{
 			addItem((new BehaviorSwitchControl<AutoGetupBehavior>("Auto Getup",false)));
+			addItem((new BehaviorSwitchControl<FlashIPAddrBehavior>("Flash IP Address",false))->start());
 			addItem((new BehaviorSwitchControl<WorldStateVelDaemon>("World State Vel Daemon",false))->start());
 			addItem((new BehaviorSwitchControl<BatteryMonitorBehavior>("Battery Monitor",false))->start());
+			addItem((new BehaviorSwitchControl<PitchDetector>("Pitch Detection",false))->start());
 		}
 		endSubMenu();
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/StartupBehavior_SetupTekkotsuMon.cc ./project/StartupBehavior_SetupTekkotsuMon.cc
--- ../Tekkotsu_2.4.1/project/StartupBehavior_SetupTekkotsuMon.cc	2005-08-05 15:44:23.000000000 -0400
+++ ./project/StartupBehavior_SetupTekkotsuMon.cc	2006-08-03 18:58:36.000000000 -0400
@@ -32,7 +32,9 @@
 		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 BehaviorSwitchControl<WorldStateSerializerBehavior>("World State Serializer",false)));
+		BehaviorSwitchControlBase * wss=NULL;
+		addItem((wss=new BehaviorSwitchControl<WorldStateSerializerBehavior>("World State Serializer",false)));
+		Aibo3DControllerBehavior::setSerializerControl(wss);
 		addItem((new BehaviorSwitchControl<RawCamBehavior>("Raw Cam Server",false)));
 		addItem((new BehaviorSwitchControl<SegCamBehavior>("Seg Cam Server",false)));
 		addItem((new BehaviorSwitchControl<RegionCamBehavior>("Region Cam Server",false)));
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/StartupBehavior_SetupVision.cc ./project/StartupBehavior_SetupVision.cc
--- ../Tekkotsu_2.4.1/project/StartupBehavior_SetupVision.cc	2005-07-10 16:03:11.000000000 -0400
+++ ./project/StartupBehavior_SetupVision.cc	2006-06-30 12:35:32.000000000 -0400
@@ -15,6 +15,7 @@
 #endif
 #include "Vision/InterleavedYUVGenerator.h"
 #include "Vision/JPEGGenerator.h"
+#include "Vision/PNGGenerator.h"
 #include "Vision/SegmentedColorGenerator.h"
 #include "Vision/RLEGenerator.h"
 #include "Vision/RegionGenerator.h"
@@ -28,7 +29,9 @@
 
 BallDetectionGenerator * pball=NULL;
 BallDetectionGenerator * bball=NULL;
-BallDetectionGenerator * handball=NULL;
+BallDetectionGenerator * gball=NULL;
+BallDetectionGenerator * yball=NULL;
+BallDetectionGenerator * handball=NULL; //aka orange
 
 /*! We set the default vision generators and source IDs here.
  *
@@ -55,23 +58,28 @@
 #endif
 	
 
-	// These JPEG generators select the "deactivate" stage, so they will work on
+	// These JPEG & PNG generators select the "deactivate" stage, so they will work on
 	// the potentially marked up versions of the raw camera.  The camera GUIs use
 	// these to provide vision feedback without requiring an extra pipeline stage
 	// or image copy.
-	// Of course, if you want to analyze the JPEG compression as a part of a
+	// Of course, if you want to analyze the compression as a part of a
 	// computer vision algorithm, you'll want the un-marked up versions, and so
-	// you may need to add another JPEG compressor instance that uses the
+	// you may need to add another compressor instance that uses the
 	// "activate" stage to ensure you get the original data.
 
-	//need to do pixel interleaving for JPEG compression
+	//need to do pixel interleaving for JPEG & PNG compression
 	//if the results of visRawCameraEGID are already in the proper format (e.g. source layer of BufferedImageGenerator) then InterleavedYUVGenerator is a pass-through
 	defInterleavedYUVGenerator = new InterleavedYUVGenerator(visInterleaveSID,RawCameraGenerator::CHAN_Y,RawCameraGenerator::CHAN_U,RawCameraGenerator::CHAN_V,defRawCameraGenerator,EventBase::deactivateETID);
+	
 	defColorJPEGGenerator = new JPEGGenerator(visColorJPEGSID,defInterleavedYUVGenerator,EventBase::deactivateETID);
 	defColorJPEGGenerator->setName("ColorJPEGGenerator");
 	defGrayscaleJPEGGenerator = new JPEGGenerator(visGrayscaleJPEGSID,defRawCameraGenerator,EventBase::deactivateETID);
 	defGrayscaleJPEGGenerator->setName("GrayscaleJPEGGenerator");
 
+	defColorPNGGenerator = new PNGGenerator(visColorPNGSID,defInterleavedYUVGenerator,EventBase::deactivateETID);
+	defColorPNGGenerator->setName("ColorPNGGenerator");
+	defGrayscalePNGGenerator = new PNGGenerator(visGrayscalePNGSID,defRawCameraGenerator,EventBase::deactivateETID);
+	defGrayscalePNGGenerator->setName("GrayscalePNGGenerator");
 
 	// the hardware level CDT generator allows faster, but less flexible
 	// segmenting it still needs a little work though before it can be
@@ -79,7 +87,8 @@
 	// defSegmentedColorGenerator = new CDTGenerator(numSystemLayers,numLayers,EventBase::visOFbkEGID,0,visSegmentSID);
 	defSegmentedColorGenerator = new SegmentedColorGenerator(visSegmentSID,defRawCameraGenerator,EventBase::activateETID);
 	SegmentedColorGenerator * segcol = defSegmentedColorGenerator; //just using segcol as a shorthand for the following setup
-	segcol->loadColorInfo(config->vision.colors);
+	if(config->vision.colors[0]!='\0')
+		segcol->loadColorInfo(config->vision.colors);
 	for(unsigned int i=0; i<config->vision.thresh.size(); i++)
 		segcol->loadThresholdMap(config->vision.thresh[i]);
 
@@ -97,7 +106,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.rlecam_channel;
+	unsigned int threshChan=config->vision.segcam_channel;
 
 	// higher value reduce false events, but increase reaction time [0-inf]
 	unsigned int noiseFiltering=1;
@@ -105,7 +114,7 @@
 	// lower values increase sensitivity (and noise) [0-1]
 	float confidenceThreshold=.8;
 
-	unsigned int pinkIdx=segcol->getColorIndex("red");
+	unsigned int pinkIdx=segcol->getColorIndex("pink");
 	if(pinkIdx!=-1U) {
 		pball = new BallDetectionGenerator(visPinkBallSID,defRegionGenerator,pinkIdx,threshChan,noiseFiltering,confidenceThreshold);
 		pball->setName("PinkBallDetectionGenerator");
@@ -115,7 +124,17 @@
 		bball = new BallDetectionGenerator(visBlueBallSID,defRegionGenerator,blueIdx,threshChan,noiseFiltering,confidenceThreshold);
 		bball->setName("BlueBallDetectionGenerator");
 	}
-	unsigned int skinIdx=segcol->getColorIndex("brown");
+	unsigned int greenIdx=segcol->getColorIndex("green");
+	if(greenIdx!=-1U) {
+		gball = new BallDetectionGenerator(visGreenBallSID,defRegionGenerator,greenIdx,threshChan,noiseFiltering,confidenceThreshold);
+		gball->setName("GreenBallDetectionGenerator");
+	}
+	unsigned int yellowIdx=segcol->getColorIndex("yellow");
+	if(yellowIdx!=-1U) {
+		yball = new BallDetectionGenerator(visYellowBallSID,defRegionGenerator,yellowIdx,threshChan,noiseFiltering,confidenceThreshold);
+		yball->setName("YellowBallDetectionGenerator");
+	}
+	unsigned int skinIdx=segcol->getColorIndex("orange");
 	if(skinIdx!=-1U) {
 		handball = new BallDetectionGenerator(visHandSID,defRegionGenerator,skinIdx,threshChan,noiseFiltering,confidenceThreshold);
 		handball->setName("HandBallDetectionGenerator");
@@ -145,10 +164,16 @@
 
 		if(defColorJPEGGenerator)
 			addItem((new BehaviorSwitchControlBase(defColorJPEGGenerator))->start());
-
+		
 		if(defGrayscaleJPEGGenerator)
 			addItem((new BehaviorSwitchControlBase(defGrayscaleJPEGGenerator))->start());
 		
+		if(defColorPNGGenerator)
+			addItem((new BehaviorSwitchControlBase(defColorPNGGenerator))->start());
+		
+		if(defGrayscalePNGGenerator)
+			addItem((new BehaviorSwitchControlBase(defGrayscalePNGGenerator))->start());
+		
 		if(config->vision.colors!="" && config->vision.thresh.size()>0)
 			addItem((new BehaviorSwitchControlBase(defSegmentedColorGenerator))->start());
 		else
@@ -163,17 +188,27 @@
 		if(pball)
 			addItem((new BehaviorSwitchControlBase(pball))->start());
 		else
-			addItem(new NullControl("Error: PinkBallDetectionGenerator","Color \"red\" is undefined"));
+			addItem(new NullControl("Error: PinkBallDetectionGenerator","Color \"pink\" is undefined"));
 
 		if(bball)
 			addItem((new BehaviorSwitchControlBase(bball))->start());
 		else
 			addItem(new NullControl("Error: BlueBallDetectionGenerator","Color \"blue\" is undefined"));
 
+		if(gball)
+			addItem((new BehaviorSwitchControlBase(gball))->start());
+		else
+			addItem(new NullControl("Error: BlueBallDetectionGenerator","Color \"green\" is undefined"));
+
+		if(yball)
+			addItem((new BehaviorSwitchControlBase(yball))->start());
+		else
+			addItem(new NullControl("Error: BlueBallDetectionGenerator","Color \"yellow\" is undefined"));
+
 		if(handball)
 			addItem((new BehaviorSwitchControlBase(handball))->start());
 		else
-			addItem(new NullControl("Error: HandBallDetectionGenerator","Color \"brown\" is undefined"));
+			addItem(new NullControl("Error: HandBallDetectionGenerator","Color \"orange\" is undefined"));
 	}
 	return endSubMenu();
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/StartupBehavior_SetupWalkEdit.cc ./project/StartupBehavior_SetupWalkEdit.cc
--- ../Tekkotsu_2.4.1/project/StartupBehavior_SetupWalkEdit.cc	2004-05-14 03:18:19.000000000 -0400
+++ ./project/StartupBehavior_SetupWalkEdit.cc	2005-09-22 17:54:17.000000000 -0400
@@ -32,8 +32,10 @@
 	addItem(new ControlBase("Walk Edit","Edit the walk parameters"));
 	startSubMenu();
 	{ 
+		//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();
-		addItem((new BehaviorSwitchControlBase(walker)));
+		addItem((new BehaviorSwitchControlBase("Walk GUI: test changes",walker)));
 
 		addItem(new ValueEditControl<float>("Slow Motion",walker->getWalkMC()->getSlowMo()));
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/aperios/Makefile.aperios ./project/aperios/Makefile.aperios
--- ../Tekkotsu_2.4.1/project/aperios/Makefile.aperios	2005-06-03 18:55:49.000000000 -0400
+++ ./project/aperios/Makefile.aperios	2006-09-12 16:17:54.000000000 -0400
@@ -2,7 +2,7 @@
 $(error This makefile is not meant to be run directly.  It is intended to contain Aperios-specific build instructions.  Please run 'make' from the main project directory.);
 endif
 
-.PHONY: newstick install update cleanTemps checkInstallBinTimestamp
+.PHONY: newstick compile-install compile-update cleanTemps checkInstallBinTimestamp
 
 #Each directory represents a separate OObject aka process/thread
 #PROJ_OOBJECTS holds those defined in the project, OOBJECTS
@@ -16,6 +16,7 @@
 ifeq ($(FILENAME_CASE),lower)
   TRCMD=tr "[:upper:]" "[:lower:]"
   CONVERTCASE=$(TEKKOTSU_ROOT)/tools/makelowercase
+  #BINSUFFIX applies to stuff in the "installdir", but not the PROJ_BD dir (for which we assume/hardcode ".bin", no case switching)
   BINSUFFIX=.bin
   MSIMGDIR=ms
   INSTALLDIR=$(MSIMGDIR)/open-r/mw/objs
@@ -23,6 +24,7 @@
 else
   TRCMD=tr "[:lower:]" "[:upper:]"
   CONVERTCASE=$(TEKKOTSU_ROOT)/tools/makeuppercase
+  #BINSUFFIX applies to stuff in the "installdir", but not the PROJ_BD dir (for which we assume/hardcode just ".bin", no case switching)
   BINSUFFIX=.BIN
   MSIMGDIR=MS
   INSTALLDIR=$(MSIMGDIR)/OPEN-R/MW/OBJS
@@ -33,7 +35,8 @@
 # memstick image directory
 INSTALL_BINS:=$(shell echo $(addprefix $(INSTALLDIR)/, $(addsuffix $(BINSUFFIX), MainObj MotoObj $(filter-out MMCombo,$(OOBJECTS)))) | $(TRCMD))
 
-$(PROJ_BD)/aperios/aperios.d: $(shell find aperios -name "*$(SRCSUFFIX)") $(wildcard $(TK_BD)/aperios/*)
+$(PROJ_BD)/aperios/aperios.d: $(shell find aperios -name "*$(SRCSUFFIX)")
+	$(testEnvScr)
 	@echo Generating $@...
 	@mkdir -p $(dir $@)
 	@rm -f $@;
@@ -75,7 +78,7 @@
 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: checkLibs cleanTemps checkInstallBinTimestamp $(PROJ_BD)/installbin.timestamp
+compile: cleanTemps checkInstallBinTimestamp $(PROJ_BD)/installbin.timestamp
 	@image="$(PROJ_BD)/$(notdir $(MEMSTICK_ROOT))" ; \
 	if [ \! -d "$$image" ] ; then \
 		if [ \! -d "$(SYSTEM_BINARIES)" ] ; then \
@@ -87,11 +90,52 @@
 		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 \{\} \; ; \
 		curt=`date +%Y%m%d%H%M`; \
 		find "$$image" -exec touch -ft $$curt \{\} \; ; \
 	fi;
+	@badfiles=`find ./$(MSIMGDIR) -name CVS -prune -o -type f -print | grep -v '.*/[^/]\{0,8\}\.\{0,1\}[^/]\{0,3\}~\{0,1\}$$' | grep -v '^./$(MSIMGDIR)/.'`; \
+	if [ "$$badfiles" ] ; then \
+		echo "ERROR: Bad file names were detected:" ; \
+		echo "$$badfiles" ; \
+		echo "Filenames in '$(MSIMGDIR)' directory must conform to the DOS-style 8.3 naming system"; \
+		exit 1; \
+	fi;
+	@baddirs=`find ./$(MSIMGDIR) -name CVS -prune -o -type d -print | grep -v '.*/[^/]\{0,8\}$$'`; \
+	if [ "$$baddirs" ] ; then \
+		echo "ERROR: Bad directory names were detected:" ; \
+		echo "$$baddirs" ; \
+		echo "Directories in '$(MSIMGDIR)' must conform to the DOS-style 8.3 naming system (dirs less than 8 characters)"; \
+		exit 1; \
+	fi;
+	@ms=`find . -ipath './$(MSIMGDIR)'`; \
+	if [ "$(FILENAME_CASE)" = "lower" ] ; then \
+		casefiles=`find "$$ms" -name CVS -prune -o -regex '.*/[^./]*[[:upper:]][^/]*' -print` ; \
+	else \
+		casefiles=`find "$$ms" -name CVS -prune -o -regex '.*/[^./]*[[:lower:]][^/]*' -print` ; \
+	fi; \
+	if [  "$$casefiles" ] ; then \
+		echo "WARNING: filenames of the wrong case detected in $$ms -- may cause excessive resyncing"; \
+		echo "$$casefiles"; \
+		if [ "$(FILENAME_CASE)" = "lower" ] ; then echo "Try running ../tools/makelowercase -r $$ms" ; \
+		else echo "Try running ../tools/makeuppercase -r $$ms" ; fi; \
+	fi;
+	@bldinfo=$(shell echo "$(MSIMGDIR)/bld_info.txt" | $(TRCMD)); \
+	printf "Built with $(TEKKOTSU_VERSION), at %s by %s\n" "`date +\"%Y/%m/%d %H:%M:%S\"`" "$$USER" > $$bldinfo ; \
+	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
 
 checkInstallBinTimestamp:
+	@if [ \! -d "$(MSIMGDIR)" ] ; then \
+		echo "ERROR: could not find memory stick image directory $(MSIMGDIR)" ; \
+		ms=`find . -ipath './$(MSIMGDIR)'`; \
+		if [ "$$ms" ] ; then \
+			if [ "$(FILENAME_CASE)" = "lower" ] ; then echo "May be the wrong case on case-sensitive file system?  Try running ../tools/makelowercase -r $$ms" ; \
+			else echo "May be the wrong case on case-sensitive file system?  Try running ../tools/makeuppercase -r $$ms" ; fi; \
+		fi; \
+		exit 1; \
+	fi;
 	@for x in $(INSTALL_BINS) ; do \
 		if [ "$$x" -nt "$(PROJ_BD)/installbin.timestamp" ] ; then \
 			printf "Target switch detected, cleaning binaries..." ; \
@@ -108,7 +152,7 @@
 # we have to do a couple extra steps to cd into the builddir because
 # mkbin doesn't support -o target in a different directory... drops an
 # intermediate file in . and then complains (as of 1.1.3 anyway)
-$(PROJ_BD)/aperios/%$(BINSUFFIX):
+$(PROJ_BD)/aperios/%.bin:
 	@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 ; \
@@ -154,40 +198,45 @@
 $(PROJ_BD)/installbin.timestamp: $(INSTALL_BINS)
 	@touch $@
 
-install: compile
-	@echo "Installing files to memory stick at $(MEMSTICK_ROOT)"
-	$(TEKKOTSU_ROOT)/tools/mntmem "$(MEMSTICK_ROOT)"
-	@if [ \! -r "$(MEMSTICK_ROOT)/open-r/version.txt" -o \! -r "$(MEMSTICK_ROOT)/open-r/system/objs/ipstack.bin" -o \! -r "$(MEMSTICK_ROOT)/open-r/system/objs/vr.bin" -o \! -r "$(MEMSTICK_ROOT)/open-r/system/objs/wlanenbl.bin" ] ; then \
+compile-install: compile
+	@export MEMSTICK_ROOT="$(MEMSTICK_ROOT)"; \
+	echo "Installing files to memory stick at $$MEMSTICK_ROOT" \
+	$(TEKKOTSU_ROOT)/tools/mntmem; \
+	if [ \! -r "$$MEMSTICK_ROOT/open-r/version.txt" -o \! -r "$$MEMSTICK_ROOT/open-r/system/objs/ipstack.bin" -o \! -r "$$MEMSTICK_ROOT/open-r/system/objs/vr.bin" -o \! -r "$$MEMSTICK_ROOT/open-r/system/objs/wlanenbl.bin" ] ; then \
 		echo "** ERROR: It looks like your memory stick is missing critical system files."; \
 		echo "**        You may want to 'make newstick' first to clear the memory stick"; \
 		echo "**        and copy the OPEN-R system files onto it."; \
-		echo $(TEKKOTSU_ROOT)/tools/umntmem "$(MEMSTICK_ROOT)"; \
-		$(TEKKOTSU_ROOT)/tools/umntmem "$(MEMSTICK_ROOT)"; \
+		echo Unmounting "$$MEMSTICK_ROOT"; \
+		$(TEKKOTSU_ROOT)/tools/umntmem; \
 		exit 1; \
-	fi;
-	@if [ -z "`grep \"$(if $(findstring TGT_ERS7,$(TEKKOTSU_TARGET_MODEL)),ERS-7,ERS-210/220)\" \"$(MEMSTICK_ROOT)/open-r/version.txt\"`" ] ; then \
+	fi; \
+	if [ -z "`grep \"$(if $(findstring TGT_ERS7,$(TEKKOTSU_TARGET_MODEL)),ERS-7,ERS-210/220)\" \"$$MEMSTICK_ROOT/open-r/version.txt\"`" ] ; then \
 		echo "** ERROR: It looks like your memory stick has the system files for the wrong"; \
 		echo "**        model of AIBO.  You may want to 'make newstick' first to clear the"; \
 		echo "**        memory stick and reinstall the OPEN-R system files onto it."; \
-		echo $(TEKKOTSU_ROOT)/tools/umntmem "$(MEMSTICK_ROOT)"; \
-		$(TEKKOTSU_ROOT)/tools/umntmem "$(MEMSTICK_ROOT)"; \
+		echo Unmounting "$$MEMSTICK_ROOT"; \
+		$(TEKKOTSU_ROOT)/tools/umntmem; \
 		exit 1; \
-	fi;
-	@$(TEKKOTSU_ROOT)/tools/cpymem --all --img $(MSIMGDIR) --tgt "$(MEMSTICK_ROOT)" --tools $(TEKKOTSU_ROOT)/tools
-	@touch .copiedtomemstick.timestamp
+	fi; \
+	$(TEKKOTSU_ROOT)/tools/cpymem --all --img $(MSIMGDIR) --tgt "$$MEMSTICK_ROOT" --tools $(TEKKOTSU_ROOT)/tools; \
+	touch .copiedtomemstick.timestamp
 
-update: compile
-	@echo "Syncing $(MSIMGDIR) and $(MEMSTICK_ROOT)"
-	@$(TEKKOTSU_ROOT)/tools/evenmodtime/evenmodtime `find $(MSIMGDIR)` $(PROJ_BD)/installbin.timestamp
-	@$(TEKKOTSU_ROOT)/tools/mntmem "$(MEMSTICK_ROOT)"
-	@if [ $(STRICT_MEMSTICK_IMAGE) ] ; then \
+compile-update: compile
+	@export MEMSTICK_ROOT="$(MEMSTICK_ROOT)"; \
+	echo "Syncing $(MSIMGDIR) and $$MEMSTICK_ROOT"; \
+	$(TEKKOTSU_ROOT)/tools/mntmem "$$MEMSTICK_ROOT" || exit 1; \
+	if [ $(STRICT_MEMSTICK_IMAGE) ] ; then \
 		echo "Strict image copy is on." ; \
-		rsync -rLtWCv --delete $(MSIMGDIR)/* "$(PROJ_BD)/$(notdir $(MEMSTICK_ROOT))/"* "$(MEMSTICK_ROOT)" ; \
+		rsync -rLtWCv --exclude='.*' --delete --modify-window=1 $(MSIMGDIR)/* "$(PROJ_BD)/$(notdir $(MEMSTICK_ROOT))/"* "$$MEMSTICK_ROOT" || exit 1 ; \
 	else \
-		rsync -rLtWCv $(MSIMGDIR)/* "$(PROJ_BD)/$(notdir $(MEMSTICK_ROOT))/"* "$(MEMSTICK_ROOT)" ; \
-	fi;
-	@$(TEKKOTSU_ROOT)/tools/umntmem "$(MEMSTICK_ROOT)"
-	@touch .copiedtomemstick.timestamp
+		rsync -rLtWCv --exclude='.*' --modify-window=1 $(MSIMGDIR)/* "$(PROJ_BD)/$(notdir $(MEMSTICK_ROOT))/"* "$$MEMSTICK_ROOT" || exit 1 ; \
+	fi; \
+	$(TEKKOTSU_ROOT)/tools/umntmem "$$MEMSTICK_ROOT"; \
+	touch .copiedtomemstick.timestamp
+
+compile-ftpupdate: compile
+	@echo "Updating the memorystick via ftp using ftpupdate with the IP adress $(IPADDRESS)" 
+	@$(TEKKOTSU_ROOT)/tools/ftpupdate $(IPADDRESS) $(MSIMGDIR);
 
 newstick:
 	@echo "  We are about to delete all the files contained within '$(MEMSTICK_ROOT)':"
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/local/Makefile.local ./project/local/Makefile.local
--- ../Tekkotsu_2.4.1/project/local/Makefile.local	2005-06-29 19:13:05.000000000 -0400
+++ ./project/local/Makefile.local	2006-05-10 17:36:23.000000000 -0400
@@ -39,11 +39,7 @@
 compile: $(TGTEXECS)
 	@echo "You probably now want to run './sim$(subst TGT_,-,$(TEKKOTSU_TARGET_MODEL))'";
 
-ifneq ($(filter sim-%,$(MAKECMDGOALS)),)
-$(TGTEXECS): checkLibs $(PROJ_BD)/project.a
-else
 $(TGTEXECS): $(PROJ_BD)/project.a
-endif
 	@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 ; \
Binary files ../Tekkotsu_2.4.1/project/ms/config/210genrl.tm and ./project/ms/config/210genrl.tm differ
Binary files ../Tekkotsu_2.4.1/project/ms/config/210pb.tm and ./project/ms/config/210pb.tm differ
Binary files ../Tekkotsu_2.4.1/project/ms/config/210phb.tm and ./project/ms/config/210phb.tm differ
Binary files ../Tekkotsu_2.4.1/project/ms/config/7general.tm and ./project/ms/config/7general.tm differ
Binary files ../Tekkotsu_2.4.1/project/ms/config/7red.tm and ./project/ms/config/7red.tm differ
Binary files ../Tekkotsu_2.4.1/project/ms/config/ball.tm and ./project/ms/config/ball.tm differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/ms/config/default.col ./project/ms/config/default.col
--- ../Tekkotsu_2.4.1/project/ms/config/default.col	2003-07-28 02:58:16.000000000 -0400
+++ ./project/ms/config/default.col	2006-10-03 23:28:00.000000000 -0400
@@ -1,10 +1,7 @@
 0 (128 128 128) "unclassified" 8 1.00
-1 (24 43 93) "blue" 8 0.75
-2 (255 255 255) "white" 8 0.75
-3 (237 131 54) "orange" 8 0.75
-4 (43 150 180) "azure" 8 0.75
-5 (36 67 23) "green" 8 0.75
-6 (209 60 97) "red" 8 0.75
-7 (200 189 123) "yellow" 8 0.75
-8 (0 0 0) "black" 8 0.75
-9 (113 80 34) "brown" 8 0.75
+1 (167 152 116) "unsaturated" 8 0.75
+2 (108 191 73) "green" 8 0.75
+3 (188 166 13) "yellow" 8 0.75
+4 (235 127 52) "orange" 8 0.75
+5 (235 99 163) "pink" 8 0.75
+6 (120 158 208) "blue" 8 0.75
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/ms/config/easytrn/7gen-hsb.spc ./project/ms/config/easytrn/7gen-hsb.spc
--- ../Tekkotsu_2.4.1/project/ms/config/easytrn/7gen-hsb.spc	1969-12-31 19:00:00.000000000 -0500
+++ ./project/ms/config/easytrn/7gen-hsb.spc	2006-10-03 23:28:00.000000000 -0400
@@ -0,0 +1,2039 @@
+HSB
+6
+unsaturated
+<AREA>
+START 0.714399149377822 0.46033921307557046
+LINE 0.7143991493778219 0.4603392130755705
+LINE 0.714399149377822 0.4603392130755705
+LINE 0.714399149377822 0.46033921307557046
+CLOSE
+START 0.7753928103146791 0.5329028867573274
+LINE 0.758282184600828 0.5333917488857
+LINE 0.7582821846008301 0.5333917488857
+LINE 0.7582821846008301 0.54969322681427
+LINE 0.7739739107650481 0.54969322681427
+LINE 0.7753928103146793 0.5329028867573274
+CLOSE
+START 0.832462829316045 0.6995632181601883
+LINE 0.833410766109232 0.718521977048311
+LINE 0.8334107661092359 0.718521977048311
+LINE 0.8472047549730767 0.718246104507914
+LINE 0.8472047549730802 0.718246104507914
+LINE 0.8459608190706278 0.7014529396109207
+LINE 0.8459608190706266 0.7014529396109207
+LINE 0.8324628293160447 0.6995632181601883
+CLOSE
+START -0.0015174506697803736 -0.0015174506697803736
+LINE -0.0015174506697803736 0.0
+LINE -0.0015174506697803736 0.003034901339560747
+LINE -0.0015174506697803736 0.006069802679121494
+LINE -0.0015174506697803736 0.013657055795192719
+LINE -0.0015174506697803736 0.019726859405636787
+LINE -0.0015174506697803736 0.027314111590385437
+LINE -0.0015174506697803736 0.037936266511678696
+LINE -0.0015174506697803736 0.045523520559072495
+LINE -0.0015174506697803736 0.051593322306871414
+LINE -0.0015174506697803736 0.06221547722816467
+LINE -0.0015174506697803736 0.07132018357515335
+LINE -0.0015174506697803736 0.08042488247156143
+LINE -0.0015174506697803736 0.08801213651895523
+LINE -0.0015174506697803736 0.09559939056634903
+LINE -0.0015174506697803736 0.10470409691333771
+LINE -0.0015174506697803736 0.1122913509607315
+LINE -0.0015174506697803736 0.12139605730772018
+LINE -0.0015174506697803736 0.1274658590555191
+LINE -0.0015174506697803736 0.13808801770210266
+LINE -0.0015174506697803736 0.14719271659851074
+LINE -0.0015174506697803736 0.1578148752450943
+LINE -0.0015174506697803736 0.16691957414150238
+LINE -0.0015174506697803736 0.17450682818889618
+LINE -0.0015174506697803736 0.1805766373872757
+LINE -0.0015174506697803736 0.18361152708530426
+LINE -0.0015174506697803736 0.1881638914346695
+LINE -0.001226993859745562 0.18816345930099487
+LINE -0.001226993859745562 0.19141104817390442
+LINE -0.001226993859745562 0.20122699439525604
+LINE -0.001226993859745562 0.21104294061660767
+LINE -0.001226993859745562 0.21840490400791168
+LINE -0.001226993859745562 0.2257668673992157
+LINE -0.001226993859745562 0.23558282852172852
+LINE -0.001226993859745562 0.24294479191303253
+LINE -0.001226993859745562 0.25153374671936035
+LINE -0.001226993859745562 0.2588956952095032
+LINE -0.001226993859745562 0.2650306820869446
+LINE -0.001226993859745562 0.2711656391620636
+LINE -0.001226993859745562 0.277300626039505
+LINE -0.001226993859745562 0.2846625745296478
+LINE -0.001226993859745562 0.29202455282211304
+LINE -0.001226993859745562 0.29938650131225586
+LINE -0.001226993859745562 0.3055214583873749
+LINE -0.001226993859745562 0.3116564452648163
+LINE -0.001226993859745562 0.3202453851699829
+LINE -0.001226993859745562 0.3263803720474243
+LINE -0.001226993859745562 0.33251532912254333
+LINE -0.001226993859745562 0.33987730741500854
+LINE -0.001226993859745562 0.349693238735199
+LINE -0.001226993859745562 0.3656441569328308
+LINE -0.001226993859745562 0.38159510493278503
+LINE -0.001226993859745562 0.39754602313041687
+LINE -0.001226993859745562 0.4147239327430725
+LINE -0.001226993859745562 0.42822086811065674
+LINE -0.001226993859745562 0.43926379084587097
+LINE -0.001226993859745562 0.4490797519683838
+LINE -0.001226993859745562 0.4588957130908966
+LINE -0.001226993859745562 0.47239264845848083
+LINE -0.001226993859745562 0.48098158836364746
+LINE -0.001226993859745562 0.4895705580711365
+LINE -0.001226993859745562 0.4969325065612793
+LINE -0.001226993859745562 0.5055214762687683
+LINE -0.001226993859745562 0.5128834247589111
+LINE -0.001226993859745562 0.5190184116363525
+LINE -0.001226993859745562 0.5239263772964478
+LINE -0.001226993859745562 0.5312883257865906
+LINE -0.001226993859745562 0.5337423086166382
+LINE -0.001226993859745562 0.5398772954940796
+LINE -0.001226993859745562 0.5447852611541748
+LINE -0.001226993859745562 0.5484662652015686
+LINE -0.001226993859745562 0.5509202480316162
+LINE -0.001226993859745562 0.5521472096443176
+LINE -0.001226993859745562 0.5533742308616638
+LINE 0.017177913337945938 0.5533742308616638
+LINE 0.01840490847826004 0.5521472096443176
+LINE 0.023312883451581 0.5521472096443176
+LINE 0.02699386514723301 0.5509202480316162
+LINE 0.028220858424901962 0.5509202480316162
+LINE 0.029447853565216064 0.54969322681427
+LINE 0.03190184012055397 0.5484662652015686
+LINE 0.03558282181620598 0.5472392439842224
+LINE 0.039263803511857986 0.546012282371521
+LINE 0.04171779006719589 0.546012282371521
+LINE 0.0453987717628479 0.5435582995414734
+LINE 0.047852762043476105 0.5435582995414734
+LINE 0.05153374373912811 0.5423312783241272
+LINE 0.05153374373912811 0.5411043167114258
+LINE 0.052760735154151917 0.5411043167114258
+LINE 0.05521472543478012 0.5398772954940796
+LINE 0.05766871199011803 0.5398772954940796
+LINE 0.05889570713043213 0.5386503338813782
+LINE 0.061349693685770035 0.5386503338813782
+LINE 0.06257668882608414 0.537423312664032
+LINE 0.06625767052173615 0.5361962914466858
+LINE 0.06993865221738815 0.5349693298339844
+LINE 0.07239263504743576 0.5325153470039368
+LINE 0.07484662532806396 0.5312883257865906
+LINE 0.07730061560869217 0.5300613641738892
+LINE 0.07975459843873978 0.528834342956543
+LINE 0.08343558013439178 0.5263803601264954
+LINE 0.08588957041501999 0.525153398513794
+LINE 0.08711656183004379 0.5239263772964478
+LINE 0.089570552110672 0.5214723944664001
+LINE 0.0920245423913002 0.520245373249054
+LINE 0.093251533806324 0.520245373249054
+LINE 0.09447849914422524 0.5190184116363525
+LINE 0.09447852522134781 0.5190184116363525
+LINE 0.09447852522134781 0.5190183855593091
+LINE 0.09447852522134782 0.5190183855593091
+LINE 0.09570552408695221 0.5177913904190063
+LINE 0.09693251550197601 0.5177913904190063
+LINE 0.09693251550197601 0.5171779096126556
+LINE 0.09815950691699982 0.5165644288063049
+LINE 0.09938650578260422 0.5153374075889587
+LINE 0.10061349719762802 0.5153374075889587
+LINE 0.10184048861265182 0.5141104459762573
+LINE 0.10306748747825623 0.5141104459762573
+LINE 0.10306748747825623 0.5128834247589111
+LINE 0.10429447889328003 0.5128834247589111
+LINE 0.1028555541011366 0.5106413791666877
+LINE 0.10285555410113659 0.5106413791666877
+LINE 0.10306748747825623 0.5104294419288635
+LINE 0.10429447889328003 0.5079754590988159
+LINE 0.10674846917390823 0.5067484378814697
+LINE 0.10797546058893204 0.5042944550514221
+LINE 0.10920245200395584 0.5006135106086731
+LINE 0.11165644228458405 0.4981594979763031
+LINE 0.11288343369960785 0.4944785237312317
+LINE 0.11411043256521225 0.4920245409011841
+LINE 0.11779141426086426 0.4895705580711365
+LINE 0.11901840567588806 0.48711657524108887
+LINE 0.12024539709091187 0.48466256260871887
+LINE 0.12147239595651627 0.48466256260871887
+LINE 0.12147239595651627 0.48220857977867126
+LINE 0.12269938737154007 0.48098158836364746
+LINE 0.12269938737154007 0.47975459694862366
+LINE 0.12392637878656387 0.47852760553359985
+LINE 0.12392637878656387 0.47607362270355225
+LINE 0.12515337765216827 0.47484663128852844
+LINE 0.12638036906719208 0.47239264845848083
+LINE 0.12883435189723969 0.46871164441108704
+LINE 0.1300613433122635 0.46625766158103943
+LINE 0.1312883496284485 0.4638036787509918
+LINE 0.1325153410434723 0.4613496959209442
+LINE 0.1337423324584961 0.4576687216758728
+LINE 0.1337423324584961 0.456441730260849
+LINE 0.1337423324584961 0.4552147090435028
+LINE 0.1349693238735199 0.453987717628479
+LINE 0.1349693238735199 0.4527607262134552
+LINE 0.1361963152885437 0.4527607262134552
+LINE 0.1361963152885437 0.4515337347984314
+LINE 0.1374233067035675 0.4490797519683838
+LINE 0.1374233067035675 0.44785276055336
+LINE 0.1386503130197525 0.4441717863082886
+LINE 0.1398773044347763 0.44171780347824097
+LINE 0.1398773044347763 0.44049081206321716
+LINE 0.1423312872648239 0.43803679943084717
+LINE 0.1423312872648239 0.43680980801582336
+LINE 0.1423312872648239 0.43558281660079956
+LINE 0.14355827867984772 0.43435582518577576
+LINE 0.14478527009487152 0.43312883377075195
+LINE 0.14478527009487152 0.43190184235572815
+LINE 0.14601227641105652 0.43067485094070435
+LINE 0.14723926782608032 0.43067485094070435
+LINE 0.14723926782608032 0.42944785952568054
+LINE 0.14846625924110413 0.42822086811065674
+LINE 0.14969325065612793 0.42822086811065674
+LINE 0.14969325065612793 0.42699387669563293
+LINE 0.15092024207115173 0.42699387669563293
+LINE 0.15092024207115173 0.43067485094070435
+LINE 0.15092024207115173 0.43926379084587097
+LINE 0.15092024207115173 0.4453987777233124
+LINE 0.15092024207115173 0.4503067433834076
+LINE 0.15092024207115173 0.456441730260849
+LINE 0.15092024207115173 0.4613496959209442
+LINE 0.15092024207115173 0.4650306701660156
+LINE 0.15092024207115173 0.46748465299606323
+LINE 0.15092024207115173 0.47116565704345703
+LINE 0.15092024207115173 0.47361963987350464
+LINE 0.15092024207115173 0.47484663128852844
+LINE 0.15092024207115173 0.47607362270355225
+LINE 0.15092024207115173 0.47852760553359985
+LINE 0.15092024207115173 0.47975459694862366
+LINE 0.15092024207115173 0.48098158836364746
+LINE 0.15092024207115173 0.48220857977867126
+LINE 0.15092024207115173 0.48343557119369507
+LINE 0.15092024207115173 0.48466256260871887
+LINE 0.15092024207115173 0.48588958382606506
+LINE 0.15092024207115173 0.48711657524108887
+LINE 0.15092024207115173 0.48834356665611267
+LINE 0.15092024207115173 0.4895705580711365
+LINE 0.15092024207115173 0.4907975494861603
+LINE 0.15092024207115173 0.4932515323162079
+LINE 0.15092024207115173 0.4944785237312317
+LINE 0.15214723348617554 0.4957055151462555
+LINE 0.15214723348617554 0.4981594979763031
+LINE 0.15460123121738434 0.5006135106086731
+LINE 0.15460123121738434 0.5018404722213745
+LINE 0.15582822263240814 0.5042944550514221
+LINE 0.15705521404743195 0.5067484378814697
+LINE 0.15828220546245575 0.5092024803161621
+LINE 0.15950919687747955 0.5104294419288635
+LINE 0.15950919687747955 0.5128834247589111
+LINE 0.1766871213912964 0.5128834247589111
+LINE 0.1815950870513916 0.5141104459762573
+LINE 0.186503067612648 0.5153374075889587
+LINE 0.19018404185771942 0.5165644288063049
+LINE 0.19386503100395203 0.5177913904190063
+LINE 0.19754600524902344 0.5190184116363525
+LINE 0.20000000298023224 0.520245373249054
+LINE 0.20122699439525604 0.520245373249054
+LINE 0.20490796864032745 0.5226994156837463
+LINE 0.20736196637153625 0.5239263772964478
+LINE 0.21104294061660767 0.525153398513794
+LINE 0.21104294061660767 0.5263803601264954
+LINE 0.21349693834781647 0.5276073813438416
+LINE 0.21472392976284027 0.5300613641738892
+LINE 0.21595092117786407 0.5312883257865906
+LINE 0.21717791259288788 0.5312883257865906
+LINE 0.21963189542293549 0.5337423086166382
+LINE 0.2220858931541443 0.5361962914466858
+LINE 0.2233128845691681 0.537423312664032
+LINE 0.2245398759841919 0.5386503338813782
+LINE 0.2269938588142395 0.5411043167114258
+LINE 0.2282208651304245 0.5435582995414734
+LINE 0.2294478565454483 0.5447852611541748
+LINE 0.2306748479604721 0.546012282371521
+LINE 0.2319018393754959 0.5484662652015686
+LINE 0.2319018393754959 0.54969322681427
+LINE 0.2319018393754959 0.5509202480316162
+LINE 0.23312883079051971 0.5533742308616638
+LINE 0.23435582220554352 0.5558282136917114
+LINE 0.23558282852172852 0.5595092177391052
+LINE 0.23680981993675232 0.5619632005691528
+LINE 0.23926380276679993 0.5656441450119019
+LINE 0.24049079418182373 0.5693251490592957
+LINE 0.24417178332805634 0.5730061531066895
+LINE 0.24539877474308014 0.5766870975494385
+LINE 0.24662576615810394 0.5779141187667847
+LINE 0.24662576615810394 0.5791410803794861
+LINE 0.24785275757312775 0.5803681015968323
+LINE 0.24785275757312775 0.5828220844268799
+LINE 0.24785275757312775 0.5840491056442261
+LINE 0.24785275757312775 0.5865030884742737
+LINE 0.24785275757312775 0.5889570713043213
+LINE 0.24785275757312775 0.5938650369644165
+LINE 0.24785275757312775 0.5975460410118103
+LINE 0.24785275757312775 0.6012269854545593
+LINE 0.24785275757312775 0.6036809682846069
+LINE 0.24785275757312775 0.6085889339447021
+LINE 0.24785275757312775 0.612269937992096
+LINE 0.24785275757312775 0.6134969592094421
+LINE 0.24785275757312775 0.6171779036521912
+LINE 0.24785275757312775 0.6184049248695374
+LINE 0.24785275757312775 0.620858907699585
+LINE 0.24785275757312775 0.6233128905296326
+LINE 0.24785275757312775 0.6257668733596802
+LINE 0.24785275757312775 0.6282208561897278
+LINE 0.24785275757312775 0.633128821849823
+LINE 0.24785275757312775 0.6380367875099182
+LINE 0.24785275757312775 0.6404907703399658
+LINE 0.24662576615810394 0.6466257572174072
+LINE 0.24662576615810394 0.6515337228775024
+LINE 0.24662576615810394 0.6564416885375977
+LINE 0.24539877474308014 0.6601226925849915
+LINE 0.24539877474308014 0.6625766754150391
+LINE 0.24539877474308014 0.6662576794624329
+LINE 0.24539877474308014 0.6687116622924805
+LINE 0.24539877474308014 0.6699386239051819
+LINE 0.24539877474308014 0.6711656451225281
+LINE 0.24539877474308014 0.6723926663398743
+LINE 0.24539877474308014 0.6736196279525757
+LINE 0.24539877474308014 0.6748466491699219
+LINE 0.24539877474308014 0.6760736107826233
+LINE 0.24539877474308014 0.6773006319999695
+LINE 0.24417178332805634 0.6773006319999695
+LINE 0.24417178332805634 0.6785275936126709
+LINE 0.24294479191303253 0.6797546148300171
+LINE 0.24171778559684753 0.6809815764427185
+LINE 0.24171778559684753 0.6822085976600647
+LINE 0.24171778559684753 0.6858895421028137
+LINE 0.24171778559684753 0.6895705461502075
+LINE 0.24171778559684753 0.6920245289802551
+LINE 0.24171778559684753 0.6957055330276489
+LINE 0.24171778559684753 0.7018405199050903
+LINE 0.24171778559684753 0.7042945027351379
+LINE 0.24171778559684753 0.7067484855651855
+LINE 0.24171778559684753 0.7092024683952332
+LINE 0.24294479191303253 0.7128834128379822
+LINE 0.24294479191303253 0.7141104340553284
+LINE 0.24294479191303253 0.7177914381027222
+LINE 0.24294479191303253 0.7214723825454712
+LINE 0.24294479191303253 0.725153386592865
+LINE 0.24294479191303253 0.7276073694229126
+LINE 0.24294479191303253 0.7300613522529602
+LINE 0.24294479191303253 0.7312883138656616
+LINE 0.24294479191303253 0.7325153350830078
+LINE 0.24294479191303253 0.7349693179130554
+LINE 0.24294479191303253 0.7361963391304016
+LINE 0.24294479191303253 0.737423300743103
+LINE 0.24294479191303253 0.7386503219604492
+LINE 0.24294479191303253 0.7398772835731506
+LINE 0.24294479191303253 0.7411043047904968
+LINE 0.24294479191303253 0.7423312664031982
+LINE 0.24294479191303253 0.7435582876205444
+LINE 0.24294479191303253 0.7447852492332458
+LINE 0.24294479191303253 0.746012270450592
+LINE 0.24294479191303253 0.7472392916679382
+LINE 0.24294479191303253 0.7484662532806396
+LINE 0.24294479191303253 0.7496932744979858
+LINE 0.24294479191303253 0.7509202361106873
+LINE 0.24417178332805634 0.7533742189407349
+LINE 0.24417178332805634 0.7558282017707825
+LINE 0.24539877474308014 0.7582821846008301
+LINE 0.24662576615810394 0.7607361674308777
+LINE 0.24662576615810394 0.7619631886482239
+LINE 0.24785275757312775 0.7631902098655701
+LINE 0.24785275757312775 0.7656441926956177
+LINE 0.24907974898815155 0.7668711543083191
+LINE 0.25030675530433655 0.7680981755256653
+LINE 0.25030675530433655 0.7693251371383667
+LINE 0.25030675530433655 0.7705521583557129
+LINE 0.25153374671936035 0.7717791199684143
+LINE 0.25276073813438416 0.7742331027984619
+LINE 0.25276073813438416 0.7766871452331543
+LINE 0.25398772954940796 0.7766871452331543
+LINE 0.25398772954940796 0.7779141068458557
+LINE 0.25521472096443176 0.7791411280632019
+LINE 0.25766870379447937 0.7840490937232971
+LINE 0.2588956952095032 0.7852760553359985
+LINE 0.2588956952095032 0.7865030765533447
+LINE 0.2588956952095032 0.7877300381660461
+LINE 0.2588956952095032 0.7901840209960938
+LINE 0.2588956952095032 0.7914110422134399
+LINE 0.2588956952095032 0.7926380634307861
+LINE 0.260122686624527 0.7938650250434875
+LINE 0.260122686624527 0.7950920462608337
+LINE 0.260122686624527 0.7963190078735352
+LINE 0.260122686624527 0.7975460290908813
+LINE 0.260122686624527 0.7987729907035828
+LINE 0.260122686624527 0.800000011920929
+LINE 0.260122686624527 0.8012269735336304
+LINE 0.26134970784187317 0.8012269735336304
+LINE 0.26134970784187317 0.8024539947509766
+LINE 0.262576699256897 0.8049079775810242
+LINE 0.2638036906719208 0.8061349987983704
+LINE 0.2638036906719208 0.8073619604110718
+LINE 0.2650306820869446 0.808588981628418
+LINE 0.2662576735019684 0.8098159432411194
+LINE 0.2674846649169922 0.812269926071167
+LINE 0.268711656332016 0.8134969472885132
+LINE 0.268711656332016 0.8147239089012146
+LINE 0.2699386477470398 0.8147239089012146
+LINE 0.2699386477470398 0.8159509301185608
+LINE 0.2711656391620636 0.8171778917312622
+LINE 0.2736196219921112 0.8196318745613098
+LINE 0.2736196219921112 0.820858895778656
+LINE 0.274846613407135 0.820858895778656
+LINE 0.274846613407135 0.8220859169960022
+LINE 0.2760736048221588 0.8245398998260498
+LINE 0.277300626039505 0.8269938826560974
+LINE 0.2785276174545288 0.8282208442687988
+LINE 0.2797546088695526 0.8282208442687988
+LINE 0.2797546088695526 0.829447865486145
+LINE 0.2809816002845764 0.8319018483161926
+LINE 0.2822085916996002 0.8319018483161926
+LINE 0.2822085916996002 0.833128809928894
+LINE 0.283435583114624 0.833128809928894
+LINE 0.283435583114624 0.8343558311462402
+LINE 0.2846625745296478 0.8355827927589417
+LINE 0.28711655735969543 0.8368098139762878
+LINE 0.28834354877471924 0.838036835193634
+LINE 0.28957054018974304 0.8392637968063354
+LINE 0.29079753160476685 0.8392637968063354
+LINE 0.29079753160476685 0.8404908180236816
+LINE 0.29202455282211304 0.8404908180236816
+LINE 0.29447847604896343 0.8417177498355083
+LINE 0.2944784760489635 0.8417177498355083
+LINE 0.29447853565216053 0.8417178094387053
+LINE 0.29447853565216064 0.8417178094387053
+LINE 0.29447853565216064 0.8429448008537292
+LINE 0.29570552706718445 0.8429448008537292
+LINE 0.29570552706718445 0.8441717624664307
+LINE 0.29693251848220814 0.8453987538814544
+LINE 0.29693251848220825 0.8453987538814544
+LINE 0.29693251848220825 0.8453987836837769
+LINE 0.29693254828453064 0.8453987836837769
+LINE 0.29815950989723206 0.8466257452964783
+LINE 0.29938650131225586 0.8478527665138245
+LINE 0.30061349272727966 0.8503067493438721
+LINE 0.30061349272727966 0.8515337705612183
+LINE 0.30184048414230347 0.8539877533912659
+LINE 0.30306747555732727 0.8552147150039673
+LINE 0.3042944669723511 0.8576686978340149
+LINE 0.3042944669723511 0.8588957190513611
+LINE 0.3042944669723511 0.8601226806640625
+LINE 0.3055214583873749 0.8601226806640625
+LINE 0.3055214583873749 0.8613497018814087
+LINE 0.30674847960472107 0.8625766634941101
+LINE 0.30674847960472107 0.8638036847114563
+LINE 0.3079754710197449 0.8650306463241577
+LINE 0.3092024624347687 0.8650306463241577
+LINE 0.3092024624347687 0.8662576675415039
+LINE 0.3104294538497925 0.8662576675415039
+LINE 0.3104294538497925 0.8674846887588501
+LINE 0.3116564452648163 0.8674846887588501
+LINE 0.3116564452648163 0.8687116503715515
+LINE 0.3141104280948639 0.8699386715888977
+LINE 0.3153374195098877 0.8711656332015991
+LINE 0.3177914023399353 0.8723926544189453
+LINE 0.3177914023399353 0.8711656332015991
+LINE 0.3177914023399353 0.8699386715888977
+LINE 0.3177914023399353 0.8687116503715515
+LINE 0.3177914023399353 0.8674846887588501
+LINE 0.3177914023399353 0.8662576675415039
+LINE 0.3202453851699829 0.8662576675415039
+LINE 0.32747669513905425 0.7551239134516564
+LINE 0.3274766951390543 0.7551239134516564
+LINE 0.3276073634624481 0.754601240158081
+LINE 0.3276073634624481 0.7531157487648301
+LINE 0.32777159482977863 0.7505917733760262
+LINE 0.3288343548774719 0.7484662532806396
+LINE 0.3288343548774719 0.746012270450592
+LINE 0.3300613462924957 0.7423312664031982
+LINE 0.33128833770751953 0.737423300743103
+LINE 0.33251532912254333 0.7325153350830078
+LINE 0.33496931195259094 0.725153386592865
+LINE 0.33496931195259094 0.7202454209327698
+LINE 0.33619633316993713 0.7177914381027222
+LINE 0.33619633316993713 0.7141104340553284
+LINE 0.33742332458496094 0.7104294300079346
+LINE 0.33742332458496094 0.7092024683952332
+LINE 0.33742332458496094 0.7055214643478394
+LINE 0.33742332458496094 0.7018405199050903
+LINE 0.33742332458496094 0.699386477470398
+LINE 0.33742332458496094 0.6957055330276489
+LINE 0.33742332458496094 0.6920245289802551
+LINE 0.33742332458496094 0.6907975673675537
+LINE 0.33865031599998474 0.6871165633201599
+LINE 0.33865031599998474 0.6858895421028137
+LINE 0.33865031599998474 0.6846625804901123
+LINE 0.33865031599998474 0.6834355592727661
+LINE 0.33865031599998474 0.6797546148300171
+LINE 0.33865031599998474 0.6785275936126709
+LINE 0.33865031599998474 0.6773006319999695
+LINE 0.33865031599998474 0.6760736107826233
+LINE 0.33865031599998474 0.6748466491699219
+LINE 0.33865031599998474 0.6736196279525757
+LINE 0.33865031599998474 0.6723926663398743
+LINE 0.33987730741500854 0.6711656451225281
+LINE 0.33987730741500854 0.6699386239051819
+LINE 0.33987730741500854 0.6674846410751343
+LINE 0.33987730741500854 0.6662576794624329
+LINE 0.33987730741500854 0.6650306582450867
+LINE 0.34110429883003235 0.6638036966323853
+LINE 0.34110429883003235 0.6625766754150391
+LINE 0.34110429883003235 0.6613497138023376
+LINE 0.34110429883003235 0.65889573097229
+LINE 0.34110429883003235 0.6564416885375977
+LINE 0.34110429883003235 0.6552147269248962
+LINE 0.34110429883003235 0.65398770570755
+LINE 0.34110429883003235 0.6527607440948486
+LINE 0.34110429883003235 0.6515337228775024
+LINE 0.34110429883003235 0.650306761264801
+LINE 0.34110429883003235 0.6490797400474548
+LINE 0.34110429883003235 0.6478527784347534
+LINE 0.34110429883003235 0.6466257572174072
+LINE 0.34110429883003235 0.6453987956047058
+LINE 0.34110429883003235 0.6441717743873596
+LINE 0.34110429883003235 0.6429448127746582
+LINE 0.34110429883003235 0.641717791557312
+LINE 0.34110429883003235 0.6404907703399658
+LINE 0.34110429883003235 0.6392638087272644
+LINE 0.34110429883003235 0.6380367875099182
+LINE 0.34110429883003235 0.6368098258972168
+LINE 0.34110429883003235 0.6355828046798706
+LINE 0.34110429883003235 0.6343558430671692
+LINE 0.34110429883003235 0.633128821849823
+LINE 0.34110429883003235 0.6319018602371216
+LINE 0.34110429883003235 0.6306748390197754
+LINE 0.34110429883003235 0.629447877407074
+LINE 0.34110429883003235 0.6282208561897278
+LINE 0.34110429883003235 0.6257668733596802
+LINE 0.34110429883003235 0.624539852142334
+LINE 0.34110429883003235 0.6233128905296326
+LINE 0.34110429883003235 0.6220858693122864
+LINE 0.34233129024505615 0.620858907699585
+LINE 0.34233129024505615 0.6196318864822388
+LINE 0.34233129024505615 0.6184049248695374
+LINE 0.34233129024505615 0.6171779036521912
+LINE 0.34233129024505615 0.6147239208221436
+LINE 0.34233129024505615 0.6134969592094421
+LINE 0.34233129024505615 0.612269937992096
+LINE 0.34233129024505615 0.6110429167747498
+LINE 0.34233129024505615 0.6098159551620483
+LINE 0.34233129024505615 0.6085889339447021
+LINE 0.34233129024505615 0.6073619723320007
+LINE 0.34233129024505615 0.6061349511146545
+LINE 0.34355828166007996 0.6049079895019531
+LINE 0.34355828166007996 0.6036809682846069
+LINE 0.34355828166007996 0.6024540066719055
+LINE 0.34355828166007996 0.6012269854545593
+LINE 0.34478527307510376 0.5987730026245117
+LINE 0.34478527307510376 0.5975460410118103
+LINE 0.34478527307510376 0.5963190197944641
+LINE 0.34478527307510376 0.5950919985771179
+LINE 0.34601226449012756 0.5926380157470703
+LINE 0.34601226449012756 0.5901840329170227
+LINE 0.34601226449012756 0.5889570713043213
+LINE 0.34601226449012756 0.5865030884742737
+LINE 0.34601226449012756 0.5852760672569275
+LINE 0.34601226449012756 0.5840491056442261
+LINE 0.34601226449012756 0.5828220844268799
+LINE 0.34601226449012756 0.5815950632095337
+LINE 0.34601226449012756 0.5803681015968323
+LINE 0.34601226449012756 0.5791410803794861
+LINE 0.34601226449012756 0.5779141187667847
+LINE 0.34601226449012756 0.5754601359367371
+LINE 0.34601226449012756 0.5742331147193909
+LINE 0.34601226449012756 0.5730061531066895
+LINE 0.34601226449012756 0.5717791318893433
+LINE 0.34601226449012756 0.5705521702766418
+LINE 0.34601226449012756 0.5693251490592957
+LINE 0.34601226449012756 0.5680981874465942
+LINE 0.34601226449012756 0.566871166229248
+LINE 0.34601226449012756 0.5644171833992004
+LINE 0.34601226449012756 0.5631901621818542
+LINE 0.34601226449012756 0.5619632005691528
+LINE 0.34601226449012756 0.5607361793518066
+LINE 0.34601226449012756 0.5595092177391052
+LINE 0.34601226449012756 0.558282196521759
+LINE 0.34601226449012756 0.5570552349090576
+LINE 0.34601226449012756 0.5558282136917114
+LINE 0.34601226449012756 0.55460125207901
+LINE 0.34601226449012756 0.5533742308616638
+LINE 0.34601226449012756 0.5521472096443176
+LINE 0.34601226449012756 0.5484662652015686
+LINE 0.34601226449012756 0.5472392439842224
+LINE 0.34601226449012756 0.5447852611541748
+LINE 0.34601226449012756 0.5423312783241272
+LINE 0.34601226449012756 0.5398772954940796
+LINE 0.34601226449012756 0.5361962914466858
+LINE 0.34601226449012756 0.5349693298339844
+LINE 0.34601226449012756 0.5337423086166382
+LINE 0.34601226449012756 0.5312883257865906
+LINE 0.34601226449012756 0.5300613641738892
+LINE 0.34601226449012756 0.5276073813438416
+LINE 0.34601226449012756 0.5263803601264954
+LINE 0.34478527307510376 0.5239263772964478
+LINE 0.34478527307510376 0.5226994156837463
+LINE 0.34478527307510376 0.5214723944664001
+LINE 0.34478527307510376 0.520245373249054
+LINE 0.34478527307510376 0.5190184116363525
+LINE 0.34355828166007996 0.5190184116363525
+LINE 0.34355828166007996 0.5177913904190063
+LINE 0.34355828166007996 0.5165644288063049
+LINE 0.34355828166007996 0.5141104459762573
+LINE 0.34320505496774667 0.5134039925915908
+LINE 0.34355828166007996 0.5079754590988159
+LINE 0.34355828166007996 0.5067484378814697
+LINE 0.34233129024505615 0.5067484378814697
+LINE 0.34233129024505615 0.5055214762687683
+LINE 0.34233129024505615 0.5042944550514221
+LINE 0.34233129024505615 0.5030674934387207
+LINE 0.34233129024505615 0.5018404722213745
+LINE 0.34233129024505615 0.5006135106086731
+LINE 0.34233129024505615 0.4993864893913269
+LINE 0.34233129024505615 0.4981594979763031
+LINE 0.34233129024505615 0.4969325065612793
+LINE 0.34233129024505615 0.4957055151462555
+LINE 0.34233129024505615 0.4944785237312317
+LINE 0.34233129024505615 0.4932515323162079
+LINE 0.34233129024505615 0.4920245409011841
+LINE 0.34233129024505615 0.4907975494861603
+LINE 0.34233129024505615 0.4895705580711365
+LINE 0.34233129024505615 0.48711657524108887
+LINE 0.34233129024505615 0.48588958382606506
+LINE 0.34233129024505615 0.48343557119369507
+LINE 0.34110429883003235 0.48220857977867126
+LINE 0.34110429883003235 0.47975459694862366
+LINE 0.34110429883003235 0.47852760553359985
+LINE 0.34110429883003235 0.47730061411857605
+LINE 0.34110429883003235 0.47607362270355225
+LINE 0.34110429883003235 0.47484663128852844
+LINE 0.34110429883003235 0.47361963987350464
+LINE 0.33987730741500854 0.47239264845848083
+LINE 0.33987730741500854 0.46993863582611084
+LINE 0.33987730741500854 0.46625766158103943
+LINE 0.33987730741500854 0.4638036787509918
+LINE 0.33987730741500854 0.4613496959209442
+LINE 0.33987730741500854 0.4576687216758728
+LINE 0.33987730741500854 0.453987717628479
+LINE 0.33987730741500854 0.4527607262134552
+LINE 0.34110429883003235 0.4490797519683838
+LINE 0.34110429883003235 0.44785276055336
+LINE 0.34110429883003235 0.4466257691383362
+LINE 0.34233129024505615 0.44294479489326477
+LINE 0.34233129024505615 0.44171780347824097
+LINE 0.34233129024505615 0.44049081206321716
+LINE 0.34233129024505615 0.43680980801582336
+LINE 0.34233129024505615 0.43312883377075195
+LINE 0.34233129024505615 0.43190184235572815
+LINE 0.34233129024505615 0.42822086811065674
+LINE 0.34233129024505615 0.42699387669563293
+LINE 0.34233129024505615 0.42453986406326294
+LINE 0.34355828166007996 0.42208588123321533
+LINE 0.34355828166007996 0.42085888981819153
+LINE 0.34355828166007996 0.4171779155731201
+LINE 0.34355828166007996 0.4159509241580963
+LINE 0.34478527307510376 0.4147239327430725
+LINE 0.34478527307510376 0.4134969413280487
+LINE 0.34601226449012756 0.4122699499130249
+LINE 0.34601226449012756 0.4098159372806549
+LINE 0.34723925590515137 0.4073619544506073
+LINE 0.34723925590515137 0.4061349630355835
+LINE 0.34723925590515137 0.4049079716205597
+LINE 0.34723925590515137 0.4036809802055359
+LINE 0.34723925590515137 0.4024539887905121
+LINE 0.34723925590515137 0.4012269973754883
+LINE 0.34723925590515137 0.4000000059604645
+LINE 0.34846624732017517 0.4000000059604645
+LINE 0.34846624732017517 0.3987730145454407
+LINE 0.34846624732017517 0.39754602313041687
+LINE 0.35092025995254517 0.39754602313041687
+LINE 0.35092025995254517 0.3987730145454407
+LINE 0.35214725136756897 0.3987730145454407
+LINE 0.3533742427825928 0.4000000059604645
+LINE 0.3546012341976166 0.4012269973754883
+LINE 0.3558282256126404 0.4024539887905121
+LINE 0.3558282256126404 0.4036809802055359
+LINE 0.3570552170276642 0.4049079716205597
+LINE 0.3570552170276642 0.4061349630355835
+LINE 0.3595091998577118 0.4098159372806549
+LINE 0.3607361912727356 0.4122699499130249
+LINE 0.3619631826877594 0.4134969413280487
+LINE 0.3619631826877594 0.4159509241580963
+LINE 0.3631901741027832 0.4159509241580963
+LINE 0.3631901741027832 0.4171779155731201
+LINE 0.364417165517807 0.4184049069881439
+LINE 0.364417165517807 0.4196318984031677
+LINE 0.364417165517807 0.42085888981819153
+LINE 0.364417165517807 0.42208588123321533
+LINE 0.3656441569328308 0.42331287264823914
+LINE 0.3656441569328308 0.42576688528060913
+LINE 0.366871178150177 0.42699387669563293
+LINE 0.366871178150177 0.43067485094070435
+LINE 0.366871178150177 0.43190184235572815
+LINE 0.366871178150177 0.43312883377075195
+LINE 0.36783909316294744 0.4350646637962928
+LINE 0.3678390931629469 0.4350646637962928
+LINE 0.4651902914047241 0.44180434942245483
+LINE 0.46582460403442383 0.4453987777233124
+LINE 0.47116565704345703 0.4453987777233124
+LINE 0.4715092182159424 0.4466257691383362
+LINE 0.47484663128852844 0.4466257691383362
+LINE 0.47975459694862366 0.44785276055336
+LINE 0.48343557119369507 0.44785276055336
+LINE 0.48466256260871887 0.4490797519683838
+LINE 0.4895705580711365 0.4490797519683838
+LINE 0.4907975494861603 0.4503067433834076
+LINE 0.4932515323162079 0.4503067433834076
+LINE 0.4932515323162079 0.4527607262134552
+LINE 0.4955270290374756 0.5324037075042725
+LINE 0.5007116794586182 0.5509202480316162
+LINE 0.5225820541381836 0.5509202480316162
+LINE 0.5278711318969727 0.5349137783050537
+LINE 0.5312883257865906 0.4515337347984314
+LINE 0.5386503338813782 0.4515337347984314
+LINE 0.5435582995414734 0.4527607262134552
+LINE 0.5484662652015686 0.453987717628479
+LINE 0.55460125207901 0.453987717628479
+LINE 0.5546108484268188 0.4539909064769745
+LINE 0.5558282136917114 0.4503067433834076
+LINE 0.566871166229248 0.4503067433834076
+LINE 0.5742331147193909 0.4515337347984314
+LINE 0.5769637227058411 0.4520798623561859
+LINE 0.5775687098503113 0.44958439469337463
+LINE 0.7141391634941101 0.45903927087783813
+LINE 0.714399149377822 0.4603392130755704
+LINE 0.714399149377822 0.46033921307557046
+LINE 0.7143991493778221 0.4603392130755704
+LINE 0.716564416885376 0.4588957130908966
+LINE 0.7202454209327698 0.4576687216758728
+LINE 0.7239263653755188 0.456441730260849
+LINE 0.7239263653755188 0.4552147090435028
+LINE 0.7239263653755188 0.4527607262134552
+LINE 0.725153386592865 0.4503067433834076
+LINE 0.725153386592865 0.4490797519683838
+LINE 0.725153386592865 0.44785276055336
+LINE 0.7263803482055664 0.4453987777233124
+LINE 0.7263803482055664 0.44294479489326477
+LINE 0.7263803482055664 0.44171780347824097
+LINE 0.7263803482055664 0.44049081206321716
+LINE 0.7263803482055664 0.43803679943084717
+LINE 0.7263803482055664 0.43680980801582336
+LINE 0.7263803482055664 0.43558281660079956
+LINE 0.7276073694229126 0.43312883377075195
+LINE 0.7276073694229126 0.43190184235572815
+LINE 0.7276073694229126 0.42944785952568054
+LINE 0.728834331035614 0.42822086811065674
+LINE 0.728834331035614 0.42576688528060913
+LINE 0.728834331035614 0.42331287264823914
+LINE 0.728834331035614 0.42208588123321533
+LINE 0.728834331035614 0.4196318984031677
+LINE 0.728834331035614 0.4184049069881439
+LINE 0.728834331035614 0.4171779155731201
+LINE 0.728834331035614 0.4159509241580963
+LINE 0.728834331035614 0.4147239327430725
+LINE 0.728834331035614 0.4122699499130249
+LINE 0.728834331035614 0.4110429584980011
+LINE 0.728834331035614 0.4098159372806549
+LINE 0.728834331035614 0.4061349630355835
+LINE 0.728834331035614 0.4049079716205597
+LINE 0.7300613522529602 0.4012269973754883
+LINE 0.7300613522529602 0.4000000059604645
+LINE 0.7300613522529602 0.3987730145454407
+LINE 0.7300613522529602 0.39631903171539307
+LINE 0.7300613522529602 0.39386501908302307
+LINE 0.7300613522529602 0.39263802766799927
+LINE 0.7300613522529602 0.39141103625297546
+LINE 0.7300613522529602 0.39018404483795166
+LINE 0.7300613522529602 0.38895705342292786
+LINE 0.7300613522529602 0.38650307059288025
+LINE 0.7300613522529602 0.38527607917785645
+LINE 0.7312883138656616 0.38404908776283264
+LINE 0.7312883138656616 0.38282209634780884
+LINE 0.7312883138656616 0.38159510493278503
+LINE 0.7312883138656616 0.38036808371543884
+LINE 0.7312883138656616 0.37914109230041504
+LINE 0.7325153350830078 0.37791410088539124
+LINE 0.7325153350830078 0.37668710947036743
+LINE 0.733742356300354 0.3742331266403198
+LINE 0.733742356300354 0.373006135225296
+LINE 0.733742356300354 0.3717791438102722
+LINE 0.733742356300354 0.3693251609802246
+LINE 0.733742356300354 0.3680981695652008
+LINE 0.733742356300354 0.366871178150177
+LINE 0.733742356300354 0.3656441569328308
+LINE 0.733742356300354 0.3631901741027832
+LINE 0.733742356300354 0.3619631826877594
+LINE 0.733742356300354 0.3607361912727356
+LINE 0.733742356300354 0.3595091998577118
+LINE 0.733742356300354 0.358282208442688
+LINE 0.733742356300354 0.3570552170276642
+LINE 0.733742356300354 0.3558282256126404
+LINE 0.733742356300354 0.3546012341976166
+LINE 0.733742356300354 0.3533742427825928
+LINE 0.733742356300354 0.35214725136756897
+LINE 0.733742356300354 0.34846624732017517
+LINE 0.733742356300354 0.34723925590515137
+LINE 0.733742356300354 0.34601226449012756
+LINE 0.733742356300354 0.34478527307510376
+LINE 0.733742356300354 0.34110429883003235
+LINE 0.733742356300354 0.33865031599998474
+LINE 0.733742356300354 0.33742332458496094
+LINE 0.733742356300354 0.33619633316993713
+LINE 0.733742356300354 0.33496931195259094
+LINE 0.733742356300354 0.33374232053756714
+LINE 0.733742356300354 0.33251532912254333
+LINE 0.733742356300354 0.33128833770751953
+LINE 0.733742356300354 0.3276073634624481
+LINE 0.733742356300354 0.3251533806324005
+LINE 0.733742356300354 0.3190183937549591
+LINE 0.733742356300354 0.3165644109249115
+LINE 0.733742356300354 0.3128834366798401
+LINE 0.733742356300354 0.3092024624347687
+LINE 0.733742356300354 0.3079754710197449
+LINE 0.733742356300354 0.3055214583873749
+LINE 0.733742356300354 0.30306747555732727
+LINE 0.733742356300354 0.30061349272727966
+LINE 0.733742356300354 0.29938650131225586
+LINE 0.733742356300354 0.29815950989723206
+LINE 0.733742356300354 0.29447853565216064
+LINE 0.733742356300354 0.29202455282211304
+LINE 0.733742356300354 0.28834354877471924
+LINE 0.733742356300354 0.28711655735969543
+LINE 0.733742356300354 0.2846625745296478
+LINE 0.733742356300354 0.2822085916996002
+LINE 0.733742356300354 0.2797546088695526
+LINE 0.733742356300354 0.2760736048221588
+LINE 0.733742356300354 0.274846613407135
+LINE 0.733742356300354 0.2711656391620636
+LINE 0.733742356300354 0.2699386477470398
+LINE 0.733742356300354 0.2674846649169922
+LINE 0.733742356300354 0.2662576735019684
+LINE 0.733742356300354 0.2650306820869446
+LINE 0.733742356300354 0.2638036906719208
+LINE 0.733742356300354 0.26134970784187317
+LINE 0.7349693179130554 0.25766870379447937
+LINE 0.7349693179130554 0.25644171237945557
+LINE 0.7361963391304016 0.25398772954940796
+LINE 0.7361963391304016 0.25276073813438416
+LINE 0.737423300743103 0.25153374671936035
+LINE 0.7386503219604492 0.24907974898815155
+LINE 0.7398772835731506 0.24907974898815155
+LINE 0.7398772835731506 0.24785275757312775
+LINE 0.7411043047904968 0.24662576615810394
+LINE 0.7411043047904968 0.24539877474308014
+LINE 0.7411043047904968 0.24417178332805634
+LINE 0.7411043047904968 0.24049079418182373
+LINE 0.7423312664031982 0.23926380276679993
+LINE 0.7423312664031982 0.23680981993675232
+LINE 0.7447852492332458 0.23435582220554352
+LINE 0.746012270450592 0.23312883079051971
+LINE 0.7484662532806396 0.2319018393754959
+LINE 0.7496932744979858 0.2306748479604721
+LINE 0.7521472573280334 0.2306748479604721
+LINE 0.7533742189407349 0.2294478565454483
+LINE 0.800000011920929 0.2294478565454483
+LINE 0.8061349987983704 0.2306748479604721
+LINE 0.8098159432411194 0.2306748479604721
+LINE 0.8147239089012146 0.2319018393754959
+LINE 0.8159509301185608 0.23312883079051971
+LINE 0.8184049129486084 0.23435582220554352
+LINE 0.8196318745613098 0.23435582220554352
+LINE 0.8220859169960022 0.23558282852172852
+LINE 0.8245398998260498 0.23680981993675232
+LINE 0.829447865486145 0.23926380276679993
+LINE 0.8343558311462402 0.24171778559684753
+LINE 0.8355827927589417 0.24171778559684753
+LINE 0.8368098139762878 0.24294479191303253
+LINE 0.8392637968063354 0.24417178332805634
+LINE 0.8417177796363831 0.24662576615810394
+LINE 0.8441717624664307 0.24785275757312775
+LINE 0.8490797281265259 0.25153374671936035
+LINE 0.8503067493438721 0.25398772954940796
+LINE 0.8515337705612183 0.25398772954940796
+LINE 0.8539877533912659 0.25644171237945557
+LINE 0.8552147150039673 0.25766870379447937
+LINE 0.8576686978340149 0.2588956952095032
+LINE 0.8588957190513611 0.260122686624527
+LINE 0.8613497018814087 0.262576699256897
+LINE 0.8625766634941101 0.2638036906719208
+LINE 0.8638036847114563 0.2662576735019684
+LINE 0.8650306463241577 0.268711656332016
+LINE 0.8662576675415039 0.2711656391620636
+LINE 0.8687116503715515 0.2736196219921112
+LINE 0.8699386715888977 0.2760736048221588
+LINE 0.8699386715888977 0.277300626039505
+LINE 0.8723926544189453 0.2797546088695526
+LINE 0.8736196160316467 0.283435583114624
+LINE 0.8760735988616943 0.28588956594467163
+LINE 0.8760735988616943 0.28711655735969543
+LINE 0.8773006200790405 0.28957054018974304
+LINE 0.8785275816917419 0.29325154423713684
+LINE 0.8797546029090881 0.29570552706718445
+LINE 0.8809816241264343 0.29938650131225586
+LINE 0.8822085857391357 0.30061349272727966
+LINE 0.8834356069564819 0.30306747555732727
+LINE 0.8846625685691833 0.3055214583873749
+LINE 0.8858895897865295 0.3079754710197449
+LINE 0.8858895897865295 0.3116564452648163
+LINE 0.8858895897865295 0.3128834366798401
+LINE 0.8883435726165771 0.3153374195098877
+LINE 0.8883435726165771 0.3190183937549591
+LINE 0.8907975554466248 0.3214724063873291
+LINE 0.8907975554466248 0.3226993978023529
+LINE 0.8907975554466248 0.3251533806324005
+LINE 0.8920245170593262 0.3276073634624481
+LINE 0.8920245170593262 0.33128833770751953
+LINE 0.8932515382766724 0.33251532912254333
+LINE 0.8932515382766724 0.33496931195259094
+LINE 0.8932515382766724 0.33742332458496094
+LINE 0.8944784998893738 0.33987730741500854
+LINE 0.8944784998893738 0.34233129024505615
+LINE 0.8944784998893738 0.34478527307510376
+LINE 0.89570552110672 0.34723925590515137
+LINE 0.8969325423240662 0.349693238735199
+LINE 0.8969325423240662 0.35214725136756897
+LINE 0.8981595039367676 0.3558282256126404
+LINE 0.8993865251541138 0.358282208442688
+LINE 0.8993865251541138 0.3607361912727356
+LINE 0.8993865251541138 0.364417165517807
+LINE 0.9006134867668152 0.3705521523952484
+LINE 0.9006134867668152 0.3742331266403198
+LINE 0.9006134867668152 0.37668710947036743
+LINE 0.9018405079841614 0.38036808371543884
+LINE 0.9018405079841614 0.38404908776283264
+LINE 0.9030674695968628 0.38773006200790405
+LINE 0.9030674695968628 0.39018404483795166
+LINE 0.9030674695968628 0.39386501908302307
+LINE 0.904294490814209 0.39754602313041687
+LINE 0.904294490814209 0.3987730145454407
+LINE 0.904294490814209 0.4024539887905121
+LINE 0.904294490814209 0.4036809802055359
+LINE 0.904294490814209 0.4049079716205597
+LINE 0.9055214524269104 0.4085889458656311
+LINE 0.9055214524269104 0.4098159372806549
+LINE 0.9055214524269104 0.4134969413280487
+LINE 0.9055214524269104 0.4147239327430725
+LINE 0.9055214524269104 0.4171779155731201
+LINE 0.9055214524269104 0.4184049069881439
+LINE 0.9055214524269104 0.4196318984031677
+LINE 0.9055214524269104 0.42085888981819153
+LINE 0.9055214524269104 0.42331287264823914
+LINE 0.9055214524269104 0.42576688528060913
+LINE 0.9059304594993591 0.4278118709723155
+LINE 0.9067484736442566 0.42944785952568054
+LINE 0.9067484736442566 0.43067485094070435
+LINE 0.9067484736442566 0.43190184235572815
+LINE 0.907975435256958 0.43435582518577576
+LINE 0.907975435256958 0.43803679943084717
+LINE 0.907975435256958 0.44049081206321716
+LINE 0.9092024564743042 0.4441717863082886
+LINE 0.9104294180870056 0.4490797519683838
+LINE 0.9104294180870056 0.4527607262134552
+LINE 0.9104294180870056 0.456441730260849
+LINE 0.9116564393043518 0.4576687216758728
+LINE 0.9116564393043518 0.4613496959209442
+LINE 0.9116564393043518 0.4650306701660156
+LINE 0.9116564393043518 0.46871164441108704
+LINE 0.9116564393043518 0.47116565704345703
+LINE 0.9116564393043518 0.47239264845848083
+LINE 0.9116564393043518 0.47607362270355225
+LINE 0.9116564393043518 0.47730061411857605
+LINE 0.9116564393043518 0.47975459694862366
+LINE 0.9116564393043518 0.48343557119369507
+LINE 0.9116564393043518 0.48711657524108887
+LINE 0.9104294180870056 0.4895705580711365
+LINE 0.9104294180870056 0.4944785237312317
+LINE 0.9104294180870056 0.4981594979763031
+LINE 0.9104294180870056 0.5018404722213745
+LINE 0.9104294180870056 0.5042944550514221
+LINE 0.9104294180870056 0.5079754590988159
+LINE 0.9104294180870056 0.5104294419288635
+LINE 0.9104294180870056 0.5128834247589111
+LINE 0.9104294180870056 0.5141104459762573
+LINE 0.9104294180870056 0.5165644288063049
+LINE 0.9104294180870056 0.5177913904190063
+LINE 0.9104294180870056 0.5190184116363525
+LINE 0.9104294180870056 0.5214723944664001
+LINE 0.9104294180870056 0.5226994156837463
+LINE 0.9104294180870056 0.5263803601264954
+LINE 0.9104294180870056 0.5276073813438416
+LINE 0.9092024564743042 0.5312883257865906
+LINE 0.9092024564743042 0.5325153470039368
+LINE 0.9092024564743042 0.5349693298339844
+LINE 0.9092024564743042 0.5386503338813782
+LINE 0.9092024564743042 0.5398772954940796
+LINE 0.9092024564743042 0.5435582995414734
+LINE 0.907975435256958 0.5472392439842224
+LINE 0.907975435256958 0.54969322681427
+LINE 0.9067484736442566 0.5509202480316162
+LINE 0.9067484736442566 0.5558282136917114
+LINE 0.9067484736442566 0.5570552349090576
+LINE 0.9067484736442566 0.558282196521759
+LINE 0.9067484736442566 0.5595092177391052
+LINE 0.9067484736442566 0.5607361793518066
+LINE 0.9055214524269104 0.5631901621818542
+LINE 0.9055214524269104 0.5644171833992004
+LINE 0.9067484736442566 0.5717791318893433
+LINE 0.9067484736442566 0.5766870975494385
+LINE 0.907975435256958 0.5852760672569275
+LINE 0.907975435256958 0.5889570713043213
+LINE 0.907975435256958 0.5975460410118103
+LINE 0.907975435256958 0.6036809682846069
+LINE 0.9092024564743042 0.612269937992096
+LINE 0.9104294180870056 0.6171779036521912
+LINE 0.9104294180870056 0.624539852142334
+LINE 0.9104294180870056 0.6306748390197754
+LINE 0.9104294180870056 0.6355828046798706
+LINE 0.9104294180870056 0.6429448127746582
+LINE 0.9116564393043518 0.6478527784347534
+LINE 0.9116564393043518 0.6552147269248962
+LINE 0.9116564393043518 0.6601226925849915
+LINE 0.9116564393043518 0.6638036966323853
+LINE 0.912883460521698 0.6723926663398743
+LINE 0.912883460521698 0.6797546148300171
+LINE 0.912883460521698 0.6846625804901123
+LINE 0.912883460521698 0.6932515501976013
+LINE 0.912883460521698 0.7006134986877441
+LINE 0.912883460521698 0.7067484855651855
+LINE 0.912883460521698 0.7092024683952332
+LINE 0.912883460521698 0.7153373956680298
+LINE 0.912883460521698 0.7177914381027222
+LINE 0.912883460521698 0.7190183997154236
+LINE 0.912883460521698 0.7214723825454712
+LINE 0.912883460521698 0.7226994037628174
+LINE 0.912883460521698 0.7239263653755188
+LINE 0.912883460521698 0.7276073694229126
+LINE 0.9116564393043518 0.7312883138656616
+LINE 0.9116564393043518 0.7361963391304016
+LINE 0.9116564393043518 0.7398772835731506
+LINE 0.9116564393043518 0.746012270450592
+LINE 0.9116564393043518 0.7496932744979858
+LINE 0.9104294180870056 0.7521472573280334
+LINE 0.9141104221343994 0.7521472573280334
+LINE 0.9141104221343994 0.7533742189407349
+LINE 0.9153374433517456 0.7533742189407349
+LINE 0.9153374433517456 0.754601240158081
+LINE 0.916564404964447 0.754601240158081
+LINE 0.9177914261817932 0.7558282017707825
+LINE 0.9202454090118408 0.7570552229881287
+LINE 0.9226993918418884 0.7595092058181763
+LINE 0.925153374671936 0.7607361674308777
+LINE 0.9276073575019836 0.7631902098655701
+LINE 0.9288343787193298 0.7631902098655701
+LINE 0.9300613403320312 0.7644171714782715
+LINE 0.9312883615493774 0.7644171714782715
+LINE 0.933742344379425 0.7656441926956177
+LINE 0.9349693059921265 0.7656441926956177
+LINE 0.9361963272094727 0.7668711543083191
+LINE 0.9386503100395203 0.7668711543083191
+LINE 0.9398772716522217 0.7680981755256653
+LINE 0.9423313140869141 0.7680981755256653
+LINE 0.9447852969169617 0.7693251371383667
+LINE 0.9472392797470093 0.7705521583557129
+LINE 0.9496932625770569 0.7717791199684143
+LINE 0.9533742070198059 0.7730061411857605
+LINE 0.9570552110671997 0.7742331027984619
+LINE 0.9607362151145935 0.7754601240158081
+LINE 0.9644171595573425 0.7754601240158081
+LINE 0.9680981636047363 0.7766871452331543
+LINE 0.9717791676521301 0.7766871452331543
+LINE 0.9754601120948792 0.7779141068458557
+LINE 0.9852761030197144 0.7779141068458557
+LINE 0.9889570474624634 0.7791411280632019
+LINE 1.0012270212173462 0.7791411280632019
+LINE 1.0012270212173462 0.7779141068458557
+LINE 1.0012270212173462 0.7766871452331543
+LINE 1.0012270212173462 0.7754601240158081
+LINE 1.0012270212173462 0.7730061411857605
+LINE 1.0012270212173462 0.7717791199684143
+LINE 1.0012270212173462 0.7693251371383667
+LINE 1.0012270212173462 0.7668711543083191
+LINE 1.0012270212173462 0.7631902098655701
+LINE 1.0012270212173462 0.7558282017707825
+LINE 1.0012270212173462 0.754601240158081
+LINE 1.0012270212173462 0.7521472573280334
+LINE 1.0012270212173462 0.7509202361106873
+LINE 1.0012270212173462 0.7484662532806396
+LINE 1.0012270212173462 0.7472392916679382
+LINE 1.0012270212173462 0.7423312664031982
+LINE 1.0012270212173462 0.7386503219604492
+LINE 1.0012270212173462 0.7361963391304016
+LINE 1.0012270212173462 0.7325153350830078
+LINE 1.0012270212173462 0.728834331035614
+LINE 1.0012270212173462 0.725153386592865
+LINE 1.0012270212173462 0.7226994037628174
+LINE 1.0012270212173462 0.7177914381027222
+LINE 1.0012270212173462 0.7104294300079346
+LINE 1.0012270212173462 0.7055214643478394
+LINE 1.0012270212173462 0.7006134986877441
+LINE 1.0012270212173462 0.6932515501976013
+LINE 1.0012270212173462 0.6883435845375061
+LINE 1.0012270212173462 0.6834355592727661
+LINE 1.0012270212173462 0.6785275936126709
+LINE 1.0012270212173462 0.6736196279525757
+LINE 1.0012270212173462 0.6699386239051819
+LINE 1.0012270212173462 0.6638036966323853
+LINE 1.0012270212173462 0.6576687097549438
+LINE 1.0012270212173462 0.6515337228775024
+LINE 1.0012270212173462 0.641717791557312
+LINE 1.0012270212173462 0.6368098258972168
+LINE 1.0012270212173462 0.6319018602371216
+LINE 1.0012270212173462 0.629447877407074
+LINE 1.0012270212173462 0.6233128905296326
+LINE 1.0012270212173462 0.6196318864822388
+LINE 1.0012270212173462 0.6159509420394897
+LINE 1.0012270212173462 0.612269937992096
+LINE 1.0012270212173462 0.6000000238418579
+LINE 1.0012270212173462 0.5987730026245117
+LINE 1.0012270212173462 0.48834356665611267
+LINE 1.0012270212173462 0.44294479489326477
+LINE 1.0012270212173462 0.39386501908302307
+LINE 1.0012270212173462 0.34355828166007996
+LINE 1.0012270212173462 0.29570552706718445
+LINE 1.0012270212173462 0.25644171237945557
+LINE 1.0012270212173462 0.21717791259288788
+LINE 1.0012270212173462 0.19141104817390442
+LINE 1.0012270212173462 0.18664686381816864
+LINE 1.001517415046692 0.18664643168449402
+LINE 1.001517415046692 0.18512898683547974
+LINE 1.001517415046692 0.18209408223628998
+LINE 1.001517415046692 0.1805766373872757
+LINE 1.001517415046692 0.17602427303791046
+LINE 1.001517415046692 0.16995447874069214
+LINE 1.001517415046692 0.15933232009410858
+LINE 1.001517415046692 0.1502276211977005
+LINE 1.001517415046692 0.14112290740013123
+LINE 1.001517415046692 0.13201820850372314
+LINE 1.001517415046692 0.12443095445632935
+LINE 1.001517415046692 0.11532625555992126
+LINE 1.001517415046692 0.10773900151252747
+LINE 1.001517415046692 0.09711684286594391
+LINE 1.001517415046692 0.08952958881855011
+LINE 1.001517415046692 0.08345978707075119
+LINE 1.001517415046692 0.07587253302335739
+LINE 1.001517415046692 0.07283763587474823
+LINE 1.001517415046692 0.07132018357515335
+LINE 1.001517415046692 0.06828527897596359
+LINE 1.001517415046692 0.06676782667636871
+LINE 1.001517415046692 0.06373292952775955
+LINE 1.001517415046692 0.06069802865386009
+LINE 1.001517415046692 0.05766312777996063
+LINE 1.001517415046692 0.054628223180770874
+LINE 1.001517415046692 0.051593322306871414
+LINE 1.001517415046692 0.048558421432971954
+LINE 1.001517415046692 0.044006068259477615
+LINE 1.001517415046692 0.037936266511678696
+LINE 1.001517415046692 0.031866464763879776
+LINE 1.001517415046692 0.025796661153435707
+LINE 1.001517415046692 0.01669195666909218
+LINE 1.001517415046692 0.009104704484343529
+LINE 1.001517415046692 0.003034901339560747
+LINE 1.001517415046692 -0.0015174506697803736
+CLOSE
+</AREA>
+green
+<AREA>
+START 0.7216400639235591 0.15214723348617554
+LINE 0.7276073694229126 0.17307424782141448
+LINE 0.7276073694229126 0.17055214941501617
+LINE 0.7276073694229126 0.16809816658496857
+LINE 0.7276073694229126 0.16687116026878357
+LINE 0.7276073694229126 0.16564416885375977
+LINE 0.7263803482055664 0.16441717743873596
+LINE 0.7263803482055664 0.16196319460868835
+LINE 0.7263803482055664 0.16073620319366455
+LINE 0.7263803482055664 0.15950919687747955
+LINE 0.725153386592865 0.15828220546245575
+LINE 0.725153386592865 0.15705521404743195
+LINE 0.725153386592865 0.15582822263240814
+LINE 0.7239263653755188 0.15460123121738434
+LINE 0.7226994037628174 0.15337423980236053
+LINE 0.7226994037628174 0.15214723348617554
+CLOSE
+START 0.7283763956522704 0.17577118078851145
+LINE 0.7312883138656616 0.18598311885692148
+LINE 0.7312883138656616 0.1840490847826004
+LINE 0.7300613522529602 0.1815950870513916
+LINE 0.7300613522529602 0.179141104221344
+LINE 0.7283763956522704 0.17577118078851145
+CLOSE
+START 0.5006135106086731 0.11901840567588806
+LINE 0.4944785237312317 0.12024539709091187
+LINE 0.48711657524108887 0.12269938737154007
+LINE 0.47484663128852844 0.12760736048221588
+LINE 0.4650306701660156 0.1325153410434723
+LINE 0.4576687216758728 0.1374233067035675
+LINE 0.4503067433834076 0.14355827867984772
+LINE 0.44294479489326477 0.14969325065612793
+LINE 0.43680980801582336 0.15460123121738434
+LINE 0.43190184235572815 0.15950919687747955
+LINE 0.42699387669563293 0.16441717743873596
+LINE 0.42085888981819153 0.17300613224506378
+LINE 0.4159509241580963 0.179141104221344
+LINE 0.4134969413280487 0.1852760761976242
+LINE 0.4110429584980011 0.19018404185771942
+LINE 0.4085889458656311 0.19631901383399963
+LINE 0.4073619544506073 0.20122699439525604
+LINE 0.4049079716205597 0.20736196637153625
+LINE 0.4024539887905121 0.21472392976284027
+LINE 0.4000000059604645 0.22085890173912048
+LINE 0.3987730145454407 0.2282208651304245
+LINE 0.39631903171539307 0.23558282852172852
+LINE 0.39386501908302307 0.24049079418182373
+LINE 0.39263802766799927 0.24907974898815155
+LINE 0.39018404483795166 0.25521472096443176
+LINE 0.39018404483795166 0.2638036906719208
+LINE 0.38773006200790405 0.2736196219921112
+LINE 0.38650307059288025 0.2822085916996002
+LINE 0.38527607917785645 0.29202455282211304
+LINE 0.38404908776283264 0.30184048414230347
+LINE 0.38159510493278503 0.3104294538497925
+LINE 0.38036808371543884 0.3190183937549591
+LINE 0.38036808371543884 0.3263803720474243
+LINE 0.37914109230041504 0.33251532912254333
+LINE 0.37914109230041504 0.33865031599998474
+LINE 0.37914109230041504 0.34233129024505615
+LINE 0.37914109230041504 0.34478527307510376
+LINE 0.37914109230041504 0.34601226449012756
+LINE 0.37914109230041504 0.34723925590515137
+LINE 0.37914109230041504 0.34846624732017517
+LINE 0.37914109230041504 0.349693238735199
+LINE 0.37914109230041504 0.35092025995254517
+LINE 0.37914109230041504 0.3533742427825928
+LINE 0.37914109230041504 0.3558282256126404
+LINE 0.37914109230041504 0.3619631826877594
+LINE 0.37914109230041504 0.3680981695652008
+LINE 0.37914109230041504 0.37546011805534363
+LINE 0.37914109230041504 0.38527607917785645
+LINE 0.37914109230041504 0.39141103625297546
+LINE 0.37914109230041504 0.39754602313041687
+LINE 0.37914109230041504 0.4036809802055359
+LINE 0.37914109230041504 0.4085889458656311
+LINE 0.37914109230041504 0.4122699499130249
+LINE 0.37914109230041504 0.4171779155731201
+LINE 0.37914109230041504 0.42085888981819153
+LINE 0.37914109230041504 0.42453986406326294
+LINE 0.37914109230041504 0.42699387669563293
+LINE 0.37914109230041504 0.42944785952568054
+LINE 0.37914109230041504 0.43067485094070435
+LINE 0.37914109230041504 0.43312883377075195
+LINE 0.37914109230041504 0.43558281660079956
+LINE 0.37914109230041504 0.43803679943084717
+LINE 0.37914109230041504 0.44049081206321716
+LINE 0.37914109230041504 0.44294479489326477
+LINE 0.37914109230041504 0.4453987777233124
+LINE 0.37914109230041504 0.44785276055336
+LINE 0.37914109230041504 0.4503067433834076
+LINE 0.37914109230041504 0.4527607262134552
+LINE 0.37914109230041504 0.4552147090435028
+LINE 0.37914109230041504 0.456441730260849
+LINE 0.37914109230041504 0.4601227045059204
+LINE 0.37914109230041504 0.462576687335968
+LINE 0.37914109230041504 0.4650306701660156
+LINE 0.37914109230041504 0.46748465299606323
+LINE 0.37914109230041504 0.46871164441108704
+LINE 0.37914109230041504 0.47116565704345703
+LINE 0.37914109230041504 0.47239264845848083
+LINE 0.37914109230041504 0.47484663128852844
+LINE 0.37914109230041504 0.47730061411857605
+LINE 0.37914109230041504 0.47852760553359985
+LINE 0.37914109230041504 0.48098158836364746
+LINE 0.37914109230041504 0.48220857977867126
+LINE 0.37914109230041504 0.48343557119369507
+LINE 0.37914109230041504 0.48466256260871887
+LINE 0.37914109230041504 0.48588958382606506
+LINE 0.37914109230041504 0.48834356665611267
+LINE 0.37914109230041504 0.4895705580711365
+LINE 0.37914109230041504 0.4920245409011841
+LINE 0.37914109230041504 0.4944785237312317
+LINE 0.37914109230041504 0.4957055151462555
+LINE 0.37914109230041504 0.4969325065612793
+LINE 0.37914109230041504 0.4981594979763031
+LINE 0.37914109230041504 0.4993864893913269
+LINE 0.37914109230041504 0.5006135106086731
+LINE 0.37914109230041504 0.5018404722213745
+LINE 0.37914109230041504 0.5030674934387207
+LINE 0.37914109230041504 0.5055214762687683
+LINE 0.37914109230041504 0.5079754590988159
+LINE 0.37914109230041504 0.5092024803161621
+LINE 0.37914109230041504 0.5116564631462097
+LINE 0.38036808371543884 0.5141104459762573
+LINE 0.38036808371543884 0.5165644288063049
+LINE 0.38159510493278503 0.520245373249054
+LINE 0.38159510493278503 0.5239263772964478
+LINE 0.38159510493278503 0.5276073813438416
+LINE 0.38159510493278503 0.5312883257865906
+LINE 0.38159510493278503 0.5337423086166382
+LINE 0.38159510493278503 0.5361962914466858
+LINE 0.38159510493278503 0.5398772954940796
+LINE 0.38282209634780884 0.5435582995414734
+LINE 0.38282209634780884 0.546012282371521
+LINE 0.38282209634780884 0.5484662652015686
+LINE 0.38282209634780884 0.5509202480316162
+LINE 0.38282209634780884 0.5533742308616638
+LINE 0.38282209634780884 0.55460125207901
+LINE 0.38404908776283264 0.558282196521759
+LINE 0.38404908776283264 0.5619632005691528
+LINE 0.38404908776283264 0.5644171833992004
+LINE 0.38404908776283264 0.566871166229248
+LINE 0.38404908776283264 0.5693251490592957
+LINE 0.38404908776283264 0.5717791318893433
+LINE 0.38404908776283264 0.5742331147193909
+LINE 0.38404908776283264 0.5791410803794861
+LINE 0.38404908776283264 0.5815950632095337
+LINE 0.38527607917785645 0.5852760672569275
+LINE 0.38527607917785645 0.5889570713043213
+LINE 0.38650307059288025 0.5938650369644165
+LINE 0.38650307059288025 0.5963190197944641
+LINE 0.38773006200790405 0.6000000238418579
+LINE 0.38895705342292786 0.6036809682846069
+LINE 0.38895705342292786 0.6049079895019531
+LINE 0.38895705342292786 0.6073619723320007
+LINE 0.38895705342292786 0.6098159551620483
+LINE 0.38895705342292786 0.6110429167747498
+LINE 0.38895705342292786 0.6134969592094421
+LINE 0.39141103625297546 0.6147239208221436
+LINE 0.39141103625297546 0.6171779036521912
+LINE 0.39141103625297546 0.6184049248695374
+LINE 0.39141103625297546 0.6196318864822388
+LINE 0.39200687408447266 0.6196318864822388
+LINE 0.3915022909641266 0.6221547722816467
+LINE 0.3915022909641266 0.6297420263290405
+LINE 0.3915022909641266 0.6358118653297424
+LINE 0.3899848163127899 0.6418816447257996
+LINE 0.3899848163127899 0.6479514241218567
+LINE 0.3899848163127899 0.6540212631225586
+LINE 0.3899848163127899 0.6600910425186157
+LINE 0.38846737146377563 0.6661608219146729
+LINE 0.38846737146377563 0.6707131862640381
+LINE 0.38846737146377563 0.6737480759620667
+LINE 0.38846737146377563 0.6813353300094604
+LINE 0.38846737146377563 0.6843702793121338
+LINE 0.38846737146377563 0.6904400587081909
+LINE 0.38846737146377563 0.696509838104248
+LINE 0.38694992661476135 0.7010622024536133
+LINE 0.38694992661476135 0.7071320414543152
+LINE 0.38694992661476135 0.714719295501709
+LINE 0.38694992661476135 0.7177541851997375
+LINE 0.38543248176574707 0.7253414392471313
+LINE 0.38543248176574707 0.7314112186431885
+LINE 0.38543248176574707 0.7389984726905823
+LINE 0.38543248176574707 0.7465857267379761
+LINE 0.3839150369167328 0.752655565738678
+LINE 0.3839150369167328 0.7587253451347351
+LINE 0.3839150369167328 0.7647951245307922
+LINE 0.3839150369167328 0.7678300738334656
+LINE 0.3839150369167328 0.772382378578186
+LINE 0.3839150369167328 0.7769347429275513
+LINE 0.3839150369167328 0.7799696326255798
+LINE 0.3839150369167328 0.7830045819282532
+LINE 0.3839150369167328 0.7890743613243103
+LINE 0.3839150369167328 0.7905917763710022
+LINE 0.3839150369167328 0.7936267256736755
+LINE 0.3839150369167328 0.7966616153717041
+LINE 0.3839150369167328 0.7996965050697327
+LINE 0.3839150369167328 0.8027313947677612
+LINE 0.3839150369167328 0.8057662844657898
+LINE 0.3839150369167328 0.8088012337684631
+LINE 0.3839150369167328 0.810318648815155
+LINE 0.3839150369167328 0.8133535385131836
+LINE 0.3839150369167328 0.8179059028625488
+LINE 0.3839150369167328 0.8209407925605774
+LINE 0.3839150369167328 0.8254931569099426
+LINE 0.3839150369167328 0.8285280466079712
+LINE 0.3839150369167328 0.8315629959106445
+LINE 0.3839150369167328 0.8345978856086731
+LINE 0.3839150369167328 0.836115300655365
+LINE 0.3839150369167328 0.8391502499580383
+LINE 0.3839150369167328 0.8421851396560669
+LINE 0.3839150369167328 0.8452200293540955
+LINE 0.3839150369167328 0.8512898087501526
+LINE 0.3839150369167328 0.8588770627975464
+LINE 0.3839150369167328 0.8619120121002197
+LINE 0.3839150369167328 0.8649469017982483
+LINE 0.3839150369167328 0.8679817914962769
+LINE 0.3839150369167328 0.8710166811943054
+LINE 0.3839150369167328 0.8725341558456421
+LINE 0.3839150369167328 0.8770865201950073
+LINE 0.3839150369167328 0.8816388249397278
+LINE 0.3839150369167328 0.8877086639404297
+LINE 0.3839150369167328 0.8907435536384583
+LINE 0.3839150369167328 0.8952959179878235
+LINE 0.3839150369167328 0.898330807685852
+LINE 0.3839150369167328 0.9013656973838806
+LINE 0.3839150369167328 0.9044005870819092
+LINE 0.3839150369167328 0.9059180617332458
+LINE 0.3839150369167328 0.9089529514312744
+LINE 0.3839150369167328 0.9104704260826111
+LINE 0.3839150369167328 0.9150227904319763
+LINE 0.3839150369167328 0.9180576801300049
+LINE 0.3839150369167328 0.9210925698280334
+LINE 0.3839150369167328 0.924127459526062
+LINE 0.3839150369167328 0.9271623492240906
+LINE 0.3839150369167328 0.9301972389221191
+LINE 0.3839150369167328 0.9332321882247925
+LINE 0.3839150369167328 0.9347496032714844
+LINE 0.3839150369167328 0.9393019676208496
+LINE 0.3839150369167328 0.9438543319702148
+LINE 0.3839150369167328 0.9484066963195801
+LINE 0.3839150369167328 0.949924111366272
+LINE 0.3839150369167328 0.9514415860176086
+LINE 0.3839150369167328 0.9544764757156372
+LINE 0.3839150369167328 0.9559939503669739
+LINE 0.3839150369167328 0.9590288400650024
+LINE 0.3839150369167328 0.9605462551116943
+LINE 0.3839150369167328 0.9635812044143677
+LINE 0.3839150369167328 0.9650986194610596
+LINE 0.3839150369167328 0.9666160941123962
+LINE 0.3839150369167328 0.9681335091590881
+LINE 0.3839150369167328 0.9711684584617615
+LINE 0.3839150369167328 0.9726858735084534
+LINE 0.3839150369167328 0.97420334815979
+LINE 0.3839150369167328 0.9772382378578186
+LINE 0.3839150369167328 0.9787557125091553
+LINE 0.3839150369167328 0.9802731275558472
+LINE 0.3839150369167328 0.9833080172538757
+LINE 0.3839150369167328 0.9863429665565491
+LINE 0.3839150369167328 0.987860381603241
+LINE 0.38543248176574707 0.9908952713012695
+LINE 0.38543248176574707 0.9939302206039429
+LINE 0.38543248176574707 0.9969651103019714
+LINE 0.38543248176574707 0.9984825253486633
+LINE 0.38543248176574707 1.0
+LINE 0.38543248176574707 1.001517415046692
+LINE 0.638846755027771 1.001517415046692
+LINE 0.638846755027771 1.0012270212173462
+LINE 0.6858895421028137 1.0012270212173462
+LINE 0.6858895421028137 1.0
+LINE 0.6858895421028137 0.9987729787826538
+LINE 0.6858895421028137 0.9975460171699524
+LINE 0.6858895421028137 0.9950920343399048
+LINE 0.6858895421028137 0.9926380515098572
+LINE 0.6858895421028137 0.9901840686798096
+LINE 0.6858895421028137 0.9865030646324158
+LINE 0.6858895421028137 0.9840490818023682
+LINE 0.6858895421028137 0.9815950989723206
+LINE 0.6858895421028137 0.9779140949249268
+LINE 0.6858895421028137 0.9754601120948792
+LINE 0.6858895421028137 0.9730061292648315
+LINE 0.6858895421028137 0.9705521464347839
+LINE 0.6858895421028137 0.9680981636047363
+LINE 0.6858895421028137 0.9656441807746887
+LINE 0.6858895421028137 0.9631901979446411
+LINE 0.6871165633201599 0.9595091938972473
+LINE 0.6871165633201599 0.9570552110671997
+LINE 0.6883435845375061 0.9509202241897583
+LINE 0.6883435845375061 0.9472392797470093
+LINE 0.6895705461502075 0.9423313140869141
+LINE 0.6895705461502075 0.9386503100395203
+LINE 0.6895705461502075 0.9361963272094727
+LINE 0.6895705461502075 0.9312883615493774
+LINE 0.6895705461502075 0.9276073575019836
+LINE 0.6895705461502075 0.9239263534545898
+LINE 0.6895705461502075 0.9214723706245422
+LINE 0.6895705461502075 0.9177914261817932
+LINE 0.6895705461502075 0.916564404964447
+LINE 0.6895705461502075 0.9141104221343994
+LINE 0.6895705461502075 0.912883460521698
+LINE 0.6895705461502075 0.9116564393043518
+LINE 0.6895705461502075 0.9104294180870056
+LINE 0.6895705461502075 0.9092024564743042
+LINE 0.6895705461502075 0.907975435256958
+LINE 0.6895705461502075 0.9055214524269104
+LINE 0.6889837490419334 0.9049346553186363
+LINE 0.6889837490419333 0.9049346553186363
+LINE 0.6884676621517333 0.8885917338726056
+LINE 0.6883435845375061 0.8883435726165771
+LINE 0.6871165633201599 0.8858895897865295
+LINE 0.6871165633201599 0.8846625685691833
+LINE 0.6871165633201599 0.8834356069564819
+LINE 0.6858895421028137 0.8809816241264343
+LINE 0.6858895421028137 0.8797546029090881
+LINE 0.6858895421028137 0.8785275816917419
+LINE 0.6846625804901123 0.8736196160316467
+LINE 0.6846625804901123 0.8723926544189453
+LINE 0.6846625804901123 0.8711656332015991
+LINE 0.6846625804901123 0.8674846887588501
+LINE 0.6846625804901123 0.8662576675415039
+LINE 0.6846625804901123 0.8638036847114563
+LINE 0.6822085976600647 0.8564417362213135
+LINE 0.6822085976600647 0.8503067493438721
+LINE 0.6822085976600647 0.8453987836837769
+LINE 0.6822085976600647 0.8392637968063354
+LINE 0.6822085976600647 0.8355827927589417
+LINE 0.6822085976600647 0.8319018483161926
+LINE 0.6822085976600647 0.8233128786087036
+LINE 0.6822085976600647 0.8171778917312622
+LINE 0.6822085976600647 0.8110429644584656
+LINE 0.6822085976600647 0.8061349987983704
+LINE 0.6822085976600647 0.800000011920929
+LINE 0.6822085976600647 0.7963190078735352
+LINE 0.6822085976600647 0.7840490937232971
+LINE 0.6809815764427185 0.7779141068458557
+LINE 0.6797546148300171 0.7730061411857605
+LINE 0.6797546148300171 0.7680981755256653
+LINE 0.6797546148300171 0.7631902098655701
+LINE 0.6797546148300171 0.7607361674308777
+LINE 0.6785275936126709 0.7533742189407349
+LINE 0.6785275936126709 0.7509202361106873
+LINE 0.6785275936126709 0.7472392916679382
+LINE 0.6785275936126709 0.746012270450592
+LINE 0.6785275936126709 0.7411043047904968
+LINE 0.6785275936126709 0.737423300743103
+LINE 0.6785275936126709 0.7349693179130554
+LINE 0.6785275936126709 0.733742356300354
+LINE 0.6785275936126709 0.7312883138656616
+LINE 0.6785275936126709 0.7300613522529602
+LINE 0.6785275936126709 0.7276073694229126
+LINE 0.6785275936126709 0.7263803482055664
+LINE 0.6785275936126709 0.7226994037628174
+LINE 0.6785275936126709 0.7214723825454712
+LINE 0.6785275936126709 0.7177914381027222
+LINE 0.6785275936126709 0.7141104340553284
+LINE 0.6785275936126709 0.7104294300079346
+LINE 0.6785275936126709 0.7055214643478394
+LINE 0.6785275936126709 0.7030674815177917
+LINE 0.6785275936126709 0.699386477470398
+LINE 0.6785275936126709 0.6957055330276489
+LINE 0.6785275936126709 0.6920245289802551
+LINE 0.6785275936126709 0.6895705461502075
+LINE 0.6785275936126709 0.6871165633201599
+LINE 0.6785275936126709 0.6846625804901123
+LINE 0.6785275936126709 0.6822085976600647
+LINE 0.6785275936126709 0.6785275936126709
+LINE 0.6785275936126709 0.6748466491699219
+LINE 0.6785275936126709 0.6711656451225281
+LINE 0.6773006319999695 0.6674846410751343
+LINE 0.6773006319999695 0.6638036966323853
+LINE 0.6760736107826233 0.6601226925849915
+LINE 0.6760736107826233 0.6564416885375977
+LINE 0.6760736107826233 0.6527607440948486
+LINE 0.6748466491699219 0.6515337228775024
+LINE 0.6748466491699219 0.6478527784347534
+LINE 0.6748466491699219 0.6453987956047058
+LINE 0.6748466491699219 0.6429448127746582
+LINE 0.6736196279525757 0.6404907703399658
+LINE 0.6736196279525757 0.6392638087272644
+LINE 0.6736196279525757 0.6380367875099182
+LINE 0.6736196279525757 0.6343558430671692
+LINE 0.6736196279525757 0.6319018602371216
+LINE 0.6736196279525757 0.6257668733596802
+LINE 0.6736196279525757 0.6220858693122864
+LINE 0.6736196279525757 0.6171779036521912
+LINE 0.6736196279525757 0.6147239208221436
+LINE 0.6748466491699219 0.6110429167747498
+LINE 0.6748466491699219 0.6085889339447021
+LINE 0.6748466491699219 0.6073619723320007
+LINE 0.6748466491699219 0.6061349511146545
+LINE 0.6748466491699219 0.6049079895019531
+LINE 0.6748466491699219 0.6024540066719055
+LINE 0.6748466491699219 0.6000000238418579
+LINE 0.6748466491699219 0.5963190197944641
+LINE 0.6760736107826233 0.5926380157470703
+LINE 0.6760736107826233 0.5889570713043213
+LINE 0.6760736107826233 0.5865030884742737
+LINE 0.6773006319999695 0.5828220844268799
+LINE 0.6773006319999695 0.5803681015968323
+LINE 0.6773006319999695 0.5766870975494385
+LINE 0.6785275936126709 0.5730061531066895
+LINE 0.6785275936126709 0.5693251490592957
+LINE 0.6797546148300171 0.566871166229248
+LINE 0.6797546148300171 0.5631901621818542
+LINE 0.6809815764427185 0.5595092177391052
+LINE 0.6809815764427185 0.5570552349090576
+LINE 0.6822085976600647 0.5533742308616638
+LINE 0.6822085976600647 0.54969322681427
+LINE 0.6834355592727661 0.5447852611541748
+LINE 0.6834355592727661 0.5411043167114258
+LINE 0.6834355592727661 0.5386503338813782
+LINE 0.6834355592727661 0.5325153470039368
+LINE 0.6834355592727661 0.528834342956543
+LINE 0.6834355592727661 0.5226994156837463
+LINE 0.6834355592727661 0.5190184116363525
+LINE 0.6834355592727661 0.5153374075889587
+LINE 0.6834355592727661 0.5116564631462097
+LINE 0.6834355592727661 0.5092024803161621
+LINE 0.6834355592727661 0.5055214762687683
+LINE 0.6834355592727661 0.5030674934387207
+LINE 0.6834355592727661 0.4993864893913269
+LINE 0.6834355592727661 0.4957055151462555
+LINE 0.6846625804901123 0.4920245409011841
+LINE 0.6846625804901123 0.4895705580711365
+LINE 0.6846625804901123 0.48834356665611267
+LINE 0.6846625804901123 0.48711657524108887
+LINE 0.6846625804901123 0.48343557119369507
+LINE 0.6846625804901123 0.48220857977867126
+LINE 0.6846625804901123 0.47975459694862366
+LINE 0.6846625804901123 0.47730061411857605
+LINE 0.6846625804901123 0.47607362270355225
+LINE 0.6846625804901123 0.47239264845848083
+LINE 0.6846625804901123 0.47116565704345703
+LINE 0.6846625804901123 0.46993863582611084
+LINE 0.6846625804901123 0.46625766158103943
+LINE 0.6846625804901123 0.4650306701660156
+LINE 0.6846625804901123 0.4638036787509918
+LINE 0.6846625804901123 0.462576687335968
+LINE 0.6846625804901123 0.4613496959209442
+LINE 0.6846625804901123 0.4588957130908966
+LINE 0.6846625804901123 0.4576687216758728
+LINE 0.6846625804901123 0.456441730260849
+LINE 0.6846625804901123 0.453987717628479
+LINE 0.6846625804901123 0.4503067433834076
+LINE 0.6846625804901123 0.4466257691383362
+LINE 0.6846625804901123 0.4441717863082886
+LINE 0.6846625804901123 0.44049081206321716
+LINE 0.6846625804901123 0.43680980801582336
+LINE 0.6846625804901123 0.43190184235572815
+LINE 0.6846625804901123 0.42944785952568054
+LINE 0.6846625804901123 0.42576688528060913
+LINE 0.6846625804901123 0.42331287264823914
+LINE 0.6846625804901123 0.42085888981819153
+LINE 0.6846625804901123 0.4196318984031677
+LINE 0.6846625804901123 0.4159509241580963
+LINE 0.6846625804901123 0.4147239327430725
+LINE 0.6846625804901123 0.4110429584980011
+LINE 0.6846625804901123 0.4061349630355835
+LINE 0.6858895421028137 0.4024539887905121
+LINE 0.6858895421028137 0.4000000059604645
+LINE 0.6858895421028137 0.39631903171539307
+LINE 0.6871165633201599 0.39018404483795166
+LINE 0.6871165633201599 0.38650307059288025
+LINE 0.6871165633201599 0.38404908776283264
+LINE 0.6871165633201599 0.38159510493278503
+LINE 0.6883435845375061 0.37791410088539124
+LINE 0.6883435845375061 0.37668710947036743
+LINE 0.6883435845375061 0.37546011805534363
+LINE 0.6883435845375061 0.3742331266403198
+LINE 0.6883435845375061 0.373006135225296
+LINE 0.6895705461502075 0.3717791438102722
+LINE 0.6895705461502075 0.3680981695652008
+LINE 0.6895705461502075 0.366871178150177
+LINE 0.6895705461502075 0.364417165517807
+LINE 0.6895705461502075 0.3619631826877594
+LINE 0.6907975673675537 0.3607361912727356
+LINE 0.6907975673675537 0.358282208442688
+LINE 0.6920245289802551 0.3546012341976166
+LINE 0.6932515501976013 0.35214725136756897
+LINE 0.6932515501976013 0.35092025995254517
+LINE 0.6944785118103027 0.34723925590515137
+LINE 0.6944785118103027 0.34601226449012756
+LINE 0.6944785118103027 0.34478527307510376
+LINE 0.6944785118103027 0.34110429883003235
+LINE 0.6944785118103027 0.33987730741500854
+LINE 0.6944785118103027 0.33619633316993713
+LINE 0.6944785118103027 0.33251532912254333
+LINE 0.6944785118103027 0.3300613462924957
+LINE 0.6944785118103027 0.3276073634624481
+LINE 0.6957055330276489 0.3239263892173767
+LINE 0.6969324946403503 0.3177914023399353
+LINE 0.6969324946403503 0.3153374195098877
+LINE 0.6981595158576965 0.3104294538497925
+LINE 0.699386477470398 0.30674847960472107
+LINE 0.699386477470398 0.30306747555732727
+LINE 0.7018405199050903 0.29938650131225586
+LINE 0.7018405199050903 0.29815950989723206
+LINE 0.7030674815177917 0.29693251848220825
+LINE 0.7030674815177917 0.29570552706718445
+LINE 0.7030674815177917 0.29447853565216064
+LINE 0.7030674815177917 0.29202455282211304
+LINE 0.7030674815177917 0.28957054018974304
+LINE 0.7030674815177917 0.28834354877471924
+LINE 0.7030674815177917 0.28588956594467163
+LINE 0.7030674815177917 0.2822085916996002
+LINE 0.7042945027351379 0.2797546088695526
+LINE 0.7042945027351379 0.2760736048221588
+LINE 0.7055214643478394 0.2723926305770874
+LINE 0.7055214643478394 0.2699386477470398
+LINE 0.7067484855651855 0.2674846649169922
+LINE 0.7067484855651855 0.2638036906719208
+LINE 0.707975447177887 0.260122686624527
+LINE 0.707975447177887 0.2588956952095032
+LINE 0.707975447177887 0.25521472096443176
+LINE 0.707975447177887 0.25276073813438416
+LINE 0.7092024683952332 0.24785275757312775
+LINE 0.7092024683952332 0.24294479191303253
+LINE 0.7092024683952332 0.23803681135177612
+LINE 0.7104294300079346 0.23435582220554352
+LINE 0.7104294300079346 0.2306748479604721
+LINE 0.7104294300079346 0.2245398759841919
+LINE 0.7116564512252808 0.21963189542293549
+LINE 0.7128834128379822 0.21349693834781647
+LINE 0.7128834128379822 0.21104294061660767
+LINE 0.7128834128379822 0.20736196637153625
+LINE 0.7141104340553284 0.20245398581027985
+LINE 0.7141104340553284 0.20000000298023224
+LINE 0.7141104340553284 0.19877301156520844
+LINE 0.7141104340553284 0.19509202241897583
+LINE 0.7141104340553284 0.19141104817390442
+LINE 0.7141104340553284 0.19018404185771942
+LINE 0.7141104340553284 0.18773005902767181
+LINE 0.7141104340553284 0.1840490847826004
+LINE 0.7141104340553284 0.1815950870513916
+LINE 0.7141104340553284 0.179141104221344
+LINE 0.7141104340553284 0.17546012997627258
+LINE 0.7141104340553284 0.17177914083003998
+LINE 0.7141104340553284 0.16809816658496857
+LINE 0.7141104340553284 0.16564416885375977
+LINE 0.7153373956680298 0.16196319460868835
+LINE 0.7153373956680298 0.16073620319366455
+LINE 0.7153373956680298 0.15828220546245575
+LINE 0.7153373956680298 0.15705521404743195
+LINE 0.7153373956680298 0.15460123121738434
+LINE 0.7153373956680298 0.15337423980236053
+LINE 0.7153373956680298 0.15214723348617554
+LINE 0.7153373956680298 0.15092024207115173
+LINE 0.7153373956680298 0.14969325065612793
+LINE 0.7153373956680298 0.14846625924110413
+LINE 0.7141104340553284 0.14846625924110413
+LINE 0.7116564512252808 0.14723926782608032
+LINE 0.707975447177887 0.14478527009487152
+LINE 0.7030674815177917 0.14355827867984772
+LINE 0.6957055330276489 0.1398773044347763
+LINE 0.6871165633201599 0.1374233067035675
+LINE 0.6797546148300171 0.1349693238735199
+LINE 0.6711656451225281 0.1312883496284485
+LINE 0.6638036966323853 0.1300613433122635
+LINE 0.65398770570755 0.12760736048221588
+LINE 0.6429448127746582 0.12638036906719208
+LINE 0.6319018602371216 0.12392637878656387
+LINE 0.6196318864822388 0.12147239595651627
+LINE 0.6085889339447021 0.12024539709091187
+LINE 0.5963190197944641 0.11901840567588806
+CLOSE
+</AREA>
+yellow
+<AREA>
+START 0.3399089574813843 0.3899848163127899
+LINE 0.3399089574813843 0.3915022611618042
+LINE 0.34142640233039856 0.3899848163127899
+CLOSE
+START 0.3368740379810333 0.39301973581314087
+LINE 0.3368740379810333 0.39453718066215515
+LINE 0.3383914828300476 0.39301973581314087
+CLOSE
+START 0.3368740379810332 0.39453718066215526
+LINE 0.33535659313201904 0.39605462551116943
+LINE 0.33535659313201904 0.3966616094112396
+LINE 0.33687403798103327 0.39453718066215526
+CLOSE
+START 0.3323217034339905 0.399089515209198
+LINE 0.3323217034339905 0.40060698986053467
+LINE 0.3323217034339905 0.4009104371070862
+LINE 0.33362236618995667 0.399089515209198
+CLOSE
+START 0.3550834655761719 0.3839150369167328
+LINE 0.3520485460758209 0.38543248176574707
+LINE 0.34901365637779236 0.38694992661476135
+LINE 0.34714794158935547 0.3878827691078186
+LINE 0.3232170045375824 0.7647951245307922
+LINE 0.3171471953392029 0.7647951245307922
+LINE 0.3171471953392029 0.7632777094841003
+LINE 0.3141123056411743 0.7632777094841003
+LINE 0.3141123056411743 0.7617602348327637
+LINE 0.31259483098983765 0.7617602348327637
+LINE 0.31259483098983765 0.7602428197860718
+LINE 0.31259483098983765 0.7587253451347351
+LINE 0.31234192848205566 0.7587253451347351
+LINE 0.31107738614082336 0.7663125991821289
+LINE 0.3095599412918091 0.772382378578186
+LINE 0.3080424964427948 0.7799696326255798
+LINE 0.3065250515937805 0.7845219969749451
+LINE 0.3065250515937805 0.7875568866729736
+LINE 0.30349013209342957 0.7936267256736755
+LINE 0.30349013209342957 0.7951441407203674
+LINE 0.30349013209342957 0.798179030418396
+LINE 0.30320993065834045 0.7987394332885742
+LINE 0.3019726872444153 0.8238967657089233
+LINE 0.3019726872444153 0.8254931569099426
+LINE 0.30188560485839844 0.8256673216819763
+LINE 0.300455242395401 0.8547515273094177
+LINE 0.300455242395401 0.8558421730995178
+LINE 0.300455242395401 0.8573596477508545
+LINE 0.300455242395401 0.8619120121002197
+LINE 0.300455242395401 0.8634294271469116
+LINE 0.300455242395401 0.8679817914962769
+LINE 0.300455242395401 0.8725341558456421
+LINE 0.300455242395401 0.8755690455436707
+LINE 0.29925423860549927 0.879172146320343
+LINE 0.29325154423713684 1.0012270212173462
+LINE 0.28380173444747925 1.0012270212173462
+LINE 0.2837632894515991 1.001517415046692
+LINE 0.37936267256736755 1.001517415046692
+LINE 0.38049793243408203 0.9245096445083618
+LINE 0.37936267256736755 0.9256449341773987
+LINE 0.37936267256736755 0.9271623492240906
+LINE 0.37784522771835327 0.9271623492240906
+LINE 0.37784522771835327 0.9286798238754272
+LINE 0.371987521648407 0.3839150369167328
+CLOSE
+</AREA>
+orange
+<AREA>
+START 0.29590287804603577 0.4962063729763031
+LINE 0.2685887813568115 0.5068285465240479
+LINE 0.250379353761673 0.5189681053161621
+LINE 0.22761760652065277 0.5462822318077087
+LINE 0.2109256386756897 0.5705614686012268
+LINE 0.19726859033107758 0.600910484790802
+LINE 0.18512898683547974 0.6464340090751648
+LINE 0.18209408223628998 0.6737480759620667
+LINE 0.1805766373872757 0.696509838104248
+LINE 0.1805766373872757 0.7101669311523438
+LINE 0.1805766373872757 0.7207890748977661
+LINE 0.1805766373872757 0.7283763289451599
+LINE 0.1805766373872757 0.734446108341217
+LINE 0.1805766373872757 0.7420333623886108
+LINE 0.1805766373872757 0.7556904554367065
+LINE 0.18209408223628998 0.7678300738334656
+LINE 0.18411734700202942 0.777946412563324
+LINE 0.18361152708530426 0.7784522175788879
+LINE 0.18361152708530426 0.7799696326255798
+LINE 0.18361152708530426 0.7845219969749451
+LINE 0.17905917763710022 0.7936267256736755
+LINE 0.17754173278808594 0.8027313947677612
+LINE 0.17754173278808594 0.8088012337684631
+LINE 0.17754173278808594 0.8148710131645203
+LINE 0.17754173278808594 0.8194233775138855
+LINE 0.17754173278808594 0.8270106315612793
+LINE 0.17754173278808594 0.836115300655365
+LINE 0.17754173278808594 0.8437025547027588
+LINE 0.17754173278808594 0.8467375040054321
+LINE 0.17754173278808594 0.8543247580528259
+LINE 0.17754173278808594 0.8603945374488831
+LINE 0.17754173278808594 0.8679817914962769
+LINE 0.17754173278808594 0.8725341558456421
+LINE 0.1805766373872757 0.8816388249397278
+LINE 0.18209408223628998 0.886191189289093
+LINE 0.18361152708530426 0.8892260789871216
+LINE 0.18361152708530426 0.8952959179878235
+LINE 0.18664643168449402 0.898330807685852
+LINE 0.18664643168449402 0.9013656973838806
+LINE 0.18664643168449402 0.9044005870819092
+LINE 0.19024716317653656 0.9064581394195557
+LINE 0.19156557321548462 0.9572165608406067
+LINE 0.20485584437847137 1.001517415046692
+LINE 0.3308042585849762 1.001517415046692
+LINE 0.3308042585849762 0.6176024079322815
+LINE 0.3295263946056366 0.6176024079322815
+LINE 0.32776933908462524 0.600910484790802
+LINE 0.3232170045375824 0.5523520708084106
+LINE 0.31259483098983765 0.5144158005714417
+LINE 0.300455242395401 0.49924126267433167
+LINE 0.29590287804603577 0.4962063729763031
+CLOSE
+</AREA>
+pink
+<AREA>
+START 0.1729893833398819 0.39453718066215515
+LINE 0.16995447874069214 0.3975720703601837
+LINE 0.15629741549491882 0.3975720703601837
+LINE 0.15174506604671478 0.399089515209198
+LINE 0.1426403671503067 0.40212443470954895
+LINE 0.13960546255111694 0.40212443470954895
+LINE 0.1350531131029129 0.4051593244075775
+LINE 0.13050076365470886 0.4066767692565918
+LINE 0.1289833039045334 0.40819424390792847
+LINE 0.12443095445632935 0.40971168875694275
+LINE 0.12139605730772018 0.41122913360595703
+LINE 0.1198786050081253 0.4142640233039856
+LINE 0.11684370040893555 0.41578149795532227
+LINE 0.11380880326032639 0.4203338325023651
+LINE 0.1122913509607315 0.42336875200271606
+LINE 0.10925644636154175 0.42640364170074463
+LINE 0.10622154921293259 0.43095600605010986
+LINE 0.10470409691333771 0.437025785446167
+LINE 0.10166919231414795 0.4430955946445465
+LINE 0.09711684286594391 0.4506828486919403
+LINE 0.09408194571733475 0.4582701027393341
+LINE 0.09104704111814499 0.4658573567867279
+LINE 0.08801213651895523 0.4734446108341217
+LINE 0.08497723937034607 0.4810318648815155
+LINE 0.08194233477115631 0.4901365637779236
+LINE 0.07738998532295227 0.500758707523346
+LINE 0.07435508072376251 0.5113808512687683
+LINE 0.06980273127555847 0.525037944316864
+LINE 0.06676782667636871 0.5356600880622864
+LINE 0.06373292952775955 0.5462822318077087
+LINE 0.06069802865386009 0.5553869605064392
+LINE 0.05918057635426521 0.562974214553833
+LINE 0.05614567548036575 0.5735963582992554
+LINE 0.05614567548036575 0.5827010869979858
+LINE 0.05311077460646629 0.588770866394043
+LINE 0.05311077460646629 0.5963581204414368
+LINE 0.051593322306871414 0.6039453744888306
+LINE 0.050075873732566833 0.6100151538848877
+LINE 0.050075873732566833 0.6176024079322815
+LINE 0.048558421432971954 0.626707136631012
+LINE 0.045523520559072495 0.6358118653297424
+LINE 0.044006068259477615 0.6449165344238281
+LINE 0.044006068259477615 0.6525037884712219
+LINE 0.040971167385578156 0.6631259322166443
+LINE 0.040971167385578156 0.6707131862640381
+LINE 0.039453718811273575 0.6798179149627686
+LINE 0.037936266511678696 0.6858876943588257
+LINE 0.037936266511678696 0.6934749484062195
+LINE 0.036418817937374115 0.7010622024536133
+LINE 0.036418817937374115 0.7116843461990356
+LINE 0.036418817937374115 0.7177541851997375
+LINE 0.036418817937374115 0.7298938035964966
+LINE 0.036418817937374115 0.7420333623886108
+LINE 0.036418817937374115 0.7541729807853699
+LINE 0.036418817937374115 0.7647951245307922
+LINE 0.036418817937374115 0.7769347429275513
+LINE 0.036418817937374115 0.7936267256736755
+LINE 0.037936266511678696 0.810318648815155
+LINE 0.037936266511678696 0.8254931569099426
+LINE 0.039453718811273575 0.8391502499580383
+LINE 0.039453718811273575 0.8543247580528259
+LINE 0.039453718811273575 0.8649469017982483
+LINE 0.040971167385578156 0.8755690455436707
+LINE 0.040971167385578156 0.8846737742424011
+LINE 0.040971167385578156 0.8922610282897949
+LINE 0.040971167385578156 0.898330807685852
+LINE 0.040971167385578156 0.9059180617332458
+LINE 0.042488619685173035 0.9180576801300049
+LINE 0.045523520559072495 0.9286798238754272
+LINE 0.047040972858667374 0.9408194422721863
+LINE 0.050075873732566833 0.9514415860176086
+LINE 0.051593322306871414 0.9605462551116943
+LINE 0.054628223180770874 0.9681335091590881
+LINE 0.05614567548036575 0.97420334815979
+LINE 0.05614567548036575 0.9772382378578186
+LINE 0.05766312777996063 0.9787557125091553
+LINE 0.05918057635426521 0.9817906022071838
+LINE 0.06069802865386009 0.9833080172538757
+LINE 0.06221547722816467 0.987860381603241
+LINE 0.06373292952775955 0.987860381603241
+LINE 0.06373292952775955 0.9893778562545776
+LINE 0.06373292952775955 0.9954476356506348
+LINE 0.06373292952775955 0.9984825253486633
+LINE 0.06373292952775955 1.001517415046692
+LINE 0.2564491629600525 1.001517415046692
+LINE 0.3080424964427948 0.41881638765335083
+LINE 0.3065250515937805 0.41881638765335083
+LINE 0.30349013209342957 0.41729894280433655
+LINE 0.29742032289505005 0.41578149795532227
+LINE 0.2928679883480072 0.4127465784549713
+LINE 0.28983306884765625 0.4127465784549713
+LINE 0.28831562399864197 0.41122913360595703
+LINE 0.28072836995124817 0.41122913360595703
+LINE 0.2792109251022339 0.40971168875694275
+LINE 0.27314111590385437 0.40971168875694275
+LINE 0.27314111590385437 0.4066767692565918
+LINE 0.26707130670547485 0.4066767692565918
+LINE 0.2640364170074463 0.40364187955856323
+LINE 0.2549317181110382 0.40364187955856323
+LINE 0.2534142732620239 0.4028831720352173
+LINE 0.2534142732620239 0.40212443470954895
+LINE 0.25189679861068726 0.40212443470954895
+LINE 0.25189679861068726 0.40060698986053467
+LINE 0.2488619089126587 0.40060698986053467
+LINE 0.2488619089126587 0.399089515209198
+LINE 0.24582700431346893 0.399089515209198
+LINE 0.24582700431346893 0.3975720703601837
+LINE 0.24430955946445465 0.3975720703601837
+LINE 0.24279211461544037 0.39605462551116943
+LINE 0.2397572100162506 0.39605462551116943
+LINE 0.2397572100162506 0.39453718066215515
+CLOSE
+</AREA>
+blue
+<AREA>
+START 0.7647951245307922 0.14415781199932098
+LINE 0.7602428197860718 0.14567527174949646
+LINE 0.7572078704833984 0.14719271659851074
+LINE 0.7511380910873413 0.14719271659851074
+LINE 0.7481032013893127 0.1502276211977005
+LINE 0.7450683116912842 0.15174506604671478
+LINE 0.7420333623886108 0.15477997064590454
+LINE 0.7389984726905823 0.16084976494312286
+LINE 0.734446108341217 0.1654021292924881
+LINE 0.7314112186431885 0.17147192358970642
+LINE 0.7283763289451599 0.17602427303791046
+LINE 0.7253414392471313 0.18209408223628998
+LINE 0.7223065495491028 0.1881638914346695
+LINE 0.7192716002464294 0.19726859033107758
+LINE 0.7162367105484009 0.20637328922748566
+LINE 0.7101669311523438 0.2169954478740692
+LINE 0.7086494565010071 0.22761760652065277
+LINE 0.7056145668029785 0.2397572100162506
+LINE 0.7010622024536133 0.250379353761673
+LINE 0.6995447874069214 0.262518972158432
+LINE 0.696509838104248 0.27465856075286865
+LINE 0.6934749484062195 0.28983306884765625
+LINE 0.6919575333595276 0.3019726872444153
+LINE 0.6904400587081909 0.31259483098983765
+LINE 0.6904400587081909 0.3216995298862457
+LINE 0.6904400587081909 0.33383914828300476
+LINE 0.6889225840568542 0.3459787666797638
+LINE 0.6889225840568542 0.3550834655761719
+LINE 0.6889225840568542 0.3672230541706085
+LINE 0.6889225840568542 0.37784522771835327
+LINE 0.6889225840568542 0.38694992661476135
+LINE 0.6889225840568542 0.3975720703601837
+LINE 0.6889225840568542 0.40971168875694275
+LINE 0.6889225840568542 0.4203338325023651
+LINE 0.6889225840568542 0.437025785446167
+LINE 0.6889225840568542 0.4522002935409546
+LINE 0.6889225840568542 0.4643399119377136
+LINE 0.6889225840568542 0.4825493097305298
+LINE 0.6889225840568542 0.4946889281272888
+LINE 0.6904400587081909 0.5022761821746826
+LINE 0.6904400587081909 0.5113808512687683
+LINE 0.6919575333595276 0.5220030546188354
+LINE 0.6934749484062195 0.5356600880622864
+LINE 0.6949924230575562 0.550834596157074
+LINE 0.6949924230575562 0.5675265789031982
+LINE 0.6949924230575562 0.5842185020446777
+LINE 0.6949924230575562 0.6024278998374939
+LINE 0.6949924230575562 0.6206373572349548
+LINE 0.6949924230575562 0.6373292803764343
+LINE 0.6949924230575562 0.6600910425186157
+LINE 0.6949924230575562 0.6783004403114319
+LINE 0.6949924230575562 0.6809815764427185
+LINE 0.6957055330276489 0.6809815764427185
+LINE 0.7034111872709414 0.9323790842214136
+LINE 0.7044210923429935 0.940811789488044
+LINE 0.7038717254885185 0.9474041757295749
+LINE 0.7055214643478394 1.0012270212173462
+LINE 0.6676782965660095 1.0012270212173462
+LINE 0.6676782965660095 1.001517415046692
+LINE 0.9726858735084534 1.001517415046692
+LINE 0.9726858735084534 0.9998220801353455
+LINE 0.9730061292648315 1.0
+LINE 0.982822060585022 1.0012270212173462
+LINE 0.9938650131225586 1.0012270212173462
+LINE 0.9717791676521301 0.2245398759841919
+LINE 0.9668711423873901 0.2245398759841919
+LINE 0.9656441807746887 0.2233128845691681
+LINE 0.9570552110671997 0.2233128845691681
+LINE 0.9521472454071045 0.2220858931541443
+LINE 0.9460122585296631 0.2220858931541443
+LINE 0.9398772716522217 0.22085890173912048
+LINE 0.9325153231620789 0.21963189542293549
+LINE 0.925153374671936 0.21840490400791168
+LINE 0.9190183877944946 0.21840490400791168
+LINE 0.9116564393043518 0.21717791259288788
+LINE 0.9067484736442566 0.21717791259288788
+LINE 0.904294490814209 0.21595092117786407
+LINE 0.902936577796936 0.21595092117786407
+LINE 0.898330807685852 0.20789074897766113
+LINE 0.8937784433364868 0.20030349493026733
+LINE 0.8877086639404297 0.19423368573188782
+LINE 0.8846737742424011 0.18968133628368378
+LINE 0.8816388249397278 0.18361152708530426
+LINE 0.8755690455436707 0.17754173278808594
+LINE 0.8710166811943054 0.1729893833398819
+LINE 0.8679817914962769 0.16995447874069214
+LINE 0.8634294271469116 0.1654021292924881
+LINE 0.8588770627975464 0.16236722469329834
+LINE 0.8558421730995178 0.16236722469329834
+LINE 0.8543247580528259 0.16084976494312286
+LINE 0.8467375040054321 0.1578148752450943
+LINE 0.836115300655365 0.15477997064590454
+LINE 0.8209407925605774 0.1502276211977005
+LINE 0.8088012337684631 0.14567527174949646
+LINE 0.7951441407203674 0.14415781199932098
+CLOSE
+</AREA>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/ms/config/easytrn/7gen-info.txt ./project/ms/config/easytrn/7gen-info.txt
--- ../Tekkotsu_2.4.1/project/ms/config/easytrn/7gen-info.txt	1969-12-31 19:00:00.000000000 -0500
+++ ./project/ms/config/easytrn/7gen-info.txt	2006-10-03 23:28:00.000000000 -0400
@@ -0,0 +1,14 @@
+The provided "7general.tm" file was produced by classifying a series of images
+with the EasyTrain tool (Tekkotsu/tools/easytrain), in each of HSB, xy, and YUV
+color spaces.  The EasyTrain color specification files for each of these spaces
+are provided here (*.spc).  The corresponding threshold files are *not* provided 
+to save space, but can be regenerated by loading each of the .spc files in 
+EasyTrain and then clicking 'Save' within the GUI.
+
+Each of these color spaces gives pretty good results on their own, but as a
+post-processing step, we used the Vote tool (Tekkotsu/tools/seg/Vote.java) to
+combine their results into a single threshold file, which yields the 7general.tm
+you see in ms/config.
+    e.g.:  $ cd Tekkotsu/tools/seg
+           $ java Vote /path/to/7gen-*.tm .../project/ms/config/7general.tm
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/ms/config/easytrn/7gen-xy.spc ./project/ms/config/easytrn/7gen-xy.spc
--- ../Tekkotsu_2.4.1/project/ms/config/easytrn/7gen-xy.spc	1969-12-31 19:00:00.000000000 -0500
+++ ./project/ms/config/easytrn/7gen-xy.spc	2006-10-03 23:28:00.000000000 -0400
@@ -0,0 +1,868 @@
+xy
+6
+unsaturated
+<AREA>
+START 0.7635983824729919 0.6432414054870605
+LINE 0.7710446715354919 0.6558429002761841
+LINE 0.7728769183158875 0.6434752941131592
+LINE 0.7635983824729919 0.6432414054870605
+CLOSE
+START 0.28652870655059814 0.16182905435562134
+LINE 0.29610758196949694 0.2082109499086188
+LINE 0.29815950989723206 0.2118310182262339
+LINE 0.29815950989723206 0.21226993203163147
+LINE 0.29815950989723206 0.21349693834781647
+LINE 0.29815950989723206 0.21472392976284027
+LINE 0.29815950989723206 0.21717791259288788
+LINE 0.29815950989723206 0.21963189542293549
+LINE 0.29938650131225586 0.2220858931541443
+LINE 0.29938650131225586 0.2233128845691681
+LINE 0.29938650131225586 0.2245398759841919
+LINE 0.30061349272727966 0.2269938588142395
+LINE 0.30061349272727966 0.2282208651304245
+LINE 0.30184048414230347 0.2306748479604721
+LINE 0.30184048414230347 0.2319018393754959
+LINE 0.30306747555732727 0.23435582220554352
+LINE 0.3042944669723511 0.23680981993675232
+LINE 0.3042944669723511 0.23803681135177612
+LINE 0.3055214583873749 0.23926380276679993
+LINE 0.3055214583873749 0.24049079418182373
+LINE 0.30674847960472107 0.24171778559684753
+LINE 0.30674847960472107 0.24294479191303253
+LINE 0.30674847960472107 0.24417178332805634
+LINE 0.3079754710197449 0.24417178332805634
+LINE 0.3079754710197449 0.24539877474308014
+LINE 0.3079754710197449 0.24662576615810394
+LINE 0.3092024624347687 0.24662576615810394
+LINE 0.3092024624347687 0.24907974898815155
+LINE 0.3104294538497925 0.24907974898815155
+LINE 0.3104294538497925 0.25030675530433655
+LINE 0.3104294538497925 0.25153374671936035
+LINE 0.3116564452648163 0.25153374671936035
+LINE 0.3116564452648163 0.25276073813438416
+LINE 0.3116564452648163 0.25337423384189606
+LINE 0.3128834366798401 0.25398772954940796
+LINE 0.3128834366798401 0.25521472096443176
+LINE 0.3141104280948639 0.25521472096443176
+LINE 0.3165644109249115 0.25644171237945557
+LINE 0.3190183937549591 0.25644171237945557
+LINE 0.3202453851699829 0.25766870379447937
+LINE 0.3239263892173767 0.25766870379447937
+LINE 0.3239263892173767 0.2588956952095032
+LINE 0.3251533806324005 0.2588956952095032
+LINE 0.3251533806324005 0.260122686624527
+LINE 0.3263803720474243 0.260122686624527
+LINE 0.3263803720474243 0.26134970784187317
+LINE 0.3263803720474243 0.262576699256897
+LINE 0.3276073634624481 0.262576699256897
+LINE 0.3276073634624481 0.2638036906719208
+LINE 0.3276073634624481 0.2650306820869446
+LINE 0.3276073634624481 0.2662576735019684
+LINE 0.3288343548774719 0.2674846649169922
+LINE 0.3288343548774719 0.268711656332016
+LINE 0.3288343548774719 0.2699386477470398
+LINE 0.3300613462924957 0.2699386477470398
+LINE 0.3300613462924957 0.2711656391620636
+LINE 0.3300613462924957 0.2723926305770874
+LINE 0.33128833770751953 0.2723926305770874
+LINE 0.33128833770751953 0.2736196219921112
+LINE 0.33128833770751953 0.274846613407135
+LINE 0.33251532912254333 0.274846613407135
+LINE 0.33251532912254333 0.2760736048221588
+LINE 0.33251532912254333 0.277300626039505
+LINE 0.33251532912254333 0.2785276174545288
+LINE 0.33374232053756714 0.2785276174545288
+LINE 0.33374232053756714 0.2797546088695526
+LINE 0.33374232053756714 0.2809816002845764
+LINE 0.33496931195259094 0.2822085916996002
+LINE 0.33496931195259094 0.283435583114624
+LINE 0.33496931195259094 0.2846625745296478
+LINE 0.33496931195259094 0.28588956594467163
+LINE 0.33619633316993713 0.28711655735969543
+LINE 0.33619633316993713 0.28834354877471924
+LINE 0.33619633316993713 0.28957054018974304
+LINE 0.33619633316993713 0.29079753160476685
+LINE 0.33619633316993713 0.29202455282211304
+LINE 0.33619633316993713 0.29325154423713684
+LINE 0.33742332458496094 0.29325154423713684
+LINE 0.33742332458496094 0.29447853565216064
+LINE 0.33742332458496094 0.29570552706718445
+LINE 0.33742332458496094 0.29693251848220825
+LINE 0.33742332458496094 0.29815950989723206
+LINE 0.33742332458496094 0.29938650131225586
+LINE 0.33742332458496094 0.30061349272727966
+LINE 0.33742332458496094 0.30184048414230347
+LINE 0.33742332458496094 0.30306747555732727
+LINE 0.33742332458496094 0.3042944669723511
+LINE 0.33742332458496094 0.3055214583873749
+LINE 0.33742332458496094 0.30674847960472107
+LINE 0.33742332458496094 0.3079754710197449
+LINE 0.33865031599998474 0.3092024624347687
+LINE 0.33865031599998474 0.3104294538497925
+LINE 0.33987730741500854 0.3104294538497925
+LINE 0.33987730741500854 0.3116564452648163
+LINE 0.34110429883003235 0.3128834366798401
+LINE 0.34110429883003235 0.3141104280948639
+LINE 0.34233129024505615 0.3141104280948639
+LINE 0.34233129024505615 0.3153374195098877
+LINE 0.34355828166007996 0.3153374195098877
+LINE 0.34355828166007996 0.3165644109249115
+LINE 0.34478527307510376 0.3165644109249115
+LINE 0.34478527307510376 0.3177914023399353
+LINE 0.34601226449012756 0.3190183937549591
+LINE 0.34723925590515137 0.3190183937549591
+LINE 0.34723925590515137 0.3202453851699829
+LINE 0.349693238735199 0.3202453851699829
+LINE 0.349693238735199 0.3214724063873291
+LINE 0.3603064658838563 0.3214724063873291
+LINE 0.4145542838548195 0.4171779155731201
+LINE 0.4147239327430725 0.4171779155731201
+LINE 0.4147239327430725 0.4174772148599919
+LINE 0.41472393274307257 0.4174772148599919
+LINE 0.4152497674011735 0.4184049069881439
+LINE 0.4159509241580963 0.4184049069881439
+LINE 0.4171779155731201 0.4196318984031677
+LINE 0.4184049069881439 0.4196318984031677
+LINE 0.4184049069881439 0.42085888981819153
+LINE 0.4196318984031677 0.42208588123321533
+LINE 0.4196318984031677 0.42331287264823914
+LINE 0.42085888981819153 0.42331287264823914
+LINE 0.42085888981819153 0.42453986406326294
+LINE 0.42208588123321533 0.42453986406326294
+LINE 0.42208588123321533 0.42576688528060913
+LINE 0.42208588123321533 0.42699387669563293
+LINE 0.42331287264823914 0.42822086811065674
+LINE 0.42453986406326294 0.42822086811065674
+LINE 0.42453986406326294 0.43067485094070435
+LINE 0.42576688528060913 0.43067485094070435
+LINE 0.42576688528060913 0.43190184235572815
+LINE 0.42699387669563293 0.43312883377075195
+LINE 0.42699387669563293 0.43435582518577576
+LINE 0.42822086811065674 0.43435582518577576
+LINE 0.42822086811065674 0.43558281660079956
+LINE 0.42944785952568054 0.43558281660079956
+LINE 0.42944785952568054 0.43680980801582336
+LINE 0.42944785952568054 0.43803679943084717
+LINE 0.43067485094070435 0.43803679943084717
+LINE 0.43067485094070435 0.43926379084587097
+LINE 0.43067485094070435 0.44049081206321716
+LINE 0.43190184235572815 0.44049081206321716
+LINE 0.43190184235572815 0.44171780347824097
+LINE 0.43190184235572815 0.44294479489326477
+LINE 0.43312883377075195 0.4441717863082886
+LINE 0.43435582518577576 0.4441717863082886
+LINE 0.43435582518577576 0.4453987777233124
+LINE 0.43435582518577576 0.4466257691383362
+LINE 0.43558281660079956 0.4466257691383362
+LINE 0.43558281660079956 0.44785276055336
+LINE 0.43558281660079956 0.4490797519683838
+LINE 0.43680980801582336 0.4503067433834076
+LINE 0.43680980801582336 0.4515337347984314
+LINE 0.43803679943084717 0.4515337347984314
+LINE 0.43803679943084717 0.4527607262134552
+LINE 0.43803679943084717 0.453987717628479
+LINE 0.43926379084587097 0.453987717628479
+LINE 0.43926379084587097 0.4552147090435028
+LINE 0.43926379084587097 0.456441730260849
+LINE 0.44049081206321716 0.456441730260849
+LINE 0.44049081206321716 0.4576687216758728
+LINE 0.44171780347824097 0.4576687216758728
+LINE 0.44171780347824097 0.4588957130908966
+LINE 0.44171780347824097 0.4601227045059204
+LINE 0.44294479489326477 0.4601227045059204
+LINE 0.44294479489326477 0.4613496959209442
+LINE 0.4441717863082886 0.4613496959209442
+LINE 0.4441717863082886 0.462576687335968
+LINE 0.4441717863082886 0.4638036787509918
+LINE 0.3900983876300415 0.43245679006997345
+LINE 0.3900983876300417 0.43245679006997345
+LINE 0.3937392312419029 0.43915124537328226
+LINE 0.39373923124190285 0.43915124537328226
+LINE 0.4130638864626089 0.456441730260849
+LINE 0.41453517211360275 0.456441730260849
+LINE 0.4147239327430725 0.4566648109885289
+LINE 0.4147239327430725 0.4576687216758728
+LINE 0.4155733956941992 0.4576687216758728
+LINE 0.44049081206321716 0.48711657524108887
+LINE 0.43558281660079956 0.48711657524108887
+LINE 0.43558281660079956 0.48834356665611267
+LINE 0.43312883377075195 0.48834356665611267
+LINE 0.43190184235572815 0.4895705580711365
+LINE 0.42699387669563293 0.4907975494861603
+LINE 0.42576688528060913 0.4907975494861603
+LINE 0.42576688528060913 0.4920245409011841
+LINE 0.42085888981819153 0.4932515323162079
+LINE 0.4184049069881439 0.4944785237312317
+LINE 0.4159509241580963 0.4944785237312317
+LINE 0.4147239327430725 0.4957055151462555
+LINE 0.4122699499130249 0.4957055151462555
+LINE 0.4110429584980011 0.4969325065612793
+LINE 0.4061349630355835 0.4969325065612793
+LINE 0.4049079716205597 0.4981594979763031
+LINE 0.4012269973754883 0.4993864893913269
+LINE 0.3930296420955432 0.4993864893913269
+LINE 0.4110429584980011 0.551220715045929
+LINE 0.4110429584980011 0.5521472096443176
+LINE 0.4110429584980011 0.5558282136917114
+LINE 0.4122699499130249 0.5595092177391052
+LINE 0.4134969413280487 0.5631901621818542
+LINE 0.4147239327430725 0.5656441450119019
+LINE 0.4147239327430725 0.566871166229248
+LINE 0.4159509241580963 0.5693251490592957
+LINE 0.4159509241580963 0.5705521702766418
+LINE 0.4171779155731201 0.5705521702766418
+LINE 0.4171779155731201 0.5730061531066895
+LINE 0.4196318984031677 0.5730061531066895
+LINE 0.4196318984031677 0.5717791318893433
+LINE 0.42085888981819153 0.5717791318893433
+LINE 0.42208588123321533 0.5705521702766418
+LINE 0.42208588123321533 0.5693251490592957
+LINE 0.42331287264823914 0.5680981874465942
+LINE 0.42453986406326294 0.5656441450119019
+LINE 0.42576688528060913 0.5631901621818542
+LINE 0.42699387669563293 0.5607361793518066
+LINE 0.42944785952568054 0.5558282136917114
+LINE 0.43067485094070435 0.5533742308616638
+LINE 0.43312883377075195 0.54969322681427
+LINE 0.43558281660079956 0.546012282371521
+LINE 0.43803679943084717 0.5423312783241272
+LINE 0.43926379084587097 0.5386503338813782
+LINE 0.44008180499076843 0.5370143055915833
+LINE 0.4441717863082886 0.5337423086166382
+LINE 0.4490797519683838 0.5312883257865906
+LINE 0.4527607262134552 0.528834342956543
+LINE 0.4552147090435028 0.5276073813438416
+LINE 0.4576687216758728 0.5276073813438416
+LINE 0.4576687216758728 0.525153398513794
+LINE 0.4588957130908966 0.525153398513794
+LINE 0.45592448115348816 0.5346144437789917
+LINE 0.4576687216758728 0.5337423086166382
+LINE 0.4588957130908966 0.5337423086166382
+LINE 0.4601227045059204 0.5325153470039368
+LINE 0.4613496959209442 0.5325153470039368
+LINE 0.4621630012989044 0.6268602609634399
+LINE 0.4760028123855591 0.6399716734886169
+LINE 0.47730061411857605 0.6404907703399658
+LINE 0.47852760553359985 0.6408588886260986
+LINE 0.47852760553359985 0.6404907703399658
+LINE 0.47730061411857605 0.633128821849823
+LINE 0.47730061411857605 0.629447877407074
+LINE 0.47730061411857605 0.624539852142334
+LINE 0.47730061411857605 0.6220858693122864
+LINE 0.47730061411857605 0.6171779036521912
+LINE 0.47607362270355225 0.6147239208221436
+LINE 0.47607362270355225 0.612269937992096
+LINE 0.47607362270355225 0.6085889339447021
+LINE 0.47607362270355225 0.6061349511146545
+LINE 0.47607362270355225 0.6036809682846069
+LINE 0.47607362270355225 0.6012269854545593
+LINE 0.47607362270355225 0.5987730026245117
+LINE 0.47607362270355225 0.5975460410118103
+LINE 0.47607362270355225 0.5950919985771179
+LINE 0.47607362270355225 0.5926380157470703
+LINE 0.47607362270355225 0.5901840329170227
+LINE 0.47730061411857605 0.5877300500869751
+LINE 0.47730061411857605 0.5852760672569275
+LINE 0.47730061411857605 0.5828220844268799
+LINE 0.47852760553359985 0.5791410803794861
+LINE 0.47852760553359985 0.5766870975494385
+LINE 0.47852760553359985 0.5754601359367371
+LINE 0.47852760553359985 0.5730061531066895
+LINE 0.47975459694862366 0.5705521702766418
+LINE 0.47975459694862366 0.5693251490592957
+LINE 0.47975459694862366 0.566871166229248
+LINE 0.47975459694862366 0.5656441450119019
+LINE 0.47975459694862366 0.5631901621818542
+LINE 0.48098158836364746 0.5607361793518066
+LINE 0.48098158836364746 0.5595092177391052
+LINE 0.48098158836364746 0.5570552349090576
+LINE 0.48098158836364746 0.5558282136917114
+LINE 0.48098158836364746 0.55460125207901
+LINE 0.48098158836364746 0.5533742308616638
+LINE 0.4890328645706177 0.5712414383888245
+LINE 0.4895705580711365 0.5717791318893433
+LINE 0.4899386763572693 0.5732516050338745
+LINE 0.5508150458335876 0.7083470821380615
+LINE 0.5521472096443176 0.7067484855651855
+LINE 0.5570552349090576 0.6981595158576965
+LINE 0.5644171833992004 0.6871165633201599
+LINE 0.5690184235572815 0.6779141426086426
+LINE 0.5690622329711914 0.6780017614364624
+LINE 0.5715141296386719 0.6790915131568909
+LINE 0.6594330072402954 0.6594981551170349
+LINE 0.6624035239219666 0.6568745374679565
+LINE 0.6625766754150391 0.6564416885375977
+LINE 0.6650306582450867 0.65398770570755
+LINE 0.6699386239051819 0.6490797400474548
+LINE 0.6723926663398743 0.6429448127746582
+LINE 0.6773006319999695 0.6380367875099182
+LINE 0.6809815764427185 0.6319018602371216
+LINE 0.6858895421028137 0.6269938945770264
+LINE 0.6883435845375061 0.620858907699585
+LINE 0.6944785118103027 0.6147239208221436
+LINE 0.6981595158576965 0.6085889339447021
+LINE 0.7042945027351379 0.6012269854545593
+LINE 0.707975447177887 0.5963190197944641
+LINE 0.7141104340553284 0.5889570713043213
+LINE 0.7190183997154236 0.5791410803794861
+LINE 0.7191371321678162 0.5789431929588318
+LINE 0.716564416885376 0.5779141187667847
+LINE 0.7092024683952332 0.5766870975494385
+LINE 0.7116564512252808 0.5754601359367371
+LINE 0.7153373956680298 0.5730061531066895
+LINE 0.7177914381027222 0.5717791318893433
+LINE 0.7190183997154236 0.5705521702766418
+LINE 0.7202454209327698 0.5705521702766418
+LINE 0.7214723825454712 0.5693251490592957
+LINE 0.7214723825454712 0.5680981874465942
+LINE 0.7226994037628174 0.566871166229248
+LINE 0.7226994037628174 0.5644171833992004
+LINE 0.7226994037628174 0.5631901621818542
+LINE 0.7214723825454712 0.5607361793518066
+LINE 0.7214723825454712 0.5595092177391052
+LINE 0.7214723825454712 0.558282196521759
+LINE 0.7190183997154236 0.55460125207901
+LINE 0.7128834128379822 0.54969322681427
+LINE 0.7067484855651855 0.546012282371521
+LINE 0.699386477470398 0.5398772954940796
+LINE 0.6907975673675537 0.5337423086166382
+LINE 0.6822085976600647 0.5276073813438416
+LINE 0.6711656451225281 0.520245373249054
+LINE 0.6601226925849915 0.5128834247589111
+LINE 0.6466257572174072 0.5042944550514221
+LINE 0.6355828046798706 0.4957055151462555
+LINE 0.6257668733596802 0.48834356665611267
+LINE 0.6184049248695374 0.48343557119369507
+LINE 0.6110429167747498 0.47852760553359985
+LINE 0.6036809682846069 0.47361963987350464
+LINE 0.5987730026245117 0.46871164441108704
+LINE 0.5938650369644165 0.4650306701660156
+LINE 0.5889570713043213 0.4601227045059204
+LINE 0.5852760672569275 0.456441730260849
+LINE 0.5828220844268799 0.456441730260849
+LINE 0.5828220844268799 0.4552147090435028
+LINE 0.5813336372375488 0.4548928737640381
+LINE 0.5840491056442261 0.453987717628479
+LINE 0.5852760672569275 0.453987717628479
+LINE 0.5858306884765625 0.4534331262111664
+LINE 0.5599393248558044 0.43247345089912415
+LINE 0.5523520708084106 0.41729894280433655
+LINE 0.5660091042518616 0.40364187955856323
+LINE 0.5918856263160706 0.3842344880104065
+LINE 0.5732601284980774 0.36992931365966797
+LINE 0.531619668006897 0.35347461700439453
+LINE 0.5285044312477112 0.3560579717159271
+LINE 0.5144158005714417 0.34901365637779236
+LINE 0.4825493097305298 0.3308042585849762
+LINE 0.44792288541793823 0.31459614634513855
+LINE 0.4453987777233124 0.313069931650224
+LINE 0.4453987777233124 0.3141104280948639
+LINE 0.4466257691383362 0.3177914023399353
+LINE 0.4466257691383362 0.3190183937549591
+LINE 0.44785276055336 0.3226993978023529
+LINE 0.44785276055336 0.3251533806324005
+LINE 0.44785276055336 0.3263803720474243
+LINE 0.4490797519683838 0.3300613462924957
+LINE 0.4490797519683838 0.33251532912254333
+LINE 0.4490797519683838 0.33374232053756714
+LINE 0.4503067433834076 0.33619633316993713
+LINE 0.4503067433834076 0.33742332458496094
+LINE 0.4503067433834076 0.33865031599998474
+LINE 0.4503067433834076 0.34110429883003235
+LINE 0.4503067433834076 0.34355828166007996
+LINE 0.4503067433834076 0.34601226449012756
+LINE 0.4503067433834076 0.34846624732017517
+LINE 0.4503067433834076 0.35214725136756897
+LINE 0.4503067433834076 0.3533742427825928
+LINE 0.4503067433834076 0.3546012341976166
+LINE 0.4503067433834076 0.3595091998577118
+LINE 0.4503067433834076 0.3607361912727356
+LINE 0.4503067433834076 0.3619631826877594
+LINE 0.4503067433834076 0.3631901741027832
+LINE 0.4503067433834076 0.364417165517807
+LINE 0.4503067433834076 0.3656441569328308
+LINE 0.4503067433834076 0.366871178150177
+LINE 0.4503067433834076 0.3680981695652008
+LINE 0.4503067433834076 0.3693251609802246
+LINE 0.4503067433834076 0.3705521523952484
+LINE 0.4503067433834076 0.3717791438102722
+LINE 0.4503067433834076 0.373006135225296
+LINE 0.4515337347984314 0.37546011805534363
+LINE 0.4515337347984314 0.37668710947036743
+LINE 0.4515337347984314 0.37791410088539124
+LINE 0.4515337347984314 0.37914109230041504
+LINE 0.4515337347984314 0.38159510493278503
+LINE 0.4515337347984314 0.38527607917785645
+LINE 0.4515337347984314 0.38650307059288025
+LINE 0.4515337347984314 0.38773006200790405
+LINE 0.4515337347984314 0.38895705342292786
+LINE 0.4515337347984314 0.39018404483795166
+LINE 0.4515337347984314 0.39141103625297546
+LINE 0.4515337347984314 0.39263802766799927
+LINE 0.4515337347984314 0.39386501908302307
+LINE 0.4515337347984314 0.3950920104980469
+LINE 0.4515337347984314 0.39631903171539307
+LINE 0.4515337347984314 0.39754602313041687
+LINE 0.37494366859688383 0.26264305144316197
+LINE 0.3749436685968839 0.26264305144316197
+LINE 0.30038389563560486 0.17191369831562042
+LINE 0.29693251848220825 0.16932515799999237
+LINE 0.29202455282211304 0.16441717743873596
+LINE 0.28834354877471924 0.16319018602371216
+LINE 0.28652870655059814 0.16182905435562134
+CLOSE
+</AREA>
+green
+<AREA>
+START 0.4795144200325012 0.5235204696655273
+LINE 0.47647950053215027 0.5280728340148926
+LINE 0.4719271659851074 0.5295903086662292
+LINE 0.4658573567867279 0.5341426134109497
+LINE 0.4582701027393341 0.5386949777603149
+LINE 0.449165403842926 0.5447648167610168
+LINE 0.437025785446167 0.5523520708084106
+LINE 0.42488619685173035 0.5599393248558044
+LINE 0.41881638765335083 0.562974214553833
+LINE 0.40819424390792847 0.5675265789031982
+LINE 0.3975720703601837 0.5735963582992554
+LINE 0.38543248176574707 0.5811836123466492
+LINE 0.37329286336898804 0.588770866394043
+LINE 0.35811835527420044 0.5993930101394653
+LINE 0.3444612920284271 0.6115326285362244
+LINE 0.3308042585849762 0.626707136631012
+LINE 0.31866464018821716 0.6418816447257996
+LINE 0.31107738614082336 0.6600910425186157
+LINE 0.30349013209342957 0.6995447874069214
+LINE 0.3019726872444153 0.7253414392471313
+LINE 0.3019726872444153 0.7496206164360046
+LINE 0.30349013209342957 0.7738998532295227
+LINE 0.3141123056411743 0.8209407925605774
+LINE 0.33383914828300476 0.874051570892334
+LINE 0.3474962115287781 0.9028831720352173
+LINE 0.3748103082180023 0.9468892216682434
+LINE 0.39605462551116943 0.962063729763031
+LINE 0.4355083405971527 0.9757207632064819
+LINE 0.47647950053215027 0.9772382378578186
+LINE 0.5083459615707397 0.9726858735084534
+LINE 0.5265553593635559 0.9605462551116943
+LINE 0.5432473421096802 0.9484066963195801
+LINE 0.5584218502044678 0.9393019676208496
+LINE 0.5690439939498901 0.9301972389221191
+LINE 0.5796661376953125 0.9180576801300049
+LINE 0.5918057560920715 0.9013656973838806
+LINE 0.5978755950927734 0.8952959179878235
+LINE 0.600910484790802 0.8922610282897949
+LINE 0.6069802641868591 0.8801214098930359
+LINE 0.6084977388381958 0.8755690455436707
+LINE 0.613050103187561 0.8694992661476135
+LINE 0.6176024079322815 0.8649469017982483
+LINE 0.6191198825836182 0.8603945374488831
+LINE 0.6221547722816467 0.8558421730995178
+LINE 0.6221547722816467 0.8528072834014893
+LINE 0.4810318648815155 0.5235204696655273
+CLOSE
+</AREA>
+yellow
+<AREA>
+START 0.7595006227493286 0.6217737793922424
+LINE 0.7556904554367065 0.6221547722816467
+LINE 0.7450683116912842 0.6251896619796753
+LINE 0.7268588542938232 0.6327769160270691
+LINE 0.714719295501709 0.638846755027771
+LINE 0.7040970921516418 0.6418816447257996
+LINE 0.6980273127555847 0.6433990597724915
+LINE 0.6934749484062195 0.6449165344238281
+LINE 0.6919575333595276 0.6479514241218567
+LINE 0.6828528046607971 0.6509863138198853
+LINE 0.6798179149627686 0.6525037884712219
+LINE 0.67678302526474 0.6540212631225586
+LINE 0.6737480759620667 0.658573567867279
+LINE 0.6661608219146729 0.6616085171699524
+LINE 0.6570561528205872 0.6661608219146729
+LINE 0.6494688987731934 0.6691957712173462
+LINE 0.6449165344238281 0.6722306609153748
+LINE 0.638846755027771 0.6752655506134033
+LINE 0.6342943906784058 0.67678302526474
+LINE 0.6312595009803772 0.6783004403114319
+LINE 0.626707136631012 0.6798179149627686
+LINE 0.6236722469329834 0.6828528046607971
+LINE 0.6221547722816467 0.6828528046607971
+LINE 0.6206373572349548 0.6843702793121338
+LINE 0.6176024079322815 0.6858876943588257
+LINE 0.6145675182342529 0.6874051690101624
+LINE 0.6145675182342529 0.6889225840568542
+LINE 0.6115326285362244 0.6904400587081909
+LINE 0.6054628491401672 0.6934749484062195
+LINE 0.600910484790802 0.6949924230575562
+LINE 0.5948406457901001 0.6980273127555847
+LINE 0.5933232307434082 0.6980273127555847
+LINE 0.588770866394043 0.7010622024536133
+LINE 0.5857359766960144 0.70257967710495
+LINE 0.5827010869979858 0.70257967710495
+LINE 0.5781487226486206 0.7056145668029785
+LINE 0.5766312479972839 0.7071320414543152
+LINE 0.5735963582992554 0.7086494565010071
+LINE 0.5705614686012268 0.7086494565010071
+LINE 0.5690439939498901 0.7101669311523438
+LINE 0.5675265789031982 0.7116843461990356
+LINE 0.5660091042518616 0.7132018208503723
+LINE 0.5644916296005249 0.7132018208503723
+LINE 0.5644916296005249 0.714719295501709
+LINE 0.5644916296005249 0.7162367105484009
+LINE 0.5644916296005249 0.7177541851997375
+LINE 0.5644916296005249 0.7207890748977661
+LINE 0.5644916296005249 0.7223065495491028
+LINE 0.5660091042518616 0.7268588542938232
+LINE 0.5660091042518616 0.7298938035964966
+LINE 0.5690439939498901 0.7329286932945251
+LINE 0.5690439939498901 0.7374810576438904
+LINE 0.5705614686012268 0.740515947341919
+LINE 0.575113832950592 0.7511380910873413
+LINE 0.5766312479972839 0.7556904554367065
+LINE 0.5811836123466492 0.7632777094841003
+LINE 0.5827010869979858 0.7678300738334656
+LINE 0.5872533917427063 0.7769347429275513
+LINE 0.5872533917427063 0.7799696326255798
+LINE 0.5918057560920715 0.7860394716262817
+LINE 0.5918057560920715 0.7890743613243103
+LINE 0.5948406457901001 0.7905917763710022
+LINE 0.5963581204414368 0.7921092510223389
+LINE 0.5963581204414368 0.7936267256736755
+LINE 0.7921092510223389 0.7223065495491028
+LINE 0.7921092510223389 0.7192716002464294
+LINE 0.7951441407203674 0.7101669311523438
+LINE 0.7966616153717041 0.696509838104248
+LINE 0.7966616153717041 0.6874051690101624
+LINE 0.7966616153717041 0.6788424253463745
+LINE 0.7595006227493286 0.6217737793922424
+CLOSE
+</AREA>
+orange
+<AREA>
+START 0.8552147150039673 0.47607362270355225
+LINE 0.8503067493438721 0.47730061411857605
+LINE 0.8404908180236816 0.47730061411857605
+LINE 0.833128809928894 0.47852760553359985
+LINE 0.8306748270988464 0.48220857977867126
+LINE 0.8245398998260498 0.48343557119369507
+LINE 0.8073619604110718 0.48343557119369507
+LINE 0.8024539947509766 0.48466256260871887
+LINE 0.7963190078735352 0.48588958382606506
+LINE 0.7914110422134399 0.48588958382606506
+LINE 0.7852760553359985 0.48711657524108887
+LINE 0.7791411280632019 0.48711657524108887
+LINE 0.7705521583557129 0.48834356665611267
+LINE 0.7619631886482239 0.4895705580711365
+LINE 0.7521472573280334 0.4907975494861603
+LINE 0.7447852492332458 0.4907975494861603
+LINE 0.7361963391304016 0.4920245409011841
+LINE 0.7276073694229126 0.4944785237312317
+LINE 0.7116564512252808 0.4944785237312317
+LINE 0.7055214643478394 0.4957055151462555
+LINE 0.6981595158576965 0.4957055151462555
+LINE 0.6920245289802551 0.4969325065612793
+LINE 0.6809815764427185 0.4969325065612793
+LINE 0.6748466491699219 0.4981594979763031
+LINE 0.6674846410751343 0.4993864893913269
+LINE 0.6601226925849915 0.5006135106086731
+LINE 0.6527607440948486 0.5006135106086731
+LINE 0.6429448127746582 0.5018404722213745
+LINE 0.6343558430671692 0.5030674934387207
+LINE 0.624539852142334 0.5055214762687683
+LINE 0.6159509420394897 0.5055214762687683
+LINE 0.6085889339447021 0.5067484378814697
+LINE 0.6024540066719055 0.5079754590988159
+LINE 0.5938650369644165 0.5092024803161621
+LINE 0.5865030884742737 0.5104294419288635
+LINE 0.5828220844268799 0.5104294419288635
+LINE 0.5779141187667847 0.5116564631462097
+LINE 0.5754601359367371 0.5128834247589111
+LINE 0.5742331147193909 0.5128834247589111
+LINE 0.5742331147193909 0.5141104459762573
+LINE 0.5730061531066895 0.5153374075889587
+LINE 0.5717791318893433 0.5165644288063049
+LINE 0.5693251490592957 0.5190184116363525
+LINE 0.5656441450119019 0.5239263772964478
+LINE 0.5644171833992004 0.528834342956543
+LINE 0.5644171833992004 0.5300613641738892
+LINE 0.5644171833992004 0.5337423086166382
+LINE 0.5644171833992004 0.5349693298339844
+LINE 0.5644171833992004 0.537423312664032
+LINE 0.5656441450119019 0.5411043167114258
+LINE 0.5680981874465942 0.546012282371521
+LINE 0.5705521702766418 0.5484662652015686
+LINE 0.5742331147193909 0.5533742308616638
+LINE 0.5791410803794861 0.5570552349090576
+LINE 0.5840491056442261 0.5619632005691528
+LINE 0.5901840329170227 0.5656441450119019
+LINE 0.5987730026245117 0.5693251490592957
+LINE 0.6024540066719055 0.5717791318893433
+LINE 0.6061349511146545 0.5730061531066895
+LINE 0.6098159551620483 0.5754601359367371
+LINE 0.612269937992096 0.5754601359367371
+LINE 0.6159509420394897 0.5766870975494385
+LINE 0.6171779036521912 0.5779141187667847
+LINE 0.620858907699585 0.5791410803794861
+LINE 0.6220858693122864 0.5803681015968323
+LINE 0.6233128905296326 0.5803681015968323
+LINE 0.6257668733596802 0.5815950632095337
+LINE 0.6282208561897278 0.5828220844268799
+LINE 0.629447877407074 0.5828220844268799
+LINE 0.6319018602371216 0.5877300500869751
+LINE 0.6355828046798706 0.5889570713043213
+LINE 0.6392638087272644 0.5901840329170227
+LINE 0.641717791557312 0.5914110541343689
+LINE 0.6466257572174072 0.5938650369644165
+LINE 0.6515337228775024 0.5963190197944641
+LINE 0.65889573097229 0.6000000238418579
+LINE 0.6687116622924805 0.6036809682846069
+LINE 0.6773006319999695 0.6073619723320007
+LINE 0.6858895421028137 0.6110429167747498
+LINE 0.6944785118103027 0.6147239208221436
+LINE 0.7006134986877441 0.6171779036521912
+LINE 0.7010622024536133 0.6173461675643921
+LINE 0.7010622024536133 0.6312595009803772
+LINE 0.7010622024536133 0.6449165344238281
+LINE 0.7010622024536133 0.6479514241218567
+LINE 0.7040970921516418 0.6499746441841125
+LINE 0.7040970921516418 0.6509863138198853
+LINE 0.7040970921516418 0.6525037884712219
+LINE 0.7040970921516418 0.6540212631225586
+LINE 0.7040970921516418 0.6570561528205872
+LINE 0.7040970921516418 0.658573567867279
+LINE 0.7040970921516418 0.6616085171699524
+LINE 0.7056145668029785 0.6616085171699524
+LINE 0.7056145668029785 0.6631259322166443
+LINE 0.7086494565010071 0.664643406867981
+LINE 0.7101669311523438 0.6661608219146729
+LINE 0.7132018208503723 0.6691957712173462
+LINE 0.7162367105484009 0.6707131862640381
+LINE 0.7192716002464294 0.6722306609153748
+LINE 0.7253414392471313 0.67678302526474
+LINE 0.7283763289451599 0.67678302526474
+LINE 0.7329286932945251 0.6828528046607971
+LINE 0.7359635829925537 0.6843702793121338
+LINE 0.7420333623886108 0.6904400587081909
+LINE 0.7435508370399475 0.6904400587081909
+LINE 0.7435508370399475 0.6934749484062195
+LINE 0.7496206164360046 0.6949924230575562
+LINE 0.7496206164360046 0.6980273127555847
+LINE 0.7617602348327637 0.6980273127555847
+LINE 0.9575113654136658 0.6828528046607971
+LINE 0.9575113654136658 0.6798179149627686
+LINE 0.9575113654136658 0.6707131862640381
+LINE 0.9635812044143677 0.6464340090751648
+LINE 0.9726858735084534 0.6160849928855896
+LINE 0.979243278503418 0.5728061199188232
+LINE 0.9908952713012695 0.5660091042518616
+LINE 1.001517415046692 0.5462822318077087
+LINE 1.001517415046692 0.5235204696655273
+LINE 1.001517415046692 0.5083459615707397
+LINE 1.001517415046692 0.49924126267433167
+LINE 1.0012270212173462 0.49918681383132935
+LINE 1.0012270212173462 0.4993864893913269
+LINE 1.0012270212173462 0.5006135106086731
+LINE 1.0012270212173462 0.5018404722213745
+LINE 1.0012270212173462 0.5030674934387207
+LINE 1.0012270212173462 0.5042944550514221
+LINE 1.0012270212173462 0.5055214762687683
+LINE 0.9579607844352722 0.4959067702293396
+LINE 0.9575113654136658 0.4962063729763031
+LINE 0.9544764757156372 0.4977238178253174
+LINE 0.9528518915176392 0.4985361099243164
+LINE 0.9343558549880981 0.4932515323162079
+LINE 0.9214723706245422 0.4932515323162079
+LINE 0.9190183877944946 0.4920245409011841
+LINE 0.916564404964447 0.4920245409011841
+LINE 0.912883460521698 0.4907975494861603
+LINE 0.9104294180870056 0.4895705580711365
+LINE 0.907975435256958 0.48834356665611267
+LINE 0.9067484140396118 0.48711657524108887
+LINE 0.9018405079841614 0.48711657524108887
+LINE 0.9006134867668152 0.48588958382606506
+LINE 0.89570552110672 0.48343557119369507
+LINE 0.8932515382766724 0.48220857977867126
+LINE 0.8895705342292786 0.47975459694862366
+LINE 0.8860552906990051 0.47799697518348694
+LINE 0.883070707321167 0.47799697518348694
+LINE 0.8809816241264343 0.47730061411857605
+LINE 0.8760735988616943 0.47730061411857605
+LINE 0.8736196160316467 0.47607362270355225
+CLOSE
+</AREA>
+pink
+<AREA>
+START 0.5675265789031982 0.23520486056804657
+LINE 0.550834596157074 0.2397572100162506
+LINE 0.5386949777603149 0.24582700431346893
+LINE 0.5376670360565186 0.25096675753593445
+LINE 0.537177562713623 0.250379353761673
+LINE 0.5356600880622864 0.250379353761673
+LINE 0.525037944316864 0.45371776819229126
+LINE 0.5270611643791199 0.45371776819229126
+LINE 0.5280728340148926 0.4658573567867279
+LINE 0.5295903086662292 0.4719271659851074
+LINE 0.5417298674583435 0.47647950053215027
+LINE 0.5720788836479187 0.47799697518348694
+LINE 0.6433990597724915 0.47799697518348694
+LINE 0.644847571849823 0.4779452383518219
+LINE 0.6509863138198853 0.4825493097305298
+LINE 0.6661608219146729 0.4901365637779236
+LINE 0.6783004403114319 0.49317148327827454
+LINE 0.7010622024536133 0.49924126267433167
+LINE 0.7268588542938232 0.5022761821746826
+LINE 0.752655565738678 0.5053110718727112
+LINE 0.7936267256736755 0.5068285465240479
+LINE 0.8239757418632507 0.5083459615707397
+LINE 0.8497723937034607 0.5083459615707397
+LINE 0.8547205924987793 0.5063666701316833
+LINE 0.8573596477508545 0.5083459615707397
+LINE 0.8634294271469116 0.5113808512687683
+LINE 0.8664643168449402 0.512898325920105
+LINE 0.8710166811943054 0.5144158005714417
+LINE 0.8801214098930359 0.5189681053161621
+LINE 0.8831562995910645 0.5204855799674988
+LINE 0.886191189289093 0.5204855799674988
+LINE 0.8937784433364868 0.5235204696655273
+LINE 0.9028831720352173 0.525037944316864
+LINE 0.9059180617332458 0.5265553593635559
+LINE 0.9150227904319763 0.5265553593635559
+LINE 0.9195750951766968 0.5280728340148926
+LINE 0.9256449341773987 0.5295903086662292
+LINE 0.9377844929695129 0.5311077237129211
+LINE 0.9438543319702148 0.5326251983642578
+LINE 0.9468892216682434 0.5326251983642578
+LINE 0.9529590010643005 0.5341426134109497
+LINE 0.9605462551116943 0.5341426134109497
+LINE 1.0 0.4901365637779236
+LINE 1.0 0.487101674079895
+LINE 0.9969651103019714 0.48406675457954407
+LINE 0.9939302206039429 0.47040972113609314
+LINE 0.9939302206039429 0.4643399119377136
+LINE 0.9939302206039429 0.46130502223968506
+LINE 0.987860381603241 0.45523521304130554
+LINE 0.9817906022071838 0.4506828486919403
+LINE 0.9559939503669739 0.43095600605010986
+LINE 0.9438543319702148 0.41881638765335083
+LINE 0.9180576801300049 0.39605462551116943
+LINE 0.8907435536384583 0.3748103082180023
+LINE 0.8391502499580383 0.3459787666797638
+LINE 0.8148710131645203 0.33383914828300476
+LINE 0.798179030418396 0.3308042585849762
+LINE 0.752655565738678 0.31866464018821716
+LINE 0.7396523952484131 0.3163004517555237
+LINE 0.7268588542938232 0.2989377975463867
+LINE 0.7010622024536133 0.2716236710548401
+LINE 0.6828528046607971 0.2610015273094177
+LINE 0.6358118653297424 0.2412746548652649
+LINE 0.5978755950927734 0.23520486056804657
+CLOSE
+</AREA>
+blue
+<AREA>
+START 0.3019726872444153 0.034901365637779236
+LINE 0.24430955946445465 0.039453718811273575
+LINE 0.15174506604671478 0.044006068259477615
+LINE 0.13050076365470886 0.05614567548036575
+LINE 0.12443095445632935 0.06221547722816467
+LINE 0.12443095445632935 0.06980273127555847
+LINE 0.1289833039045334 0.10622154921293259
+LINE 0.14415781199932098 0.17905917763710022
+LINE 0.1654021292924881 0.2488619089126587
+LINE 0.18361152708530426 0.3095599412918091
+LINE 0.22154779732227325 0.399089515209198
+LINE 0.26555386185646057 0.49924126267433167
+LINE 0.2928679883480072 0.5493171215057373
+LINE 0.3080424964427948 0.5538694858551025
+LINE 0.3216995298862457 0.5493171215057373
+LINE 0.35053110122680664 0.5341426134109497
+LINE 0.3672230541706085 0.525037944316864
+LINE 0.3823975622653961 0.5144158005714417
+LINE 0.4051593244075775 0.500758707523346
+LINE 0.40648365020751953 0.4999861717224121
+LINE 0.40633372923168404 0.4993864893913269
+LINE 0.4073619544506073 0.4993864893913269
+LINE 0.4085889458656311 0.4981594979763031
+LINE 0.4110429584980011 0.4981594979763031
+LINE 0.4110429584980011 0.4969325065612793
+LINE 0.4122699499130249 0.4969325065612793
+LINE 0.4134969413280487 0.4957055151462555
+LINE 0.4159509241580963 0.4944785237312317
+LINE 0.4171779155731201 0.4932515323162079
+LINE 0.4196318984031677 0.4920245409011841
+LINE 0.42085888981819153 0.4920245409011841
+LINE 0.42208588123321533 0.4907975494861603
+LINE 0.42208588123321533 0.4895705580711365
+LINE 0.42208588123321533 0.48834356665611267
+LINE 0.42331287264823914 0.48711657524108887
+LINE 0.42453986406326294 0.48711657524108887
+LINE 0.42576688528060913 0.48466256260871887
+LINE 0.42699387669563293 0.48220857977867126
+LINE 0.42944785952568054 0.47975459694862366
+LINE 0.43067485094070435 0.47730061411857605
+LINE 0.43190184235572815 0.47607362270355225
+LINE 0.43312883377075195 0.47361963987350464
+LINE 0.43558281660079956 0.47116565704345703
+LINE 0.43803679943084717 0.46871164441108704
+LINE 0.43926379084587097 0.4650306701660156
+LINE 0.44171780347824097 0.462576687335968
+LINE 0.4441717863082886 0.4588957130908966
+LINE 0.4466257691383362 0.4552147090435028
+LINE 0.44785276055336 0.4515337347984314
+LINE 0.4503067433834076 0.44785276055336
+LINE 0.4515337347984314 0.4453987777233124
+LINE 0.453987717628479 0.44294479489326477
+LINE 0.4552147090435028 0.44171780347824097
+LINE 0.456441730260849 0.43926379084587097
+LINE 0.4576687216758728 0.43680980801582336
+LINE 0.4588957130908966 0.43680980801582336
+LINE 0.4601227045059204 0.43558281660079956
+LINE 0.4601227045059204 0.43312883377075195
+LINE 0.4613496959209442 0.43190184235572815
+LINE 0.462576687335968 0.43067485094070435
+LINE 0.4638036787509918 0.42944785952568054
+LINE 0.4650306701660156 0.42699387669563293
+LINE 0.46625766158103943 0.42453986406326294
+LINE 0.46625766158103943 0.42331287264823914
+LINE 0.46748465299606323 0.42085888981819153
+LINE 0.46871164441108704 0.4196318984031677
+LINE 0.46993863582611084 0.4171779155731201
+LINE 0.46993863582611084 0.4159509241580963
+LINE 0.46993863582611084 0.4147239327430725
+LINE 0.47239264845848083 0.4134969413280487
+LINE 0.47239264845848083 0.4110429584980011
+LINE 0.47361963987350464 0.4098159372806549
+LINE 0.47484663128852844 0.4061349630355835
+LINE 0.47533742785453803 0.4051533699035644
+LINE 0.4753374278545382 0.4051533699035644
+LINE 0.47975459694862366 0.4036809802055359
+LINE 0.48834356665611267 0.4024539887905121
+LINE 0.4932515323162079 0.4000000059604645
+LINE 0.5006135106086731 0.3987730145454407
+LINE 0.5067484378814697 0.39754602313041687
+LINE 0.5141104459762573 0.39631903171539307
+LINE 0.5190184116363525 0.39386501908302307
+LINE 0.5226994156837463 0.39263802766799927
+LINE 0.5263803601264954 0.39018404483795166
+LINE 0.5300613641738892 0.39018404483795166
+LINE 0.5325153470039368 0.38773006200790405
+LINE 0.5361962914466858 0.38650307059288025
+LINE 0.5386503338813782 0.38404908776283264
+LINE 0.5411043167114258 0.38282209634780884
+LINE 0.5423312783241272 0.38159510493278503
+LINE 0.5447852611541748 0.38036808371543884
+LINE 0.546012282371521 0.38036808371543884
+LINE 0.5484662652015686 0.37914109230041504
+LINE 0.54969322681427 0.37668710947036743
+LINE 0.5509202480316162 0.37546011805534363
+LINE 0.5533742308616638 0.3742331266403198
+LINE 0.5543359739198922 0.37327140694124467
+LINE 0.554384708404541 0.3732979893684387
+LINE 0.5544565597132786 0.37315082407668854
+LINE 0.5544565597132785 0.37315082407668854
+LINE 0.55460125207901 0.373006135225296
+LINE 0.55460125207901 0.3728544662985069
+LINE 0.6113540530204773 0.2566138207912445
+LINE 0.34901365637779236 0.034901365637779236
+CLOSE
+</AREA>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/ms/config/easytrn/7gen-yuv.spc ./project/ms/config/easytrn/7gen-yuv.spc
--- ../Tekkotsu_2.4.1/project/ms/config/easytrn/7gen-yuv.spc	1969-12-31 19:00:00.000000000 -0500
+++ ./project/ms/config/easytrn/7gen-yuv.spc	2006-10-03 23:28:00.000000000 -0400
@@ -0,0 +1,1159 @@
+YUV
+6
+unsaturated
+<AREA>
+START 0.4907975494861603 0.48466256260871887
+LINE 0.48834356665611267 0.48588958382606506
+LINE 0.47852760553359985 0.48588958382606506
+LINE 0.47852760553359985 0.48711657524108887
+LINE 0.47607362270355225 0.48711657524108887
+LINE 0.47607362270355225 0.48834356665611267
+LINE 0.47361963987350464 0.48834356665611267
+LINE 0.47361963987350464 0.4895705580711365
+LINE 0.47116565704345703 0.4895705580711365
+LINE 0.47104808998329645 0.487101674079895
+LINE 0.46889224648475647 0.487101674079895
+LINE 0.4673748016357422 0.4886191189289093
+LINE 0.4658573567867279 0.4901365637779236
+LINE 0.4597875475883484 0.49317148327827454
+LINE 0.4582701027393341 0.4946889281272888
+LINE 0.45523521304130554 0.4946889281272888
+LINE 0.45371776819229126 0.4962063729763031
+LINE 0.4506828486919403 0.4962063729763031
+LINE 0.4506828486919403 0.4977238178253174
+LINE 0.449165403842926 0.4977238178253174
+LINE 0.44613051414489746 0.49924126267433167
+LINE 0.44613051414489746 0.500758707523346
+LINE 0.4446130394935608 0.5022761821746826
+LINE 0.4430955946445465 0.5022761821746826
+LINE 0.44006070494651794 0.5037935972213745
+LINE 0.43854326009750366 0.5037935972213745
+LINE 0.4355083405971527 0.5053110718727112
+LINE 0.43095600605010986 0.5053110718727112
+LINE 0.43095600605010986 0.5083459615707397
+LINE 0.4279210865497589 0.5083459615707397
+LINE 0.42488619685173035 0.5098634362220764
+LINE 0.42336875200271606 0.5098634362220764
+LINE 0.4203338325023651 0.5083459615707397
+LINE 0.3975720703601837 0.5083459615707397
+LINE 0.39453718066215515 0.5113808512687683
+LINE 0.3899848163127899 0.512898325920105
+LINE 0.38846737146377563 0.5144158005714417
+LINE 0.38694992661476135 0.5174506902694702
+LINE 0.38543248176574707 0.5189681053161621
+LINE 0.3839150369167328 0.5220030546188354
+LINE 0.38088011741638184 0.5220030546188354
+LINE 0.37936267256736755 0.5235204696655273
+LINE 0.376327782869339 0.5235204696655273
+LINE 0.3748103082180023 0.525037944316864
+LINE 0.3748103082180023 0.5265553593635559
+LINE 0.37329286336898804 0.5265553593635559
+LINE 0.37177541851997375 0.5295903086662292
+LINE 0.3702579736709595 0.5311077237129211
+LINE 0.3702579736709595 0.5326251983642578
+LINE 0.3672230541706085 0.5326251983642578
+LINE 0.36570560932159424 0.5341426134109497
+LINE 0.36418816447257996 0.5356600880622864
+LINE 0.3613429367542267 0.5413505434989929
+LINE 0.35770222544670105 0.5777577757835388
+LINE 0.3655233085155487 0.5877785682678223
+LINE 0.39715638756752014 0.593967616558075
+LINE 0.4355083107948303 0.581183671951294
+LINE 0.4355083405971527 0.5811836123466492
+LINE 0.4355083405971527 0.5781487226486206
+LINE 0.437025785446167 0.5766312479972839
+LINE 0.43854326009750366 0.575113832950592
+LINE 0.44006070494651794 0.575113832950592
+LINE 0.4415781497955322 0.5735963582992554
+LINE 0.4446130394935608 0.5735963582992554
+LINE 0.4446130394935608 0.5705614686012268
+LINE 0.4506828486919403 0.5705614686012268
+LINE 0.45371776819229126 0.5675265789031982
+LINE 0.45523521304130554 0.5660091042518616
+LINE 0.4567526578903198 0.5660091042518616
+LINE 0.4567526578903198 0.5644916296005249
+LINE 0.4597875475883484 0.5644916296005249
+LINE 0.46130502223968506 0.562974214553833
+LINE 0.46889224648475647 0.562974214553833
+LINE 0.4719271659851074 0.5599393248558044
+LINE 0.4901365637779236 0.5599393248558044
+LINE 0.49165400862693787 0.5584218502044678
+LINE 0.49317148327827454 0.5584218502044678
+LINE 0.49317148327827454 0.5569043755531311
+LINE 0.4977238178253174 0.5569043755531311
+LINE 0.49924126267433167 0.5553869605064392
+LINE 0.49924126267433167 0.5538694858551025
+LINE 0.500758707523346 0.5538694858551025
+LINE 0.500758707523346 0.5523520708084106
+LINE 0.5015174150466919 0.550834596157074
+LINE 0.5037935972213745 0.550834596157074
+LINE 0.5037935972213745 0.5477997064590454
+LINE 0.512898325920105 0.5477997064590454
+LINE 0.5159332156181335 0.5462822318077087
+LINE 0.5204855799674988 0.5462822318077087
+LINE 0.5204855799674988 0.5447648167610168
+LINE 0.5235204696655273 0.5447648167610168
+LINE 0.5235204696655273 0.5432473421096802
+LINE 0.5280728340148926 0.5417298674583435
+LINE 0.5311077237129211 0.5402124524116516
+LINE 0.5326251983642578 0.5402124524116516
+LINE 0.5341426134109497 0.5386949777603149
+LINE 0.5356600880622864 0.5386949777603149
+LINE 0.5356600880622864 0.5356600880622864
+LINE 0.5402124524116516 0.5356600880622864
+LINE 0.5402124524116516 0.5341426134109497
+LINE 0.5405355845051238 0.5341426134109497
+LINE 0.5395544334792406 0.5051985985695954
+LINE 0.5386503338813782 0.5042944550514221
+LINE 0.537423312664032 0.5030674934387207
+LINE 0.5361962914466858 0.5018404722213745
+LINE 0.5337423086166382 0.4993864893913269
+LINE 0.5325153470039368 0.4981594979763031
+LINE 0.5325153470039368 0.4969325065612793
+LINE 0.5312883257865906 0.4969325065612793
+LINE 0.5312883257865906 0.4957055151462555
+LINE 0.5300613641738892 0.4944785237312317
+LINE 0.5300613641738892 0.4932515323162079
+LINE 0.528834342956543 0.4932515323162079
+LINE 0.528834342956543 0.4920245409011841
+LINE 0.5276073813438416 0.4907975494861603
+LINE 0.5263803601264954 0.4895705580711365
+LINE 0.525153398513794 0.48834356665611267
+LINE 0.5239263772964478 0.48834356665611267
+LINE 0.5239263772964478 0.48711657524108887
+LINE 0.520245373249054 0.48711657524108887
+LINE 0.5190184116363525 0.48588958382606506
+LINE 0.5165644288063049 0.48588958382606506
+LINE 0.5153374075889587 0.48466256260871887
+CLOSE
+</AREA>
+green
+<AREA>
+START 0.3095599412918091 0.22003035247325897
+LINE 0.30500757694244385 0.22154779732227325
+LINE 0.3019726872444153 0.22154779732227325
+LINE 0.29590287804603577 0.22306525707244873
+LINE 0.28983306884765625 0.22306525707244873
+LINE 0.28072836995124817 0.224582701921463
+LINE 0.2716236710548401 0.2261001467704773
+LINE 0.2640364170074463 0.22761760652065277
+LINE 0.2549317181110382 0.22913505136966705
+LINE 0.2534142732620239 0.23065251111984253
+LINE 0.25189679861068726 0.23065251111984253
+LINE 0.2488619089126587 0.2336874008178711
+LINE 0.24582700431346893 0.2336874008178711
+LINE 0.24430955946445465 0.23520486056804657
+LINE 0.24279211461544037 0.23672230541706085
+LINE 0.2412746548652649 0.23823975026607513
+LINE 0.23823975026607513 0.2412746548652649
+LINE 0.23520486056804657 0.24430955946445465
+LINE 0.23065251111984253 0.2473444640636444
+LINE 0.224582701921463 0.2579666078090668
+LINE 0.2185128927230835 0.26555386185646057
+LINE 0.21396054327487946 0.27465856075286865
+LINE 0.20789074897766113 0.2852807343006134
+LINE 0.2033383846282959 0.29590287804603577
+LINE 0.20030349493026733 0.30500757694244385
+LINE 0.19726859033107758 0.3156297504901886
+LINE 0.19423368573188782 0.3232170045375824
+LINE 0.19271624088287354 0.32776933908462524
+LINE 0.19271624088287354 0.3368740379810333
+LINE 0.19271624088287354 0.34294384717941284
+LINE 0.19271624088287354 0.3474962115287781
+LINE 0.19271624088287354 0.3550834655761719
+LINE 0.19271624088287354 0.3596358001232147
+LINE 0.19271624088287354 0.3672230541706085
+LINE 0.19423368573188782 0.37329286336898804
+LINE 0.19423368573188782 0.37936267256736755
+LINE 0.1957511454820633 0.3839150369167328
+LINE 0.19726859033107758 0.3899848163127899
+LINE 0.19878603518009186 0.39301973581314087
+LINE 0.20030349493026733 0.3975720703601837
+LINE 0.20030349493026733 0.40212443470954895
+LINE 0.20182093977928162 0.4051593244075775
+LINE 0.2033383846282959 0.40971168875694275
+LINE 0.2033383846282959 0.4127465784549713
+LINE 0.20485584437847137 0.41578149795532227
+LINE 0.20789074897766113 0.42336875200271606
+LINE 0.20940819382667542 0.4279210865497589
+LINE 0.2109256386756897 0.43247345089912415
+LINE 0.21396054327487946 0.44006070494651794
+LINE 0.2185128927230835 0.44613051414489746
+LINE 0.22003035247325897 0.4506828486919403
+LINE 0.22306525707244873 0.45371776819229126
+LINE 0.224582701921463 0.4567526578903198
+LINE 0.224582701921463 0.4582701027393341
+LINE 0.2261001467704773 0.46130502223968506
+LINE 0.22913505136966705 0.4673748016357422
+LINE 0.2321699559688568 0.47040972113609314
+LINE 0.23520486056804657 0.474962055683136
+LINE 0.23672230541706085 0.47799697518348694
+LINE 0.23823975026607513 0.4810318648815155
+LINE 0.2412746548652649 0.48558422923088074
+LINE 0.24279211461544037 0.4901365637779236
+LINE 0.2473444640636444 0.4977238178253174
+LINE 0.250379353761673 0.5037935972213745
+LINE 0.2534142732620239 0.5098634362220764
+LINE 0.2564491629600525 0.5098634362220764
+LINE 0.2564491629600525 0.512898325920105
+LINE 0.25948405265808105 0.5144158005714417
+LINE 0.2610015273094177 0.5174506902694702
+LINE 0.2640364170074463 0.5189681053161621
+LINE 0.26555386185646057 0.5204855799674988
+LINE 0.2685887813568115 0.5235204696655273
+LINE 0.2701062262058258 0.525037944316864
+LINE 0.27314111590385437 0.525037944316864
+LINE 0.27465856075286865 0.5265553593635559
+LINE 0.33839151263237 0.5265553593635559
+LINE 0.3474962115287781 0.525037944316864
+LINE 0.3550834655761719 0.525037944316864
+LINE 0.3672230541706085 0.5235204696655273
+LINE 0.376327782869339 0.5235204696655273
+LINE 0.3915022909641266 0.5220030546188354
+LINE 0.41729894280433655 0.5220030546188354
+LINE 0.4294385313987732 0.5204855799674988
+LINE 0.43260428309440613 0.5204855799674988
+LINE 0.4380200207233429 0.5159332156181335
+LINE 0.4446130394935608 0.5159332156181335
+LINE 0.44613051414489746 0.5144158005714417
+LINE 0.44764795899391174 0.5144158005714417
+LINE 0.4506828486919403 0.512898325920105
+LINE 0.45523521304130554 0.5113808512687683
+LINE 0.4567526578903198 0.5098634362220764
+LINE 0.4582701027393341 0.5098634362220764
+LINE 0.4582701027393341 0.5083459615707397
+LINE 0.46130502223968506 0.5083459615707397
+LINE 0.46282246708869934 0.5068285465240479
+LINE 0.4643399119377136 0.5053110718727112
+LINE 0.4658573567867279 0.5053110718727112
+LINE 0.4658573567867279 0.5037935972213745
+LINE 0.46889224648475647 0.500758707523346
+LINE 0.46889224648475647 0.49924126267433167
+LINE 0.47040972113609314 0.4977238178253174
+LINE 0.4719271659851074 0.4962063729763031
+LINE 0.474962055683136 0.4962063729763031
+LINE 0.47647950053215027 0.49317148327827454
+LINE 0.47799697518348694 0.49165400862693787
+LINE 0.4795144200325012 0.49317148327827454
+LINE 0.4810318648815155 0.49317148327827454
+LINE 0.4818697075049083 0.49359040458997094
+LINE 0.4818697075049082 0.49359040458997094
+LINE 0.48220857977867126 0.4932515323162079
+LINE 0.48343557119369507 0.4920245409011841
+LINE 0.48466256260871887 0.4920245409011841
+LINE 0.48466256260871887 0.4907975494861603
+LINE 0.48588958382606506 0.4907975494861603
+LINE 0.48711657524108887 0.4895705580711365
+LINE 0.4895705580711365 0.4895705580711365
+LINE 0.4895705580711365 0.48834356665611267
+LINE 0.4920245409011841 0.48834356665611267
+LINE 0.499163245093415 0.4841443246961871
+LINE 0.49916324509341486 0.4841443246961871
+LINE 0.5007233964252192 0.48220857977867126
+LINE 0.5018404722213745 0.48220857977867126
+LINE 0.5018404722213745 0.48098158836364746
+LINE 0.5030674934387207 0.48098158836364746
+LINE 0.5030674934387207 0.47975459694862366
+LINE 0.5055214762687683 0.47975459694862366
+LINE 0.5055214762687683 0.47852760553359985
+LINE 0.5067484378814697 0.47852760553359985
+LINE 0.5067484378814697 0.47730061411857605
+LINE 0.5079754590988159 0.47730061411857605
+LINE 0.5079754590988159 0.47607362270355225
+LINE 0.5092024803161621 0.47607362270355225
+LINE 0.5104294419288635 0.47484663128852844
+LINE 0.5111890018481882 0.47484663128852844
+LINE 0.5141104459762573 0.4702453590929743
+LINE 0.5141104459762573 0.46993863582611084
+LINE 0.5143051910052052 0.46993863582611084
+LINE 0.5447852611541748 0.42193254940210595
+LINE 0.5447852611541748 0.42085888981819153
+LINE 0.5447852611541748 0.4196318984031677
+LINE 0.5447852611541748 0.4184049069881439
+LINE 0.5447852611541748 0.4171779155731201
+LINE 0.5447852611541748 0.4159509241580963
+LINE 0.5447852611541748 0.41493062654893775
+LINE 0.5462822318077087 0.40819424390792847
+LINE 0.5493171215057373 0.40060698986053467
+LINE 0.550834596157074 0.3915022909641266
+LINE 0.5523520708084106 0.38543248176574707
+LINE 0.5538694858551025 0.3748103082180023
+LINE 0.5569043755531311 0.36418816447257996
+LINE 0.5569043755531311 0.3550834655761719
+LINE 0.5599393248558044 0.34142640233039856
+LINE 0.5644916296005249 0.3308042585849762
+LINE 0.5675265789031982 0.32018208503723145
+LINE 0.5705614686012268 0.31259486079216003
+LINE 0.5675265789031982 0.3095599412918091
+LINE 0.5614567399024963 0.3065250515937805
+LINE 0.5569043755531311 0.30349013209342957
+LINE 0.5538694858551025 0.3010622262954712
+LINE 0.5538694858551025 0.300455242395401
+LINE 0.5523520708084106 0.2989377975463867
+LINE 0.550834596157074 0.29590287804603577
+LINE 0.5477997064590454 0.2913505434989929
+LINE 0.5432473421096802 0.2852807343006134
+LINE 0.5386949777603149 0.2792109251022339
+LINE 0.5341426134109497 0.27314111590385437
+LINE 0.5295903086662292 0.2701062262058258
+LINE 0.5280728340148926 0.2685887813568115
+LINE 0.525037944316864 0.2685887813568115
+LINE 0.5227617621421814 0.2678300440311432
+LINE 0.5220030546188354 0.26707130670547485
+LINE 0.5174506902694702 0.2610015273094177
+LINE 0.5144158005714417 0.2579666078090668
+LINE 0.5098634362220764 0.2534142732620239
+LINE 0.5083459615707397 0.25189679861068726
+LINE 0.5053110718727112 0.2488619089126587
+LINE 0.49924126267433167 0.24582700431346893
+LINE 0.4901365637779236 0.24279211461544037
+LINE 0.474962055683136 0.23823975026607513
+LINE 0.4567526578903198 0.2336874008178711
+LINE 0.4415781497955322 0.22913505136966705
+LINE 0.43095600605010986 0.2261001467704773
+LINE 0.42336875200271606 0.22306525707244873
+LINE 0.41881638765335083 0.22154779732227325
+LINE 0.4066767692565918 0.22154779732227325
+LINE 0.3975720703601837 0.22003035247325897
+CLOSE
+</AREA>
+yellow
+<AREA>
+START 0.2989377975463867 0.5220030546188354
+LINE 0.2928679883480072 0.5235204696655273
+LINE 0.2549317181110382 0.5235204696655273
+LINE 0.25189679861068726 0.525037944316864
+LINE 0.18512898683547974 0.525037944316864
+LINE 0.17754173278808594 0.5265553593635559
+LINE 0.16843701899051666 0.5280728340148926
+LINE 0.16084976494312286 0.5295903086662292
+LINE 0.15477997064590454 0.5311077237129211
+LINE 0.14567527174949646 0.5341426134109497
+LINE 0.13657055795192719 0.5356600880622864
+LINE 0.1289833039045334 0.5402124524116516
+LINE 0.12291350215673447 0.5417298674583435
+LINE 0.11836115270853043 0.5462822318077087
+LINE 0.1122913509607315 0.5493171215057373
+LINE 0.10773900151252747 0.5538694858551025
+LINE 0.10470409691333771 0.5599393248558044
+LINE 0.09863429516553879 0.5660091042518616
+LINE 0.09559939056634903 0.5705614686012268
+LINE 0.09256449341773987 0.5766312479972839
+LINE 0.09104704111814499 0.5811836123466492
+LINE 0.08952958881855011 0.5857359766960144
+LINE 0.08952958881855011 0.5872533917427063
+LINE 0.08801213651895523 0.5902883410453796
+LINE 0.08801213651895523 0.5933232307434082
+LINE 0.08801213651895523 0.5963581204414368
+LINE 0.08649469166994095 0.5993930101394653
+LINE 0.08649469166994095 0.6054628491401672
+LINE 0.08649469166994095 0.6084977388381958
+LINE 0.08649469166994095 0.6145675182342529
+LINE 0.08649469166994095 0.6191198825836182
+LINE 0.08649469166994095 0.6251896619796753
+LINE 0.08649469166994095 0.6297420263290405
+LINE 0.08649469166994095 0.638846755027771
+LINE 0.08952958881855011 0.6464340090751648
+LINE 0.09104704111814499 0.6570561528205872
+LINE 0.09408194571733475 0.664643406867981
+LINE 0.09711684286594391 0.6722306609153748
+LINE 0.09863429516553879 0.6783004403114319
+LINE 0.10166919231414795 0.6858876943588257
+LINE 0.10470409691333771 0.6934749484062195
+LINE 0.10622154921293259 0.6980273127555847
+LINE 0.10622154921293259 0.6995447874069214
+LINE 0.10622154921293259 0.7010622024536133
+LINE 0.10622154921293259 0.70257967710495
+LINE 0.10925644636154175 0.70257967710495
+LINE 0.10925644636154175 0.7040970921516418
+LINE 0.10925644636154175 0.7056145668029785
+LINE 0.11077389866113663 0.7071320414543152
+LINE 0.1122913509607315 0.7086494565010071
+LINE 0.1122913509607315 0.7101669311523438
+LINE 0.1122913509607315 0.7116843461990356
+LINE 0.11532625555992126 0.7116843461990356
+LINE 0.11532625555992126 0.7132018208503723
+LINE 0.11684370040893555 0.7132018208503723
+LINE 0.11684370040893555 0.7154780030250549
+LINE 0.1198786050081253 0.714719295501709
+LINE 0.1274658590555191 0.7132018208503723
+LINE 0.13808801770210266 0.7101669311523438
+LINE 0.1426403671503067 0.7101669311523438
+LINE 0.14719271659851074 0.7086494565010071
+LINE 0.15326252579689026 0.7071320414543152
+LINE 0.15933232009410858 0.7040970921516418
+LINE 0.16691957414150238 0.70257967710495
+LINE 0.17602427303791046 0.7010622024536133
+LINE 0.18209408223628998 0.6980273127555847
+LINE 0.19119878113269806 0.6980273127555847
+LINE 0.1957511454820633 0.696509838104248
+LINE 0.20182093977928162 0.6949924230575562
+LINE 0.2109256386756897 0.6949924230575562
+LINE 0.2169954478740692 0.6934749484062195
+LINE 0.26707130670547485 0.6934749484062195
+LINE 0.27465856075286865 0.6904400587081909
+LINE 0.28072836995124817 0.6889225840568542
+LINE 0.2852807343006134 0.6858876943588257
+LINE 0.28831562399864197 0.6858876943588257
+LINE 0.2913505434989929 0.6828528046607971
+LINE 0.29590287804603577 0.6813353300094604
+LINE 0.29590287804603577 0.6798179149627686
+LINE 0.300455242395401 0.6783004403114319
+LINE 0.30500757694244385 0.6752655506134033
+LINE 0.3095599412918091 0.6737480759620667
+LINE 0.3141123056411743 0.6722306609153748
+LINE 0.32018208503723145 0.6691957712173462
+LINE 0.32625189423561096 0.6661608219146729
+LINE 0.3308042585849762 0.6631259322166443
+LINE 0.3368740379810333 0.6616085171699524
+LINE 0.3399089574813843 0.6616085171699524
+LINE 0.34294384717941284 0.6600910425186157
+LINE 0.3459787666797638 0.658573567867279
+LINE 0.34901365637779236 0.6570561528205872
+LINE 0.3535660207271576 0.6555386781692505
+LINE 0.3550834655761719 0.6540212631225586
+LINE 0.35811835527420044 0.6540212631225586
+LINE 0.3596358001232147 0.6525037884712219
+LINE 0.3611532747745514 0.6525037884712219
+LINE 0.36418816447257996 0.6509863138198853
+LINE 0.36570560932159424 0.6509863138198853
+LINE 0.3687405288219452 0.6479514241218567
+LINE 0.37177541851997375 0.6479514241218567
+LINE 0.37329286336898804 0.6464340090751648
+LINE 0.376327782869339 0.6433990597724915
+LINE 0.376327782869339 0.6403641700744629
+LINE 0.37936267256736755 0.6373292803764343
+LINE 0.3839150369167328 0.6312595009803772
+LINE 0.38846737146377563 0.6251896619796753
+LINE 0.3915022909641266 0.6206373572349548
+LINE 0.39453718066215515 0.6160849928855896
+LINE 0.3975720703601837 0.613050103187561
+LINE 0.399089515209198 0.6100151538848877
+LINE 0.40060698986053467 0.6084977388381958
+LINE 0.40212443470954895 0.6039453744888306
+LINE 0.40313607454299927 0.6024278998374939
+LINE 0.40364187955856323 0.6024278998374939
+LINE 0.40364187955856323 0.601669192314148
+LINE 0.4051593244075775 0.5993930101394653
+LINE 0.4056651294231415 0.5983814001083374
+LINE 0.4066767692565918 0.5978755950927734
+LINE 0.40971168875694275 0.5963581204414368
+LINE 0.4127465784549713 0.5963581204414368
+LINE 0.4142640233039856 0.5948406457901001
+LINE 0.41578149795532227 0.5948406457901001
+LINE 0.41578149795532227 0.5918057560920715
+LINE 0.41578149795532227 0.588770866394043
+LINE 0.41729894280433655 0.5857359766960144
+LINE 0.41881638765335083 0.5857359766960144
+LINE 0.41881638765335083 0.5827010869979858
+LINE 0.4203338325023651 0.5796661376953125
+LINE 0.4218512773513794 0.5766312479972839
+LINE 0.4218512773513794 0.575113832950592
+LINE 0.4218512773513794 0.5735963582992554
+LINE 0.42488619685173035 0.5735963582992554
+LINE 0.42488619685173035 0.5720788836479187
+LINE 0.42488619685173035 0.5705614686012268
+LINE 0.42640364170074463 0.5690439939498901
+LINE 0.42640364170074463 0.5675265789031982
+LINE 0.42640364170074463 0.5660091042518616
+LINE 0.42640364170074463 0.5644916296005249
+LINE 0.42640364170074463 0.562974214553833
+LINE 0.4279210865497589 0.5614567399024963
+LINE 0.4279210865497589 0.5599393248558044
+LINE 0.4279210865497589 0.5584218502044678
+LINE 0.4279210865497589 0.5553869605064392
+LINE 0.4279210865497589 0.5538694858551025
+LINE 0.4279210865497589 0.550834596157074
+LINE 0.4279210865497589 0.5493171215057373
+LINE 0.4279210865497589 0.5477997064590454
+LINE 0.4279210865497589 0.5462822318077087
+LINE 0.42488619685173035 0.5462822318077087
+LINE 0.42488619685173035 0.5447648167610168
+LINE 0.42488619685173035 0.5432473421096802
+LINE 0.42488619685173035 0.5417298674583435
+LINE 0.42336875200271606 0.5417298674583435
+LINE 0.42336875200271606 0.5386949777603149
+LINE 0.42336875200271606 0.537177562713623
+LINE 0.42336875200271606 0.5356600880622864
+LINE 0.42336875200271606 0.5341426134109497
+LINE 0.42336875200271606 0.5326251983642578
+LINE 0.42336875200271606 0.5311077237129211
+LINE 0.4218512773513794 0.5311077237129211
+LINE 0.4218512773513794 0.5280728340148926
+LINE 0.376327782869339 0.5220030546188354
+CLOSE
+</AREA>
+orange
+<AREA>
+START 0.4597875475883484 0.5538694858551025
+LINE 0.4597875475883484 0.5553869605064392
+LINE 0.4582701027393341 0.5553869605064392
+LINE 0.45371776819229126 0.5569043755531311
+LINE 0.4506828486919403 0.5584218502044678
+LINE 0.44613051414489746 0.5599393248558044
+LINE 0.43854326009750366 0.562974214553833
+LINE 0.43095600605010986 0.5660091042518616
+LINE 0.42488619685173035 0.5675265789031982
+LINE 0.41578149795532227 0.5705614686012268
+LINE 0.4066767692565918 0.5735963582992554
+LINE 0.40060698986053467 0.5766312479972839
+LINE 0.39605462551116943 0.5781487226486206
+LINE 0.39301973581314087 0.5781487226486206
+LINE 0.39301973581314087 0.5796661376953125
+LINE 0.38694992661476135 0.5827010869979858
+LINE 0.37936267256736755 0.588770866394043
+LINE 0.3702579736709595 0.5948406457901001
+LINE 0.3596358001232147 0.600910484790802
+LINE 0.35053110122680664 0.6084977388381958
+LINE 0.3399089574813843 0.6145675182342529
+LINE 0.33535659313201904 0.6176024079322815
+LINE 0.32776933908462524 0.6236722469329834
+LINE 0.31866464018821716 0.6282246112823486
+LINE 0.31107738614082336 0.6342943906784058
+LINE 0.3019726872444153 0.6418816447257996
+LINE 0.28983306884765625 0.6479514241218567
+LINE 0.28072836995124817 0.6540212631225586
+LINE 0.27314111590385437 0.6600910425186157
+LINE 0.26555386185646057 0.6631259322166443
+LINE 0.2564491629600525 0.6631259322166443
+LINE 0.2488619089126587 0.664643406867981
+LINE 0.2412746548652649 0.6676782965660095
+LINE 0.2321699559688568 0.6676782965660095
+LINE 0.224582701921463 0.6691957712173462
+LINE 0.21244309842586517 0.6722306609153748
+LINE 0.20030349493026733 0.6737480759620667
+LINE 0.18968133628368378 0.6752655506134033
+LINE 0.17905917763710022 0.6783004403114319
+LINE 0.17450682818889618 0.6798179149627686
+LINE 0.16995447874069214 0.6798179149627686
+LINE 0.16084976494312286 0.6828528046607971
+LINE 0.15174506604671478 0.6843702793121338
+LINE 0.14871016144752502 0.6858876943588257
+LINE 0.14415781199932098 0.6874051690101624
+LINE 0.13960546255111694 0.6874051690101624
+LINE 0.13657055795192719 0.6889225840568542
+LINE 0.1289833039045334 0.6904400587081909
+LINE 0.1274658590555191 0.6904400587081909
+LINE 0.1274658590555191 0.6934749484062195
+LINE 0.12594839930534363 0.6949924230575562
+LINE 0.12291350215673447 0.6949924230575562
+LINE 0.12291350215673447 0.696509838104248
+LINE 0.12291350215673447 0.6995447874069214
+LINE 0.12594839930534363 0.7056145668029785
+LINE 0.13050076365470886 0.7132018208503723
+LINE 0.13657055795192719 0.7223065495491028
+LINE 0.1426403671503067 0.7283763289451599
+LINE 0.14719271659851074 0.7314112186431885
+LINE 0.15629741549491882 0.7374810576438904
+LINE 0.15730905532836914 0.7379868626594543
+LINE 0.15629741549491882 0.7389984726905823
+LINE 0.15629741549491882 0.740515947341919
+LINE 0.15629741549491882 0.7420333623886108
+LINE 0.15629741549491882 0.7435508370399475
+LINE 0.15477997064590454 0.7450683116912842
+LINE 0.15477997064590454 0.7465857267379761
+LINE 0.15477997064590454 0.7496206164360046
+LINE 0.15477997064590454 0.752655565738678
+LINE 0.15477997064590454 0.7541729807853699
+LINE 0.15477997064590454 0.7572078704833984
+LINE 0.15477997064590454 0.7602428197860718
+LINE 0.15477997064590454 0.7632777094841003
+LINE 0.15477997064590454 0.7663125991821289
+LINE 0.15629741549491882 0.7708649635314941
+LINE 0.1578148752450943 0.7738998532295227
+LINE 0.1578148752450943 0.7754173278808594
+LINE 0.15933232009410858 0.7769347429275513
+LINE 0.16084976494312286 0.7799696326255798
+LINE 0.16236722469329834 0.7814871072769165
+LINE 0.16388466954231262 0.7830045819282532
+LINE 0.1654021292924881 0.7875568866729736
+LINE 0.16843701899051666 0.7905917763710022
+LINE 0.16995447874069214 0.7921092510223389
+LINE 0.16995447874069214 0.7936267256736755
+LINE 0.17147192358970642 0.7951441407203674
+LINE 0.1729893833398819 0.7966616153717041
+LINE 0.1729893833398819 0.7996965050697327
+LINE 0.17602427303791046 0.8027313947677612
+LINE 0.17602427303791046 0.8042488694190979
+LINE 0.17754173278808594 0.8057662844657898
+LINE 0.17905917763710022 0.8057662844657898
+LINE 0.17905917763710022 0.8088012337684631
+LINE 0.18209408223628998 0.8088012337684631
+LINE 0.18209408223628998 0.8118361234664917
+LINE 0.18361152708530426 0.8125948309898376
+LINE 0.18361152708530426 0.8133535385131836
+LINE 0.18361152708530426 0.8148710131645203
+LINE 0.18664643168449402 0.8179059028625488
+LINE 0.18664643168449402 0.8209407925605774
+LINE 0.1881638914346695 0.8224582672119141
+LINE 0.1881638914346695 0.8239757418632507
+LINE 0.1881638914346695 0.8254931569099426
+LINE 0.18968133628368378 0.8270106315612793
+LINE 0.19271624088287354 0.8300455212593079
+LINE 0.19423368573188782 0.8300455212593079
+LINE 0.19726859033107758 0.8330804109573364
+LINE 0.20182093977928162 0.836115300655365
+LINE 0.20637328922748566 0.8406676650047302
+LINE 0.21547800302505493 0.8467375040054321
+LINE 0.22154779732227325 0.8528072834014893
+LINE 0.2261001467704773 0.8558421730995178
+LINE 0.2321699559688568 0.8588770627975464
+LINE 0.23520486056804657 0.8588770627975464
+LINE 0.2412746548652649 0.8603945374488831
+LINE 0.24582700431346893 0.8619120121002197
+LINE 0.24582700431346893 0.8634294271469116
+LINE 0.24582700431346893 0.8664643168449402
+LINE 0.24582700431346893 0.8694992661476135
+LINE 0.24582700431346893 0.8770865201950073
+LINE 0.24582700431346893 0.886191189289093
+LINE 0.2473444640636444 0.8952959179878235
+LINE 0.2488619089126587 0.9028831720352173
+LINE 0.250379353761673 0.9104704260826111
+LINE 0.25189679861068726 0.9150227904319763
+LINE 0.2534142732620239 0.9165402054786682
+LINE 0.2549317181110382 0.9195750951766968
+LINE 0.2564491629600525 0.9210925698280334
+LINE 0.2579666078090668 0.9226100444793701
+LINE 0.25948405265808105 0.9226100444793701
+LINE 0.25948405265808105 0.9256449341773987
+LINE 0.2640364170074463 0.9271623492240906
+LINE 0.26707130670547485 0.9301972389221191
+LINE 0.2716236710548401 0.9317147135734558
+LINE 0.2761760354042053 0.9332321882247925
+LINE 0.2837632894515991 0.9332321882247925
+LINE 0.2837632894515991 0.9347496032714844
+LINE 0.2852807343006134 0.9393019676208496
+LINE 0.2852807343006134 0.9423368573188782
+LINE 0.28831562399864197 0.9468892216682434
+LINE 0.28983306884765625 0.949924111366272
+LINE 0.28983306884765625 0.9514415860176086
+LINE 0.2913505434989929 0.9529590010643005
+LINE 0.2943854331970215 0.9559939503669739
+LINE 0.29742032289505005 0.9575113654136658
+LINE 0.2989377975463867 0.9590288400650024
+LINE 0.300455242395401 0.9605462551116943
+LINE 0.3019726872444153 0.9605462551116943
+LINE 0.30349013209342957 0.962063729763031
+LINE 0.3065250515937805 0.9650986194610596
+LINE 0.31107738614082336 0.9650986194610596
+LINE 0.3156297504901886 0.9666160941123962
+LINE 0.3368740379810333 0.9666160941123962
+LINE 0.3399089574813843 0.9681335091590881
+LINE 0.3444612920284271 0.9681335091590881
+LINE 0.3448735475540161 0.9666160941123962
+LINE 0.3596358001232147 0.9666160941123962
+LINE 0.3626707196235657 0.9635812044143677
+LINE 0.36418816447257996 0.9635812044143677
+LINE 0.36570560932159424 0.962063729763031
+LINE 0.3672230541706085 0.9605462551116943
+LINE 0.3687405288219452 0.9605462551116943
+LINE 0.37177541851997375 0.9575113654136658
+LINE 0.37329286336898804 0.9559939503669739
+LINE 0.3748103082180023 0.9544764757156372
+LINE 0.376327782869339 0.9514415860176086
+LINE 0.37772849202156067 0.9472394585609436
+LINE 0.3702579736709595 0.9332321882247925
+LINE 0.36660486459732056 0.9178890585899353
+LINE 0.36570560932159424 0.9165402054786682
+LINE 0.3626707196235657 0.9044005870819092
+LINE 0.3611532747745514 0.8831562995910645
+LINE 0.3611532747745514 0.8755690455436707
+LINE 0.3611532747745514 0.8679817914962769
+LINE 0.3611532747745514 0.8587506413459778
+LINE 0.3596358001232147 0.8573596477508545
+LINE 0.3596358001232147 0.8501958847045898
+LINE 0.3611532747745514 0.8471962213516235
+LINE 0.3611532747745514 0.8391502499580383
+LINE 0.3622913658618927 0.8334597945213318
+LINE 0.3626707196235657 0.8330804109573364
+LINE 0.36570560932159424 0.8300455212593079
+LINE 0.3687405288219452 0.8254931569099426
+LINE 0.3702579736709595 0.8239757418632507
+LINE 0.3702579736709595 0.8224582672119141
+LINE 0.3702579736709595 0.8209407925605774
+LINE 0.3702579736709595 0.8194233775138855
+LINE 0.3702579736709595 0.8163884878158569
+LINE 0.37177541851997375 0.8163884878158569
+LINE 0.37177541851997375 0.8148710131645203
+LINE 0.37177541851997375 0.8133535385131836
+LINE 0.3748103082180023 0.8133535385131836
+LINE 0.3748103082180023 0.8118361234664917
+LINE 0.376327782869339 0.8088012337684631
+LINE 0.37784522771835327 0.8088012337684631
+LINE 0.37784522771835327 0.8072837591171265
+LINE 0.37936267256736755 0.8072837591171265
+LINE 0.38088011741638184 0.8057662844657898
+LINE 0.38088011741638184 0.8042488694190979
+LINE 0.3823975622653961 0.8027313947677612
+LINE 0.38543248176574707 0.8027313947677612
+LINE 0.38543248176574707 0.8012139797210693
+LINE 0.38694992661476135 0.7996965050697327
+LINE 0.38846737146377563 0.7966616153717041
+LINE 0.3899848163127899 0.7966616153717041
+LINE 0.3899848163127899 0.7951441407203674
+LINE 0.3915022909641266 0.7951441407203674
+LINE 0.3915022909641266 0.7921092510223389
+LINE 0.39301973581314087 0.7921092510223389
+LINE 0.39453718066215515 0.7905917763710022
+LINE 0.39605462551116943 0.7890743613243103
+LINE 0.39605462551116943 0.7860394716262817
+LINE 0.3975720703601837 0.7860394716262817
+LINE 0.3975720703601837 0.7799696326255798
+LINE 0.399089515209198 0.7784522175788879
+LINE 0.399089515209198 0.7754173278808594
+LINE 0.39984825253486633 0.7738998532295227
+LINE 0.40060698986053467 0.7738998532295227
+LINE 0.40060698986053467 0.772382378578186
+LINE 0.40364187955856323 0.772382378578186
+LINE 0.40364187955856323 0.7708649635314941
+LINE 0.4051593244075775 0.7693474888801575
+LINE 0.4066767692565918 0.7678300738334656
+LINE 0.4066767692565918 0.7663125991821289
+LINE 0.40819424390792847 0.7663125991821289
+LINE 0.40819424390792847 0.7647951245307922
+LINE 0.40971168875694275 0.7647951245307922
+LINE 0.40971168875694275 0.7632777094841003
+LINE 0.4127465784549713 0.7632777094841003
+LINE 0.4127465784549713 0.7617602348327637
+LINE 0.4142640233039856 0.7602428197860718
+LINE 0.4142640233039856 0.7587253451347351
+LINE 0.41729894280433655 0.7587253451347351
+LINE 0.41729894280433655 0.7572078704833984
+LINE 0.41729894280433655 0.7556904554367065
+LINE 0.41881638765335083 0.7556904554367065
+LINE 0.41881638765335083 0.7541729807853699
+LINE 0.41881638765335083 0.7511380910873413
+LINE 0.4203338325023651 0.7511380910873413
+LINE 0.4203338325023651 0.7496206164360046
+LINE 0.4203338325023651 0.7481032013893127
+LINE 0.4203338325023651 0.7465857267379761
+LINE 0.4203338325023651 0.7435508370399475
+LINE 0.4218512773513794 0.7435508370399475
+LINE 0.42336875200271606 0.740515947341919
+LINE 0.42640364170074463 0.740515947341919
+LINE 0.42640364170074463 0.7389984726905823
+LINE 0.4279210865497589 0.7374810576438904
+LINE 0.4294385313987732 0.7359635829925537
+LINE 0.43095600605010986 0.7329286932945251
+LINE 0.4339908957481384 0.7329286932945251
+LINE 0.4339908957481384 0.7314112186431885
+LINE 0.437025785446167 0.7314112186431885
+LINE 0.437025785446167 0.7298938035964966
+LINE 0.43854326009750366 0.7268588542938232
+LINE 0.44006070494651794 0.7268588542938232
+LINE 0.44006070494651794 0.7253414392471313
+LINE 0.4415781497955322 0.7238239645957947
+LINE 0.4415781497955322 0.7223065495491028
+LINE 0.4415781497955322 0.7207890748977661
+LINE 0.4415781497955322 0.7192716002464294
+LINE 0.4446130394935608 0.7192716002464294
+LINE 0.4446130394935608 0.7177541851997375
+LINE 0.4446130394935608 0.714719295501709
+LINE 0.44764795899391174 0.714719295501709
+LINE 0.44764795899391174 0.7132018208503723
+LINE 0.44764795899391174 0.7116843461990356
+LINE 0.44764795899391174 0.7101669311523438
+LINE 0.449165403842926 0.7086494565010071
+LINE 0.449165403842926 0.7071320414543152
+LINE 0.449165403842926 0.7056145668029785
+LINE 0.4506828486919403 0.7040970921516418
+LINE 0.4506828486919403 0.70257967710495
+LINE 0.4506828486919403 0.7010622024536133
+LINE 0.4506828486919403 0.6995447874069214
+LINE 0.4506828486919403 0.6980273127555847
+LINE 0.4506828486919403 0.696509838104248
+LINE 0.4506828486919403 0.6949924230575562
+LINE 0.4506828486919403 0.6934749484062195
+LINE 0.4506828486919403 0.6919575333595276
+LINE 0.4506828486919403 0.6904400587081909
+LINE 0.4506828486919403 0.6889225840568542
+LINE 0.4506828486919403 0.6874051690101624
+LINE 0.44764795899391174 0.6874051690101624
+LINE 0.44764795899391174 0.6858876943588257
+LINE 0.44764795899391174 0.6843702793121338
+LINE 0.44764795899391174 0.6828528046607971
+LINE 0.44764795899391174 0.6813353300094604
+LINE 0.44764795899391174 0.6798179149627686
+LINE 0.44764795899391174 0.6783004403114319
+LINE 0.4468892514705658 0.6783004403114319
+LINE 0.44764795899391174 0.67678302526474
+LINE 0.4522002935409546 0.6661608219146729
+LINE 0.4538070261478424 0.6605373620986938
+LINE 0.45523521304130554 0.658573567867279
+LINE 0.46130502223968506 0.6479514241218567
+LINE 0.46282246708869934 0.6418816447257996
+LINE 0.46282246708869934 0.6358118653297424
+LINE 0.46282246708869934 0.6251896619796753
+LINE 0.4620683789253235 0.6229274272918701
+LINE 0.47069165110588074 0.5925735831260681
+LINE 0.4605063498020172 0.5538694858551025
+CLOSE
+</AREA>
+pink
+<AREA>
+START 0.4506828486919403 0.5493171215057373
+LINE 0.38543248176574707 0.7162367105484009
+LINE 0.38543248176574707 0.7177541851997375
+LINE 0.3823975622653961 0.7177541851997375
+LINE 0.3823975622653961 0.7192716002464294
+LINE 0.37936267256736755 0.7192716002464294
+LINE 0.37784522771835327 0.7223065495491028
+LINE 0.37329286336898804 0.7268588542938232
+LINE 0.3687405288219452 0.7329286932945251
+LINE 0.3626707196235657 0.740515947341919
+LINE 0.35660091042518616 0.7481032013893127
+LINE 0.35053110122680664 0.7556904554367065
+LINE 0.3444612920284271 0.7632777094841003
+LINE 0.3368740379810333 0.7738998532295227
+LINE 0.3308042585849762 0.7814871072769165
+LINE 0.32625189423561096 0.7890743613243103
+LINE 0.32018208503723145 0.798179030418396
+LINE 0.3141123056411743 0.8057662844657898
+LINE 0.3080424964427948 0.8133535385131836
+LINE 0.30349013209342957 0.8209407925605774
+LINE 0.29742032289505005 0.8270106315612793
+LINE 0.2928679883480072 0.8330804109573364
+LINE 0.28831562399864197 0.8391502499580383
+LINE 0.2837632894515991 0.8452200293540955
+LINE 0.28072836995124817 0.8497723937034607
+LINE 0.2792109251022339 0.8528072834014893
+LINE 0.2761760354042053 0.8588770627975464
+LINE 0.27314111590385437 0.8619120121002197
+LINE 0.2701062262058258 0.8679817914962769
+LINE 0.2685887813568115 0.8725341558456421
+LINE 0.26707130670547485 0.8755690455436707
+LINE 0.2640364170074463 0.8846737742424011
+LINE 0.262518972158432 0.8892260789871216
+LINE 0.262518972158432 0.8952959179878235
+LINE 0.262518972158432 0.898330807685852
+LINE 0.262518972158432 0.9028831720352173
+LINE 0.262518972158432 0.9059180617332458
+LINE 0.262518972158432 0.9089529514312744
+LINE 0.2640364170074463 0.9104704260826111
+LINE 0.2640364170074463 0.9135053157806396
+LINE 0.26555386185646057 0.9150227904319763
+LINE 0.2685887813568115 0.9195750951766968
+LINE 0.27314111590385437 0.9226100444793701
+LINE 0.2776934802532196 0.9256449341773987
+LINE 0.2837632894515991 0.9301972389221191
+LINE 0.2913505434989929 0.9332321882247925
+LINE 0.300455242395401 0.936267077922821
+LINE 0.3141123056411743 0.9408194422721863
+LINE 0.3292867839336395 0.9438543319702148
+LINE 0.34142640233039856 0.9453717470169067
+LINE 0.35660091042518616 0.9468892216682434
+LINE 0.37177541851997375 0.9468892216682434
+LINE 0.38846737146377563 0.9484066963195801
+LINE 0.40364187955856323 0.9484066963195801
+LINE 0.41578149795532227 0.949924111366272
+LINE 0.4279210865497589 0.949924111366272
+LINE 0.44006070494651794 0.9514415860176086
+LINE 0.5189681053161621 0.9514415860176086
+LINE 0.5235204696655273 0.949924111366272
+LINE 0.5326251983642578 0.9484066963195801
+LINE 0.5432473421096802 0.9438543319702148
+LINE 0.5553869605064392 0.9393019676208496
+LINE 0.5690439939498901 0.9332321882247925
+LINE 0.5781487226486206 0.9286798238754272
+LINE 0.5842185020446777 0.924127459526062
+LINE 0.588770866394043 0.9195750951766968
+LINE 0.5933232307434082 0.9150227904319763
+LINE 0.5978755950927734 0.9074355363845825
+LINE 0.6054628491401672 0.8968133330345154
+LINE 0.613050103187561 0.8877086639404297
+LINE 0.6221547722816467 0.8786039352416992
+LINE 0.626707136631012 0.8710166811943054
+LINE 0.6312595009803772 0.8649469017982483
+LINE 0.6327769160270691 0.8619120121002197
+LINE 0.6342943906784058 0.8558421730995178
+LINE 0.6373292803764343 0.8497723937034607
+LINE 0.638846755027771 0.8421851396560669
+LINE 0.6418816447257996 0.836115300655365
+LINE 0.6418816447257996 0.8285280466079712
+LINE 0.6433990597724915 0.8209407925605774
+LINE 0.6449165344238281 0.8088012337684631
+LINE 0.6464340090751648 0.798179030418396
+LINE 0.6464340090751648 0.7890743613243103
+LINE 0.6464340090751648 0.7784522175788879
+LINE 0.6479514241218567 0.7708649635314941
+LINE 0.6494688987731934 0.7602428197860718
+LINE 0.6509863138198853 0.752655565738678
+LINE 0.6509863138198853 0.7450683116912842
+LINE 0.6509863138198853 0.740515947341919
+LINE 0.6509863138198853 0.7329286932945251
+LINE 0.6509863138198853 0.7268588542938232
+LINE 0.6509863138198853 0.7192716002464294
+LINE 0.6509863138198853 0.7101669311523438
+LINE 0.6509863138198853 0.7056145668029785
+LINE 0.6509863138198853 0.6949924230575562
+LINE 0.6494688987731934 0.6889225840568542
+LINE 0.6494688987731934 0.6828528046607971
+LINE 0.6479514241218567 0.6798179149627686
+LINE 0.6479514241218567 0.6752655506134033
+LINE 0.6464340090751648 0.6722306609153748
+LINE 0.6464340090751648 0.6691957712173462
+LINE 0.6464340090751648 0.6661608219146729
+LINE 0.6464340090751648 0.6631259322166443
+LINE 0.6449165344238281 0.658573567867279
+LINE 0.6433990597724915 0.6540212631225586
+LINE 0.6433990597724915 0.6509863138198853
+LINE 0.6433990597724915 0.6494688987731934
+LINE 0.6418816447257996 0.6449165344238281
+LINE 0.6418816447257996 0.6418816447257996
+LINE 0.6403641700744629 0.6373292803764343
+LINE 0.6403641700744629 0.6342943906784058
+LINE 0.638846755027771 0.6297420263290405
+LINE 0.638846755027771 0.6282246112823486
+LINE 0.638846755027771 0.626707136631012
+LINE 0.6358118653297424 0.626707136631012
+LINE 0.6358118653297424 0.6236722469329834
+LINE 0.6358118653297424 0.6206373572349548
+LINE 0.6358118653297424 0.6191198825836182
+LINE 0.6342943906784058 0.6176024079322815
+LINE 0.6342943906784058 0.6160849928855896
+LINE 0.6312595009803772 0.6160849928855896
+LINE 0.6312595009803772 0.6145675182342529
+LINE 0.6312595009803772 0.613050103187561
+LINE 0.6282246112823486 0.613050103187561
+LINE 0.6282246112823486 0.6115326285362244
+LINE 0.626707136631012 0.6100151538848877
+LINE 0.626707136631012 0.6084977388381958
+LINE 0.6236722469329834 0.6084977388381958
+LINE 0.6236722469329834 0.6069802641868591
+LINE 0.6221547722816467 0.6054628491401672
+LINE 0.6206373572349548 0.6039453744888306
+LINE 0.6206373572349548 0.6024278998374939
+LINE 0.6191198825836182 0.600910484790802
+LINE 0.6145675182342529 0.600910484790802
+LINE 0.613050103187561 0.5993930101394653
+LINE 0.6115326285362244 0.5978755950927734
+LINE 0.6100151538848877 0.5978755950927734
+LINE 0.6084977388381958 0.5963581204414368
+LINE 0.6069802641868591 0.5963581204414368
+LINE 0.6054628491401672 0.5948406457901001
+LINE 0.6039453744888306 0.5933232307434082
+LINE 0.6024278998374939 0.5933232307434082
+LINE 0.5993930101394653 0.5918057560920715
+LINE 0.5963581204414368 0.5902883410453796
+LINE 0.5933232307434082 0.588770866394043
+LINE 0.5918057560920715 0.588770866394043
+LINE 0.5918057560920715 0.5872533917427063
+LINE 0.588770866394043 0.5872533917427063
+LINE 0.5872533917427063 0.5857359766960144
+LINE 0.5827010869979858 0.5857359766960144
+LINE 0.5811836123466492 0.5842185020446777
+LINE 0.5766312479972839 0.5842185020446777
+LINE 0.575113832950592 0.5827010869979858
+LINE 0.5690439939498901 0.5827010869979858
+LINE 0.5660091042518616 0.5811836123466492
+LINE 0.562974214553833 0.5811836123466492
+LINE 0.5599393248558044 0.5781487226486206
+LINE 0.5553869605064392 0.5766312479972839
+LINE 0.550834596157074 0.575113832950592
+LINE 0.5462822318077087 0.5735963582992554
+LINE 0.5432473421096802 0.5735963582992554
+LINE 0.5402124524116516 0.5720788836479187
+LINE 0.537177562713623 0.5720788836479187
+LINE 0.537177562713623 0.5690439939498901
+LINE 0.5326251983642578 0.5690439939498901
+LINE 0.5280728340148926 0.5675265789031982
+LINE 0.5235204696655273 0.5660091042518616
+LINE 0.5189681053161621 0.5644916296005249
+LINE 0.5159332156181335 0.562974214553833
+LINE 0.512898325920105 0.562974214553833
+LINE 0.512898325920105 0.5599393248558044
+LINE 0.5098634362220764 0.5599393248558044
+LINE 0.5053110718727112 0.5584218502044678
+LINE 0.500758707523346 0.5569043755531311
+LINE 0.4977238178253174 0.5569043755531311
+LINE 0.49317148327827454 0.5553869605064392
+LINE 0.4901365637779236 0.5538694858551025
+LINE 0.47799697518348694 0.5538694858551025
+LINE 0.474962055683136 0.550834596157074
+LINE 0.46889224648475647 0.550834596157074
+LINE 0.4658573567867279 0.5493171215057373
+CLOSE
+</AREA>
+blue
+<AREA>
+START 0.638846755027771 0.24430955946445465
+LINE 0.6312595009803772 0.2473444640636444
+LINE 0.6206373572349548 0.2488619089126587
+LINE 0.6069802641868591 0.2549317181110382
+LINE 0.5963581204414368 0.25948405265808105
+LINE 0.5857359766960144 0.26555386185646057
+LINE 0.575113832950592 0.27314111590385437
+LINE 0.5690439939498901 0.2792109251022339
+LINE 0.562974214553833 0.2852807343006134
+LINE 0.5553869605064392 0.2913505434989929
+LINE 0.5493171215057373 0.2989377975463867
+LINE 0.5447648167610168 0.3065250515937805
+LINE 0.5386949777603149 0.3141123056411743
+LINE 0.5341426134109497 0.3216995298862457
+LINE 0.5280728340148926 0.3308042585849762
+LINE 0.5235204696655273 0.33839151263237
+LINE 0.5220030546188354 0.34294384717941284
+LINE 0.5189681053161621 0.35053110122680664
+LINE 0.5159332156181335 0.3550834655761719
+LINE 0.5144158005714417 0.3596358001232147
+LINE 0.5113808512687683 0.36418816447257996
+LINE 0.5098634362220764 0.3687405288219452
+LINE 0.5083459615707397 0.37329286336898804
+LINE 0.5068285465240479 0.37784522771835327
+LINE 0.5053110718727112 0.38088011741638184
+LINE 0.5037935972213745 0.38543248176574707
+LINE 0.5037935972213745 0.3899848163127899
+LINE 0.5022761821746826 0.39453718066215515
+LINE 0.500758707523346 0.3975720703601837
+LINE 0.49924126267433167 0.4051593244075775
+LINE 0.4977238178253174 0.4127465784549713
+LINE 0.4962063729763031 0.41881638765335083
+LINE 0.49317148327827454 0.4279210865497589
+LINE 0.49165400862693787 0.4339908957481384
+LINE 0.4901365637779236 0.44006070494651794
+LINE 0.48558422923088074 0.44764795899391174
+LINE 0.4825493097305298 0.45523521304130554
+LINE 0.4810318648815155 0.4582701027393341
+LINE 0.47799697518348694 0.4643399119377136
+LINE 0.47799697518348694 0.4658573567867279
+LINE 0.47647950053215027 0.4673748016357422
+LINE 0.47647950053215027 0.46889224648475647
+LINE 0.47647950053215027 0.47040972113609314
+LINE 0.47647950053215027 0.4719271659851074
+LINE 0.474962055683136 0.4734446108341217
+LINE 0.474962055683136 0.474962055683136
+LINE 0.474962055683136 0.47647950053215027
+LINE 0.4734446108341217 0.47799697518348694
+LINE 0.4719271659851074 0.4810318648815155
+LINE 0.4719271659851074 0.48406675457954407
+LINE 0.46889224648475647 0.48406675457954407
+LINE 0.46889224648475647 0.48558422923088074
+LINE 0.46889224648475647 0.487101674079895
+LINE 0.4673748016357422 0.4901365637779236
+LINE 0.4658573567867279 0.49317148327827454
+LINE 0.4658573567867279 0.4962063729763031
+LINE 0.4658573567867279 0.4977238178253174
+LINE 0.4658573567867279 0.49924126267433167
+LINE 0.4658573567867279 0.500758707523346
+LINE 0.4658573567867279 0.5022761821746826
+LINE 0.46282246708869934 0.5022761821746826
+LINE 0.46282246708869934 0.5037935972213745
+LINE 0.46282246708869934 0.5053110718727112
+LINE 0.46282246708869934 0.5068285465240479
+LINE 0.46130502223968506 0.5083459615707397
+LINE 0.46130502223968506 0.5098634362220764
+LINE 0.46130502223968506 0.5113808512687683
+LINE 0.46130502223968506 0.512898325920105
+LINE 0.46130502223968506 0.5144158005714417
+LINE 0.46130502223968506 0.5159332156181335
+LINE 0.46130502223968506 0.5174506902694702
+LINE 0.46130502223968506 0.5189681053161621
+LINE 0.46130502223968506 0.5204855799674988
+LINE 0.46130502223968506 0.5220030546188354
+LINE 0.46130502223968506 0.5235204696655273
+LINE 0.46130502223968506 0.525037944316864
+LINE 0.46130502223968506 0.5280728340148926
+LINE 0.46130502223968506 0.5311077237129211
+LINE 0.46130502223968506 0.5341426134109497
+LINE 0.46130502223968506 0.537177562713623
+LINE 0.46282246708869934 0.5432473421096802
+LINE 0.46282246708869934 0.5462822318077087
+LINE 0.46282246708869934 0.5477997064590454
+LINE 0.46282246708869934 0.5493171215057373
+LINE 0.46282246708869934 0.550834596157074
+LINE 0.46282246708869934 0.5523520708084106
+LINE 0.4658573567867279 0.5523520708084106
+LINE 0.4658573567867279 0.5538694858551025
+LINE 0.4658573567867279 0.5569043755531311
+LINE 0.4673748016357422 0.5569043755531311
+LINE 0.4673748016357422 0.5584218502044678
+LINE 0.46889224648475647 0.5599393248558044
+LINE 0.47040972113609314 0.5599393248558044
+LINE 0.47040972113609314 0.562974214553833
+LINE 0.4719271659851074 0.562974214553833
+LINE 0.4719271659851074 0.5644916296005249
+LINE 0.4734446108341217 0.5644916296005249
+LINE 0.4734446108341217 0.5660091042518616
+LINE 0.474962055683136 0.5660091042518616
+LINE 0.47647950053215027 0.5675265789031982
+LINE 0.47799697518348694 0.5690439939498901
+LINE 0.47799697518348694 0.5705614686012268
+LINE 0.4795144200325012 0.5705614686012268
+LINE 0.4810318648815155 0.5735963582992554
+LINE 0.48406675457954407 0.5735963582992554
+LINE 0.48406675457954407 0.575113832950592
+LINE 0.48558422923088074 0.5766312479972839
+LINE 0.487101674079895 0.5766312479972839
+LINE 0.487101674079895 0.5796661376953125
+LINE 0.4886191189289093 0.5796661376953125
+LINE 0.4901365637779236 0.5811836123466492
+LINE 0.49317148327827454 0.5842185020446777
+LINE 0.4962063729763031 0.5857359766960144
+LINE 0.4977238178253174 0.5872533917427063
+LINE 0.49924126267433167 0.588770866394043
+LINE 0.500758707523346 0.5902883410453796
+LINE 0.5037935972213745 0.5902883410453796
+LINE 0.5068285465240479 0.5933232307434082
+LINE 0.5159332156181335 0.5963581204414368
+LINE 0.5235204696655273 0.5993930101394653
+LINE 0.5280728340148926 0.6024278998374939
+LINE 0.5341426134109497 0.6039453744888306
+LINE 0.5386949777603149 0.6069802641868591
+LINE 0.5417298674583435 0.6084977388381958
+LINE 0.5477997064590454 0.6100151538848877
+LINE 0.5553869605064392 0.6115326285362244
+LINE 0.5644916296005249 0.613050103187561
+LINE 0.575113832950592 0.6145675182342529
+LINE 0.5827010869979858 0.6160849928855896
+LINE 0.5948406457901001 0.6176024079322815
+LINE 0.6024278998374939 0.6191198825836182
+LINE 0.6115326285362244 0.6206373572349548
+LINE 0.6858876943588257 0.6206373572349548
+LINE 0.8649469017982483 0.47799697518348694
+LINE 0.8649469017982483 0.47647950053215027
+LINE 0.8649469017982483 0.474962055683136
+LINE 0.8649469017982483 0.4734446108341217
+LINE 0.8649469017982483 0.4719271659851074
+LINE 0.8649469017982483 0.47040972113609314
+LINE 0.8649469017982483 0.46889224648475647
+LINE 0.8649469017982483 0.4658573567867279
+LINE 0.8649469017982483 0.4643399119377136
+LINE 0.8649469017982483 0.4582701027393341
+LINE 0.8649469017982483 0.4567526578903198
+LINE 0.8649469017982483 0.45371776819229126
+LINE 0.8649469017982483 0.4506828486919403
+LINE 0.8649469017982483 0.4446130394935608
+LINE 0.8649469017982483 0.44006070494651794
+LINE 0.8649469017982483 0.437025785446167
+LINE 0.8649469017982483 0.43095600605010986
+LINE 0.8634294271469116 0.42488619685173035
+LINE 0.8634294271469116 0.41729894280433655
+LINE 0.8634294271469116 0.41122913360595703
+LINE 0.8619120121002197 0.4066767692565918
+LINE 0.8603945374488831 0.40212443470954895
+LINE 0.8603945374488831 0.3975720703601837
+LINE 0.8588770627975464 0.3899848163127899
+LINE 0.8573596477508545 0.3839150369167328
+LINE 0.8543247580528259 0.3748103082180023
+LINE 0.8497723937034607 0.36570560932159424
+LINE 0.8452200293540955 0.3535660207271576
+LINE 0.8391502499580383 0.34142640233039856
+LINE 0.8315629959106445 0.3308042585849762
+LINE 0.8254931569099426 0.31866464018821716
+LINE 0.8194233775138855 0.31107738614082336
+LINE 0.8148710131645203 0.30349013209342957
+LINE 0.8088012337684631 0.29742032289505005
+LINE 0.8012139797210693 0.28831562399864197
+LINE 0.7905917763710022 0.2792109251022339
+LINE 0.7845219969749451 0.27314111590385437
+LINE 0.7784522175788879 0.2685887813568115
+LINE 0.7708649635314941 0.2640364170074463
+LINE 0.7632777094841003 0.25948405265808105
+LINE 0.7541729807853699 0.2549317181110382
+LINE 0.7435508370399475 0.25189679861068726
+LINE 0.7314112186431885 0.2488619089126587
+LINE 0.7162367105484009 0.2473444640636444
+LINE 0.70257967710495 0.24582700431346893
+LINE 0.6843702793121338 0.24430955946445465
+CLOSE
+</AREA>
Binary files ../Tekkotsu_2.4.1/project/ms/config/general.tm and ./project/ms/config/general.tm differ
Binary files ../Tekkotsu_2.4.1/project/ms/config/pb.tm and ./project/ms/config/pb.tm differ
Binary files ../Tekkotsu_2.4.1/project/ms/config/phb.tm and ./project/ms/config/phb.tm differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/ms/config/sim_ovrd.cfg ./project/ms/config/sim_ovrd.cfg
--- ../Tekkotsu_2.4.1/project/ms/config/sim_ovrd.cfg	1969-12-31 19:00:00.000000000 -0500
+++ ./project/ms/config/sim_ovrd.cfg	2006-10-03 23:28:00.000000000 -0400
@@ -0,0 +1,47 @@
+##################################################################
+######################   Tekkotsu config   #######################
+##################################################################
+##################### $Name: HEAD $ ######################
+####################### $Revision: 1.1 $ ########################
+################## $Date: 2006/10/04 04:21:12 $ ##################
+##################################################################
+#
+# 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_2.4.1/project/ms/config/tekkotsu.cfg ./project/ms/config/tekkotsu.cfg
--- ../Tekkotsu_2.4.1/project/ms/config/tekkotsu.cfg	2005-08-05 15:44:23.000000000 -0400
+++ ./project/ms/config/tekkotsu.cfg	2006-10-03 23:28:00.000000000 -0400
@@ -66,7 +66,7 @@
 
 # gain           low | mid | high
 # higher gain will brighten the image, but increases noise
-gain=high
+gain=mid
 
 # shutter_speed  slow | mid | fast
 # slower shutter will brighten image, but increases motion blur
@@ -85,32 +85,32 @@
 ### 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 more
-# threshold files is memory - the CPU cost of actual segmenting is
-# only done when the channel is accessed.
+# 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*>
-# phb.tm - pink, skin (hand), and blue
+# 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... :(
-# general.tm - general colors, previously 'default'
+# 210genrl.tm - general colors for the ERS-210
 # ball.tm - standard Sony pink ball definition
-# pb.tm - pink and blue
-thresh=config/phb.tm
-#thresh=config/general.tm
+thresh=config/210phb.tm
+thresh=config/210genrl.tm
 thresh=config/ball.tm
-#thresh=config/pb.tm
-#thresh=config/ttt.tm
 </ERS-2*>
 <ERS-7>
-# 7red.tm - just your usual pink/red/purple color detection, nothing too fancy
+# 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/7red.tm
-thresh=config/ball.tm
+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
 
 
@@ -119,14 +119,14 @@
 # transport can be either 'udp' or 'tcp'
 rawcam_port=10011
 rawcam_transport=udp
-rle_port=10012
-rle_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
-rle_interval=0
+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
@@ -147,6 +147,11 @@
 # 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
 
@@ -163,16 +168,16 @@
 
 # you can send the original segmented image
 # or an RLE compressed version (which includes some noise removal)
-#rlecam_compression   none | rle
-rlecam_compression=rle
+#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
-rlecam_channel=0
+segcam_channel=0
 
-# this is the log_2 of pixels to skip when sending RLE encoded
+# this is the log_2 of pixels to skip when sending
 # segmented camera images, same idea as rawcam_*_skip
-rlecam_skip=1
+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)
@@ -217,7 +222,13 @@
 # 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
@@ -228,12 +239,12 @@
 aibo3d_port=10051
 headControl_port=10052
 estopControl_port=10053
-stewart_port=10055
+#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
+#worldState_interval=0
 
 
 ##################################################################
@@ -387,6 +398,10 @@
 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
@@ -398,7 +413,7 @@
 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_length=64
+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_2.4.1/project/ms/data/motion/k-stsit.mot ./project/ms/data/motion/k-stsit.mot
--- ../Tekkotsu_2.4.1/project/ms/data/motion/k-stsit.mot	1969-12-31 19:00:00.000000000 -0500
+++ ./project/ms/data/motion/k-stsit.mot	2006-10-03 23:28:00.000000000 -0400
@@ -0,0 +1,102 @@
+#MSq
+# Contributed by Ignacio Herrero Reder
+radians
+delay	800
+degrees
+delay	595
+NECK:tilt	-35
+NECK:pan~	0
+NECK:nod	25
+MOUTH~~~~	-5
+EAR:left~	0
+EAR:right	0
+LFr:rotor	15
+LFr:elvtr	3
+LFr:knee~	57
+LBk:rotor	-95
+LBk:elvtr	6
+LBk:knee~	110
+RFr:rotor	15
+RFr:elvtr	3
+RFr:knee~	57
+RBk:rotor	-95
+RBk:elvtr	6
+RBk:knee~	110
+TAIL:tilt	5
+TAIL:pan	0
+delay	175
+NECK:nod	21
+LFr:rotor	7
+LFr:elvtr	1
+LFr:knee~	50
+LBk:rotor	-91
+LBk:elvtr	8
+RFr:rotor	7
+RFr:elvtr	1
+RFr:knee~	50
+RBk:rotor	-91
+RBk:elvtr	8
+delay	175
+NECK:tilt	-36
+NECK:nod	18
+LFr:rotor	0
+LFr:elvtr	0
+LFr:knee~	43
+LBk:rotor	-88
+LBk:elvtr	11
+RFr:rotor	0
+RFr:elvtr	0
+RFr:knee~	43
+RBk:rotor	-88
+RBk:elvtr	11
+delay	175
+NECK:tilt	-37
+NECK:nod	15
+LFr:rotor	-6
+LFr:knee~	36
+LBk:rotor	-85
+LBk:elvtr	13
+RFr:rotor	-6
+RFr:knee~	36
+RBk:rotor	-85
+RBk:elvtr	13
+delay	175
+NECK:tilt	-38
+NECK:nod	11
+LFr:rotor	-14
+LFr:elvtr	-2
+LFr:knee~	30
+LBk:rotor	-82
+LBk:elvtr	16
+RFr:rotor	-14
+RFr:elvtr	-2
+RFr:knee~	30
+RBk:rotor	-82
+RBk:elvtr	16
+delay	175
+NECK:tilt	-39
+NECK:nod	8
+LFr:rotor	-21
+LFr:elvtr	-3
+LFr:knee~	23
+LBk:rotor	-79
+LBk:elvtr	18
+RFr:rotor	-21
+RFr:elvtr	-3
+RFr:knee~	23
+RBk:rotor	-79
+RBk:elvtr	18
+delay	175
+NECK:tilt	-40
+NECK:nod	7
+LFr:rotor	-25
+LFr:elvtr	-4
+LFr:knee~	20
+LBk:rotor	-78
+LBk:elvtr	20
+RFr:rotor	-25
+RFr:elvtr	-4
+RFr:knee~	20
+RBk:rotor	-78
+RBk:elvtr	20
+#END
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/ms/open-r/mw/conf/connect.cfg ./project/ms/open-r/mw/conf/connect.cfg
--- ../Tekkotsu_2.4.1/project/ms/open-r/mw/conf/connect.cfg	2005-06-29 18:06:47.000000000 -0400
+++ ./project/ms/open-r/mw/conf/connect.cfg	2006-10-03 23:28:00.000000000 -0400
@@ -1,10 +1,10 @@
 #System->Main
-OVirtualRobotComm.Sensor.OSensorFrameVectorData.S MainObj.SensorFrame.OSensorFrameVectorData.O
+OVirtualRobotComm.Sensor.OSensorFrameVectorData.S MotoObj.SensorFrame.OSensorFrameVectorData.O
 OVirtualRobotComm.FbkImageSensor.OFbkImageVectorData.S MainObj.Image.OFbkImageVectorData.O
 OVirtualRobotAudioComm.Mic.OSoundVectorData.S MainObj.Mic.OSoundVectorData.O
 
 #Main<->Motion
-MainObj.RegisterWorldState.WorldState.S MotoObj.ReceiveWorldState.WorldState.O
+MainObj.RegisterWorldStatePool.WorldStatePool.S MotoObj.ReceiveWorldStatePool.WorldStatePool.O
 MotoObj.RegisterMotionManager.MotionManager.S MainObj.ReceiveMotionManager.MotionManager.O
 
 #MotionManagerMsgs
@@ -22,6 +22,10 @@
 SndPlay.RegisterSoundManager.SoundManager.S MainObj.ReceiveSoundManager.SoundManager.O
 SndPlay.RegisterSoundManager.SoundManager.S MotoObj.ReceiveSoundManager.SoundManager.O
 
+#SndPlay, Motion -> Main (Profiler)
+MotoObj.RegisterProfiler.Profiler.S MainObj.ReceiveMotionProfiler.Profiler.O
+SndPlay.RegisterProfiler.Profiler.S MainObj.ReceiveSoundProfiler.Profiler.O
+
 #SoundManagerMsgs
 MainObj.SoundManagerComm.SoundManagerMsg.S SndPlay.SoundManagerComm.SoundManagerMsg.O
 MotoObj.SoundManagerComm.SoundManagerMsg.S SndPlay.SoundManagerComm.SoundManagerMsg.O
@@ -30,3 +34,6 @@
 MotoObj.EventTranslatorComm.EventBase.S MainObj.EventTranslatorComm.EventBase.O
 SndPlay.EventTranslatorComm.EventBase.S MainObj.EventTranslatorComm.EventBase.O
 
+#Process ID entry point map (Main -> Motion,SndPlay)
+MainObj.RegisterProcessMap.StackFrames.S MotoObj.ReceiveProcessMap.StackFrames.O
+MainObj.RegisterProcessMap.StackFrames.S SndPlay.ReceiveProcessMap.StackFrames.O
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/templates/behavior.h ./project/templates/behavior.h
--- ../Tekkotsu_2.4.1/project/templates/behavior.h	2005-06-01 01:48:08.000000000 -0400
+++ ./project/templates/behavior.h	2006-04-10 14:09:38.000000000 -0400
@@ -26,11 +26,10 @@
 	virtual void DoStop() {
 		// <your shutdown code here>
 
-		erouter->removeListener(this); //generally a good idea, unsubscribe all
 		BehaviorBase::DoStop(); // do this last (required)
 	}
 
-	virtual void processEvent(const EventBase& e) {
+	virtual void processEvent(const EventBase& event) {
 		// <your event processing code here>
 		// you can delete this function if you don't use any events...
 		// (in which case, you may want to call DoStop() at the end of DoStart()
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/templates/motioncommand.h ./project/templates/motioncommand.h
--- ../Tekkotsu_2.4.1/project/templates/motioncommand.h	1969-12-31 19:00:00.000000000 -0500
+++ ./project/templates/motioncommand.h	2005-10-25 23:56:08.000000000 -0400
@@ -0,0 +1,77 @@
+//-*-c++-*-
+#ifndef INCLUDED_CLASSNAME_h_
+#define INCLUDED_CLASSNAME_h_
+
+// This is an empty MotionCommand template file.
+// 
+// Typically, no destructor, copy, or assignment operators are needed.  If
+// you think you do need one, reread the MotionCommand documentation, because
+// you shouldn't be storing pointers in MotionCommands (see IPC/ListMemBuf for
+// a memory pool interface)
+//
+// You may want to consider subclassing a pre-existing MotionCommand instead
+// of subclassing the base MotionCommand.
+//
+// Replace YOURNAMEHERE, CLASSNAME, and DESCRIPTION as appropriate, and go to town!
+
+
+
+#include "Motion/MotionCommand.h"
+#include "Motion/MotionManager.h"
+
+//! DESCRIPTION
+class CLASSNAME : public MotionCommand {
+public:
+	//! constructor
+	CLASSNAME() : MotionCommand() {}
+
+	// This is where all the real work is done
+	// It will be called by the MotionManager at a high frequency (32ms period)
+	virtual int updateOutputs() {
+		// For each joint you wish to control, call:
+		//   motman->setOutput(this, jointOffset, ...)
+		// Do your computations and return as quickly as possible
+		// Pre-compute and/or cache values whenever possible.
+	}
+	
+	// Return true if any desired joint values may have changed since the last
+	// call to updateOutputs()
+	virtual int isDirty() { return true; }
+	
+	// Return true if this motion still has work to be done -- returning
+	// false may allow the MotionManager to delete this motion and send
+	// a deactivation event, but only if the motion was added with
+	// MotionManager::addPrunableMotion()
+	virtual int isAlive() { return true; }
+	
+
+	// These start and stop functions are called when the motion is
+	// added or removed from the MotionManager.
+	// This may not matter to you -- feel free to delete these functions:
+	virtual void DoStart() {
+		MotionCommand::DoStart(); // do this first (required)
+		// <your startup code here>
+	}
+	virtual void DoStop() {
+		// <your shutdown code here>
+		MotionCommand::DoStop(); // do this last (required)
+	}	
+
+protected:
+	// <class members go here>
+
+	
+};
+
+/*! @file
+ * @brief Defines CLASSNAME, which DESCRIPTION
+ * @author YOURNAMEHERE (Creator)
+ *
+ * $Author: ejt $
+ * $Name: HEAD $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2006/10/04 04:21:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/templates/statemachine.h ./project/templates/statemachine.h
--- ../Tekkotsu_2.4.1/project/templates/statemachine.h	2005-06-01 01:48:08.000000000 -0400
+++ ./project/templates/statemachine.h	2005-11-11 16:12:49.000000000 -0500
@@ -41,9 +41,9 @@
 	}
 
 protected:
-  //! constructor for subclasses (which would need to provide a different class name)
-  CLASSNAME(const std::string &class_name, const std::string &node_name)
-    : StateNode(class_name,node_name), start(NULL)
+	//! constructor for subclasses (which would need to provide a different class name)
+	CLASSNAME(const std::string &class_name, const std::string &node_name)
+		: StateNode(class_name,node_name), start(NULL)
 	{}
 	
 	
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/templates/statenode.h ./project/templates/statenode.h
--- ../Tekkotsu_2.4.1/project/templates/statenode.h	2005-06-01 01:48:08.000000000 -0400
+++ ./project/templates/statenode.h	2006-04-10 14:09:38.000000000 -0400
@@ -37,9 +37,9 @@
 	{}
 
 protected:
-  //! constructor for subclasses (which would need to provide a different class name)
-  CLASSNAME(const std::string &class_name, const std::string &node_name)
-    : StateNode(class_name,node_name)
+	//! constructor for subclasses (which would need to provide a different class name)
+	CLASSNAME(const std::string &class_name, const std::string &node_name)
+		: StateNode(class_name,node_name)
 	{}
 	
 	
@@ -58,7 +58,7 @@
 		// it when deemed appropriate
 	}
 
-	virtual void processEvent(const EventBase& /*e*/) {
+	virtual void processEvent(const EventBase& /*event*/) {
 		// <your event processing code here>
 		// you can delete this function if you don't use any events...
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/project/templates/transition.h ./project/templates/transition.h
--- ../Tekkotsu_2.4.1/project/templates/transition.h	2005-06-01 01:48:08.000000000 -0400
+++ ./project/templates/transition.h	2006-04-10 14:09:38.000000000 -0400
@@ -54,7 +54,7 @@
 		// StateNode do it when a transition (perhaps this one) fires
 	}
 
-	virtual void processEvent(const EventBase& /*e*/) {
+	virtual void processEvent(const EventBase& /*event*/) {
 		// <your event processing code here>
 		// Call fire() (a method of the Transition base class) whenever the
 		// environment satisifies whatever condition this Transition is supposed to
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/Makefile ./tools/Makefile
--- ../Tekkotsu_2.4.1/tools/Makefile	2005-08-16 17:11:04.000000000 -0400
+++ ./tools/Makefile	2006-09-06 15:45:30.000000000 -0400
@@ -1,16 +1,21 @@
-COMPONENTS=binstrswap filtersyswarn evenmodtime mon mipaltools easytrain
-TARGETS=all clean releaseCheck
 
-.PHONY: $(TARGETS)
+COMPONENTS:=filtersyswarn binstrswap mon mipaltools easytrain
 
-all clean:
-	@for dir in $(COMPONENTS); do \
-		printf "Making tool $$dir: "; \
-		(cd $$dir && $(MAKE) $@); \
-		if [ $$? -ne 0 ] ; then \
-			exit 1; \
-		fi; \
-	done
+.PHONY: all clean releaseCheck $(COMPONENTS)
+
+TOOLS_BUILT_FLAG?=.toolsBuilt
+
+all: $(COMPONENTS)
+	@if [ ! -f $(TOOLS_BUILT_FLAG) ] ; then \
+		touch $(TOOLS_BUILT_FLAG); \
+	fi
+
+clean: $(COMPONENTS)
+	@rm -f $(TOOLS_BUILT_FLAG)
+
+$(COMPONENTS):
+	@printf "Making tool $@: "
+	@$(MAKE) -C "$@" $(MAKECMDGOALS)
 
 releaseCheck:
 	@for dir in $(dir $(shell find * test/* -maxdepth 1 -name Makefile)) ; do \
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/binstrswap/Makefile ./tools/binstrswap/Makefile
--- ../Tekkotsu_2.4.1/tools/binstrswap/Makefile	2005-08-16 16:47:42.000000000 -0400
+++ ./tools/binstrswap/Makefile	2006-05-09 12:37:58.000000000 -0400
@@ -3,7 +3,7 @@
 all: binstrswap
 
 binstrswap: binstrswap.cc
-	g++ -o binstrswap -Wall -O2 binstrswap.cc
+	$(CXX) -o binstrswap -Wall -O2 binstrswap.cc
 
 clean:
 	rm -f binstrswap
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/buildRelease ./tools/buildRelease
--- ../Tekkotsu_2.4.1/tools/buildRelease	2005-08-09 19:22:27.000000000 -0400
+++ ./tools/buildRelease	2006-09-29 06:54:48.000000000 -0400
@@ -79,13 +79,13 @@
 rm -rf Tekkotsu_$2
 cvs -q export -r ${oldtag} -d Tekkotsu_$2 Tekkotsu
 cd Tekkotsu_$1;
-diff -urdN ../Tekkotsu_$2 . > "${tmp}/Tekkotsu_patch_$2_to_$1.diff";
+diff -urdN --exclude=CVS '-I\$[^$]*:[^$]*\$' ../Tekkotsu_$2 . > "${tmp}/Tekkotsu_patch_$2_to_$1.diff";
 if [ "`head -n 1 "${tmp}/Tekkotsu_patch_$2_to_$1.diff" | sed 's/ .*//'`" != "diff" ] ; then
 	echo "Framework patch file failed"
 	exit 1;
 fi;
 cd project;
-diff -urdN ../../Tekkotsu_$2/project . > "${tmp}/Tekkotsu_patch_project_$2_to_$1.diff"
+diff -urdN --exclude=CVS '-I\$[^$]*:[^$]*\$' ../../Tekkotsu_$2/project . > "${tmp}/Tekkotsu_patch_project_$2_to_$1.diff"
 if [ "`head -n 1 "${tmp}/Tekkotsu_patch_project_$2_to_$1.diff" | sed 's/ .*//'`" != "diff" ] ; then
 	echo "Project patch file failed"
 	exit 1;
@@ -102,7 +102,7 @@
 	export TEKKOTSU_TARGET_MODEL=$x;
 	printf "\n\nTesting $x build\n\n\n";
 	cd ${tmp}/Tekkotsu_$1;
-	${MAKE}
+	${MAKE} -j2
 	if [ $? -ne 0 ] ; then
 		echo "Framework build failed for $x"
 		exit 1;
@@ -114,12 +114,12 @@
 		exit 1;
 	fi;
 	cd ${tmp}/Tekkotsu_$1/project;
-	${MAKE};
+	${MAKE} -j2;
 	if [ $? -ne 0 ] ; then
 		echo "Project Build failed for $x"
 		exit 1;
 	fi;
-	${MAKE} sim;
+	${MAKE} -j2 sim;
 	if [ $? -ne 0 ] ; then
 		echo "sim build failed for $x"
 		exit 1;
@@ -129,7 +129,7 @@
 echo "Enter memstick to be built onto for ERS-2xx - this memstick will be erased";
 read -p "Press return when ready... (^C to stop)"
 
-mntmem $MEMSTICK_ROOT;
+$TEKKOTSU_ROOT/tools/mntmem $MEMSTICK_ROOT;
 rm -rf /mnt/memstick/*;
 ${MAKE} update;
 if [ $? -ne 0 ] ; then
@@ -137,10 +137,10 @@
 	exit 1;
 fi;
 
-mntmem $MEMSTICK_ROOT;
+$TEKKOTSU_ROOT/tools/mntmem $MEMSTICK_ROOT;
 rm -rf ${tmp}/Tekkotsu_memstick_ERS2xx_$1;
-cp -arp /mnt/memstick ${tmp}/Tekkotsu_memstick_ERS2xx_$1;
-umntmem $MEMSTICK_ROOT;
+cp -rp $MEMSTICK_ROOT ${tmp}/Tekkotsu_memstick_ERS2xx_$1;
+$TEKKOTSU_ROOT/tools/umntmem $MEMSTICK_ROOT;
 chmod a+rx ${tmp}/Tekkotsu_memstick_ERS2xx_$1
 
 cd ${tmp};
@@ -156,9 +156,11 @@
 
 for x in TGT_ERS7; do
 	export TEKKOTSU_TARGET_MODEL=$x;
+	# turn off precompiled headers to check that all of the #includes are correct
+	export TEKKOTSU_PCH="";
 	printf "\n\nTesting $x build\n\n\n";
 	cd ${tmp}/Tekkotsu_$1;
-	${MAKE}
+	${MAKE} -j2
 	if [ $? -ne 0 ] ; then
 		echo "Framework build failed for $x"
 		exit 1;
@@ -170,12 +172,12 @@
 		exit 1;
 	fi;
 	cd ${tmp}/Tekkotsu_$1/project;
-	${MAKE};
+	${MAKE} -j2
 	if [ $? -ne 0 ] ; then
 		echo "Project Build failed for $x"
 		exit 1;
 	fi;
-	${MAKE} sim;
+	${MAKE} -j2 sim;
 	if [ $? -ne 0 ] ; then
 		echo "sim build failed for $x"
 		exit 1;
@@ -185,7 +187,7 @@
 echo "Enter memstick to be built onto for ERS-7 - this memstick will be erased";
 read -p "Press return when ready... (^C to stop)"
 
-mntmem $MEMSTICK_ROOT;
+$TEKKOTSU_ROOT/tools/mntmem $MEMSTICK_ROOT;
 rm -rf /mnt/memstick/*;
 ${MAKE} update;
 if [ $? -ne 0 ] ; then
@@ -193,10 +195,10 @@
 	exit 1;
 fi;
 
-mntmem $MEMSTICK_ROOT;
+$TEKKOTSU_ROOT/tools/mntmem $MEMSTICK_ROOT;
 rm -rf ${tmp}/Tekkotsu_memstick_ERS7_$1;
 cp -arp /mnt/memstick ${tmp}/Tekkotsu_memstick_ERS7_$1;
-umntmem $MEMSTICK_ROOT;
+$TEKKOTSU_ROOT/tools/umntmem $MEMSTICK_ROOT;
 chmod a+rx ${tmp}/Tekkotsu_memstick_ERS7_$1
 
 cd ${tmp};
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/cleanIPC ./tools/cleanIPC
--- ../Tekkotsu_2.4.1/tools/cleanIPC	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/cleanIPC	2006-03-06 17:38:57.000000000 -0500
@@ -0,0 +1,26 @@
+#!/bin/sh
+
+if [ "`whoami`" = "root" ] ; then
+	all=true;
+else
+	all=false;
+fi;
+
+if $all ; then
+	echo "Removing semaphores from all users"
+	for x in `ipcs -s | sed -n 's/^[0-9x]* *\([0-9]*\) .*/\1/p'`; do
+		echo "Removing $x...";
+		ipcrm -s $x;
+	done;
+else
+	echo "Removing semaphores for `whoami`"
+	for x in `ipcs -s | grep \`whoami\` | sed -n 's/^[0-9x]* *\([0-9]*\) .*/\1/p'`; do
+		echo "Removing $x...";
+		ipcrm -s $x;
+	done;
+	remain="`ipcs -s | sed -n 's/^[0-9x]* *\([0-9]*\) .*/\1/p'`";
+	if [ "$remain" ] ; then
+		echo "Semaphores remain for other users:";
+		ipcs -s | sed -n 's/^[0-9x]* * [0-9]* *\([^ ]*\) .*/\1/p' | sort | uniq -c
+	fi;
+fi;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/convertmot/Makefile ./tools/convertmot/Makefile
--- ../Tekkotsu_2.4.1/tools/convertmot/Makefile	2005-08-09 21:58:36.000000000 -0400
+++ ./tools/convertmot/Makefile	2006-03-28 12:08:23.000000000 -0500
@@ -25,7 +25,7 @@
 $(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))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
-include $(TEKKOTSU_ENVIRONMENT_CONFIGURATION)
+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))
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/convertmot/convertmot.cc ./tools/convertmot/convertmot.cc
--- ../Tekkotsu_2.4.1/tools/convertmot/convertmot.cc	2005-02-12 02:38:39.000000000 -0500
+++ ./tools/convertmot/convertmot.cc	2006-09-09 00:33:07.000000000 -0400
@@ -174,7 +174,7 @@
 			load_cmpack_mot(argv[i],ms);
 			if(compress)
 				ms.compress();
-			ms.SaveFile(path.c_str());
+			ms.saveFile(path.c_str());
 		}
 		used=argc;
 	} else if(argc-used==2) {
@@ -186,7 +186,7 @@
 		load_cmpack_mot(argv[used],ms);
 		if(compress)
 			ms.compress();
-		ms.SaveFile(argv[used+1]);
+		ms.saveFile(argv[used+1]);
 		used=argc;
 	} else
 		return usage(argc,argv);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/cpymem ./tools/cpymem
--- ../Tekkotsu_2.4.1/tools/cpymem	2003-04-29 23:55:58.000000000 -0400
+++ ./tools/cpymem	2006-03-27 19:54:50.000000000 -0500
@@ -1,7 +1,7 @@
 #!/bin/sh
 
 dir="ms";
-pt="/mnt/memstick";
+pt="";
 all_flag=0;
 tools=".";
 while [ $# -gt 0 ] ; do
@@ -12,12 +12,31 @@
 				--tools) tools="$2"; shift; shift;;
 				*) shift;;
 		esac;
-done;
+done
+
+if [ ! "$pt" ] ; then
+	if [ "$MEMSTICK_ROOT" ] ; then
+		pt="$MEMSTICK_ROOT";
+	else
+		case "`uname`" in
+			CYGWIN*) pt="/cygdrive/e";;
+			Darwin) d="`dirname $0`"; pt="`$d/osx_find_memstick`";;
+			*) pt="/mnt/memstick";;
+		esac
+	fi;
+fi;
 
 ${tools}/mntmem ${pt};
-if [ $all_flag -eq 1 ] ; then
-	cp -pHrv ${dir}/* $pt/
+if [ "`uname`" = "Darwin" ] ; then
+	if [ ! $all_flag -eq 1 ] ; then
+		echo "cpymem: cp 'update' unsupported on os x"
+	fi;
+	cp -pHRv ${dir}/* $pt/ || exit 1;
 else
-	cp -pHrvu ${dir}/* $pt/
+	if [ $all_flag -eq 1 ] ; then
+		cp -pHrv ${dir}/* $pt/
+	else
+		cp -pHrvu ${dir}/* $pt/
+	fi;
 fi;
 ${tools}/umntmem ${pt};
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/crashDebug ./tools/crashDebug
--- ../Tekkotsu_2.4.1/tools/crashDebug	2005-06-06 16:23:37.000000000 -0400
+++ ./tools/crashDebug	2006-03-28 19:48:04.000000000 -0500
@@ -1,4 +1,4 @@
-#!/bin/bash
+#!/bin/sh
 
 if [ "$1" = "-h" -o "$1" = "--help" -o ! -r Makefile ] ; then
 	echo "Usage: $0 [-q] [-f file] [-mipal [mi-pal_options]]";
@@ -29,7 +29,7 @@
 
 #This monstrosity will con make into parsing the environment configuration for us
 eval `make -f - <<EOF
-include $TEKKOTSU_ENVIRONMENT_CONFIGURATION
+include \\\$(shell echo "$TEKKOTSU_ENVIRONMENT_CONFIGURATION" | sed 's/ /\\ /g')
 .PHONY: all
 all:
 	@echo BUILDDIR=\\"\\\$(PROJ_BD)\\"
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/ColorControlPanel.java ./tools/easytrain/ColorControlPanel.java
--- ../Tekkotsu_2.4.1/tools/easytrain/ColorControlPanel.java	2005-08-04 16:58:05.000000000 -0400
+++ ./tools/easytrain/ColorControlPanel.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,353 +0,0 @@
-/** @file ColorControlPanel.java
- *  @brief Frame for the Control panel allowing you to switch
- *		   colors and do actions of the selected colors.
- *
- *	@author editted by: Eric Durback
- *  @bug No known bugs.
- */
-
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.util.*;
-import java.awt.geom.*;
-import java.io.*;
-import javax.swing.JScrollPane;
-import java.util.prefs.Preferences;
-
-public class ColorControlPanel extends JFrame implements ActionListener,
-    ListSelectionListener, ComponentListener 
-{
-	Container root;
-	JTextField colorname;
-	JList colorlist;
-	DefaultListModel list;
-	JScrollPane colorlistscroll;
-	JButton remove, clear, save, autoSelect, load, undo, help;
-	JCheckBox showColors,invert;
-	JFileChooser chooser;
-
-	String defaultName;
-
-	int curcolor;
-	int numDefault;
-
-	TrainCanvas trainCanvas;
-	ImageShowArea imageShow;
-
-	static Preferences prefs = Preferences.userNodeForPackage(ColorControlPanel.class);
-
-
-	public ColorControlPanel (TrainCanvas trainCanvas, ImageShowArea imageShow) 
-	{
-		this.trainCanvas=trainCanvas;
-		this.imageShow=imageShow;
-		imageShow.addMouseMotionListener(trainCanvas);
-		imageShow.addMouseListener(trainCanvas);
-		
-
-		numDefault = 1;
-		setSize(new Dimension (120,460));
-		setTitle("Control Panel");
-		setLocation(prefs.getInt("ColorControlPanel.location.x",50),prefs.getInt("ColorControlPanel.location.y",50));
-
-
-		setResizable(false);
-		root=this.getContentPane();
-		root.setLayout(new FlowLayout());
-
-		colorname=new JTextField(10);
-		colorname.addActionListener(this);
-		root.add(colorname);
-
-		list=new DefaultListModel();
-		colorlist=new JList(list);
-		colorlist.setFixedCellWidth(90);
-		colorlist.setSelectionMode(ListSelectionModel.SINGLE_SELECTION);
-		colorlist.addListSelectionListener(this);
-
-		colorlistscroll=new JScrollPane(colorlist,
-		                    JScrollPane.VERTICAL_SCROLLBAR_ALWAYS,
-		                    JScrollPane.HORIZONTAL_SCROLLBAR_NEVER);
-		root.add(colorlistscroll);
-		
-		addComponentListener(this);
-		
-		chooser = new JFileChooser();
-		chooser.setSelectedFile(new File("default"));
-		
-		//Adding Buttons
-
-		undo=new JButton("undo");
-		undo.addActionListener(this);
-		undo.setEnabled(false);
-		root.add(undo);
-
-		remove=new JButton("remove");
-		remove.addActionListener(this);
-		root.add(remove);
-
-		clear=new JButton("clear");
-		clear.addActionListener(this);
-		root.add(clear);
-
-		invert=new JCheckBox("invert");
-		invert.addActionListener(this);
-		root.add(invert);
-
-		showColors=new JCheckBox("all colors");
-		showColors.addActionListener(this);
-		root.add(showColors);
-
-		autoSelect=new JButton("auto select");
-		autoSelect.addActionListener(this);
-		//root.add(autoSelect);
-
-		help=new JButton("help");
-		help.addActionListener(this);
-		root.add(help);
-
-
-		save=new JButton("save");
-		save.addActionListener(this);
-		root.add(save);
-
-		load =new JButton("load");
-		load.addActionListener(this);
-		root.add(load);
-
-		setCurColor(-1);
-		setVisible(true);
-
-		
-	}
-
-
-	    
-	public void actionPerformed(ActionEvent e)
-	{
-		if (e.getSource()==save) 
-		{
-			
-			
-			int returnval=chooser.showSaveDialog(save);
-			if (returnval==JFileChooser.APPROVE_OPTION) 
-			{
-				try{
-					trainCanvas.save(chooser.getSelectedFile().getAbsolutePath());
-				    chooser.setSelectedFile(chooser.getSelectedFile());
-				    
-				}catch(Exception e2){}
-			}
-		}
-
-		if (e.getSource()==load) 
-		{
-			
-			int returnval=chooser.showOpenDialog(load);
-			if (returnval==JFileChooser.APPROVE_OPTION) 
-			{
-				
-				try{
-				    if(preLoad(chooser.getSelectedFile().getAbsolutePath()))
-				    {	        	
-				    	trainCanvas.load(chooser.getSelectedFile().getAbsolutePath());   
-				    	chooser.setSelectedFile(chooser.getSelectedFile());
-				    
-				    }
-				}
-				catch(Exception w){}
-
-			}
-			
-			setCurColor(0);
-		}
-		 
-		else if (e.getSource()==clear) 
-		{
-			trainCanvas.clear();
-		} 
-		else if (e.getSource()==invert) 
-		{
-			trainCanvas.invert();
-		} 
-		else if (e.getSource()==showColors) 
-		{
-			trainCanvas.showColors();
-		}
-		else if (e.getSource()==autoSelect) 
-		{
-		 	trainCanvas.autoSelect();
-		} 
-		else if (e.getSource()==undo) 
-		{
-		  	trainCanvas.undo();
-		} 
-		else if (e.getSource()==help) 
-		{
-		 	trainCanvas.help();
-		} 
-		else if (e.getSource()==remove) 
-		{
-		  	trainCanvas.remove((String)list.get(curcolor));
-		  	list.remove(curcolor);
-		  	setCurColor(-1);
-		  /*} else if (e.getSource()==imageview) {
-		imageShow.show();*/
-		} 
-		else if (e.getSource()==colorname) 
-		{
-			String s=e.getActionCommand();
-			if (!s.equals("")) 
-			{
-				int i;
-				for (i=0; i<list.getSize() && !list.get(i).equals(s); i++) {}
-				
-				if (i==list.getSize()) 
-				{
-				  list.addElement(s);
-				  colorname.setText("");
-				  colorlist.setSelectedIndex(i);
-				}
-			}
-		}
-	}
-
-	public void addDefaultColor()
-	{
-		String s="default" + numDefault++;
-		if (!s.equals("")) 
-		{
-			int i=0;
-		    while (i<list.getSize() && !list.get(i).equals(s)) 
-		    {
-		      	i++;
-		    }
-		    if (i==list.getSize()) 
-		    {
-		      	list.addElement(s);
-		      	colorname.setText("");
-		      	colorlist.setSelectedIndex(i);
-		    }
-
-		}
-	}
-
-	public void valueChanged(ListSelectionEvent e) 
-	{
-
-		if (!e.getValueIsAdjusting()) 
-		{
-			setCurColor(colorlist.getSelectedIndex());
-		}
-
-		if(colorlist.getSelectedIndex() < 0)
-		{
-			trainCanvas.setCurColor(null);
-			imageShow.setCurArea(null);
-			trainCanvas.plotImage();
-		}
-
-	}
-	//sets up the control panel for the new saved environment
-	public boolean preLoad(String filename) throws FileNotFoundException, IOException
-	{
-		int dotpos=filename.lastIndexOf('.');
-		if (dotpos>0) filename=filename.substring(0,dotpos);
-
-		BufferedReader areaFile=new BufferedReader(new FileReader(filename + ".save"));
-
-		areaFile.readLine();
-
-		int numColors = Integer.parseInt(areaFile.readLine());
-
-		//Clearing current color list
-		
-		int sizeL = list.getSize();
-
-		
-		for(int i=0; i<sizeL; i++ )
-		{
-		 
-		  	trainCanvas.remove((String)list.get(0));
-		  	list.remove(0);	
-		}
-
-		for(int j=0; j<numColors; j++)
-		{
-			String s = areaFile.readLine();
-			if (!s.equals("")) 
-		    {
-			    
-			    list.addElement(s);
-			    colorname.setText("");
-			    colorlist.setSelectedIndex(j);
-		  	}
-		}
-
-		//load all files into imageData
-		for(int i=0; i<imageShow.imglist.length; i++)
-		{
-			imageShow.imageData.setCurimg(i);
-			if(imageShow.isRGB)
-		    {
-				imageShow.imageData.loadRGBFileAsRGB(imageShow.imglist[i]);
-			
-		    }
-		 	else
-		    {
-				imageShow.imageData.loadYUVFileAsRGB(imageShow.imglist[i]);
-			
-		    }
-		}
-
-		
-
-		return true;
-
-	}
-
-	void setCurColor(int index) 
-	{
-		curcolor=index;
-
-		if (index<0) 
-		{
-		  	remove.setEnabled(false);
-		  	clear.setEnabled(false);
-		  	trainCanvas.setCurColor(null);
-		} 
-		else 
-		{
-		  	remove.setEnabled(true);
-		  	clear.setEnabled(true);
-		  	trainCanvas.setCurColor((String)list.get(curcolor));
-		}
-	}
-	
-	public void componentResized(ComponentEvent e) {}
-	public void componentHidden(ComponentEvent e) {}
-
-	public void componentMoved(ComponentEvent e)
-	{ 
-	
-		prefs.putInt("ColorControlPanel.location.x",getLocation().x);
-		prefs.putInt("ColorControlPanel.location.y",getLocation().y);
-
-	}
-	public void componentShown(ComponentEvent e) {}
-
-	public void enableUndo()
-	{
-		undo.setEnabled(true);
-	}
-
-	public void disableUndo()
-	{
-		undo.setEnabled(false);
-	}
-
-  
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/ColorConverter.java ./tools/easytrain/ColorConverter.java
--- ../Tekkotsu_2.4.1/tools/easytrain/ColorConverter.java	2005-08-03 20:27:38.000000000 -0400
+++ ./tools/easytrain/ColorConverter.java	2006-07-02 14:50:56.000000000 -0400
@@ -1,13 +1,411 @@
+import java.awt.Color;
+import java.util.Vector;
+import java.util.Iterator;
+
 public abstract class ColorConverter 
-{
-  	ColorConverter() { }
-  	public final float[] getColor(int rgb) 
-  	{
-	    int r=(rgb>>16)&0xff;
-	    int g=(rgb>>8)&0xff;
-	    int b=rgb&0xff;
-	    return getColor(r, g, b);
-  	}
-  	public abstract float[] getColor(int r, int g, int b);
-}
+{ 
+	static float[] temp=new float[3];
+	protected int components;
+	public ColorConverter() { components=3; }
+	public final int getComponents() { return components; }
+	float clip(float x) {
+		return (x>=1?1:(x<=0?0:x));
+	}
+	float clip(int x) {
+		return (x>=255?255:(x<=0?0:x));
+	}
+	public final float[] getColor(int c,float[] out) 
+	{
+		int c1=(c>>16)&0xff;
+		int c2=(c>>8)&0xff;
+		int c3=c&0xff;
+		return getColor(c1, c2, c3,out);
+	}
+	public int getColor(int c) {
+		int c1=(c>>16)&0xff;
+		int c2=(c>>8)&0xff;
+		int c3=c&0xff;
+		return getColor(c1, c2, c3);
+	}
+	public int getColor(int c1, int c2, int c3) {
+		getColor(c1,c2,c3,temp);
+		return (Math.round(temp[0]*255)<<16) | (Math.round(temp[1]*255)<<8) | (Math.round(temp[2]*255));
+	}
+	public abstract float[] getColor(int c1, int c2, int c3, float[] out);
+	public abstract float[] getColor(float c1, float c2, float c3, float[] out);
+
+
+	public static class Compose extends ColorConverter {
+		Vector v;
+		public Compose() {
+			super();
+			v=new Vector();
+		}
+		public Compose(ColorConverter cc1, ColorConverter cc2) {
+			super();
+			v=new Vector();
+			v.add(cc1);
+			v.add(cc2);
+		}
+		
+		public void add(ColorConverter cc) { v.add(cc); }
+		
+		public final float[] getColor(int c1,int c2,int c3, float[] out) { return getColor(c1/255.f,c2/255.f,c3/255.f,out); }
+		
+		public final float[] getColor(float c1, float c2, float c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			out[0]=c1; out[1]=c2; out[2]=c3;
+			for(Iterator it=v.iterator(); it.hasNext();)
+				((ColorConverter)it.next()).getColor(out[0],out[1],out[2],out);
+			return out;
+		}
+	}
+	
+	//use null instead
+	/*
+	public static class PassThrough extends ColorConverter {
+		public final float[] getColor(int r, int g, int b, float[] out) {
+			if(out==null)
+				out=new float[3];
+			out[0]=r/255.f;
+			out[1]=g/255.f;
+			out[2]=b/255.f;
+			return out;
+		}
+		public final float[] getColor(float r, float g, float b, float[] out) {
+			if(out==null)
+				out=new float[]{r,g,b};
+			else {
+				out[0]=r;
+				out[1]=g;
+				out[2]=b;
+			}
+			return out;
+		}
+	}
+	*/
+	
+	public static class RGBtoHSB extends ColorConverter {
+		public final float[] getColor(int r, int g, int b, float[] hsb) {
+			return Color.RGBtoHSB(r, g, b, hsb);
+		}
+		public final float[] getColor(float r, float g, float b, float[] hsb) {
+			return Color.RGBtoHSB((int)(r*255), (int)(g*255), (int)(b*255), hsb);
+		}
+	}
+	public static class HSBtoRGB extends ColorConverter {
+		public final float[] getColor(int c1,int c2,int c3, float[] out) { return getColor(c1/255.f,c2/255.f,c3/255.f,out); }
+		public final float[] getColor(float h, float s, float b, float[] rgb) {
+			if(rgb==null)
+				rgb=new float[3];
+			int res=Color.HSBtoRGB(h, s, b);
+			rgb[0]=((res>>16)&0xff)/255.f;
+			rgb[1]=((res>>8)&0xff)/255.f;
+			rgb[2]=(res&0xff)/255.f;
+			return rgb;
+		}			
+	}
+	public static class RGBtoRotatedHSB extends ColorConverter {
+		final static float rotation=.2f;
+		public final float[] getColor(int r, int g, int b, float[] hsb) {
+			hsb=Color.RGBtoHSB(r, g, b, hsb);
+			hsb[0]+=rotation;
+			if(hsb[0]>1)
+				hsb[0]-=1;
+			return hsb;
+		}
+		public final float[] getColor(float r, float g, float b, float[] hsb) {
+			hsb=Color.RGBtoHSB((int)(r*255), (int)(g*255), (int)(b*255), hsb);
+			hsb[0]+=rotation;
+			if(hsb[0]>1)
+				hsb[0]-=1;
+			return hsb;
+		}
+	}
+	
+	//these formulas are from http://en.wikipedia.org/wiki/YCbCr
+	//The Y channel on the AIBO is scaled to [16-235] (inclusive)
+	// so it's actually YCbCr, not YUV -- thus these formulas are for YCbCr, not YUV
+	//I think some values might be off by 1 -- it's confusing whether to scale by 255 or 256, can change rounding direction
+	public static class RGBtoUVY extends ColorConverter {
+		public final float[] getColor(int R,int G,int B, float[] out) {
+			if(out==null)
+				out=new float[3];
+			out[2] = clip(((66*R +  129*G +  25*B)>>8)+16) / 255.f;
+			out[0] = clip(((-38*R -   74*G + 112*B)>>8)+128) / 255.f;
+			out[1] = clip(((112*R -   94*G -  18*B)>>8)+128) / 255.f;
+			return out;
+		}
+		public final float[] getColor(float R,float G,float B, float[] out) {
+			if(out==null)
+				out=new float[3];
+			out[2] = clip( .2567891f*R + .5041289f*G + .0979062f*B + .0625f );
+			out[0] = clip( -.1482227f*R -.2909922f*G + .4392148f*B + .5f );
+			out[1] = clip( .4392148f*R -.3677891f*G  -.0714258f*B + .5f );
+			return out;
+		}
+	}
+	//inverted from http://en.wikipedia.org/wiki/YCbCr
+	public static class YUVtoRGB extends ColorConverter {
+		//final static ColorSpace cs=new ICC_ColorSpace(ICC_Profile.getInstance(ColorSpace.CS_PYCC));
+		public final float[] getColor(int y,int u,int v, float[] out) {
+			if(out==null)
+				out=new float[3];
+			out[0]=clip( ((298*y + 0*u + 409*v) >> 8) - 223 )/255.f;
+			out[1]=clip( ((298*y - 100*u - 208*v) >> 8) + 136)/255.f;
+			out[2]=clip( ((298*y + 516*u + 0*v) >> 8) - 227)/255.f;
+			return out;
+		}
+		public final float[] getColor(float y,float u,float v, float[] out) {
+			if(out==null)
+				out=new float[3];
+			out[0]=clip( 1.1644f*y + 0*u + 1.5960f*v - 0.8708f );
+			out[1]=clip( 1.1644f*y - 0.3918f*u - 0.8130f*v + 0.5296f );
+			out[2]=clip( 1.1644f*y + 2.0172f*u + 0*v - 1.0814f );
+			return out;
+		}
+	}
+		
+	
+	// this isn't the "real" conversion, nor a quick approx, but
+	// it will get as close as possible to an exact undo of the YUV2RGB conversion
+	// we use in VisionListener, so images saved from there will be
+	// loaded without distorting color information (too much)
+	public static class VisionListenerRGBtoYUV extends ColorConverter {
+		public final float[] getColor(int r,int g,int b, float[] out) {
+			if(out==null)
+				out=new float[3];
+			out[0]=clip( ( 8*r + 16*g  +  3*b)/(27.f * 255.f) );
+			out[1]=clip( (-4*r  -  8*g  + 12*b + 3456)/(27.f * 255.f) ); 
+			out[2]=clip( (19*r - 16*g  -   3*b + 3456)/(27.f * 255.f) );
+			//if (y<0) y=0; if (u<0) u=0; if (v<0) v=0;
+			//if (y>255) y=255; if (u>255) u=255; if (v>255) v=255;
+			return out;
+		}
+		public final float[] getColor(float r,float g,float b, float[] out) { return getColor((int)(r*255),(int)(g*255),(int)(b*255),out); }
+	}
 
+	// this isn't the "real" conversion, but a quick approx.
+	// it's the same that's used in tekkotsumon's VisionListener
+	public static class YUVtoVisionListenerRGB extends ColorConverter {
+		public final float[] getColor(int y,int u,int v, float[] out) {
+			if(out==null)
+				out=new float[3];
+			u=u*2-256;
+			v=v-128;
+			int b=y+u;
+			int r=y+v;
+			v=v>>1;
+			u=(u>>2)-(u>>4);
+			int g=y-u-v;
+			if (r<0) r=0; if (g<0) g=0; if (b<0) b=0;
+			if (r>255) r=255; if (g>255) g=255; if (b>255) b=255;
+			out[0]=r/255.f; out[1]=g/255.f; out[2]=b/255.f;
+			return out;
+		}
+		public final float[] getColor(float y,float u,float v, float[] out) { return getColor((int)(y*255),(int)(u*255),(int)(v*255),out); }
+	}
+	
+	public static class RGBtoxy_ extends ColorConverter {
+		final static ColorConverter.RGBtoXYZ toXYZ=new ColorConverter.RGBtoXYZ();
+		public final float[] getColor(int c1, int c2, int c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			toXYZ.getColor(c1,c2,c3,out);
+			float s=out[0]+out[1]+out[2];
+			out[0]=clip(out[0]/s);
+			out[1]=clip(out[1]/s);
+			return out;
+		}
+		public final float[] getColor(float c1, float c2, float c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			toXYZ.getColor(c1,c2,c3,out);
+			float s=out[0]+out[1]+out[2];
+			out[0]=clip(out[0]/s);
+			out[1]=clip(out[1]/s);
+			return out;
+		}
+	}
+	
+	public static class RGBtorg_ extends ColorConverter {
+		final static ColorConverter.RGBtoXYZ toXYZ=new ColorConverter.RGBtoXYZ();
+		public final float[] getColor(int c1, int c2, int c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			float s=c1+c2+c3;
+			out[0]=clip(c1/s);
+			out[1]=clip(c2/s);
+			return out;
+		}
+		public final float[] getColor(float c1, float c2, float c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			float s=c1+c2+c3;
+			out[0]=clip(c1/s);
+			out[1]=clip(c2/s);
+			return out;
+		}
+	}
+	
+	public static class RGBtoabL extends ColorConverter {
+		final static ColorConverter.RGBtoXYZ toXYZ=new ColorConverter.RGBtoXYZ();
+		final static ColorConverter.XYZtoabL toLab=new ColorConverter.XYZtoabL();
+		public final float[] getColor(int c1, int c2, int c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			toXYZ.getColor(c1,c2,c3,out);
+			toLab.getColor(out[0],out[1],out[2],out);
+			out[0]=clip( out[0]+.5f );
+			out[1]=clip( out[1]+.5f );
+			return out;
+		}
+		public final float[] getColor(float c1, float c2, float c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			toXYZ.getColor(c1,c2,c3,out);
+			toLab.getColor(out[0],out[1],out[2],out);
+			out[0]=clip( out[0]+.5f );
+			out[1]=clip( out[1]+.5f );
+			return out;
+		}
+	}
+	
+	
+	public static class RGBtoXYZ extends ColorConverter {
+		final static float a=0.055f;
+		final static float g=2.4f;
+		static final int lookupRes=1024;
+		static float[] powLookup=null;
+		public RGBtoXYZ() {
+			super();
+			if(powLookup==null) {
+				powLookup=new float[lookupRes];				
+				for(int i=0; i<lookupRes; i++) {
+					float K=i/(float)(lookupRes-1);
+					if(K>0.04045f) {
+						powLookup[i]=(float)Math.pow((K+a)/(1+a),g);
+					} else {
+						powLookup[i]=K/12.92f;
+					}
+				}
+			}
+		}
+		final static float f(float K) {
+			return powLookup[(int)(K*(lookupRes-1))];
+		}
+		public final float[] getColor(int c1, int c2, int c3, float[] out) {
+			return getColor(c1/255.f,c2/255.f,c3/255.f,out);
+		}
+		public final float[] getColor(float c1, float c2, float c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			float r=f(c1);
+			float g=f(c2);
+			float b=f(c3);
+			out[0]=0.412424f*r + 0.357579f*g + 0.180464f*b;
+			out[1]=0.212656f*r + 0.715158f*g + 0.072186f*b;
+			out[2]=0.019332f*r + 0.119193f*g + 0.950444f*b;
+			return out;
+		}
+	}
+	
+	public static class XYZtoabL extends ColorConverter {
+		static final float Xn=0.31382f;
+		static final float Yn=0.33100f;
+		static final float Zn=(1-Xn-Yn);
+		static final int lookupRes=1024;
+		static float[] powLookup=null;
+		public XYZtoabL() {
+			super();
+			if(powLookup==null) {
+				powLookup=new float[lookupRes];				
+				for(int i=0; i<lookupRes; i++)
+					powLookup[i]=(float)Math.pow(4*i/(float)(lookupRes-1),1.0/3.0);
+			}
+		}
+		final static float f(float t) {
+			if(t>0.008856f) {
+				return powLookup[(int)(t/4*(lookupRes-1))];
+			} else {
+				return 7.787f*t + 16.f/116.f;
+			}
+		}
+		public final float[] getColor(int c1, int c2, int c3, float[] out) {
+			return getColor(c1/255.f,c2/255.f,c3/255.f,out);
+		}
+		public final float[] getColor(float c1, float c2, float c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			out[2]=116.f/256.f*f(c2/Yn)-16/156.f;
+			out[0]=500.f/256.f*(f(c1/Xn)-f(c2/Yn));
+			out[1]=200.f/256.f*(f(c2/Yn)-f(c3/Zn));
+			return out;
+		}
+	}
+	
+	public static class YUVtoOther extends ColorConverter {
+		ColorConverter cc;
+		final static ColorConverter.YUVtoRGB toRGB=new ColorConverter.YUVtoRGB();
+		public YUVtoOther(ColorConverter cc) {
+			super();
+			this.cc=cc;
+		}
+		public final float[] getColor(int c1, int c2, int c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			toRGB.getColor(c1,c2,c3,out);
+			return cc.getColor(out[0],out[1],out[2],out);
+		}
+		public final float[] getColor(float c1, float c2, float c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			toRGB.getColor(c1,c2,c3,out);
+			return cc.getColor(out[0],out[1],out[2],out);
+		}
+	}
+	
+	public static class YUVtoUVY extends ColorConverter {
+		public final float[] getColor(int c1, int c2, int c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			out[0]=c2/255.f;
+			out[1]=c3/255.f;
+			out[2]=c1/255.f;
+			return out;
+		}
+		public final float[] getColor(float c1, float c2, float c3, float[] out) {
+			if(out==null)
+				out=new float[3];
+			out[0]=c2;
+			out[1]=c3;
+			out[2]=c1;
+			return out;
+		}
+	}
+	
+	public static class Scale extends ColorConverter {
+		ColorConverter cc;
+		float s;
+		public Scale(ColorConverter cc, float s) {
+			super();
+			this.cc=cc;
+			this.s=s;
+		}
+		public final float[] getColor(int c1, int c2, int c3, float[] out) {
+			float[] o=cc.getColor(c1,c2,c3,out);
+			o[0]=clip(o[0]*s);
+			o[1]=clip(o[1]*s);;
+			o[2]=clip(o[2]*s);;
+			return o;
+		}
+		public final float[] getColor(float c1, float c2, float c3, float[] out) {
+			float[] o=cc.getColor(c1,c2,c3,out);
+			o[0]=clip(o[0]*s);;
+			o[1]=clip(o[1]*s);;
+			o[2]=clip(o[2]*s);;
+			return o;
+		}
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/EasyTrain.java ./tools/easytrain/EasyTrain.java
--- ../Tekkotsu_2.4.1/tools/easytrain/EasyTrain.java	2005-08-04 16:58:05.000000000 -0400
+++ ./tools/easytrain/EasyTrain.java	2006-07-02 14:36:36.000000000 -0400
@@ -17,53 +17,347 @@
 http://java.sun.com/j2se/1.5.0/install-linux.html 
 **************************
 
-
 TODO
 
-1. array of thumbnails - long term
+-redraw on resize
+-resize stopping over another window
 
-2. loading with incorrect images
 */
 
 
-import java.awt.image.*;
 import java.awt.*;
 import javax.swing.*;
 import javax.swing.event.*;
+import javax.swing.undo.UndoManager;
+import javax.swing.undo.UndoableEdit;
+import javax.swing.undo.UndoableEditSupport;
+import javax.swing.undo.AbstractUndoableEdit;
 import java.awt.event.*;
 import java.util.*;
 import java.awt.geom.*;
 import java.io.*;
 import java.util.prefs.Preferences;
+import java.util.Vector;
+import java.beans.PropertyChangeListener;
+import java.beans.PropertyChangeEvent;
 
-public class EasyTrain extends JFrame implements ComponentListener
+public class EasyTrain extends JFrame implements ComponentListener, ImageSelectionManager.SelectionListener,
+ActionListener, ListSelectionListener, PropertyChangeListener, ListDataListener, DocumentListener, UndoableEditListener
 {
-	int height=700, width=700;
-	public ColorControlPanel controlPanel;
-	public static ColorConverter colorConverter;
-
+	static WindowAdapter exitOnClose=new WindowAdapter() { public void windowClosing(WindowEvent e) { System.exit(0); } };
 	static Preferences prefs = Preferences.userNodeForPackage(EasyTrain.class);
 
+	static String specExt=".spc";
+
+	ImageData imageData;
+	ColorConverter toRGB,toYUV,YUVtoSpectrum;
+	
+	SpectrumViewer spectrumFrame;
+	ImagePanel spectrum;
+	ImageSelectionManager spectrumSelection;
+	ImageSelectionManager rgbSelection;
+	
+	String space;
+	JComboBox spacelist;
+
+	ThumbnailShow thumb;
+	ImageViewer rgbImageShow;
+	SegmentedImage segmentedImageShow;
+	HelpBox helpBox;
+	HintController hc;
+	
+	Vector imageAreas; //collection of Area[]s, one per color, one Area per image file
+	Vector colorAreas; //collection of Areas, one per color
+	
+	KeyedUndoManager undoManager;
+	UndoableEditSupport undoListeners;
+	
+	class HintController extends MouseInputAdapter {
+		ImagePanel spectrum;
+		ImageData data;
+		Vector panels;
+		float[] img;
+		int width;
+		int height;
+		
+		public HintController(ImagePanel spectrum) {
+			this.spectrum=spectrum;
+			this.data=data;
+			panels=new Vector();
+		}
+		public void addImagePanel(ImagePanel img) {
+			panels.add(img);
+			addMouseEventSource(img);
+		}
+		public void addMouseEventSource(Component evtSrc) {
+			evtSrc.addMouseListener(this);
+			evtSrc.addMouseMotionListener(this);
+		}
+		public void setImage(float[] img, int width, int height) {
+			this.img=img;
+			this.width=width;
+			this.height=height;
+		}
+		public void mouseMoved(MouseEvent e) {
+			Point p=e.getPoint();
+			double x=(p.getX()+.5)/e.getComponent().getWidth();
+			double y=(p.getY()+.5)/e.getComponent().getHeight();
+			Point2D.Double p2d=new Point2D.Double(x,y);
+			for(Iterator it=panels.iterator(); it.hasNext();) {
+				ImagePanel cur=(ImagePanel)it.next();
+				if(cur!=e.getComponent()) {
+					cur.setHint(p2d);
+				}
+			}
+			int px=(int)(x*width);
+			int py=(int)(y*height);
+			int i=(py*width+px)*3;
+			spectrum.setHint(new Point2D.Float(img[i],img[i+1]));
+		}
+		public void mouseDragged(MouseEvent e) {
+			Point p=e.getPoint();
+			Component c=e.getComponent();
+			if(p.getX()<0 || p.getX()>=c.getWidth() || p.getY()<0 || p.getY()>=c.getHeight()) {
+				//in case a drag goes outside
+				for(Iterator it=panels.iterator(); it.hasNext();)
+					((ImagePanel)it.next()).setHint(null);
+				spectrum.setHint(null);
+			} else {
+				mouseMoved(e);
+			}
+		}
+		public void mouseExited(MouseEvent e) {
+			for(Iterator it=panels.iterator(); it.hasNext();)
+				((ImagePanel)it.next()).setHint(null);
+			spectrum.setHint(null);
+		}
+	}
+	
+	class KeyedUndoManager extends UndoManager implements KeyListener {
+		JComponent undoBut,redoBut;
+		KeyedUndoManager(JComponent undoBut, JComponent redoBut) {
+			super();
+			this.undoBut=undoBut;
+			this.redoBut=redoBut;
+		}
+		public boolean addEdit(UndoableEdit anEdit) {
+			boolean ans=super.addEdit(anEdit);
+			refreshButtons();
+			return ans;
+		}
+		public void undoableEditHappened(UndoableEditEvent e) {
+			super.undoableEditHappened(e);
+			refreshButtons();
+		}
+		public void undo() {
+			super.undo();
+			refreshButtons();
+		}
+		public void redo() {
+			super.redo();
+			refreshButtons();
+		}
+		public void keyPressed(KeyEvent e) {
+			if((e.getModifiersEx()&(InputEvent.META_DOWN_MASK|InputEvent.CTRL_DOWN_MASK))!=0) {
+				if(e.getKeyCode()==KeyEvent.VK_Z) {
+					if((e.getModifiersEx()&(InputEvent.SHIFT_DOWN_MASK))!=0) {
+						//System.out.println("canRedo()=="+canRedo());
+						if(canRedo())
+							redo();
+					} else {
+						//System.out.println("canUndo()=="+canUndo());
+						if(canUndo())
+							undo();
+					}
+				}
+			}
+		}
+		public void keyReleased(KeyEvent e) {} 
+		public void keyTyped(KeyEvent e) {}
+		void refreshButtons() {
+			if(undoBut!=null)
+				undoBut.setEnabled(canUndo());
+			if(redoBut!=null)
+				redoBut.setEnabled(canRedo());
+		}
+	}
+
+	class ListSelectionEdit extends AbstractUndoableEdit {
+		EasyTrain src;
+		int previous, next;
+		ListSelectionEdit(EasyTrain src, int previous, int next) {
+			super();
+			this.src=src;
+			this.previous=previous;
+			this.next=next;
+		}
+		public void redo() {
+			super.redo();
+			//System.out.println("Redo: "+this);
+			src.setIgnoreUndoRedo(true);
+			if(next<0)
+				src.colorlist.getSelectionModel().clearSelection();
+			else
+				src.colorlist.setSelectedIndex(next);
+			src.setIgnoreUndoRedo(false);
+		}
+		public void undo() {
+			super.undo();
+			//System.out.println("Undo: "+this);
+			src.setIgnoreUndoRedo(true);
+			if(previous<0)
+				src.colorlist.getSelectionModel().clearSelection();
+			else
+				src.colorlist.setSelectedIndex(previous);
+			src.setIgnoreUndoRedo(false);
+		}
+		public boolean isSignificant() {
+			return false;
+		}
+		public String toString() {
+			return super.toString()+" previous:"+previous+" next:"+next;
+		}
+	}
+	class AddColorEdit extends AbstractUndoableEdit {
+		EasyTrain src;
+		String name;
+		int index;
+		AddColorEdit(EasyTrain src, String name, int index) {
+			this.src=src;
+			this.name=name;
+			this.index=index;
+			//System.out.println("AddColorEdit("+src+","+name+","+index+")");
+		}
+		public void redo() {
+			super.redo();
+			//System.out.println("Redo: "+this);
+			src.setIgnoreUndoRedo(true);
+			src.list.add(index,name); //list listener should add (empty) entries for colorAreas and imageAreas
+			src.setIgnoreUndoRedo(false);
+		}
+		public void undo() {
+			super.undo();
+			//System.out.println("Undo: "+this);
+			src.setIgnoreUndoRedo(true);
+			src.list.remove(index); //list listener should remove entries for colorAreas and imageAreas
+			src.setIgnoreUndoRedo(false);
+		}
+		public String toString() {
+			return super.toString()+" name:"+name+" position:"+index;
+		}
+	}
+	class RemoveColorEdit extends AbstractUndoableEdit {
+		EasyTrain src;
+		String name;
+		int index;
+		Area colorArea;
+		Area[] imageAreas;
+		RemoveColorEdit(EasyTrain src, String name, int index, Area colorArea, Area[] imageAreas) {
+			this.src=src;
+			this.name=name;
+			this.index=index;
+			this.colorArea=colorArea;
+			this.imageAreas=imageAreas;
+		}
+		public void redo() {
+			super.redo();
+			//System.out.println("Redo: "+this);
+			src.setIgnoreUndoRedo(true);
+			src.list.remove(index); //list listener should remove entries for colorAreas and imageAreas
+			src.colorlist.getSelectionModel().clearSelection();
+			src.segmentedImageShow.updateMap(src.colorAreas);
+			src.setIgnoreUndoRedo(false);
+		}
+		public void undo() {
+			super.undo();
+			//System.out.println("Undo: "+this);
+			src.setIgnoreUndoRedo(true);
+			src.list.add(index,name);//list listener should add (empty) entries for colorAreas and imageAreas
+			src.colorAreas.setElementAt(colorArea,index);
+			src.imageAreas.setElementAt(imageAreas,index);
+			src.colorlist.setSelectedIndex(index);
+			src.segmentedImageShow.updateMap(src.colorAreas);
+			src.setIgnoreUndoRedo(false);
+		}
+		public String toString() {
+			return super.toString()+" name:"+name+" index:"+index;
+		}
+	}
+	class RenameColorEdit extends AbstractUndoableEdit {
+		EasyTrain src;
+		String prevname;
+		String newname;
+		int index;
+		RenameColorEdit(EasyTrain src, String prevname, String newname, int index) {
+			this.src=src;
+			this.prevname=prevname;
+			this.newname=newname;
+			this.index=index;
+		}
+		public void redo() {
+			super.redo();
+			//System.out.println("Redo: "+this);
+			src.setIgnoreUndoRedo(true);
+			src.list.setElementAt(newname,index);
+			src.colorlist.setSelectedIndex(index);
+			src.valueChanged(null);
+			src.setIgnoreUndoRedo(false);
+		}
+		public void undo() {
+			super.undo();
+			//System.out.println("Undo: "+this);
+			src.setIgnoreUndoRedo(true);
+			src.list.setElementAt(prevname,index);
+			src.colorlist.setSelectedIndex(index);
+			src.valueChanged(null);
+			src.setIgnoreUndoRedo(false);
+		}
+		public boolean addEdit(UndoableEdit anEdit) {
+			if(anEdit instanceof RenameColorEdit) {
+				RenameColorEdit rename=(RenameColorEdit)anEdit;
+				if(rename.src!=src || rename.index!=index)
+					return false;
+				newname=rename.newname;
+				rename.die();
+				return true;
+			}
+			return false;
+		}
+		public boolean replaceEdit(UndoableEdit anEdit) {
+			if(anEdit instanceof RenameColorEdit) {
+				RenameColorEdit rename=(RenameColorEdit)anEdit;
+				if(rename.src!=src || rename.index!=index)
+					return false;
+				prevname=rename.prevname;
+				rename.die();
+				return true;
+			}
+			return false;
+		}
+		public String toString() {
+			return super.toString()+" prevname:"+prevname+" newname:"+newname+" index:"+index;
+		}
+	}
+	public void addUndoableEditListener(UndoableEditListener l) { undoListeners.addUndoableEditListener(l); }
+	public void removeUndoableEditListener(UndoableEditListener l) { undoListeners.removeUndoableEditListener(l); }
+	
+	boolean ignoreUndoRedo;
+	void setIgnoreUndoRedo(boolean b) { ignoreUndoRedo=b; }
+	boolean getIgnoreUndoRedo() { return ignoreUndoRedo; }
+	public void undoableEditHappened(UndoableEditEvent e) {
+		if(!getIgnoreUndoRedo()) {
+			//System.out.println("Add Edit: "+e.getEdit());
+			undoManager.addEdit(e.getEdit());
+		}
+	}
+	
 	public static void main(String args[]) 
 	{
-		if (args.length<1) 
+		if (args.length<2) 
 		{
 			usageAndExit();
 		}
 
-		colorConverter=new ColorConverter() 
-		{
-			public final float[] getColor(int r, int g, int b) 
-			{
-				float[] hsb=new float[3];
-				Color.RGBtoHSB(r, g, b, hsb);
-				float[] res=new float[2];
-				res[0]=hsb[0];
-				res[1]=hsb[1];
-				return res;
-			}
-		};
-
 		boolean isRGB=true;
 		if(args[0].equals("-isRGB"))
 			isRGB=true;
@@ -74,119 +368,853 @@
 			System.out.println(args[0]+" is not valid color mode");
 			usageAndExit();
 		}
-			//get picture files
-		String files[]=new String[args.length-1];
-		for(int i=0; i<files.length; i++)
-			files[i]=args[i+1];
+		String[] files;
+		String space="HSB";
+		if(args[1].equals("-show")) {
+			space=args[2];
+			if(!space.equalsIgnoreCase("YUV") && !space.equalsIgnoreCase("xy") && !space.equalsIgnoreCase("Lab") && !space.equalsIgnoreCase("HSB") && !space.equalsIgnoreCase("rg"))
+				usageAndExit();
+			files=new String[args.length-3];
+			for(int i=0; i<files.length; i++)
+				files[i]=args[i+3];
+		} else {
+			files=new String[args.length-1];
+			for(int i=0; i<files.length; i++)
+				files[i]=args[i+1];
+		}
 			
 		//init training tool
-		EasyTrain easyTrain = new EasyTrain(isRGB,files);
+		EasyTrain easyTrain = new EasyTrain(isRGB,space,files);
 		
-		easyTrain.addWindowListener(new WindowAdapter() {
-		    public void windowClosing(WindowEvent e) { System.exit(0); } });
-		easyTrain.controlPanel.addWindowListener(new WindowAdapter() {
-		    public void windowClosing(WindowEvent e) { System.exit(0); } });
+		easyTrain.addWindowListener(exitOnClose);
 	}
 
 	public static void usageAndExit() 
 	{
-		System.out.println("usage: java EasyTrain (-isRGB|-isYUV) filename [filename ..]");
-		System.out.println("       Using YUV images is recommended.");
+		System.out.println("usage: java EasyTrain (-isRGB|-isYUV) [-show YUV|HSB|rg|xy|Lab] filename [filename ..]");
+		System.out.println("       Select YUV mode if you use PNG images, RGB with JPEG.");
+		System.out.println("       Using PNG format images is recommended.");
 		System.out.println("       A mode must be specified.");
 		System.exit(1);
 	}
 
-	public EasyTrain(boolean isRGB, String files[]) 
+	public EasyTrain(boolean isRGB, String space, String files[]) 
 	{
 		System.out.println("Interpreting images as "+(isRGB?"RGB":"YUV")+" colorspace");
+		System.out.println("Displaying spectrum as "+space+" colorspace");
 
-		//opening image panel
-
+		
+		//INITIALIZING PREFS
 		try{
-		if(prefs.keys() == null) //no prefs yet
+			if(prefs.keys() == null || prefs.keys().length==0) //no prefs yet
 		{
 			setDefaultPrefs();    
 		}
 		}catch(Exception e){}
-
-		setBackground(Color.black);
-		setSize(new Dimension(width, height));
-		setLocation(prefs.getInt("EasyTrain.location.x",50),prefs.getInt("EasyTrain.location.y",50));
-		setTitle("Color Spectrum");
-		Container root=this.getContentPane();
-		root.setLayout(new BorderLayout());
-
-		ImageData imageData=new ImageData(files.length);
-		ImageData YUVimageData = new ImageData(files.length);
-
-		//Thanks to martin.mueller at mni.fh-giessen.de for the bug fix:
-		if(isRGB)
-		{
-			imageData.loadRGBFileAsRGB(files[0]);
-			YUVimageData.loadRGBFileAsYUV(files[0]);
-		}
-		else
-		{ 
-			imageData.loadYUVFileAsRGB(files[0]);
-			YUVimageData.loadYUVFileAsYUV(files[0]);
+		
+		//LOADING IMAGES
+		toRGB=toYUV=YUVtoSpectrum=null;
+		if(isRGB) {
+			toYUV = new ColorConverter.VisionListenerRGBtoYUV();
+		} else {
+			toRGB = new ColorConverter.YUVtoRGB();
 		}
+		setSpace(space);
+		//System.out.println("Press return to continue...");
+		//try { System.in.read(); } catch(Exception e) {}
+		//System.out.println("Loading...");
+		imageData=new ImageData(files,toRGB,toYUV,YUVtoSpectrum);
+		//System.out.println("done");
+		imageAreas=new Vector();
+		colorAreas=new Vector();
+		undoManager=new KeyedUndoManager(null,null);
+		undoListeners=new UndoableEditSupport();
+		addUndoableEditListener(this);
+		
+		//INIT MAIN COMPONENTS
+		setupSpectrumFrame();
+		setupRGBImageShow();
+		setupSegmentedImageShow();
+		helpBox = new HelpBox();
+		thumb = new ThumbnailShow(imageData);
+		thumb.addKeyListener(undoManager);
+		thumb.addUndoableEditListener(this);
+		setupControlPanel((JComponent)getContentPane());
+		
+		hc = new HintController(spectrum);
+		hc.setImage(imageData.getSpectrumImage(0),imageData.getWidth(0),imageData.getHeight(0));
+		hc.addImagePanel(rgbImageShow.getDisplay());
+		hc.addImagePanel(segmentedImageShow.getDisplay());
+		
+		rgbImageShow.addKeyListener(thumb);
+		segmentedImageShow.addKeyListener(thumb);
+		spectrumFrame.addKeyListener(thumb);
+		thumb.addPropertyChangeListener(ThumbnailShow.CURIMG_PROPERTY,this);
 
-		ImageShowArea imageShow=new ImageShowArea(isRGB,files,imageData);
+		rgbImageShow.addWindowListener(exitOnClose);
+		segmentedImageShow.addWindowListener(exitOnClose);
+		spectrumFrame.addWindowListener(exitOnClose);		
 		
-		SegmentedImage segImage = new SegmentedImage(YUVimageData,imageShow);
-		segImage.setSize(imageShow.getSize());
+		colorlist.requestFocusInWindow();
+		colorlist.setSelectedIndex(0);
+		undoManager.discardAllEdits(); //don't want to be able to undo past initialization!
+		undoManager.undoBut=undo;
+		
+		thumb.setVisible(true);
+		rgbImageShow.setVisible(true);
+		restoreFromPrefs(rgbImageShow);
+		rgbImageShow.addComponentListener(this);
+		segmentedImageShow.setVisible(true);
+		restoreFromPrefs(segmentedImageShow);
+		segmentedImageShow.addComponentListener(this);
+		spectrumFrame.setVisible(true);
+		restoreFromPrefs(spectrumFrame);
+		spectrumFrame.addComponentListener(this);
+		setVisible(true);
+	}
+	
+	void setSpace(String space) {
+		this.space=space;
+		if(space.equalsIgnoreCase("YUV")) {
+			YUVtoSpectrum = new ColorConverter.YUVtoUVY();
+		} else if(space.equalsIgnoreCase("xy")) {
+			YUVtoSpectrum = new ColorConverter.Scale(new ColorConverter.YUVtoOther(new ColorConverter.RGBtoxy_()),1.5f);
+		} else if(space.equalsIgnoreCase("Lab")) {
+			YUVtoSpectrum = new ColorConverter.YUVtoOther(new ColorConverter.RGBtoabL());
+		} else if(space.equalsIgnoreCase("HSB")) {
+			YUVtoSpectrum = new ColorConverter.YUVtoOther(new ColorConverter.RGBtoRotatedHSB());
+		} else if(space.equalsIgnoreCase("rg")) {
+			YUVtoSpectrum = new ColorConverter.YUVtoOther(new ColorConverter.RGBtorg_());
+		} else {
+			usageAndExit();
+		}
+	}
+	
+	void setupRGBImageShow() {
+		rgbImageShow = new ImageViewer("RGB Image View");
+		rgbImageShow.setImage(imageData.getRGBImage(0));
+		rgbImageShow.setName("RGBImageShow");
+		restoreFromPrefs(rgbImageShow);
+		JComponent comp=rgbImageShow.getDisplay();
+		comp.setLayout(new BorderLayout());
+		rgbSelection=new ImageSelectionManager(comp);
+		rgbImageShow.addKeyListener(rgbSelection);
+		rgbImageShow.addKeyListener(undoManager);
+		rgbSelection.addSelectionListener(this);
+		rgbSelection.addUndoableEditListener(this);
+		comp.add(rgbSelection,BorderLayout.CENTER);
+	}
+	
+	void setupSegmentedImageShow() {
+		ThresholdMap tmap=new ThresholdMap(YUVtoSpectrum,16,64,64);
+		segmentedImageShow = new SegmentedImage("Segmented Image View",tmap);
+		segmentedImageShow.setImage(imageData.getYUVImage(0),imageData.getWidth(0),imageData.getHeight(0));
+		segmentedImageShow.setName("SegmentedImageShow");
+		restoreFromPrefs(segmentedImageShow);
+		segmentedImageShow.addKeyListener(undoManager);
+	}
+	
+	void setupSpectrumFrame() {
+		spectrumFrame=new SpectrumViewer("Color Spectrum",20);
+		spectrumFrame.setName("Spectrum");
+		restoreFromPrefs(spectrumFrame);
+		spectrumFrame.addKeyListener(undoManager);
+		spectrumFrame.getContentPane().setBackground(Color.BLACK);
+		
+		spectrum=spectrumFrame.getDisplay();
+		spectrum.setHintPointSize(2);
+		spectrum.setHintStroke(2);
+		spectrum.setLayout(new BorderLayout());
+		spectrumSelection=new ImageSelectionManager(spectrumFrame);
+		spectrumSelection.addSelectionListener(this);
+		spectrumSelection.addUndoableEditListener(this);
+		spectrum.add(spectrumSelection,BorderLayout.CENTER);
 
-		HelpBox helpBox = new HelpBox();
+		spectrumFrame.plotImages(imageData.getSpectrumImages(), imageData.getRGBImages());
+	}
+	
+	
+	JTextField colorname;
+	JList colorlist;
+	DefaultListModel list;
+	JScrollPane colorlistscroll;
+	JButton remove, clear, save, /*autoSelect,*/ load, undo, help, quit;
+	JCheckBox showColors,invert,realtime;
+	JFileChooser chooser;
+	
+	String defaultName;
+	
+	public void setupControlPanel (JComponent root) 
+	{
 
-		TrainCanvas trainCanvas=new TrainCanvas(segImage, imageShow, imageData, YUVimageData, controlPanel, helpBox, files);
-		root.add(trainCanvas);
+		setTitle("Controls");
+		setName("Controls");
+		setLocation(prefs.getInt(getName()+".location.x",50),prefs.getInt(getName()+".location.y",50));
+		setResizable(false);
 		
-		addComponentListener(this);
-		setVisible(true);
-		trainCanvas.plotImage(imageData.getSpecialHS(), imageData.getSpecialPixels());
+		//setup margins around window
+		root.setLayout(new BorderLayout());
+		root.add(Box.createVerticalStrut(10),BorderLayout.NORTH);
+		root.add(Box.createVerticalStrut(10),BorderLayout.SOUTH);
+		root.add(Box.createHorizontalStrut(10),BorderLayout.EAST);
+		root.add(Box.createHorizontalStrut(10),BorderLayout.WEST);
+		JComponent newroot=new JPanel();
+		root.add(newroot,BorderLayout.CENTER);
+		root=newroot;
+		
+		//add actual controls
+		root.setLayout(new BoxLayout(root,BoxLayout.Y_AXIS));
 
-		controlPanel=new ColorControlPanel(trainCanvas, imageShow);
+		colorname=new JTextField();
+		colorname.addActionListener(this);
+		colorname.getDocument().addDocumentListener(this);
+		colorname.setToolTipText("Press 'enter' to add a new entry");
+		root.add(colorname);
+		
+		list=new DefaultListModel();
+		list.addListDataListener(this);
+		list.addElement(new String("<add>"));
+		colorlist=new JList(list);
+		colorlist.setFixedCellWidth(1);
+		colorlist.setSelectionMode(ListSelectionModel.SINGLE_SELECTION);
+		colorlist.addListSelectionListener(this);
+		colorlist.setToolTipText("Select color for editing, click <add> and type name (then press 'enter') to add a new entry");
+		
+		colorlistscroll=new JScrollPane(colorlist, JScrollPane.VERTICAL_SCROLLBAR_ALWAYS, JScrollPane.HORIZONTAL_SCROLLBAR_NEVER);
+		root.add(colorlistscroll);
+		
+		addComponentListener(this);
+		
+		chooser = new JFileChooser();
+		chooser.setSelectedFile(new File("default"));
+		
+		root.add(Box.createVerticalStrut(10));
+		String[] spacenames={"YUV","HSB","rg","xy","Lab"};
+		spacelist=new JComboBox(spacenames);
+		for(int i=0; i<spacelist.getItemCount(); i++) {
+			if(spacelist.getItemAt(i).toString().equalsIgnoreCase(space)) {
+				spacelist.setSelectedIndex(i);
+				break;
+			}
+		}
+		space=(String)spacelist.getSelectedItem();
+		spacelist.addActionListener(this);
+		root.add(spacelist);
+		root.add(Box.createVerticalStrut(10));
+		
+		addButtons(root);
+		addKeyListener(undoManager);
+		pack();
+		addComponentListener(this);
+	}
+	
+	public void addButtons(JComponent root)
+	{
+		//Adding Buttons
+		
+		undo=new JButton("undo");
+		undo.addActionListener(this);
+		undo.setEnabled(false);
+		undo.setToolTipText("Undoes the last action, or press Ctl-Z in an editor window (Shift-Ctl-Z to redo)");
+		root.add(undo);
+		
+		remove=new JButton("remove");
+		remove.addActionListener(this);
+		remove.setToolTipText("Removes the selected color from the list");
+		root.add(remove);
+		
+		clear=new JButton("clear");
+		clear.addActionListener(this);
+		clear.setToolTipText("Clears the current color selection, or press Ctl-D in an editor window (Ctl-A to select all)");
+		root.add(clear);
+		
+		invert=new JCheckBox("invert");
+		invert.addActionListener(this);
+		invert.setToolTipText("Inverts the background of the color space window");
+		root.add(invert);
+		
+		realtime=new JCheckBox("Realtime");
+		realtime.addActionListener(this);
+		realtime.setToolTipText("Causes selection updates to be processed while selection is in progress");
+		root.add(realtime);
+		
+		showColors=new JCheckBox("all pixels");
+		showColors.addActionListener(this);
+		showColors.setToolTipText("Causes the full color spectrum to be displayed, regardless of what is selected in the image viewer");
+		root.add(showColors);
+		showColors.setSelected(false);
+		
+		//autoSelect=new JButton("auto select");
+		//autoSelect.addActionListener(this);
+		//root.add(autoSelect);
+		
+		help=new JButton("help");
+		help.addActionListener(this);
+		help.setToolTipText("Brings up the help.txt file");
+		root.add(help);
+		
+		
+		save=new JButton("save");
+		save.addActionListener(this);
+		save.setToolTipText("Saves the current color and image selections, exports a theshold (.tm) and color definition (.col) file");
+		root.add(save);
+		
+		load =new JButton("load");
+		load.addActionListener(this);
+		load.setToolTipText("Loads previously saved selections");
+		root.add(load);
+		
+		quit =new JButton("quit");
+		quit.addActionListener(this);
+		root.add(quit);
 		
-		trainCanvas.setControlPanel(controlPanel);
-		imageShow.setTrainCanvas(trainCanvas);
 		
+	}
+	
+	public void propertyChange(PropertyChangeEvent evt) {
+		if(evt.getPropertyName().equals(ThumbnailShow.CURIMG_PROPERTY)) {
+			int i=((Integer)evt.getNewValue()).intValue();
+			rgbImageShow.setImage(imageData.getRGBImage(i));
+			segmentedImageShow.setImage(imageData.getYUVImage(i),imageData.getWidth(i),imageData.getHeight(i));
+			hc.setImage(imageData.getSpectrumImage(i),imageData.getWidth(i),imageData.getHeight(i));
+			int curcolor=colorlist.getSelectedIndex();
+			if(curcolor>=0) {
+				rgbSelection.removeSelectionListener(this);
+				rgbSelection.removeUndoableEditListener(this);
+				rgbSelection.setSelectedArea(((Area[])imageAreas.get(curcolor))[i]);
+				rgbSelection.addSelectionListener(this);
+				rgbSelection.addUndoableEditListener(this);
+			}
+		}
+	}
+	
+	public void actionPerformed(ActionEvent e)
+	{
+		if (e.getSource()==save) {
+			int returnval=chooser.showSaveDialog(save);
+			if (returnval==JFileChooser.APPROVE_OPTION) {
+				saveFiles(chooser.getSelectedFile());
+				chooser.setSelectedFile(chooser.getSelectedFile());
+			}
+		}
+		else if (e.getSource()==load) {
+			chooser.setFileFilter(new javax.swing.filechooser.FileFilter() {
+				public boolean accept(File f) { return f.isDirectory() || f.getName().endsWith(specExt); }
+				public String getDescription() { return "*"+specExt; }
+			});
+			int returnval=chooser.showOpenDialog(load);
+			if (returnval==JFileChooser.APPROVE_OPTION) {
+				loadFiles(chooser.getSelectedFile());
+				chooser.setSelectedFile(chooser.getSelectedFile());
+			}
+		}
+		else if (e.getSource()==spacelist)
+		{
+			String newspace=(String)spacelist.getSelectedItem();
+			if(newspace.equalsIgnoreCase(space))
+				return;
+			
+			boolean hasArea=false;
+			for(int i=0; i<colorAreas.size(); i++) {
+				if(colorAreas.get(i)!=null && !((Area)colorAreas.get(i)).isEmpty()) {
+					hasArea=true;
+					break;
+				}
+			}
+			int s = !hasArea ? JOptionPane.OK_OPTION : JOptionPane.showConfirmDialog(this,"Changing color space will require clearing your color selections.  This cannot be undone.","Clear Color Selections?",JOptionPane.OK_CANCEL_OPTION);
+			if(s==JOptionPane.OK_OPTION) {
+				setSpace(newspace);
+				for(int i=0; i<colorAreas.size(); i++)
+					((Area)colorAreas.get(i)).reset();
+				imageData.changeSpectrum(YUVtoSpectrum);
+				segmentedImageShow.getThresh().changeSpectrum(YUVtoSpectrum);
+				spectrumSelection.clear();
+				spectrumFrame.plotImages(imageData.getSpectrumImages(),imageData.getRGBImages());
+				int curcolor=colorlist.getSelectedIndex();
+				if(curcolor>=0 && curcolor<list.size()) {
+					Area[] ims=(Area[])imageAreas.get(curcolor);
+					spectrumFrame.plotImageAreas(imageData.getSpectrumImages(),imageData.getRGBImages(),ims);
+				}
+				if(showColors.isSelected()) {
+					spectrumFrame.showFullPlot();
+				} else {
+					spectrumFrame.showCurPlot();
+				}
+				undoManager.discardAllEdits();
+			} else {
+				spacelist.setSelectedItem(space);
+			}
+		}
+		else if (e.getSource()==clear) 
+		{
+			spectrumSelection.clear();
+		} 
+		else if (e.getSource()==invert) 
+		{
+			if(invert.isSelected()) {
+				spectrumFrame.getContentPane().setBackground(Color.WHITE);
+			} else {
+				spectrumFrame.getContentPane().setBackground(Color.BLACK);
+			}
+			spectrumSelection.invertColors();
+		}
+		else if (e.getSource()==realtime)
+		{}
+		else if (e.getSource()==showColors) 
+		{
+			if(showColors.isSelected()) {
+				spectrumFrame.showFullPlot();
+			} else {
+				spectrumFrame.showCurPlot();
+			}
+		}
+		/*else if (e.getSource()==autoSelect) 
+		{
+		 	//spectrum.autoSelect();
+		}*/
+		else if (e.getSource()==undo) 
+		{
+			if(undoManager.canUndo())
+				undoManager.undo();
+		} 
+		else if (e.getSource()==help) 
+		{
+			if(helpBox.isVisible()) {
+				helpBox.toFront();
+			} else {
+				helpBox.setVisible(true);
+			}
+		} 
+		else if (e.getSource()==quit) 
+		{
+		 	System.exit(0);
+		} 
+		else if (e.getSource()==remove) 
+		{
+			int curcolor=colorlist.getSelectedIndex();
+			if(curcolor>=0 && curcolor<list.size()-1)
+				list.remove(curcolor);
+			colorlist.getSelectionModel().clearSelection();
+			segmentedImageShow.updateMap(colorAreas);
+		} 
+		else if (e.getSource()==colorname) 
+		{
+			String s=e.getActionCommand();
+			if (!s.equals("") && !(s.startsWith("<") && s.endsWith(">"))) {
+				int i;
+				for (i=0; i<list.getSize() && !list.get(i).equals(s); i++) {}
+				
+				if (i!=list.getSize()) {
+					colorname.setToolTipText("That name is already taken");
+				} else {
+					int curcolor=colorlist.getSelectedIndex();
+					if(curcolor<0) {
+						list.add(list.size()-1,s);
+						colorname.setToolTipText("Type a name and press 'enter' to add a new entry");
+					} else {
+						undoListeners.beginUpdate();
+						list.setElementAt(s,curcolor);
+						if(curcolor==list.size()-1)
+							list.addElement("<add>");
+						undoListeners.endUpdate();
+						colorname.setToolTipText("Edit text to rename current entry");
+					}
+				}
+			}
+		}
+		else
+		{
+			System.out.println("Unknown action performed: "+e);
+			System.out.println("Source is: "+e.getSource());
+		}
+	}
+	
+	int lastcurcolor=-1;
+	public void valueChanged(ListSelectionEvent e) 
+	{
+		int curcolor=colorlist.getSelectedIndex();
+		if(lastcurcolor==curcolor && e!=null) //if e is null, it's a request for refresh
+			return;
+		if(!getIgnoreUndoRedo() && e!=null)
+			undoListeners.postEdit(new ListSelectionEdit(this,lastcurcolor,curcolor));
+		if(curcolor<0 || curcolor>=list.size() || curcolor>=imageAreas.size()) {
+			lastcurcolor=-1;
+			remove.setEnabled(false);
+			colorname.setText("");
+			rgbSelection.removeSelectionListener(this);
+			rgbSelection.removeUndoableEditListener(this);
+			spectrumSelection.removeSelectionListener(this);
+			spectrumSelection.removeUndoableEditListener(this);
+			rgbSelection.clear();
+			spectrumSelection.clear();
+			rgbSelection.addSelectionListener(this);
+			rgbSelection.addUndoableEditListener(this);
+			spectrumSelection.addSelectionListener(this);
+			spectrumSelection.addUndoableEditListener(this);
+			colorname.setToolTipText("Type a name and press 'enter' to add a new entry");
+		} else {
+			lastcurcolor=curcolor;
+			remove.setEnabled(curcolor<list.size()-1); //only enable remove if the "<new>" option isn't selected
+			Area[] ims=(Area[])imageAreas.get(curcolor);
+			int curimg=thumb.getCurrentImage();
+			rgbSelection.removeSelectionListener(this);
+			rgbSelection.removeUndoableEditListener(this);
+			spectrumSelection.removeSelectionListener(this);
+			spectrumSelection.removeUndoableEditListener(this);
+			rgbSelection.setSelectedArea(ims[curimg]);
+			spectrumSelection.setSelectedArea((Area)colorAreas.get(curcolor));
+			rgbSelection.addSelectionListener(this);
+			rgbSelection.addUndoableEditListener(this);
+			spectrumSelection.addSelectionListener(this);
+			spectrumSelection.addUndoableEditListener(this);
+			if(!showColors.isSelected())
+				spectrumFrame.plotImageAreas(imageData.getSpectrumImages(),imageData.getRGBImages(),ims);
+			if(curcolor==list.size()-1) {
+				colorname.setText("<enter name>");
+				colorname.setToolTipText("Type a name and press 'enter' to add a new entry");
+			} else {
+				colorname.setText((String)list.get(curcolor));
+				colorname.setToolTipText("Edit text to rename current entry");
+			}
+			colorname.select(0,colorname.getText().length());
+			colorname.requestFocusInWindow();
+		}
+	}
+	
+	public void selectionInProgress(ImageSelectionManager src) {
+		if(realtime.isSelected())
+			doSelectionUpdate(src,src.getSelectionInProgress());
+	}
+	public void selectionChanged(ImageSelectionManager src) {
+		doSelectionUpdate(src,src.getSelectedArea());
+	}
+	void doSelectionUpdate(ImageSelectionManager src, Area selection) {
+		int curcolor=colorlist.getSelectedIndex();
+		if(curcolor<0) {
+			curcolor=list.size()-1;
+			colorlist.setSelectedIndex(curcolor);
+		}
+		if(src==spectrumSelection) {
+			colorAreas.setElementAt(selection,curcolor);
+			segmentedImageShow.updateMap(selection,(short)curcolor);
+		} else if(src==rgbSelection) {
+			int curimg=thumb.getCurrentImage();
+			Area[] a=(Area[])imageAreas.get(curcolor);
+			a[curimg]=selection;
+			spectrumFrame.updateImageArea(imageData.getSpectrumImage(curimg),imageData.getRGBImage(curimg),a[curimg],curimg);
+		}
+		//undo.setEnabled(true);
+	}
 
-		imageShow.setVisible(true);
-		segImage.toFront();
-		segImage.repaint();
+	public void restoreFromPrefs(Container c) {
+		String name=c.getName();
+		int w=prefs.getInt(name+".size.width",100);
+		int h=prefs.getInt(name+".size.height",100);
+		w+=c.getInsets().left+c.getInsets().right;
+		h+=c.getInsets().top+c.getInsets().bottom;
+		c.setSize(new Dimension(w,h));
+		c.setLocation(prefs.getInt(c.getName()+".location.x",50),prefs.getInt(c.getName()+".location.y",50));
 	}
 
-	public void componentResized(ComponentEvent e) {}
+	public void componentResized(ComponentEvent e) 
+	{
+		Container c=(Container)e.getComponent();
+		String name=c.getName();
+		//System.out.println(name+" size: "+c.getSize());
+		//System.out.println(name+" insets: "+c.getInsets());
+		int w=c.getSize().width-c.getInsets().left-c.getInsets().right;
+		int h=c.getSize().height-c.getInsets().top-c.getInsets().bottom;
+		prefs.putInt(name+".size.width",w);
+		prefs.putInt(name+".size.height",h);
+	}
 	public void componentHidden(ComponentEvent e) {}
 	
 	public void componentMoved(ComponentEvent e)
 	{ 	
-		prefs.putInt("EasyTrain.location.x",getLocation().x);
-		prefs.putInt("EasyTrain.location.y",getLocation().y);
+		prefs.putInt(e.getComponent().getName()+".location.x",e.getComponent().getLocation().x);
+		prefs.putInt(e.getComponent().getName()+".location.y",e.getComponent().getLocation().y);
 	}
 	public void componentShown(ComponentEvent e) { }
 
 	public void setDefaultPrefs()
 	{
-		prefs.putInt("EasyTrain.location.x",10);
-		prefs.putInt("EasyTrain.location.y",10);
+		prefs.putInt("Spectrum.location.x",10);
+		prefs.putInt("Spectrum.location.y",10);
+		prefs.putInt("Spectrum.size.width",700);
+		prefs.putInt("Spectrum.size.height",700);
 
-		prefs.putInt("ColorControlPanel.location.x",780);
-		prefs.putInt("ColorControlPanel.location.y",50);
+		prefs.putInt("Controls.location.x",780);
+		prefs.putInt("Controls.location.y",50);
 
 		prefs.putInt("HelpBox.location.x",100);
 		prefs.putInt("HelpBox.location.y",100);
 
-		prefs.putInt("ImageShowArea.location.x",50);
-		prefs.putInt("ImageShowArea.location.y",200);
+		prefs.putInt("RGBImageShow.location.x",50);
+		prefs.putInt("RGBImageShow.location.y",200);
 
 		prefs.putInt("SegmentedImage.location.x",400);
 		prefs.putInt("SegmentedImage.location.y",200);
-
 	}  
   
-}
-
-
+	Vector colornames=new Vector(); //to be used only as a backing so we know the names after they are removed for undo functionality
+	public void intervalAdded(ListDataEvent e) {
+		for(int i=e.getIndex0(); i<=e.getIndex1(); i++) {
+			imageAreas.add(i,new Area[imageData.getNumImages()]);
+			colorAreas.add(i,new Area());
+			colornames.add(i,list.get(i));
+			if(!getIgnoreUndoRedo())
+				undoListeners.postEdit(new AddColorEdit(this,(String)list.get(i),i));
+			//undo.setEnabled(true);
+		}
+		if(colorlist!=null) {
+			int curcolor=colorlist.getSelectedIndex();
+			remove.setEnabled(curcolor>=0 && curcolor<list.size()-1);
+		}
+	}
+	public void intervalRemoved(ListDataEvent e) {
+		if(!getIgnoreUndoRedo())
+			for(int i=e.getIndex0(); i<=e.getIndex1(); i++)
+				undoListeners.postEdit(new RemoveColorEdit(this,(String)colornames.get(i),i,(Area)colorAreas.get(i),(Area[])imageAreas.get(i)));
+		//undo.setEnabled(true);
+		for(int i=e.getIndex0(); i<=e.getIndex1(); i++) {
+			imageAreas.removeElementAt(e.getIndex0());
+			colorAreas.removeElementAt(e.getIndex0());
+			colornames.removeElementAt(e.getIndex0());
+		}
+		int curcolor=colorlist.getSelectedIndex();
+		remove.setEnabled(curcolor>0 && curcolor<list.size()-1);
+	}
+	public void contentsChanged(ListDataEvent e) {
+		if(e.getIndex0()!=e.getIndex1())
+			System.out.println("WARNING: Unhandled multi-change");
+		else {
+			//item renamed/replaced
+			int index=e.getIndex0();
+			if(!getIgnoreUndoRedo())
+				undoListeners.postEdit(new RenameColorEdit(this,(String)colornames.get(index),(String)list.get(index),index));
+			colornames.setElementAt(list.get(index),index);
+		}
+	}
 
+	public void changedUpdate(DocumentEvent e) {
+		if(e.getDocument()==colorname.getDocument()) {
+			int curcolor=colorlist.getSelectedIndex();
+			if(curcolor>=0 && curcolor<list.getSize()-1) {
+				actionPerformed(new ActionEvent(colorname,0,colorname.getText()));
+			}
+		}
+	}
+	public void insertUpdate(DocumentEvent e) { changedUpdate(e); }
+	public void removeUpdate(DocumentEvent e) { changedUpdate(e); }
+	
+	public void loadFiles(File f) {
+		String basename;
+		if(f.getName().endsWith(".tm") || f.getName().endsWith(".col")) {
+			String path=f.getPath();
+			f=new File(path.substring(0,path.lastIndexOf('.'))+specExt);
+			basename=f.getName().substring(0,f.getName().lastIndexOf('.'));
+		} if(f.getName().endsWith(specExt)) {
+			basename=f.getName().substring(0,f.getName().lastIndexOf('.'));
+		} else {
+			basename=f.getName();
+			f=new File(f.getPath()+specExt);
+		}
+		if(!f.canRead()) {
+			JOptionPane.showMessageDialog(this,"The file "+f+" could not be opened","File Access Denied",JOptionPane.ERROR_MESSAGE);
+			return;
+		}
+		setIgnoreUndoRedo(true);
+		
+		//read basic color info and color areas
+		try {
+			BufferedReader load=new BufferedReader(new FileReader(f));
+			
+			colorlist.getSelectionModel().clearSelection();
+			if(list.size()>1)
+				list.removeRange(0,list.size()-2);
+			((Area)colorAreas.get(0)).reset();
+			spacelist.setSelectedItem(load.readLine());
+			int numColors = Integer.parseInt(load.readLine());
+			for(int i=0; i<numColors; i++) {
+				String name=load.readLine();
+				list.add(list.size()-1,name); //the ListDataListener should take care of managing colorAreas, imageAreas, etc.
+				colorAreas.setElementAt(loadArea(load),i);
+			}
+			load.close();
+		} catch (Exception ex) {
+			System.out.println("Error loading from '"+f.getPath() + "': "+ex);
+			JOptionPane.showMessageDialog(this,"The file "+f+" could not be loaded","File Access Denied",JOptionPane.ERROR_MESSAGE);
+		}
+		
+		// load image areas where found
+		String[] files=imageData.getFileNames();
+		for(int i=0; i<files.length; i++) {
+			f=getImageAreaFile(basename,files[i]);
+			if(!f.exists())
+				continue;
+			try {
+				BufferedReader load=new BufferedReader(new FileReader(f));
+				for(String color=load.readLine(); color!=null; color=load.readLine()) {
+					int idx=list.indexOf(color);
+					Area a=loadArea(load);
+					if(idx==-1) {
+						System.out.println("Warning: ignoring area for color '"+color+"', found in '"+f.getPath()+"' -- was not previously defined in '"+basename+specExt+"'");
+					} else {
+						Area[] areas=(Area[])imageAreas.get(idx);
+						areas[i]=a;
+					}
+				}
+				load.close();
+			} catch (Exception ex) {
+				System.out.println("Error loading from '"+f.getPath() + "': " + ex);
+				JOptionPane.showMessageDialog(this,"The file "+f+" could not be loaded","File Access Denied",JOptionPane.ERROR_MESSAGE);
+			}
+		}
+		
+		segmentedImageShow.updateMap(colorAreas);
+		//if(!showColors.isSelected())
+		//spectrumFrame.plotImageAreas(imageData.getSpectrumImages(),imageData.getRGBImages(),(Area[])imageAreas.get(0));
+		
+		colorlist.setSelectedIndex(0);
+		setIgnoreUndoRedo(false);
+		undoManager.discardAllEdits();
+	}
+	
+	public void saveFiles(File f) {
+		ThresholdMap thresh=segmentedImageShow.getThresh();
+		if(f.getName().endsWith(specExt) || f.getName().endsWith(".tm") || f.getName().endsWith(".col"))
+			f=new File(f.getPath().substring(0,f.getPath().lastIndexOf('.')));
 
+		// Saving threshold map
+		try {
+			thresh.saveFile(new File(f.getPath()+".tm"));
+		} catch (Exception ex) {
+			System.out.println("Error saving to '"+f.getPath() + ".tm': " + ex);
+		}
+		
+		// Saving color definition file
+		try {
+			FileWriter file_col_fw=new FileWriter(f.getPath() + ".col");
+			file_col_fw.write("0 (128 128 128) \"unclassified\" 8 1.00\n");
+			for (int i=0; i<list.size()-1; i++) {
+				Color c=thresh.getRepresentitiveColor(i);
+				file_col_fw.write((i+1)+" (" + c.getRed() + " " + c.getGreen() + " " + c.getBlue() + ") " +"\"" + list.get(i)+ "\" 8 0.75\n");
+			}
+			file_col_fw.close();
+ 		} catch (Exception ex) {
+			System.out.println("Error saving to '"+f.getPath() + ".col': " + ex);
+		}
+		
+		// Saving colorAreas
+		try {
+			FileWriter save=new FileWriter(f.getPath() + specExt);
+			
+			save.write(space+"\n");
+			save.write((list.size()-1) + "\n");
+			for(int i=0; i<list.size()-1; i++) {
+				save.write(list.get(i) + "\n");   
+				
+				Area a = (Area)colorAreas.get(i);
+				String pathString = createPathString(a.getPathIterator(null));
+				save.write(pathString);  
+			}
+			save.close();
+		} catch (Exception ex) {
+			System.out.println("Error saving to '"+f.getPath() + specExt+"': " + ex);
+			JOptionPane.showMessageDialog(this,"The file "+f+" could not be saved","File Access Denied",JOptionPane.ERROR_MESSAGE);
+		}
+		
+		// Saving imageAreas
+		String[] files=imageData.getFileNames();
+		for(int i=0; i<files.length; i++) {
+			//first check if there are even any areas to save
+			boolean hasNonNull=false;
+			for(int j=0; j<list.size()-1 && !hasNonNull; j++) {
+				Area[] a = (Area[])imageAreas.get(j);
+				hasNonNull=(a[i]!=null);
+			}
+			
+			//only create a file if there's something to go in it!
+			if(hasNonNull) {
+				try {
+					FileWriter save=new FileWriter(getImageAreaFile(f.getName(),files[i]));
+					for (int j=0; j<list.size()-1; j++) {
+						Area[] a = (Area[])imageAreas.get(j);
+						if(a[i]!=null) {
+							save.write(list.get(j) + "\n");
+							String pathString = createPathString(a[i].getPathIterator(null));
+							save.write(pathString);  
+						}
+					}
+					save.close();
+				} catch (Exception ex) {
+					System.out.println("Error saving to '"+files[i] +"-"+f.getName()+".areas': " + ex);
+					JOptionPane.showMessageDialog(this,"The file '"+files[i] +"-"+f.getName()+".areas' could not be saved","File Access Denied",JOptionPane.ERROR_MESSAGE);
+				}
+			}
+		}                 
+	}
+	
+	String createPathString(PathIterator path)
+	{
+		
+		String retPath = "<AREA>\n";
+		
+		double[] coords = new double[6];
+		int type;       
+		
+		while(!path.isDone())
+		{
+			switch(path.currentSegment(coords)) {
+				case PathIterator.SEG_MOVETO: //new polygon
+					retPath += "START " + coords[0] + " " + coords[1] + "\n";
+					break;
+				case PathIterator.SEG_LINETO: //line 
+					retPath += "LINE " + coords[0] + " " + coords[1] + "\n";
+					break;
+				case PathIterator.SEG_CLOSE: //end of curr polygon
+					retPath += "CLOSE\n";
+					break;
+			}
+			path.next();
+		}
+		retPath += "</AREA>\n";
+		return retPath;
+	}
+	
+	Area loadArea(BufferedReader load) throws java.io.IOException {
+		if(!load.readLine().equals("<AREA>")) {
+			System.out.println("Error: File Format is incorrect");
+			return null;
+		}
+		GeneralPath curPath=null;
+		Area curArea=new Area();
+		for(String in = load.readLine(); !in.equals("</AREA>"); in = load.readLine()) {
+			StringTokenizer inTok = new StringTokenizer(in);
+			String t = inTok.nextToken();
+			if(t.equals("START")) {
+				curPath = new GeneralPath(GeneralPath.WIND_NON_ZERO);
+				double x = Double.parseDouble(inTok.nextToken());
+				double y = Double.parseDouble(inTok.nextToken());
+				curPath.moveTo((float)x,(float)y);
+			} else if(t.equals("LINE")) {
+				double x = Double.parseDouble(inTok.nextToken());
+				double y = Double.parseDouble(inTok.nextToken());
+				curPath.lineTo((float)x,(float)y);
+			} else if(t.equals("CLOSE")) {
+				curPath.closePath();
+				curArea.add(new Area(curPath));
+				curPath=null;
+			}
+		}
+		if(curPath!=null)
+			System.out.println("Warning: unclosed polygon during load");
+		return curArea;
+	}
+	
+	File getImageAreaFile(String basename, String imgFile) {
+		File f=new File(imgFile.substring(0,imgFile.lastIndexOf('.'))+"-"+basename+".areas");
+		//System.out.println("Checking "+f);
+		return f;
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/EasyTrain.xcodeproj/default.pbxuser ./tools/easytrain/EasyTrain.xcodeproj/default.pbxuser
--- ../Tekkotsu_2.4.1/tools/easytrain/EasyTrain.xcodeproj/default.pbxuser	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/easytrain/EasyTrain.xcodeproj/default.pbxuser	2005-11-08 18:02:18.000000000 -0500
@@ -0,0 +1,39 @@
+// !$*UTF8*$!
+{
+	00E6828EFEC88D1A11DB9C8B = {
+		activeBuildStyle = 130F8B95001BDF0A11CA292A;
+		activeExecutable = 130F8B98001BDF0A11CA292A;
+		activeTarget = 130F8B90001BDF0A11CA292A;
+		addToTargets = (
+		);
+		executables = (
+			130F8B98001BDF0A11CA292A,
+		);
+	};
+	130F8B90001BDF0A11CA292A = {
+		activeExec = 0;
+	};
+	130F8B98001BDF0A11CA292A = {
+		activeArgIndex = 0;
+		activeArgIndices = (
+			YES,
+		);
+		argumentStrings = (
+			"-jar \"EasyTrain.jar\" ",
+		);
+		debuggerPlugin = JavaDebugging;
+		enableDebugStr = 1;
+		environmentEntries = (
+		);
+		isa = PBXExecutable;
+		launchableReference = 130F8B99001BDF0A11CA292A;
+		sourceDirectories = (
+		);
+	};
+	130F8B99001BDF0A11CA292A = {
+		isa = PBXExecutableFileReference;
+		name = java;
+		path = /usr/bin/java;
+		refType = 0;
+	};
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/EasyTrain.xcodeproj/project.pbxproj ./tools/easytrain/EasyTrain.xcodeproj/project.pbxproj
--- ../Tekkotsu_2.4.1/tools/easytrain/EasyTrain.xcodeproj/project.pbxproj	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/easytrain/EasyTrain.xcodeproj/project.pbxproj	2005-11-08 18:02:18.000000000 -0500
@@ -0,0 +1,245 @@
+// !$*UTF8*$!
+{
+	archiveVersion = 1;
+	classes = {
+	};
+	objectVersion = 42;
+	objects = {
+
+/* Begin PBXBuildFile section */
+		6916C4D708ECF2DD00B61601 /* ColorConverter.java in Sources */ = {isa = PBXBuildFile; fileRef = 6916C4CC08ECF2DD00B61601 /* ColorConverter.java */; };
+		6916C4D808ECF2DD00B61601 /* EasyTrain.java in Sources */ = {isa = PBXBuildFile; fileRef = 6916C4CD08ECF2DD00B61601 /* EasyTrain.java */; };
+		6916C4D908ECF2DD00B61601 /* HelpBox.java in Sources */ = {isa = PBXBuildFile; fileRef = 6916C4CE08ECF2DD00B61601 /* HelpBox.java */; };
+		6916C4DA08ECF2DD00B61601 /* ImageData.java in Sources */ = {isa = PBXBuildFile; fileRef = 6916C4CF08ECF2DD00B61601 /* ImageData.java */; };
+		6916C4DB08ECF2DD00B61601 /* ImagePanel.java in Sources */ = {isa = PBXBuildFile; fileRef = 6916C4D008ECF2DD00B61601 /* ImagePanel.java */; };
+		6916C4DD08ECF2DD00B61601 /* SegmentedImage.java in Sources */ = {isa = PBXBuildFile; fileRef = 6916C4D208ECF2DD00B61601 /* SegmentedImage.java */; };
+		6916C4DE08ECF2DD00B61601 /* Thumbnail.java in Sources */ = {isa = PBXBuildFile; fileRef = 6916C4D308ECF2DD00B61601 /* Thumbnail.java */; };
+		6916C4DF08ECF2DD00B61601 /* ThumbnailShow.java in Sources */ = {isa = PBXBuildFile; fileRef = 6916C4D408ECF2DD00B61601 /* ThumbnailShow.java */; };
+		6916C4E308ECF31E00B61601 /* help.txt in JavaArchive */ = {isa = PBXBuildFile; fileRef = 6916C4E208ECF31E00B61601 /* help.txt */; settings = {JAVA_ARCHIVE_SUBDIR = ""; }; };
+		692A932208EF05DE00736A17 /* ImageSelectionManager.java in Sources */ = {isa = PBXBuildFile; fileRef = 692A932108EF05DE00736A17 /* ImageSelectionManager.java */; };
+		692A93B408F0AB9D00736A17 /* ThresholdMap.java in Sources */ = {isa = PBXBuildFile; fileRef = 692A93B308F0AB9D00736A17 /* ThresholdMap.java */; };
+		69AFF9B408FEDCA20002640E /* SpectrumViewer.java in Sources */ = {isa = PBXBuildFile; fileRef = 69AFF9B308FEDCA20002640E /* SpectrumViewer.java */; };
+		69D8EBA708F1D241004624EF /* ImageViewer.java in Sources */ = {isa = PBXBuildFile; fileRef = 69D8EBA608F1D241004624EF /* ImageViewer.java */; };
+/* End PBXBuildFile section */
+
+/* Begin PBXBuildStyle section */
+		130F8B95001BDF0A11CA292A /* Debug */ = {
+			isa = PBXBuildStyle;
+			buildSettings = {
+				COPY_PHASE_STRIP = NO;
+				GCC_DYNAMIC_NO_PIC = NO;
+				GCC_ENABLE_FIX_AND_CONTINUE = YES;
+				GCC_GENERATE_DEBUGGING_SYMBOLS = YES;
+				GCC_OPTIMIZATION_LEVEL = 0;
+				ZERO_LINK = YES;
+			};
+			name = Debug;
+		};
+		130F8B96001BDF0A11CA292A /* Release */ = {
+			isa = PBXBuildStyle;
+			buildSettings = {
+				COPY_PHASE_STRIP = YES;
+				GCC_ENABLE_FIX_AND_CONTINUE = NO;
+				ZERO_LINK = NO;
+			};
+			name = Release;
+		};
+/* End PBXBuildStyle section */
+
+/* Begin PBXFileReference section */
+		6916C4CC08ECF2DD00B61601 /* ColorConverter.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = ColorConverter.java; sourceTree = "<group>"; };
+		6916C4CD08ECF2DD00B61601 /* EasyTrain.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = EasyTrain.java; sourceTree = "<group>"; };
+		6916C4CE08ECF2DD00B61601 /* HelpBox.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = HelpBox.java; sourceTree = "<group>"; };
+		6916C4CF08ECF2DD00B61601 /* ImageData.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = ImageData.java; sourceTree = "<group>"; };
+		6916C4D008ECF2DD00B61601 /* ImagePanel.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = ImagePanel.java; sourceTree = "<group>"; };
+		6916C4D208ECF2DD00B61601 /* SegmentedImage.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = SegmentedImage.java; sourceTree = "<group>"; };
+		6916C4D308ECF2DD00B61601 /* Thumbnail.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = Thumbnail.java; sourceTree = "<group>"; };
+		6916C4D408ECF2DD00B61601 /* ThumbnailShow.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = ThumbnailShow.java; sourceTree = "<group>"; };
+		6916C4E108ECF31700B61601 /* README */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = text; path = README; sourceTree = "<group>"; };
+		6916C4E208ECF31E00B61601 /* help.txt */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = text; path = help.txt; sourceTree = "<group>"; };
+		692A932108EF05DE00736A17 /* ImageSelectionManager.java */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.java; path = ImageSelectionManager.java; sourceTree = "<group>"; };
+		692A93B308F0AB9D00736A17 /* ThresholdMap.java */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.java; path = ThresholdMap.java; sourceTree = "<group>"; };
+		69AFF9B308FEDCA20002640E /* SpectrumViewer.java */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.java; path = SpectrumViewer.java; sourceTree = "<group>"; };
+		69D8EBA608F1D241004624EF /* ImageViewer.java */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.java; path = ImageViewer.java; sourceTree = "<group>"; };
+		6A8008AE02C7B68F0CC91562 /* Manifest */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = Manifest; sourceTree = "<group>"; };
+		6A9ED92C02B0286D0CC91562 /* EasyTrain.jar */ = {isa = PBXFileReference; explicitFileType = archive.jar; includeInIndex = 0; path = EasyTrain.jar; sourceTree = BUILT_PRODUCTS_DIR; };
+/* End PBXFileReference section */
+
+/* Begin PBXFrameworksBuildPhase section */
+		130F8B94001BDF0A11CA292A /* Frameworks */ = {
+			isa = PBXFrameworksBuildPhase;
+			buildActionMask = 2147483647;
+			files = (
+			);
+			runOnlyForDeploymentPostprocessing = 0;
+		};
+/* End PBXFrameworksBuildPhase section */
+
+/* Begin PBXGroup section */
+		00E6828FFEC88D1A11DB9C8B = {
+			isa = PBXGroup;
+			children = (
+				6916C4CC08ECF2DD00B61601 /* ColorConverter.java */,
+				6916C4CD08ECF2DD00B61601 /* EasyTrain.java */,
+				6916C4CE08ECF2DD00B61601 /* HelpBox.java */,
+				6916C4CF08ECF2DD00B61601 /* ImageData.java */,
+				6916C4D008ECF2DD00B61601 /* ImagePanel.java */,
+				69D8EBA608F1D241004624EF /* ImageViewer.java */,
+				69AFF9B308FEDCA20002640E /* SpectrumViewer.java */,
+				6916C4D208ECF2DD00B61601 /* SegmentedImage.java */,
+				6916C4D308ECF2DD00B61601 /* Thumbnail.java */,
+				6916C4D408ECF2DD00B61601 /* ThumbnailShow.java */,
+				692A93B308F0AB9D00736A17 /* ThresholdMap.java */,
+				692A932108EF05DE00736A17 /* ImageSelectionManager.java */,
+				6A8008AE02C7B68F0CC91562 /* Manifest */,
+				6A0644A002C7BD230CC91562 /* Documentation */,
+				0120612AFEC8923411DB9C8B /* Products */,
+			);
+			sourceTree = "<group>";
+		};
+		0120612AFEC8923411DB9C8B /* Products */ = {
+			isa = PBXGroup;
+			children = (
+				6A9ED92C02B0286D0CC91562 /* EasyTrain.jar */,
+			);
+			name = Products;
+			sourceTree = "<group>";
+		};
+		6A0644A002C7BD230CC91562 /* Documentation */ = {
+			isa = PBXGroup;
+			children = (
+				6916C4E208ECF31E00B61601 /* help.txt */,
+				6916C4E108ECF31700B61601 /* README */,
+			);
+			name = Documentation;
+			sourceTree = "<group>";
+		};
+/* End PBXGroup section */
+
+/* Begin PBXJavaArchiveBuildPhase section */
+		130F8B93001BDF0A11CA292A /* JavaArchive */ = {
+			isa = PBXJavaArchiveBuildPhase;
+			buildActionMask = 2147483647;
+			files = (
+				6916C4E308ECF31E00B61601 /* help.txt in JavaArchive */,
+			);
+			runOnlyForDeploymentPostprocessing = 0;
+		};
+/* End PBXJavaArchiveBuildPhase section */
+
+/* Begin PBXProject section */
+		00E6828EFEC88D1A11DB9C8B /* Project object */ = {
+			isa = PBXProject;
+			buildConfigurationList = 697D1BC908ECE39C0002B8B1 /* Build configuration list for PBXProject "EasyTrain" */;
+			buildSettings = {
+			};
+			buildStyles = (
+				130F8B95001BDF0A11CA292A /* Debug */,
+				130F8B96001BDF0A11CA292A /* Release */,
+			);
+			hasScannedForEncodings = 1;
+			mainGroup = 00E6828FFEC88D1A11DB9C8B;
+			productRefGroup = 0120612AFEC8923411DB9C8B /* Products */;
+			projectDirPath = "";
+			targets = (
+				130F8B90001BDF0A11CA292A /* EasyTrain */,
+			);
+		};
+/* End PBXProject section */
+
+/* Begin PBXSourcesBuildPhase section */
+		130F8B91001BDF0A11CA292A /* Sources */ = {
+			isa = PBXSourcesBuildPhase;
+			buildActionMask = 2147483647;
+			files = (
+				6916C4D708ECF2DD00B61601 /* ColorConverter.java in Sources */,
+				6916C4D808ECF2DD00B61601 /* EasyTrain.java in Sources */,
+				6916C4D908ECF2DD00B61601 /* HelpBox.java in Sources */,
+				6916C4DA08ECF2DD00B61601 /* ImageData.java in Sources */,
+				6916C4DB08ECF2DD00B61601 /* ImagePanel.java in Sources */,
+				6916C4DD08ECF2DD00B61601 /* SegmentedImage.java in Sources */,
+				6916C4DE08ECF2DD00B61601 /* Thumbnail.java in Sources */,
+				6916C4DF08ECF2DD00B61601 /* ThumbnailShow.java in Sources */,
+				692A932208EF05DE00736A17 /* ImageSelectionManager.java in Sources */,
+				692A93B408F0AB9D00736A17 /* ThresholdMap.java in Sources */,
+				69D8EBA708F1D241004624EF /* ImageViewer.java in Sources */,
+				69AFF9B408FEDCA20002640E /* SpectrumViewer.java in Sources */,
+			);
+			runOnlyForDeploymentPostprocessing = 0;
+		};
+/* End PBXSourcesBuildPhase section */
+
+/* Begin PBXToolTarget section */
+		130F8B90001BDF0A11CA292A /* EasyTrain */ = {
+			isa = PBXToolTarget;
+			buildConfigurationList = 697D1BC508ECE39C0002B8B1 /* Build configuration list for PBXToolTarget "EasyTrain" */;
+			buildPhases = (
+				130F8B91001BDF0A11CA292A /* Sources */,
+				130F8B93001BDF0A11CA292A /* JavaArchive */,
+				130F8B94001BDF0A11CA292A /* Frameworks */,
+			);
+			buildSettings = {
+				JAVA_ARCHIVE_CLASSES = YES;
+				JAVA_ARCHIVE_COMPRESSION = NO;
+				JAVA_ARCHIVE_TYPE = JAR;
+				JAVA_COMPILER = /usr/bin/javac;
+				JAVA_MANIFEST_FILE = Manifest;
+				JAVA_SOURCE_SUBDIR = .;
+				PRODUCT_NAME = EasyTrain;
+				PURE_JAVA = YES;
+				REZ_EXECUTABLE = YES;
+			};
+			dependencies = (
+			);
+			name = EasyTrain;
+			productInstallPath = /usr/local/bin;
+			productName = EasyTrain;
+			productReference = 6A9ED92C02B0286D0CC91562 /* EasyTrain.jar */;
+		};
+/* End PBXToolTarget section */
+
+/* Begin XCBuildConfiguration section */
+		697D1BC808ECE39C0002B8B1 /* Default */ = {
+			isa = XCBuildConfiguration;
+			buildSettings = {
+				JAVA_ARCHIVE_CLASSES = YES;
+				JAVA_ARCHIVE_COMPRESSION = NO;
+				JAVA_ARCHIVE_TYPE = JAR;
+				JAVA_COMPILER = /usr/bin/javac;
+				JAVA_MANIFEST_FILE = Manifest;
+				JAVA_SOURCE_SUBDIR = .;
+				PRODUCT_NAME = EasyTrain;
+				PURE_JAVA = YES;
+				REZ_EXECUTABLE = YES;
+			};
+			name = Default;
+		};
+		697D1BCC08ECE39C0002B8B1 /* Default */ = {
+			isa = XCBuildConfiguration;
+			buildSettings = {
+			};
+			name = Default;
+		};
+/* End XCBuildConfiguration section */
+
+/* Begin XCConfigurationList section */
+		697D1BC508ECE39C0002B8B1 /* Build configuration list for PBXToolTarget "EasyTrain" */ = {
+			isa = XCConfigurationList;
+			buildConfigurations = (
+				697D1BC808ECE39C0002B8B1 /* Default */,
+			);
+			defaultConfigurationIsVisible = 0;
+			defaultConfigurationName = Default;
+		};
+		697D1BC908ECE39C0002B8B1 /* Build configuration list for PBXProject "EasyTrain" */ = {
+			isa = XCConfigurationList;
+			buildConfigurations = (
+				697D1BCC08ECE39C0002B8B1 /* Default */,
+			);
+			defaultConfigurationIsVisible = 0;
+			defaultConfigurationName = Default;
+		};
+/* End XCConfigurationList section */
+	};
+	rootObject = 00E6828EFEC88D1A11DB9C8B /* Project object */;
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/HelpBox.java ./tools/easytrain/HelpBox.java
--- ../Tekkotsu_2.4.1/tools/easytrain/HelpBox.java	2005-08-03 20:27:38.000000000 -0400
+++ ./tools/easytrain/HelpBox.java	2005-10-13 12:50:10.000000000 -0400
@@ -1,88 +1,88 @@
-/** @file HelpBox.java
- *  @brief Frame for a help window
- *
- *	@author Eric Durback
- *  @bug No known bugs.
- */
-
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.io.*;
-import java.util.*;
-import java.awt.geom.*;
-import java.util.prefs.Preferences;
-
-public class HelpBox extends JFrame implements ComponentListener, FocusListener 
-{
-	
-
-	static Preferences prefs = Preferences.userNodeForPackage(ImageShowArea.class);
-
-	JTextArea jtextArea;
-	JScrollPane HelpScroll;
-
-
-  	public static void main(String args[]) 
-  	{}
- 
- 	public void focusGained(FocusEvent e) {} 
- 
- 	public void focusLost(FocusEvent e) {}
-
-	public static void usageAndExit() 
-	{
-		System.out.println("usage: java ImageShow (-isRGB|-isYUV) raw_image [raw images]");
-		System.exit(1);		
-	}
-
-  	public HelpBox ()
-  	{
-     
-	    setBackground(Color.black);
-	    setSize(450,600);
-	    setTitle("EasyTrain Help");
-	    setLocation(prefs.getInt("HelpBox.location.x",50),prefs.getInt("HelpBox.location.y",50));
-	    
-	    jtextArea = new JTextArea();
-	    char buf[] = new char[8192];
-		int n;
-	    
-	    try{
-	    
-		    BufferedReader in = new BufferedReader(new FileReader("help.txt"));
-			while ((n = in.read(buf, 0, buf.length)) > 0)
-			{
-			    jtextArea.append(new String(buf, 0, n));
-			}
-			in.close();
-		} catch(Exception e){}
-	    
-	    HelpScroll = new JScrollPane(jtextArea,
-		                    JScrollPane.VERTICAL_SCROLLBAR_ALWAYS,
-		                    JScrollPane.HORIZONTAL_SCROLLBAR_NEVER);
-	    
-	    
-	  	this.getContentPane().add(HelpScroll);
-	 
-		jtextArea.setEditable(false);
-	  	
-	    addComponentListener(this);
-	    addFocusListener(this);  
-    
-	}
-
-	public void componentResized(ComponentEvent e) {    }
-	public void componentHidden(ComponentEvent e) { }
-  
-	public void componentMoved(ComponentEvent e)
-  	{ 
-		prefs.putInt("HelpBox.location.x",getLocation().x);
-		prefs.putInt("HelpBox.location.y",getLocation().y);
-  
-  	}
-  	public void componentShown(ComponentEvent e) { }
-
-}
+/** @file HelpBox.java
+ *  @brief Frame for a help window
+ *
+ *	@author Eric Durback
+ *  @bug No known bugs.
+ */
+ 
+import java.awt.image.*;
+import java.awt.*;
+import javax.swing.*;
+import javax.swing.event.*;
+import java.awt.event.*;
+import java.io.*;
+import java.util.*;
+import java.awt.geom.*;
+import java.util.prefs.Preferences;
+
+public class HelpBox extends JFrame implements ComponentListener, FocusListener 
+{
+	
+
+	static Preferences prefs = Preferences.userNodeForPackage(EasyTrain.class);
+
+	JTextArea jtextArea;
+	JScrollPane HelpScroll;
+
+
+  	public static void main(String args[]) 
+  	{}
+ 
+ 	public void focusGained(FocusEvent e) {} 
+ 
+ 	public void focusLost(FocusEvent e) {}
+
+	public static void usageAndExit() 
+	{
+		System.out.println("usage: java ImageShow (-isRGB|-isYUV) raw_image [raw images]");
+		System.exit(1);		
+	}
+
+  	public HelpBox ()
+  	{
+     
+	    setBackground(Color.black);
+	    setSize(450,600);
+	    setTitle("EasyTrain Help");
+	    setLocation(prefs.getInt("HelpBox.location.x",50),prefs.getInt("HelpBox.location.y",50));
+	    
+	    jtextArea = new JTextArea();
+	    char buf[] = new char[8192];
+		int n;
+	    
+	    try{
+	    
+		    BufferedReader in = new BufferedReader(new FileReader("help.txt"));
+			while ((n = in.read(buf, 0, buf.length)) > 0)
+			{
+			    jtextArea.append(new String(buf, 0, n));
+			}
+			in.close();
+		} catch(Exception e){}
+	    
+	    HelpScroll = new JScrollPane(jtextArea,
+		                    JScrollPane.VERTICAL_SCROLLBAR_ALWAYS,
+		                    JScrollPane.HORIZONTAL_SCROLLBAR_NEVER);
+	    
+	    
+	  	this.getContentPane().add(HelpScroll);
+	 
+		jtextArea.setEditable(false);
+	  	
+	    addComponentListener(this);
+	    addFocusListener(this);  
+    
+	}
+
+	public void componentResized(ComponentEvent e) {    }
+	public void componentHidden(ComponentEvent e) { }
+  
+	public void componentMoved(ComponentEvent e)
+  	{ 
+		prefs.putInt("HelpBox.location.x",getLocation().x);
+		prefs.putInt("HelpBox.location.y",getLocation().y);
+  
+  	}
+  	public void componentShown(ComponentEvent e) { }
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/ImageData.java ./tools/easytrain/ImageData.java
--- ../Tekkotsu_2.4.1/tools/easytrain/ImageData.java	2005-08-03 20:27:38.000000000 -0400
+++ ./tools/easytrain/ImageData.java	2006-07-02 14:50:56.000000000 -0400
@@ -24,313 +24,223 @@
 
 
 public class ImageData extends Frame {
-  Toolkit toolkit;
-
-  public int[][]retdata;
-  public int[][] data;
-  public int[] alldata;
-
-  public float[][] RG;  //change all to [][]
-  public float[][] HS;
-  public float[][] HB;
-  public float[][] SB;
-  
-  public float[] allHS;
-
-  public int image_width;
-  public int image_height;
-  
-  public int numImages;
-  public int curImage;
-  
-  public ImageData()
-  {
-  	this(1);
-  }
-  
-  public ImageData(int numI) 
-  {
-    toolkit=Toolkit.getDefaultToolkit();
-    curImage = 0;
-    numImages = numI;
-    data = new int[numI][];
-    retdata = new int[numI][];
-    HS = new float[numI][];
-    HB = new float[numI][];
-    RG = new float[numI][];
-    SB = new float[numI][];
-    
-  }
-
-  public int[] getPixels() 
-  {
-  	return retdata[curImage];
-  }
-  
-  public int[][] getAllPixels() {
-    return retdata;
-  }
-  
-   public int[] getSpecialPixels() {
-    return alldata;
-  }
-
-	// assumes retdata holds RGB
-  public float[] getRG() {
-    if (RG[curImage]==null) {
-      RG[curImage]=new float[retdata[curImage].length*2];
-      for (int i=0; i<retdata[curImage].length; i++) {
-        float r=(float)((retdata[curImage][i]>>16)&0xFF);
-        float g=(float)((retdata[curImage][i]>>8)&0xFF);
-        float b=(float)(retdata[curImage][i]&0xFF);
-        RG[curImage][i*2]=r/(r+g+b);
-        RG[curImage][i*2+1]=g/(r+g+b);
-      }
-    }
-    return RG[curImage];
-  }
-
-	// assumes retdata holds RGB
-  public float[] getHS() 
-  {
-    if (HS[curImage]==null) 
-    {
-      HS[curImage]=new float[retdata[curImage].length*2];
-      float[] hsb=new float[3];
-      for (int i=0; i<retdata[curImage].length; i++) 
-      {
-        int r=(retdata[curImage][i]>>16)&0xFF;
-        int g=(retdata[curImage][i]>>8)&0xFF;
-        int b=retdata[curImage][i]&0xFF;
-        Color.RGBtoHSB(r, g, b, hsb);
-        HS[curImage][i*2]=hsb[0];
-        HS[curImage][i*2+1]=hsb[1];
-      }
-    }
-    return HS[curImage];
-  }
-  
-  public float[] getSpecialHS() 
-  {
-  	if (allHS==null) 
-    {
-      allHS=new float[alldata.length*2];
-      float[] hsb=new float[3];
-      for (int i=0; i<alldata.length; i++) 
-      {
-        int r=(alldata[i]>>16)&0xFF;
-        int g=(alldata[i]>>8)&0xFF;
-        int b=alldata[i]&0xFF;
-        Color.RGBtoHSB(r, g, b, hsb);
-        allHS[i*2]=hsb[0];
-        allHS[i*2+1]=hsb[1];
-      }
-    }
-    return allHS;
-  	
-  }
-
-  public float[][] getAllHS()
-  {
-    
-    for(int k=0; k<numImages; k++)
-    {
-	    if (HS[k]==null && retdata[k] != null) 
-	    {
-	      HS[k]=new float[retdata[k].length*2];
-	      float[] hsb=new float[3];
-	      for (int i=0; i<retdata[k].length; i++) 
-	      {
-	        int r=(retdata[k][i]>>16)&0xFF;
-	        int g=(retdata[k][i]>>8)&0xFF;
-	        int b=retdata[k][i]&0xFF;
-	        Color.RGBtoHSB(r, g, b, hsb);
-	        HS[k][i*2]=hsb[0];
-	        HS[k][i*2+1]=hsb[1];
-	      }
-	    }
-    }
-    return HS;
-  }
-
-	// assumes retdata holds RGB
-  public float[] getHB() {
-    if (HB[curImage]==null) {
-      HB[curImage]=new float[retdata[curImage].length*2];
-      float[] hsb=new float[3];
-      for (int i=0; i<retdata[curImage].length; i++) {
-        int r=(retdata[curImage][i]>>16)&0xFF;
-        int g=(retdata[curImage][i]>>8)&0xFF;
-        int b=retdata[curImage][i]&0xFF;
-        Color.RGBtoHSB(r, g, b, hsb);
-        HB[curImage][i*2]=hsb[0];
-        HB[curImage][i*2+1]=hsb[2];
-      }
-    }
-    return HB[curImage];
-  }
-
-	// assumes retdata holds RGB
-  public float[] getSB() {
-    if (SB[curImage]==null) {
-      SB[curImage]=new float[retdata[curImage].length*2];
-      float[] hsb=new float[3];
-      for (int i=0; i<retdata[curImage].length; i++) {
-        int r=(retdata[curImage][i]>>16)&0xFF;
-        int g=(retdata[curImage][i]>>8)&0xFF;
-        int b=retdata[curImage][i]&0xFF;
-        Color.RGBtoHSB(r, g, b, hsb);
-        SB[curImage][i*2]=hsb[1];
-        SB[curImage][i*2+1]=hsb[2];
-      }
-    }
-    return SB[curImage];
-  }
-  
- 
+	String[] files;
+	int[][] originalImages;
+	BufferedImage[] rgbImages;
+	float[][] yuvImages;
+	float[][] spectrumImages;
 
-  void loadFile(String filename) 
-  {
-    // System.out.println("Loading: " + filename);
-    Image image=toolkit.createImage(filename);
-    MediaTracker mediaTracker=new MediaTracker(this);
-    mediaTracker.addImage(image, 0);
-    try {
-      mediaTracker.waitForID(0);
-    } catch (InterruptedException e) {
-      System.out.println(e);
-      System.exit(1);
-    }
-    image_width=image.getWidth(this);
-    image_height=image.getHeight(this);
+	ColorConverter OriginalToRGB;
+	ColorConverter YUVToSpectrum;
+	ColorConverter OriginalToYUV;
+	
+	int[] widths;
+	int[] heights;
+	
+	int numImages;
+	
+	public ImageData(String[] files, ColorConverter toRGB, ColorConverter toYUV, ColorConverter toSpectrum) {
+		OriginalToRGB=toRGB;
+		OriginalToYUV=toYUV;
+		YUVToSpectrum=toSpectrum;
+		loadFiles(files);
+	}
+	
+	public void loadFiles(String[] loadfiles) {
+		files=loadfiles;
+		numImages = files.length;
+		originalImages=new int[numImages][];
+		rgbImages=new BufferedImage[numImages];
+		spectrumImages=new float[numImages][];
+		yuvImages=new float[numImages][];
+		widths=new int[numImages];
+		heights=new int[numImages];
+		
+		float[] tmp=new float[3];
+		
+		for(int i=0; i<numImages; i++) {
+			//System.out.println("i="+i+" numImages="+numImages+" files="+files.length);
+			File f = new File(files[i]);
+			if(!f.isFile()) {
+				System.out.println("Could not find a File named "+files[i]);
+				System.exit(1);
+			}
+			
+			if(f.getName().toLowerCase().endsWith(".jpeg") || f.getName().toLowerCase().endsWith(".jpg")) {
+				//jpegs actually store YUV internally, we can access it directly
+				try {
+					System.out.println(f+" is a jpeg");
+					ImageInputStream jpegStream=new MemoryCacheImageInputStream(new FileInputStream(f));
+					ImageReader jpegReader=(ImageReader)ImageIO.getImageReadersByFormatName("jpeg").next();
+					jpegReader.setInput(jpegStream); 
+					
+					BufferedImage bi=jpegReader.read(0);
+					if(bi==null) {
+						System.out.println(f+" is not a valid image file (error during loading).  Skipping...");
+						removeFile(i);
+						i--;
+						continue;
+					}
+					widths[i]=bi.getWidth();
+					heights[i]=bi.getHeight();
+					originalImages[i]=bi.getRGB(0,0,widths[i],heights[i],null,0,widths[i]);
+					
+					Raster decoded=jpegReader.readRaster(0,null);
+					if(decoded==null) {
+						System.out.println(f+" is not a valid image file (error during loading).  Skipping...");
+						removeFile(i);
+						i--;
+						continue;
+					}
+					yuvImages[i] = new float[originalImages[i].length*3];
+					int off=0;
+					for(int y=0; y<heights[i]; y++)
+						for(int x=0; x<widths[i]; x++) {
+							yuvImages[i][off++]=decoded.getSampleFloat(x,y,0)/255;
+							yuvImages[i][off++]=decoded.getSampleFloat(x,y,1)/255;
+							yuvImages[i][off++]=decoded.getSampleFloat(x,y,2)/255;
+						}
 
-    BufferedImage bi = new BufferedImage(image_width, image_height,
-                                         BufferedImage.TYPE_INT_RGB);
-    Graphics big = bi.createGraphics();
-    big.drawImage(image,0,0,null);
-    data[curImage]=bi.getRGB(0,0,image_width,image_height,null,0,image_width);
-    
-  }
+					rgbImages[i]=new BufferedImage(widths[i], heights[i], BufferedImage.TYPE_INT_RGB);
+					rgbImages[i].getRaster().setDataElements(0,0,widths[i],heights[i],originalImages[i]);
+				} catch(Exception ex) {
+					System.out.println(f+" is not a valid image file (error during loading).  Skipping...");
+					//e.printStackTrace();
+					//System.exit(1);
+					removeFile(i);
+					i--;
+					continue;
+				} 
+			} else {
+				//read as a generic image
+				BufferedImage bi=null;
+				try {
+					bi=ImageIO.read(f);
+				} catch (Exception e) {
+					System.out.println(f+" is not a valid image file (error during loading).  Skipping...");
+					//e.printStackTrace();
+					//System.exit(1);
+					removeFile(i);
+					i--;
+					continue;
+				}
+				if(bi==null) {
+					System.out.println(f+" is not a valid image file (error during loading).  Skipping...");
+					removeFile(i);
+					i--;
+					continue;
+				}
+				widths[i]=bi.getWidth();
+				heights[i]=bi.getHeight();
+				originalImages[i]=bi.getRGB(0,0,widths[i],heights[i],null,0,widths[i]);
+				
+				yuvImages[i] = new float[originalImages[i].length*3];
+				if(OriginalToYUV==null) {
+					int off=0;
+					for(int j=0; j<originalImages[i].length; j++) {
+						yuvImages[i][off++]=((originalImages[i][j]>>16)&0xFF)/255.f;
+						yuvImages[i][off++]=((originalImages[i][j]>>8)&0xFF)/255.f;
+						yuvImages[i][off++]=((originalImages[i][j]>>0)&0xFF)/255.f;
+					}
+				} else {
+					int off=0;
+					for(int j=0; j<originalImages[i].length; j++) {
+						OriginalToYUV.getColor(originalImages[i][j],tmp);
+						yuvImages[i][off++]=tmp[0];
+						yuvImages[i][off++]=tmp[1];
+						yuvImages[i][off++]=tmp[2];						
+					}
+				}
 
-	public void loadYUVJPEG(String filename) {
-		try {
-			ImageInputStream jpegStream=new MemoryCacheImageInputStream(new FileInputStream(filename));
-			ImageReader jpegReader=(ImageReader)ImageIO.getImageReadersByFormatName("jpeg").next();
-			jpegReader.setInput(jpegStream); 
-			Raster decoded=jpegReader.readRaster(0,null);
-			image_width=decoded.getWidth();
-			image_height=decoded.getHeight();
-			data[curImage] = new int[image_width*image_height];
-			int off=0;
-			for(int y=0; y<image_height; y++)
-				for(int x=0; x<image_width; x++) {
-					int yc=decoded.getSample(x,y,0);
-					int uc=decoded.getSample(x,y,2);
-					int vc=decoded.getSample(x,y,1);
-					data[curImage][off++]=(yc<<16) | (uc<<8) | vc;
+				rgbImages[i]=new BufferedImage(widths[i], heights[i], BufferedImage.TYPE_INT_RGB);
+				if(OriginalToRGB==null) {
+					rgbImages[i].getRaster().setDataElements(0,0,widths[i],heights[i],originalImages[i]);
+					//rgbImages[i].getRaster().setPixels(0,0,widths[i],heights[i],yuvImages[i]);
+				} else {
+					int[] rgbData=new int[originalImages[i].length*3];
+					for(int j=0; j<originalImages[i].length; j++) {
+						OriginalToRGB.getColor(originalImages[i][j],tmp);
+						rgbData[j]=Math.round(tmp[0]*255)<<16 | Math.round(tmp[1]*255)<<8 | Math.round(tmp[2]*255);
+					}
+					rgbImages[i].getRaster().setDataElements(0,0,widths[i],heights[i],rgbData);
 				}
-		} catch(Exception ex) { ex.printStackTrace(); }
+			}
+			
+		}
+
+		changeSpectrum(YUVToSpectrum);
+			
 	}
 
-  public void loadYUVFileAsRGB(String filename) {
-    loadFile(filename);
-    YUV2RGB();
-    retdata[curImage]=data[curImage];
-  }
+	void removeFile(int i) {
+		numImages--;
 
-	public void loadRGBFileAsYUV(String filename) {
-		if(filename.endsWith(".jpg") || filename.endsWith(".jpeg") || filename.endsWith(".JPG") || filename.endsWith(".JPEG"))
-			loadYUVJPEG(filename);
-		else {
-			loadFile(filename);
-			RGB2YUV();
+		String[] fs=new String[numImages];
+		int[][] ois=new int[numImages][];
+		BufferedImage[] ris=new BufferedImage[numImages];
+		float[][] sis=new float[numImages][];
+		float[][] yis=new float[numImages][];
+		int[] ws=new int[numImages];
+		int[] hs=new int[numImages];
+		for(int j=0; j<i; j++) {
+			fs[j]=files[j];
+			ois[j]=originalImages[j];
+			ris[j]=rgbImages[j];
+			sis[j]=spectrumImages[j];
+			yis[j]=yuvImages[j];
+			ws[j]=widths[j];
+			hs[j]=heights[j];
 		}
-    retdata[curImage]=data[curImage];
-	}
-
-	public void loadRGBFileAsRGB(String filename) {
-    loadFile(filename);
-    retdata[curImage]=data[curImage];
+		for(int j=i; j<numImages; j++) {
+			fs[j]=files[j+1];
+			ois[j]=originalImages[j+1];
+			ris[j]=rgbImages[j+1];
+			sis[j]=spectrumImages[j+1];
+			yis[j]=yuvImages[j+1];
+			ws[j]=widths[j+1];
+			hs[j]=heights[j+1];
+		}
+		files=fs;
+		originalImages=ois;
+		rgbImages=ris;
+		spectrumImages=sis;
+		yuvImages=yis;
+		widths=ws;
+		heights=hs;
 	}
-
-	public void loadYUVFileAsYUV(String filename) {
-    loadFile(filename);
-    retdata[curImage]=data[curImage];
+	
+	public void changeSpectrum(ColorConverter YUVToSpectrum) {
+		this.YUVToSpectrum=YUVToSpectrum;
+		if(YUVToSpectrum==null) {
+			spectrumImages=yuvImages;
+		} else {
+			float[] tmp=new float[3];
+			for(int i=0; i<numImages; i++) {
+				if(spectrumImages[i]==null || spectrumImages[i].length!=originalImages[i].length*3)
+					spectrumImages[i]=new float[originalImages[i].length*3];
+				for(int j=0; j<yuvImages[i].length; j+=3) {
+					YUVToSpectrum.getColor(yuvImages[i][j],yuvImages[i][j+1],yuvImages[i][j+2],tmp);					
+					spectrumImages[i][j]=tmp[0];
+					spectrumImages[i][j+1]=tmp[1];
+					spectrumImages[i][j+2]=tmp[2];						
+				}
+			}
+		}
+		
 	}
 
-	// this isn't the "real" conversion, but a quick approx.
-	// it's the same that's used in tekkotsumon's VisionListener
-  public void YUV2RGB() {
-    for (int i=0; i<data[curImage].length; i++) {
-      int y=(int)((data[curImage][i]>>16)&0xFF);
-      int u=(int)((data[curImage][i]>>8)&0xFF);
-      int v=(int)(data[curImage][i]&0xFF);
-      u=u*2-255;
-      v=v*2-255;
-      int r=y+u;
-      int b=y+v;
-      u=u>>1;
-      v=(v>>2)-(v>>4);
-      int g=y-u-v;
-      if (r<0) r=0; if (g<0) g=0; if (b<0) b=0;
-      if (r>255) r=255; if (g>255) g=255; if (b>255) b=255;
-
-      data[curImage][i]= (r<<16) | (g<<8) | b;
-    }
-  }
-
-	// this isn't the "real" conversion, nor a quick approx, but
-	// it will get as close as possible to an exact undo of the YUV2RGB conversion
-	// we use in VisionListener (and here)
-  public void RGB2YUV() {
-    for (int i=0; i<data[curImage].length; i++) {
-      int r=(int)((data[curImage][i]>>16)&0xFF);
-      int g=(int)((data[curImage][i]>>8)&0xFF);
-      int b=(int)(data[curImage][i]&0xFF);
-			int y=(int)( 8*r/27 +  g/ 9  + 16*b/27 - 203/27);
-			int u=(int)(19*r/54 -  g/18  -  8*b/27 +3544/27);
-			int v=(int)(-4*r/27 +4*g/ 9  -  8*b/27 +3544/27); 
-      if (y<0) y=0; if (u<0) u=0; if (v<0) v=0;
-      if (y>255) y=255; if (u>255) u=255; if (v>255) v=255;
-      data[curImage][i]= (y<<16) | (u<<8) | v;
-    }
-  }
-
-  public void loadFullRGBFilesAsRGB(String files[]) 
-  {
-    for (int i=0; i<files.length; i++) 
-    {
-	  
-	  loadFile(files[i]);
-      
-      if (i==0) alldata=new int[files.length*data[curImage].length];
-			//for (int j=0; j<data.length; j++)
-			//retdata[j+(i*data.length)]=data[j];
-      int l=0;
-	  for (int j=i; j<retdata[curImage].length; j+=files.length)
-	  {
-	  	alldata[j]=data[curImage][l++];
-	  }
-    }
-  }
-
-  public void loadFullYUVFilesAsRGB(String files[]) 
-  {
-    for (int i=0; i<files.length; i++) 
-    {
-      loadFile(files[i]);
-      if (i==0) alldata=new int[files.length*data[curImage].length];
-      YUV2RGB();
-      int l=0;
-      for (int j=i; j<alldata.length; j+=files.length)
-        alldata[j]=data[curImage][l++];
-    }
-  }
-  
-  public void setCurimg(int curimg)
-  {
-  	curImage = curimg; 
-  
-  }
-  
+	public int getNumImages() { return numImages; }
+	public String[] getFileNames() { return files; }
+	
+	public BufferedImage[] getRGBImages() { return rgbImages; }
+	public float[][] getSpectrumImages() { return spectrumImages; }
+	public float[][] getYUVImages() { return yuvImages; }
+	
+	public BufferedImage getRGBImage(int i) { return rgbImages[i]; }
+	public float[] getSpectrumImage(int i) { return spectrumImages[i]; }
+	public float[] getYUVImage(int i) { return yuvImages[i]; }
+		
+	public int getHeight(int i) { return heights[i]; }
+	public int getWidth(int i) { return widths[i]; }
+	
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/ImagePanel.java ./tools/easytrain/ImagePanel.java
--- ../Tekkotsu_2.4.1/tools/easytrain/ImagePanel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/easytrain/ImagePanel.java	2005-11-02 12:40:38.000000000 -0500
@@ -0,0 +1,196 @@
+import java.awt.image.*;
+import java.awt.*;
+import javax.swing.*;
+import javax.swing.event.*;
+import java.awt.event.*;
+import java.util.*;
+import java.awt.geom.*;
+import java.io.*;
+import java.util.prefs.Preferences;
+
+
+public class ImagePanel extends JComponent
+{
+	BufferedImage image;
+	Point2D hint;
+	int hintStroke;
+	int pointSize;
+
+	public ImagePanel() {
+		image=new BufferedImage(1,1,BufferedImage.TYPE_INT_RGB);
+		hint=null;
+		hintStroke=1;
+		pointSize=1;
+	}
+	
+	public void setImage(BufferedImage img) { image=img; repaint(); }
+	public BufferedImage getImage() { return image; }
+	
+	public void setupGraphics(Graphics2D g2d) {
+		g2d.setRenderingHint(RenderingHints.KEY_ALPHA_INTERPOLATION,RenderingHints.VALUE_ALPHA_INTERPOLATION_QUALITY);
+		g2d.setRenderingHint(RenderingHints.KEY_ANTIALIASING ,RenderingHints.VALUE_ANTIALIAS_ON );
+		g2d.setRenderingHint(RenderingHints.KEY_COLOR_RENDERING ,RenderingHints.VALUE_COLOR_RENDER_QUALITY );
+		g2d.setRenderingHint(RenderingHints.KEY_INTERPOLATION ,RenderingHints.VALUE_INTERPOLATION_NEAREST_NEIGHBOR );
+		g2d.setRenderingHint(RenderingHints.KEY_RENDERING ,RenderingHints.VALUE_RENDER_QUALITY );
+	}
+	
+	public void paintComponent(Graphics g) {
+		Graphics2D g2d=(Graphics2D)g;
+		setupGraphics(g2d);
+
+		AffineTransform trans=AffineTransform.getScaleInstance(getWidth()/(double)image.getWidth(),getHeight()/(double)image.getHeight());
+		g2d.setColor(getParent().getBackground());
+		g2d.fill(g2d.getClip());
+		g2d.drawImage(image, trans, null);
+		if(hint!=null) {
+			g2d.setStroke(new BasicStroke(hintStroke));
+			g2d.setColor(invert(getParent().getBackground()));
+			Rectangle r=getHintRect();
+			//g2d.setRenderingHint(RenderingHints.KEY_ANTIALIASING ,RenderingHints.VALUE_ANTIALIAS_OFF );
+			//g2d.drawRect(r.x,r.y,r.width,r.height);
+			//g2d.setRenderingHint(RenderingHints.KEY_ANTIALIASING ,RenderingHints.VALUE_ANTIALIAS_ON );
+			if((hintStroke/2)*2==hintStroke) {
+				//keep drawing aligned with pixel boundaries (no half pixel drawing)
+				Rectangle2D.Float r2=new Rectangle2D.Float(r.x-.5f,r.y-.5f,r.width,r.height);
+				g2d.draw(r2);
+			} else {
+				g2d.drawRect(r.x,r.y,r.width,r.height);
+			}
+		}
+	}
+	
+	public void setHintStroke(int hintStroke) {
+		this.hintStroke=hintStroke;
+	}
+	public int getHintStroke() {
+		return hintStroke;
+	}
+	public void setHintPointSize(int pointSize) {
+		this.pointSize=pointSize;
+	}
+	public int getHintPointSize() {
+		return pointSize;
+	}
+	
+	public void setHint(Point2D hint) {
+		if(this.hint!=null)
+			repaint(getShapeBounds(getHintRect()));
+		if(hint==null) {
+			this.hint=null;
+			return;
+		}
+		this.hint=(Point2D)hint.clone();
+		repaint(getShapeBounds(getHintRect()));
+	}
+	
+	Rectangle getHintRect() {
+		int px=Math.round((float)hint.getX()*(image.getWidth()-pointSize)); //same formula used for plotting
+		int py=Math.round((float)hint.getY()*(image.getHeight()-pointSize)); // (res-pointSize so maximal point is visible)
+		float xs=getWidth()/(float)image.getWidth();
+		float ys=getHeight()/(float)image.getHeight();
+		int ul=hintStroke/2;
+		int lr=hintStroke-ul;
+		int x=Math.round(px*xs)-lr;
+		int y=Math.round(py*ys)-lr;
+		int width=Math.round((px+pointSize)*xs)-x+ul;
+		int height=Math.round((py+pointSize)*ys)-y+ul;
+		if(width<hintStroke+1) width=hintStroke+1;
+		if(height<hintStroke+1) height=hintStroke+1;
+		return new Rectangle(x,y,width,height);
+	}
+	
+	Rectangle getShapeBounds(Shape s) {
+		//AffineTransform trans=AffineTransform.getScaleInstance(getWidth(),getHeight());
+		//Rectangle2D scrnBnds=trans.createTransformedShape(s).getBounds2D();
+		Rectangle2D scrnBnds=s.getBounds();
+		int ul=hintStroke/2;
+		return new Rectangle((int)(scrnBnds.getX()-ul)-1, (int)(scrnBnds.getY()-ul)-1,(int)(scrnBnds.getWidth()+hintStroke+3),(int)(scrnBnds.getHeight()+hintStroke+3));
+	}
+	
+	static protected Color invert(Color c) {
+		//can't invert gray -- if it's close to gray, just use white/black
+		int rd=128-c.getRed();
+		int gd=128-c.getGreen();
+		int bd=128-c.getBlue();
+		if(rd*rd+gd*gd+bd*bd<10*10) //within 10 units of gray, snap to black or white
+			return ((rd+gd+bd)/3<0) ? Color.BLACK : Color.WHITE;
+		return new Color(255-c.getRed(),255-c.getGreen(),255-c.getBlue(),c.getAlpha());
+	}
+
+	/*	Rectangle getHintRect() {
+		int px=(int)(hint.getX()*image.getWidth());
+		int py=(int)(hint.getY()*image.getHeight());
+		float xs=getWidth()/(float)image.getWidth();
+		float ys=getHeight()/(float)image.getHeight();
+		int x=Math.round(px*xs-1);
+		int y=Math.round(py*ys-1);
+		int width=Math.round((px+1)*xs-x);
+		int height=Math.round((py+1)*ys-y);
+		if(width<2) width=2;
+		if(height<2) height=2;
+		return new Rectangle(x,y,width,height);
+	}*/
+	
+/*	Rectangle getShapeBounds(Shape s) {
+		//AffineTransform trans=AffineTransform.getScaleInstance(getWidth(),getHeight());
+		//Rectangle2D scrnBnds=trans.createTransformedShape(s).getBounds2D();
+		Rectangle2D scrnBnds=s.getBounds();
+		return new Rectangle((int)(scrnBnds.getX()), (int)(scrnBnds.getY()),(int)(scrnBnds.getWidth()+1),(int)(scrnBnds.getHeight()+1));
+	}
+	*/
+	/*public void Paint(Graphics g)
+	{
+		/*System.out.println("jsjsjsjs");
+		
+		
+		Dimension sz=getSize();
+		Point spot = p.spot;
+		
+		if (p._image!=null)
+		  g.drawImage(p._image, 0, 0, sz.width , sz.height , null);
+
+		g.setColor(Color.white);
+		if (p.curArea!=null)
+		  ((Graphics2D)g).draw(p.curArea);
+
+		if (p.curPoly!=null)
+		  ((Graphics2D)g).draw(p.curPoly);
+		
+		if(spot != null)
+		  g.drawRect(spot.x-2, spot.y-2, 5, 5);
+		  
+		content.faint(content.getGraphics());		
+		
+	
+	}*/
+	
+	/*public void faint(Graphics g )
+	{
+		
+		
+		//Graphics g = getGraphics();
+		
+		System.out.println("jfffjsjsjs" + g);
+		
+		Dimension sz=getSize();
+		Point spot = p.spot;
+		
+		if (p._image!=null)
+		  g.drawImage(p._image, 0, 0, sz.width , sz.height , null);
+
+		g.setColor(Color.white);
+		if (p.curArea!=null)
+		  ((Graphics2D)g).draw(p.curArea);
+
+		if (p.curPoly!=null)
+		  ((Graphics2D)g).draw(p.curPoly);
+		
+		if(spot != null)
+		  g.drawRect(spot.x-2, spot.y-2, 5, 5);	
+	
+	}
+	
+	*/
+	
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/ImageSelectionManager.java ./tools/easytrain/ImageSelectionManager.java
--- ../Tekkotsu_2.4.1/tools/easytrain/ImageSelectionManager.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/easytrain/ImageSelectionManager.java	2005-11-01 15:05:51.000000000 -0500
@@ -0,0 +1,410 @@
+import javax.swing.*;
+import javax.swing.undo.UndoableEditSupport;
+import javax.swing.undo.AbstractUndoableEdit;
+import javax.swing.event.*;
+import java.awt.*;
+import java.awt.event.*;
+import java.awt.geom.*;
+import java.util.*;
+
+public class ImageSelectionManager extends JComponent implements MouseListener, MouseMotionListener, KeyListener
+{
+	final static float selectionStrokeWidth=1.5f;
+	Color fillColor;
+	Color strokeColor;
+	UndoableEditSupport undoListeners;
+	
+	class AddEdit extends AbstractUndoableEdit {
+		ImageSelectionManager src;
+		Area addition;
+		Area previous;
+		AddEdit(ImageSelectionManager src, Area previous, Area addition) {
+			super();
+			this.src=src;
+			this.previous=(Area)previous.clone();
+			this.addition=addition;
+		}
+		public void redo() {
+			super.redo();
+			src.selection=(Area)previous.clone();
+			src.selection.add(addition);
+			src.repaint();
+			src.fireSelectionChanged();
+		}
+		public void undo() {
+			super.undo();
+			src.selection=(Area)previous.clone();
+			src.repaint();
+			src.fireSelectionChanged();
+		}
+	}
+	
+	class SubtractEdit extends AbstractUndoableEdit {
+		ImageSelectionManager src;
+		Area removal;
+		Area previous;
+		SubtractEdit(ImageSelectionManager src, Area previous, Area removal) {
+			super();
+			this.src=src;
+			this.previous=(Area)previous.clone();
+			this.removal=removal;
+		}
+		public void redo() {
+			super.redo();
+			src.selection=(Area)previous.clone();
+			src.selection.subtract(removal);
+			src.repaint();
+			src.fireSelectionChanged();
+		}
+		public void undo() {
+			super.undo();
+			src.selection=(Area)previous.clone();
+			src.repaint();
+			src.fireSelectionChanged();
+		}
+	}
+	
+	class ReplaceEdit extends AbstractUndoableEdit {
+		ImageSelectionManager src;
+		Area next;
+		Area previous;
+		ReplaceEdit(ImageSelectionManager src, Area previous, Area next) {
+			super();
+			this.src=src;
+			this.previous=(Area)previous.clone();
+			this.next=(next==null) ? null : (Area)next.clone();
+		}
+		public void redo() {
+			super.redo();
+			if(next==null) {
+				src.clear();
+			} else {
+				src.selection=(Area)next.clone();
+				src.repaint();
+				src.fireSelectionChanged();
+			}
+		}
+		public void undo() {
+			super.undo();
+			src.selection=(Area)previous.clone();
+			src.repaint();
+			src.fireSelectionChanged();
+		}
+	}
+	
+	Area selection; //the current full selection -- may contain disjoint areas; coordinates are stored in the range 0-1 (window size independent)
+	
+	GeneralPath selInProgress; //a path in the process of being drawn (null if mouse is not down); coordinates are stored in the range 0-1 (window size independent)
+	Point lastPos; // the screen X position of the last mouse event, so we know where the polyInProgress end is at
+	boolean curIsAdd; //true if the current selection in progress is a 'union' operation; if not curIsSubtract as well, is 'replace'
+	boolean curIsSubtract; //true if the current selection in progress is a 'subtract' operation; if not curIsAdd as well, is 'replace'
+	ReplaceEdit replaceInProgress; //non-null after the current selection has been replaced (only happens once mouse is dragged without modifiers)
+	
+	public ImageSelectionManager() {
+		init(this);
+	}
+	
+	public ImageSelectionManager(Component clickSrc) {
+		init(clickSrc);
+	}
+	
+	protected void init(Component clickSrc) {
+		fillColor=new Color(255,255,255,96);
+		strokeColor=Color.WHITE;
+		selection=new Area();
+		selInProgress=null;
+		listeners=new Vector();
+		clickSrc.addMouseListener(this);
+		clickSrc.addMouseMotionListener(this);
+		clickSrc.setCursor(new Cursor(Cursor.CROSSHAIR_CURSOR));
+		clickSrc.addKeyListener(this);
+		undoListeners=new UndoableEditSupport();
+		replaceInProgress=null;
+	}
+	
+	public void addUndoableEditListener(UndoableEditListener l) { undoListeners.addUndoableEditListener(l); }
+	public void removeUndoableEditListener(UndoableEditListener l) { undoListeners.removeUndoableEditListener(l); }
+	
+	public void setFillColor(Color c) {
+		fillColor=c;
+		repaintSelection();
+	}
+	
+	public void setStrokeColor(Color c) {
+		strokeColor=c;
+		repaintSelection();
+	}
+	
+	public void invertColors() {
+		fillColor=invert(fillColor);
+		strokeColor=invert(strokeColor);
+		repaintSelection();
+	}
+	
+	static protected Color invert(Color c) {
+		return new Color(255-c.getRed(),255-c.getGreen(),255-c.getBlue(),c.getAlpha());
+	}
+	
+	protected void repaintSelection() {
+		repaint(getShapeBounds(selection));
+		if(selInProgress!=null)
+			repaint(getShapeBounds(selInProgress));
+	}
+	
+	public void clear() {
+		if(!selection.isEmpty()) {
+			Rectangle r=getShapeBounds(selection);
+			undoListeners.postEdit(new ReplaceEdit(this,selection,null));
+			selection.reset();
+			repaint(r);
+			fireSelectionChanged();
+		}
+	}
+	
+	public Area getSelectedArea() { return (Area)selection.clone(); }
+	public void setSelectedArea(Area selection) {
+		if(selection==null)
+			this.selection.reset();
+		else
+			this.selection=(Area)selection.clone();
+		repaint();
+		fireSelectionChanged();
+	}
+	
+	public Area getSelectionInProgress() {
+		if(selInProgress==null) {
+			return getSelectedArea();
+		} else {
+			if(curIsSubtract) {
+				Area all=(Area)selection.clone();
+				all.subtract(new Area(selInProgress));
+				return all;
+			} else {
+				Area all=new Area(selInProgress);
+				all.add(selection);
+				return all;
+			}
+		}
+	}
+	
+	//******* LISTENER MANAGEMENT ********
+	Vector listeners; //a vector of UndoableEditListeners, to be notified whenever selection is changed
+	boolean firing; //true if in the process of notifying SelectionListeners
+	interface SelectionListener extends EventListener {
+		public void selectionInProgress(ImageSelectionManager src);
+		public void selectionChanged(ImageSelectionManager src);
+	}
+	
+	public void addSelectionListener(SelectionListener l) { listeners.add(l); }
+	public void removeSelectionListener(SelectionListener l) { listeners.remove(l); }
+	public void fireSelectionChanged() {
+		firing=true;
+		for(int i=0; i<listeners.size() && firing; i++)
+			((SelectionListener)listeners.get(i)).selectionChanged(this);
+		firing=false;
+	}
+	public void fireSelectionInProgress() {
+		firing=true;
+		for(int i=0; i<listeners.size() && firing; i++)
+			((SelectionListener)listeners.get(i)).selectionInProgress(this);
+		firing=false;
+	}
+	
+	//******* GRAPHICS ********
+	public void paintComponent(Graphics g) {
+		Graphics2D g2d=(Graphics2D) g;
+		AffineTransform origTrans=g2d.getTransform();
+		g2d.transform(AffineTransform.getScaleInstance(getWidth()-1,getHeight()-1));
+			
+		float strokeWidth=2.f/(getWidth()+getHeight()); //average of width and height so 1 pixel stroke on screen
+		g2d.setStroke(new BasicStroke(selectionStrokeWidth*strokeWidth));
+
+		if(selInProgress!=null) {
+			Area inside=(Area)selection.clone();
+			inside.intersect(new Area(selInProgress));
+			g2d.setPaint(curIsSubtract?Color.RED:strokeColor);
+			g2d.draw(inside);
+			
+			Area outside=(Area)selection.clone();
+			outside.subtract(new Area(selInProgress));
+			g2d.setPaint(fillColor);
+			g2d.fill(outside);
+			g2d.setPaint(strokeColor);
+			g2d.draw(outside);
+			
+			if(!curIsSubtract) {
+				g2d.setPaint(fillColor);
+				g2d.fill(selInProgress);
+			}
+			g2d.setPaint(strokeColor);
+			g2d.draw(selInProgress);
+		} else {
+			g2d.setPaint(fillColor);
+			g2d.fill(selection);
+			g2d.setPaint(strokeColor);
+			g2d.draw(selection);
+		}
+
+		g2d.setTransform(origTrans);
+	}
+
+	//******* MOUSE CONTROLS ********
+	
+	//workaround for bug in OS X: 
+	// http://developer.apple.com/releasenotes/Java/JavaMOSX10.3RN/Known/chapter_3_section_5.html
+	boolean button1down=false;
+	
+	//takes a mouse event from a (possibly parent) panel, translates and clips it to this
+	Point getEventPoint(MouseEvent e) {
+		Point p=e.getPoint();
+		for(Component c=this; c!=null && c!=e.getComponent(); c=c.getParent())
+			p.translate(-c.getX(),-c.getY());
+		if(p.x<0)
+			p.x=-1;
+		if(p.y<0)
+			p.y=-1;
+		if(p.x>getWidth())
+			p.x=getWidth();
+		if(p.y>getHeight())
+			p.y=getHeight();
+		return p;
+	}
+	
+	Rectangle getShapeBounds(Shape s) {
+		AffineTransform trans=AffineTransform.getScaleInstance(getWidth()-1,getHeight()-1);
+		Rectangle2D scrnBnds=trans.createTransformedShape(s).getBounds2D();
+		return new Rectangle((int)(scrnBnds.getX()-selectionStrokeWidth/2), (int)(scrnBnds.getY()-selectionStrokeWidth/2),(int)(scrnBnds.getWidth()+selectionStrokeWidth+2),(int)(scrnBnds.getHeight()+selectionStrokeWidth+2));
+	}
+	
+	public void mousePressed(MouseEvent e) 
+	{
+		//System.out.println("press: "+e);
+		
+		if (e.getButton()!=MouseEvent.BUTTON1){return;}
+		button1down=true;
+		lastPos=getEventPoint(e);
+
+		if (e.isControlDown() && e.isShiftDown()) {
+			//ambiguous, cancel operation
+			button1down=false;
+		} else {
+			selInProgress=new GeneralPath(GeneralPath.WIND_NON_ZERO);
+			selInProgress.moveTo(lastPos.x/(float)(getWidth()-1),lastPos.y/(float)(getHeight()-1));
+			curIsAdd=curIsSubtract=false;
+			replaceInProgress=null;
+			if (e.isControlDown()) {
+				curIsSubtract=true;
+			} else if (e.isShiftDown()) {
+				curIsAdd=true;
+			}
+		}
+	}
+	
+	public void mouseDragged(MouseEvent e) 
+	{	  
+		//System.out.println("drag: "+e);
+		
+		//getButton could be 0 if we are forwarding call from mouseMoved to get around OS X bug
+		if (!button1down || e.getButton()!=0 && e.getButton()!=MouseEvent.BUTTON1){return;}
+		if (selInProgress==null) return;
+		
+		if(!curIsAdd && !curIsSubtract && replaceInProgress==null) {
+			repaint(getShapeBounds(selection));
+			replaceInProgress=new ReplaceEdit(this,selection,null);
+			selection.reset();
+			fireSelectionChanged();
+		}
+		Point curPoint=getEventPoint(e);
+		if (curPoint.distance(lastPos)>0) {
+			lastPos=curPoint;
+			selInProgress.lineTo(lastPos.x/(float)(getWidth()-1),lastPos.y/(float)(getHeight()-1));
+			repaint(getShapeBounds(selInProgress));
+			fireSelectionInProgress();
+		}
+	}
+	
+	public void mouseReleased(MouseEvent e) 
+	{
+		//System.out.println("released: "+e);
+		
+		if (!button1down || e.getButton()!=MouseEvent.BUTTON1) return;
+		button1down=false;
+		
+		if (selInProgress==null) return;
+		
+		Point curPoint=getEventPoint(e);
+		if (curPoint.distance(lastPos)>0) {
+			lastPos=curPoint;
+			selInProgress.lineTo(lastPos.x/(float)(getWidth()-1),lastPos.y/(float)(getHeight()-1));
+		}
+		selInProgress.closePath();
+		
+		int npoints=0;
+		for(PathIterator it=selInProgress.getPathIterator(null); !it.isDone(); it.next(), npoints++) {}
+		
+		if (npoints>=3) 
+		{
+			if(curIsSubtract) { 
+				Area removal=new Area(selInProgress);
+				undoListeners.postEdit(new SubtractEdit(this,selection,removal));
+				selection.subtract(removal);
+			} else { //add or replace
+				Area addition=new Area(selInProgress);
+				if(replaceInProgress==null) //add
+					undoListeners.postEdit(new AddEdit(this,selection,addition));
+				else { //replace
+					replaceInProgress.next=addition;
+					undoListeners.postEdit(replaceInProgress);
+					replaceInProgress=null;
+				}
+				selection.add(addition);
+			}
+		}
+		
+		repaint();
+		selInProgress=null;
+		fireSelectionChanged();
+		
+		//		segImage.reSegment(makeTmap(), getAverageColors());
+	}
+	
+	public void mouseMoved(MouseEvent e)
+	{
+		//workaround for bug with OS X
+		// http://developer.apple.com/releasenotes/Java/JavaMOSX10.3RN/Known/chapter_3_section_5.html
+		//System.out.println("getButton()="+e.getButton()+"  button1down="+button1down+"  isControlDown()="+e.isControlDown());
+		if(e.getButton()==0 && button1down && e.isControlDown()) {
+			mouseDragged(e);
+			return;
+		}
+	}
+	
+	public void mouseClicked(MouseEvent e){}
+	public void mouseExited(MouseEvent e){}
+	public void mouseEntered(MouseEvent e){}
+	public void updateLocation(MouseEvent e){}
+
+	public void keyPressed(KeyEvent e) {
+		if((e.getModifiersEx()&(InputEvent.META_DOWN_MASK|InputEvent.CTRL_DOWN_MASK))!=0) {
+			switch(e.getKeyCode()) {
+				case KeyEvent.VK_A: {
+					Area newsel=new Area(new Rectangle(-1,-1,3,3));
+					undoListeners.postEdit(new ReplaceEdit(this,selection,newsel));
+					selection=newsel;
+					break;
+				}
+				case KeyEvent.VK_D: {
+					undoListeners.postEdit(new ReplaceEdit(this,selection,null));
+					selection.reset();
+					break;
+				}
+				default:
+					return;
+			}
+			repaint();
+			fireSelectionChanged();
+		}
+	}
+	public void keyReleased(KeyEvent e) {} 
+	public void keyTyped(KeyEvent e) {}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/ImageShowArea.java ./tools/easytrain/ImageShowArea.java
--- ../Tekkotsu_2.4.1/tools/easytrain/ImageShowArea.java	2005-08-03 20:27:38.000000000 -0400
+++ ./tools/easytrain/ImageShowArea.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,277 +0,0 @@
-/** @file ImageShowArea.java
- *  @brief 
- *
- *  Frame for showing the image
- *
- *	@author editted by: Eric Durback
- *  @bug No known bugs.
- */
-
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.io.*;
-import java.util.*;
-import java.awt.geom.*;
-import java.util.prefs.Preferences;
-
-public class ImageShowArea extends JFrame implements KeyListener, ComponentListener, FocusListener 
-{
-	BufferedImage _image;
-	String[] imglist;
-	byte[] tmap;
-	ImageData imageData,YUVimageData;
-	int curimg;
-	int numImages;
-	boolean isRGB;
-	boolean sizeFixed;
-
-	Polygon curPoly;
-	Area curArea;
-	TrainCanvas trainCanvas;
-	double resizedX;
-	double resizedY;
-	double lastX,lastY;
-	
-	static Preferences prefs = Preferences.userNodeForPackage(ImageShowArea.class);
- 
-	public void focusGained(FocusEvent e) {} 
-
-	public void focusLost(FocusEvent e) {}
-
-	public static void usageAndExit() 
-	{
-		System.out.println("usage: java ImageShow (-isRGB|-isYUV) raw_image [raw images]");
-		System.exit(1);		
-	}
-
-	public ImageShowArea (boolean isRGB, String args[], ImageData imgData) 
-	{
-	  	curPoly = null;
-	  	curArea = null;
-	  	resizedX=1.0;
-	  	resizedY=1.0;
-	  
-	  
-		numImages = args.length;
-		imageData=imgData;
-		YUVimageData = new ImageData(1);
-		sizeFixed = false;
-
-		this.isRGB=isRGB;
-		if(isRGB)
-		{
-			imageData.loadRGBFileAsRGB(args[0]);
-			imageData.loadFullRGBFilesAsRGB(args);
-		}
-		else
-		{
-			imageData.loadYUVFileAsRGB(args[0]);
-			imageData.loadFullYUVFilesAsRGB(args);
-		}
-
-		int[] data=imageData.getPixels();
-
-		setBackground(Color.black);
-		setSize(imageData.image_width*2, imageData.image_height*2);
-		setTitle((curimg+1) + ": " + args[0]);
-		setLocation(prefs.getInt("ImageShowArea.location.x",50),prefs.getInt("ImageShowArea.location.y",50));
-
-		_image=new BufferedImage(imageData.image_width, imageData.image_height,
-		    BufferedImage.TYPE_INT_RGB);
-		    
-		lastX = (double)getWidth();
-		lastY = (double)getHeight();
-
-		showImage(data, tmap, imageData.image_width, imageData.image_height);
-
-		imglist=new String[numImages];
-		curimg=0;
-		imageData.setCurimg(curimg);
-		
-		//putting images names into the image list
-		for (int i=0; i<numImages; i++) 
-		{
-			imglist[i]=args[i];
-		}
-
-		addKeyListener(this);
-		addComponentListener(this);
-		addFocusListener(this);  
-
-	}
-
-	void showImage(int[] data, byte[] tmap, int width, int height) 
-	{
-		_image.getRaster().setDataElements(0,0,width,height,data);
-		repaint();
-	}
-
-	public void setCurArea(Area _curArea)
-	{
-		curArea = _curArea;
-		repaint();
-	}
-
-	public void setCurPoly(Polygon _curPoly)
-	{
-		curPoly = _curPoly;
-		repaint();
-	}
-
-	public void paint(Graphics graphics) 
-	{
-		Dimension sz=getSize();
-		if (_image!=null)
-		  graphics.drawImage(_image, 0, 0, sz.width, sz.height, null);
-
-		graphics.setColor(Color.white);
-		if (curArea!=null)
-		  ((Graphics2D)graphics).draw(curArea);
-
-		if (curPoly!=null)
-		  ((Graphics2D)graphics).draw(curPoly);
-	}
-
-	public int getPixel(int x, int y) 
-	{
-		Dimension sz=getSize();
-		x=(x*_image.getWidth())/sz.width;
-		y=(y*_image.getHeight())/sz.height;
-		return _image.getRGB(x, y);
-	}
-
-	public void imageChange(int curimg)
-	{
-		imageData.setCurimg(curimg);
-
-		if(isRGB)
-		{
-		  	imageData.loadRGBFileAsRGB(imglist[curimg]);
-		  	YUVimageData.loadRGBFileAsYUV(imglist[curimg]);
-		}
-		else
-		{
-		  	imageData.loadYUVFileAsRGB(imglist[curimg]);
-		  	YUVimageData.loadYUVFileAsYUV(imglist[curimg]);
-		}
-					
-		setTitle(getNewTitle());
-		trainCanvas.segImage.setTitle("Segmented " + getNewTitle());
-		  
-		if(trainCanvas.curImageArea != null)
-		 	setCurArea(trainCanvas.curImageArea[curimg]);
-		  
-		trainCanvas.segImage.setImageData(YUVimageData);
-		  			
-		int[] data=imageData.getPixels();
-		showImage(data, tmap, imageData.image_width, imageData.image_height);	
-
-	}
-
-	public String getNewTitle()
-	{
-		return (curimg+1) + ": " +imglist[curimg];
-	}
-
-	public void keyPressed(KeyEvent e) 
-	{
-		if (e.getKeyCode()==KeyEvent.VK_LEFT ||
-		    e.getKeyCode()==KeyEvent.VK_UP ||
-		    e.getKeyCode()==KeyEvent.VK_PAGE_UP ||
-		    e.getKeyCode()==KeyEvent.VK_KP_UP ||
-		    e.getKeyCode()==KeyEvent.VK_KP_LEFT) 
-		{
-		  	curimg--;
-		  
-		  	if (curimg<0) curimg+=imglist.length;
-				
-		  	imageChange(curimg);
-		} 
-		else if (e.getKeyCode()==KeyEvent.VK_RIGHT ||
-		    e.getKeyCode()==KeyEvent.VK_DOWN ||
-		    e.getKeyCode()==KeyEvent.VK_PAGE_DOWN ||
-		    e.getKeyCode()==KeyEvent.VK_KP_DOWN ||
-		    e.getKeyCode()==KeyEvent.VK_KP_RIGHT) 
-		{
-		  	curimg++;
-		  	
-		  	if (curimg>=imglist.length) curimg-=imglist.length;
-		  
-		  	imageChange(curimg);
-		}
-	}
-	
-	public void keyReleased(KeyEvent e) { }
-	public void keyTyped(KeyEvent e) { }
-
-	public void componentResized(ComponentEvent e) 
-	{            	
-
-		double changeX = (double)getWidth() / lastX;
-		double changeY = (double)getHeight() / lastY;
-
-
-		if(!sizeFixed)
-		{
-		  	
-		  	//maintain aspect ratio at min sizes
-		  	if(getWidth()<= 120 || getHeight() <= 98)
-		  	{
-		  		
-		  		changeX = 120 / lastX;
-		        changeY = 98 / lastY;
-		  		this.setSize(120,98);	  		
-		  	}
-		  	
-		  	else if(   (changeX > changeY && getWidth() > lastX  ) 
-		  	   || (changeX < changeY && getWidth() < lastX  )  )
-		  	{
-		  		changeY = changeX;
-		  		this.setSize(getWidth(),(int)(lastY*changeX));
-		  	}
-		  	else
-		  	{
-		  		changeX = changeY;
-		  		this.setSize((int)(lastX*changeY),getHeight());
-		  	}
-		  	sizeFixed = true;
-
-		}
-		else
-		{
-		  	lastX = (double)getWidth(); 
-		  	lastY = (double)getHeight();
-		  	
-		  	resizedX = ((double)getWidth()) / (double)(imageData.image_width * 2);
-		  	resizedY = ((double)getHeight()) / (double)(imageData.image_height * 2);
-		  	  	
-		  	trainCanvas.resizeAreas(resizedX,resizedY,changeX,changeY);
-		  	
-		  	sizeFixed = false;
-		}  	
-	}
-
-	public void componentHidden(ComponentEvent e) { }
-	public void componentMoved(ComponentEvent e)
-	{ 
-	
-		prefs.putInt("ImageShowArea.location.x",getLocation().x);
-		prefs.putInt("ImageShowArea.location.y",getLocation().y);
-
-	}
-	public void componentShown(ComponentEvent e) { }
-
-	public void setTrainCanvas(TrainCanvas t)
-	{
-		trainCanvas = t;
-	}
-
-	public int getCurImage()
-	{
-		return curimg;
-	}
-  
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/ImageViewer.java ./tools/easytrain/ImageViewer.java
--- ../Tekkotsu_2.4.1/tools/easytrain/ImageViewer.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/easytrain/ImageViewer.java	2005-10-15 16:09:52.000000000 -0400
@@ -0,0 +1,123 @@
+import java.awt.image.BufferedImage;
+import java.awt.Color;
+import java.awt.Dimension;
+import java.awt.Graphics;
+import java.awt.Container;
+import java.awt.BorderLayout;
+import java.awt.event.*;
+import javax.swing.Box;
+import javax.swing.JFrame;
+import java.util.prefs.Preferences;
+
+public class ImageViewer extends JFrame implements ComponentListener, KeyListener {
+	ImagePanel disp;
+
+	ImageViewer() { super("Image Viewer"); init(0); }
+	ImageViewer(String title) { super(title); init(0); }
+	ImageViewer(String title, int inset) { super(title); init(inset); }
+
+	public void setImage(BufferedImage img) { disp.setImage(img); correctSize(); }
+	public BufferedImage getImage() { return disp.getImage(); }
+	public ImagePanel getDisplay() { return disp; }
+
+	protected void init(int inset) {
+		disp = new ImagePanel();
+		disp.setOpaque(true);
+		if(inset==0) {
+			setContentPane(disp);
+		} else {
+			Container root=getContentPane();
+			root.setLayout(new BorderLayout());
+			root.add(Box.createVerticalStrut(inset),BorderLayout.NORTH);
+			root.add(Box.createVerticalStrut(inset),BorderLayout.SOUTH);
+			root.add(Box.createHorizontalStrut(inset),BorderLayout.EAST);
+			root.add(Box.createHorizontalStrut(inset),BorderLayout.WEST);
+			root.add(disp,BorderLayout.CENTER);
+		}
+		setBackground(Color.BLACK);
+		disp.setPreferredSize(new Dimension(100,100));
+		pack();
+		addComponentListener(this);
+		addKeyListener(this);
+	}
+	
+	public void setBackground(Color c) {
+		super.setBackground(c);
+		if(disp!=null)
+			disp.setBackground(c);
+	}
+	
+	protected void correctSize() {
+		int imgW=getImage().getWidth();
+		int imgH=getImage().getHeight();
+		float imgAspect=imgW/(float)imgH;
+		int dispW=disp.getWidth();
+		int dispH=disp.getHeight();
+		float dispAspect=dispW/(float)dispH;
+		int corrW=dispW,corrH=dispH;
+		if(imgAspect>dispAspect) {
+			//too narrow, bring up the bottom
+			corrH=Math.round(dispW/imgAspect);
+		} else if(imgAspect<dispAspect) {
+			corrW=Math.round(dispH*imgAspect);
+		}
+		if(corrW!=dispW || corrH!=dispH) {
+			disp.setPreferredSize(new Dimension(corrW,corrH));
+			pack();
+		}
+	}
+	
+	public void componentResized(ComponentEvent e) { correctSize(); }
+	public void componentHidden(ComponentEvent e) { }
+	public void componentMoved(ComponentEvent e) { }
+	public void componentShown(ComponentEvent e) { }
+
+	public void keyPressed(KeyEvent e) {}
+	public void keyReleased(KeyEvent e) {} 
+	public void keyTyped(KeyEvent e) {
+		//System.out.println(getName()+" keyTyped: "+e.getKeyChar());
+		Dimension prev=disp.getSize();
+		//System.out.println("Previous: "+prev);
+		switch(e.getKeyChar()) {
+			case '=': {
+				disp.setPreferredSize(new Dimension(disp.getImage().getWidth(),disp.getImage().getHeight()));
+				break;
+			}
+			case '+': {
+				double xs;
+				if(disp.getWidth()>=disp.getImage().getWidth()) {
+					xs=disp.getWidth()/disp.getImage().getWidth()+1;
+				} else {
+					xs=disp.getImage().getWidth()/disp.getWidth();
+					if((int)(disp.getImage().getWidth()/xs)==disp.getWidth())
+						xs--;
+					xs=1/xs;
+				}
+				//System.out.println("xs="+xs);
+				disp.setPreferredSize(new Dimension((int)(disp.getImage().getWidth()*xs),(int)(disp.getImage().getHeight()*xs)));
+				break;
+			}
+			case '-': {
+				float xs;
+				if(disp.getWidth()>disp.getImage().getWidth()) {
+					xs=disp.getWidth()/disp.getImage().getWidth();
+					if((int)(disp.getImage().getWidth()*xs)==disp.getWidth())
+						xs--;
+				} else {
+					xs=disp.getImage().getWidth()/disp.getWidth()+1;
+					xs=1/xs;
+				}
+				//System.out.println("xs="+xs);
+				disp.setPreferredSize(new Dimension((int)(disp.getImage().getWidth()*xs),(int)(disp.getImage().getHeight()*xs)));
+				break;
+			}
+			default:
+				return;
+		}
+		//System.out.println("New: "+disp.getPreferredSize());
+		setSize(getSize().width+disp.getPreferredSize().width-prev.width,getSize().height+disp.getPreferredSize().height-prev.height);
+		//setSize(1,1);
+		//invalidate();
+		//pack();
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/Makefile ./tools/easytrain/Makefile
--- ../Tekkotsu_2.4.1/tools/easytrain/Makefile	2005-08-16 16:48:09.000000000 -0400
+++ ./tools/easytrain/Makefile	2006-08-23 15:13:25.000000000 -0400
@@ -2,37 +2,45 @@
 
 OBJS:=${SRCS:.java=.class}
 
-CXX=javac
+JAVAC=javac
 CURDIR:=$(shell pwd | sed 's/.*\///')
+PROJECT_BUILDDIR?=/tmp
+USER?=$(if $(USERNAME),$(USERNAME),$(shell whoami))
+BUILDLIST:=$(PROJECT_BUILDDIR)/$(CURDIR)_$(USER)_buildlist.txt
 
 # SEP is to use ';' on windows and ':' on unix because windows is mentally deficient
 SEP:=$(shell if [ "`uname`" = "CYGWIN" -o "`uname`" \> "CYGWIN" -a "`uname`" \< "CYGWIO" ] ; then echo ";" ; else echo ":" ; fi )
-CXXFLAGS=-deprecation -classpath ".$(SEP)../mon/ftp.jar"
+JAVACFLAGS=-deprecation -classpath ".$(SEP)../mon/ftp.jar"
 
 .PHONY: all clean msg build clearbuildlist test
 
 all: clearbuildlist build
 
 %.class: %.java
-	@printf " $<" >> tmp_buildList.txt;
+	@printf " $<" >> "$(BUILDLIST)";
+	@chown $(USER) "$(BUILDLIST)";
 
 clearbuildlist:
-	@rm -f tmp_buildList.txt;
+	@rm -f "$(BUILDLIST)";
+
+"$(BUILDLIST)": ${OBJS} ;
 
-tmp_buildList.txt: ${OBJS}
 #	@echo "Build list constructed...";
 
-build: tmp_buildList.txt
-	@if [ -r tmp_buildList.txt ] ; then \
-		$(if $(shell which $(CXX)), \
-			echo "Compiling`cat tmp_buildList.txt`..."; \
-			$(CXX) $(CXXFLAGS) `cat tmp_buildList.txt`; , \
+build: "$(BUILDLIST)"
+	@if [ -r "$(BUILDLIST)" ] ; then \
+		$(if $(shell which $(JAVAC)), \
+			echo "Compiling`cat \"$(BUILDLIST)\"`..."; \
+			$(JAVAC) $(JAVACFLAGS) `cat "$(BUILDLIST)"` || exit 1; , \
 			printf "  ***** WARNING: You don't have java... skipping EasyTrain *****\n"; \
 		) \
+		rm -f "$(BUILDLIST)"; \
+	else \
+		echo "EasyTrain: Nothing to be done."; \
 	fi;
 
 clean:
-	rm -f $(OBJS) *~ 
+	rm -f "$(BUILDLIST)" $(OBJS) *~ 
 
 test:
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/Manifest ./tools/easytrain/Manifest
--- ../Tekkotsu_2.4.1/tools/easytrain/Manifest	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/easytrain/Manifest	2005-10-03 12:33:03.000000000 -0400
@@ -0,0 +1 @@
+Main-Class: EasyTrain
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/README ./tools/easytrain/README
--- ../Tekkotsu_2.4.1/tools/easytrain/README	2005-08-03 20:27:38.000000000 -0400
+++ ./tools/easytrain/README	2005-10-29 12:43:16.000000000 -0400
@@ -1,9 +1,11 @@
 EasyTrain -- color image segmentation training program for CMVision.
 
 To compile EasyTrain, do:
-
+  make
+or:
   javac *.java
 
+
 To try out EasyTrain after compilation, do:
 
   java EasyTrain -isYUV *.png
@@ -12,8 +14,8 @@
 
 ========================================================
 
-Credits:  EasyTrain was created by Eric Durback, Matt Carson, and
-Dave Touretzky, with help from Ethan Tira-Thompson, based on an earlier
-program (VisionTrain) by Alok Ladsariya, all at Carnegie Mellon, and 
-using design ideas from yet another program (TileTrain) by Rob Salkin
-and Shawn Turner at SUNY Albany.
+Credits: EasyTrain was created by Ethan Tira-Thompson and Eric
+Durback, base on earlier work by Matt Carson and Alok Ladsariya, with
+guidance from David Touretzky, all at Carnegie Mellon, and using
+design ideas from yet another program (TileTrain) by Rob Salkin and
+Shawn Turner at SUNY Albany.
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/SegmentedImage.java ./tools/easytrain/SegmentedImage.java
--- ../Tekkotsu_2.4.1/tools/easytrain/SegmentedImage.java	2005-08-04 16:58:05.000000000 -0400
+++ ./tools/easytrain/SegmentedImage.java	2005-10-27 18:54:30.000000000 -0400
@@ -1,235 +1,213 @@
-/** @file SegmentedImage.java
- *  @brief Frame for displaying the segmented image        
- *
- *	@author editted by: Eric Durback
- *  @bug No known bugs.
- */
-
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.util.*;
-import java.awt.geom.*;
-import java.io.*;
-import java.util.prefs.Preferences;
-
-
-public class SegmentedImage extends JFrame implements KeyListener, MouseListener, ComponentListener
-{
-	BufferedImage image;
-	ImageData imageData;
-	ImageShowArea imageShow;
-	byte[] tmap;
-	int [][] averageColors;
-	Point hint;
-	
-	static Preferences prefs = Preferences.userNodeForPackage(SegmentedImage.class);
-
-  
-	public SegmentedImage (ImageData _imageData, ImageShowArea _imageShow) 
-	{
-		//STUB
-		
-		imageData = _imageData;
-		image = null;
-		imageShow = _imageShow;
-		
-		setBackground(Color.GRAY);
-		setLocation(prefs.getInt("SegmentedImage.location.x",50),prefs.getInt("SegmentedImage.location.y",50));
-        setTitle("Segmented " + imageShow.getNewTitle());
-	
-		addKeyListener(this);
-		addComponentListener(this);
-		addMouseListener(this);
-
-		setVisible(true);
-		repaint();
-	}
-
-	public void setImageData(ImageData _imageData)
-	{
-	
-		imageData = _imageData;
-		reSegment(tmap,averageColors);
-	}
-
-	public void reSegment(byte[] _tmap, int[][]_averageColors)
-	{
-
-		tmap = _tmap;
-		averageColors = _averageColors;
-
-		int[] data=imageData.getPixels();
-
-		IndexColorModel cmodel=makeColorModel(averageColors);
-
-		if (tmap==null || cmodel==null) return;
-
-		setSize(imageData.image_width*2, imageData.image_height*2);
-		image = new BufferedImage(imageData.image_width, imageData.image_height,
-		    BufferedImage.TYPE_BYTE_INDEXED,cmodel);
-
-		segmentImage(data, tmap, imageData.image_width, imageData.image_height);
-
-		repaint();
-	}
-
-	public void paint(Graphics graphics) 
-	{
-		
-		Dimension sz=getSize();
-		if (image!=null)
-		    graphics.drawImage(image, 0, 0, sz.width, sz.height, null);
-	  
-
-		if(hint!=null && image!=null)
-		{
-			graphics.drawRect(hint.x-2, hint.y-2, 5, 5);
-		}
-
-
-
-	}
-
-	public void showHint(Point p)
-	{
-
-		hint = p;
-		repaint();
-	}
-
-
-	public void segmentImage(int[] data, byte[] tmap, int width, int height) 
-	{
-		
-		int size_y=16, size_u=64, size_v=64;
-		byte[] imgdata=new byte[data.length];
-
-		for (int i=0; i<data.length; i++) 
-		{
-		    int y=(data[i]>>16)&0xff;
-		    int u=(data[i]>>8)&0xff;
-		    int v=data[i]&0xff;
-		    y=y>>4;
-		    u=u>>2;
-		    v=v>>2;
-		    imgdata[i]=tmap[(y*size_u+u)*size_v+v];
-		}
-
-		image.getRaster().setDataElements(0,0,width,height,imgdata);
-		repaint();
-	}
-
-	public IndexColorModel makeColorModel(int[][] averageColors) 
-	{
-		if (averageColors == null)
-		    return null;
-		
-		byte[] byte_cmap=new byte[(averageColors.length+1)*3];
-
-
-		int i;
-		for (i=1; i<averageColors.length+1; i++) 
-		{
-		    //byte_cmap[i*3]=(byte) ((cmap[i]>>16) & 0xff);
-		    //byte_cmap[i*3+1]=(byte) ((cmap[i]>>8) & 0xff);
-		    //byte_cmap[i*3+2]=(byte) (cmap[i] & 0xff);
-		    byte_cmap[i*3] = (byte)(averageColors[i-1][0]&0xff);
-		    byte_cmap[i*3+1] = (byte)(averageColors[i-1][1]&0xff);
-		    byte_cmap[i*3+2] = (byte)(averageColors[i-1][2]&0xff);
-		}
-
-		byte_cmap[0] = (byte)128;
-		byte_cmap[1] = (byte)128;
-		byte_cmap[2] = (byte)128;
-
-		IndexColorModel cmodel=new IndexColorModel(7, averageColors.length + 1, byte_cmap,
-						   0, false); 
-		return cmodel;
-	}
-
-	public int getPixel(int x, int y) 
-	{
-		Dimension sz=getSize();
-		x=(x * image.getWidth()) / sz.width;
-		y=(y * image.getHeight()) / sz.height;
-		return image.getRGB(x, y);
-	}
-
-	public void keyPressed(KeyEvent e) 
-	{
-		if (e.getKeyCode()==KeyEvent.VK_LEFT ||
-		    e.getKeyCode()==KeyEvent.VK_UP ||
-		    e.getKeyCode()==KeyEvent.VK_PAGE_UP ||
-		    e.getKeyCode()==KeyEvent.VK_KP_UP ||
-		    e.getKeyCode()==KeyEvent.VK_KP_LEFT) 
-		{
-			imageShow.curimg--;
-
-			if (imageShow.curimg<0) imageShow.curimg+=imageShow.imglist.length;
-				
-			imageShow.imageChange(imageShow.curimg);
-		} 
-		else if (e.getKeyCode()==KeyEvent.VK_RIGHT ||
-		    e.getKeyCode()==KeyEvent.VK_DOWN ||
-		    e.getKeyCode()==KeyEvent.VK_PAGE_DOWN ||
-		    e.getKeyCode()==KeyEvent.VK_KP_DOWN ||
-		    e.getKeyCode()==KeyEvent.VK_KP_RIGHT) 
-		{
-			imageShow.curimg++;
-
-			if (imageShow.curimg>=imageShow.imglist.length) imageShow.curimg-=imageShow.imglist.length;
-
-			imageShow.imageChange(imageShow.curimg);
-		}
-	}
-	public void keyReleased(KeyEvent e) { }
-	public void keyTyped(KeyEvent e) { }
-
-	public void mousePressed(MouseEvent e) 
-	{
-		
-	}
-
-	public void mouseDragged(MouseEvent e) 
-	{	  
-		
-	}
-
-	public void mouseReleased(MouseEvent e) 
-	{
-
-	}
-
-	public void mouseMoved(MouseEvent e)
-	{
-		
-	}
-
-	public void mouseClicked(MouseEvent e){}
-
-	public void mouseExited(MouseEvent e)
-	{
-
-		//imagePlace = null;
-		repaint();
-
-	}
-
-	public void mouseEntered(MouseEvent e){}
-	
-	public void componentResized(ComponentEvent e) {}
-	public void componentHidden(ComponentEvent e) { }
-	
-	public void componentMoved(ComponentEvent e)
-	{ 
-	
-		prefs.putInt("SegmentedImage.location.x",getLocation().x);
-		prefs.putInt("SegmentedImage.location.y",getLocation().y);
-
-	}
-	public void componentShown(ComponentEvent e) { }
-
-}
+/** @file SegmentedImage.java
+ *  @brief Frame for displaying the segmented image        
+ *
+ *	@author editted by: Eric Durback
+ *  @bug No known bugs.
+ */
+
+import java.awt.image.*;
+import java.awt.*;
+import javax.swing.*;
+import javax.swing.event.*;
+import java.awt.event.*;
+import java.util.*;
+import java.awt.geom.*;
+import java.io.*;
+import java.util.prefs.Preferences;
+
+
+public class SegmentedImage extends ImageViewer
+{
+	float[] yuvimg;
+	int width,height;
+	ThresholdMap thresh;
+	Point hint;
+  
+	public SegmentedImage(String title, ThresholdMap thresh) { super(title); init(thresh); }
+	protected void init(ThresholdMap thresh) {
+		this.thresh=thresh;
+		setBackground(Color.GRAY);
+		setTitle("Segmented Viewer");
+	}
+
+	public void setImage(float[] yuvimg, int width, int height) {
+		this.yuvimg=yuvimg;
+		this.width=width;
+		this.height=height;
+		setImage(thresh.segment(yuvimg,width,height));
+	}
+	
+	public ThresholdMap getThresh() { return thresh; }
+	public void updateMap(Area area, short index) {
+		thresh.updateMap(area,index);
+		setImage(thresh.segment(yuvimg,width,height));
+	}
+	public void updateMap(Vector areas) {
+		for(short i=0; i<areas.size(); i++)
+			thresh.updateMap((Area)areas.get(i),i);
+		setImage(thresh.segment(yuvimg,width,height));
+	}
+	
+	/*	public void reSegment(byte[] _tmap, int[][]_averageColors)
+	{
+
+		tmap = _tmap;
+		averageColors = _averageColors;
+
+		int[] data=imageData.getPixels();
+
+		IndexColorModel cmodel=makeColorModel(averageColors);
+
+		if (tmap==null || cmodel==null) return;
+
+		
+		image = new BufferedImage(imageData.image_width, imageData.image_height,
+		    BufferedImage.TYPE_BYTE_INDEXED,cmodel);
+
+		segmentImage(data, tmap, imageData.image_width, imageData.image_height);
+
+		repaint();
+	}
+
+	public void showHint(Point p)
+	{
+
+		if(p!=null) hint = scalePoint(p);
+		else hint = null;
+		
+		repaint();
+	}
+
+
+	public void segmentImage(int[] data, byte[] tmap, int width, int height) 
+	{
+		
+		touched = true;
+		int size_y=16, size_u=64, size_v=64;
+		byte[] imgdata=new byte[data.length];
+
+		for (int i=0; i<data.length; i++) 
+		{
+		    int y=(data[i]>>16)&0xff;
+		    int u=(data[i]>>8)&0xff;
+		    int v=data[i]&0xff;
+		    y=y>>4;
+		    u=u>>2;
+		    v=v>>2;
+		    imgdata[i]=tmap[(y*size_u+u)*size_v+v];
+		}
+
+		image.getRaster().setDataElements(0,0,width,height,imgdata);
+		repaint();
+	}
+
+	public IndexColorModel makeColorModel(int[][] averageColors) 
+	{
+		if (averageColors == null)
+		    return null;
+		
+		byte[] byte_cmap=new byte[(averageColors.length+1)*3];
+
+
+		int i;
+		for (i=1; i<averageColors.length+1; i++) 
+		{
+		    //byte_cmap[i*3]=(byte) ((cmap[i]>>16) & 0xff);
+		    //byte_cmap[i*3+1]=(byte) ((cmap[i]>>8) & 0xff);
+		    //byte_cmap[i*3+2]=(byte) (cmap[i] & 0xff);
+		    byte_cmap[i*3] = (byte)(averageColors[i-1][0]&0xff);
+		    byte_cmap[i*3+1] = (byte)(averageColors[i-1][1]&0xff);
+		    byte_cmap[i*3+2] = (byte)(averageColors[i-1][2]&0xff);
+		}
+
+		byte_cmap[0] = (byte)128;
+		byte_cmap[1] = (byte)128;
+		byte_cmap[2] = (byte)128;
+
+		IndexColorModel cmodel=new IndexColorModel(7, averageColors.length + 1, byte_cmap,
+						   0, false); 
+		return cmodel;
+	}
+
+	public int getPixel(int x, int y) 
+	{
+		Dimension sz=getSize();
+		x=(x * image.getWidth()) / sz.width;
+		y=(y * image.getHeight()) / sz.height;
+		return image.getRGB(x, y);
+	}
+	
+	public double getScale()
+	{
+		return (double)imagePanel.getWidth()/(double)width;
+	}
+	
+	public Point scalePoint(Point p)
+	{
+		return new Point( (int)((double)p.x * getScale()),(int)((double)p.y * getScale())); 
+	
+	}
+	
+	public void setSizes()
+	{
+		height = imagePanel.getHeight();
+		width = imagePanel.getWidth();		
+	}
+	
+	public Dimension getModifiedSize(int x, int y)
+	{
+		Insets i = this.getInsets();
+		
+		//System.out.println(i);
+		
+		return new Dimension(x+(i.left+i.right), y+(i.top+i.bottom));
+	}
+
+	public void keyPressed(KeyEvent e) 
+	{
+		//imageShow.keyImageChange(e);
+		
+	}
+	public void keyReleased(KeyEvent e) { }
+	public void keyTyped(KeyEvent e) { }
+
+	
+	
+	public void componentResized(ComponentEvent e) 
+	{
+			
+			double changeX = (double)imagePanel.getWidth() / width;
+			double changeY = (double)imagePanel.getHeight() / height;
+		
+			if(getWidth()<= 120 || getHeight() <= 98)
+		  	{
+		  		this.setSize(getModifiedSize(120,98));	  		
+		  	}
+		  	
+		  	else if(   (changeX > changeY && imagePanel.getWidth() > width  ) 
+		  	   || (changeX < changeY && imagePanel.getWidth() < width  )  )
+		  	{
+		  		changeY = changeX;
+		  		this.setSize(getModifiedSize(imagePanel.getWidth(),(int)(height*changeX)));
+		  	}
+		  	else
+		  	{
+		  		changeX = changeY;
+		  		this.setSize(getModifiedSize((int)(width*changeY),imagePanel.getHeight()));
+		  	}
+		  	
+		  	//imageShow.sizeFixed = false;
+	
+	}
+	public void componentHidden(ComponentEvent e) { }
+	
+	public void componentMoved(ComponentEvent e)
+	{ 
+	
+		prefs.putInt("SegmentedImage.location.x",getLocation().x);
+		prefs.putInt("SegmentedImage.location.y",getLocation().y);
+
+	}
+	public void componentShown(ComponentEvent e) { }
+*/
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/SpectrumViewer.java ./tools/easytrain/SpectrumViewer.java
--- ../Tekkotsu_2.4.1/tools/easytrain/SpectrumViewer.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/easytrain/SpectrumViewer.java	2005-10-30 18:05:03.000000000 -0500
@@ -0,0 +1,139 @@
+import java.awt.image.*;
+import java.awt.*;
+import javax.swing.*;
+import javax.swing.event.*;
+import java.awt.event.*;
+import java.util.*;
+import java.awt.geom.*;
+import java.io.*;
+import java.util.prefs.Preferences;
+
+public class SpectrumViewer extends ImageViewer {
+	final static int renderXRes=(1<<8)*2;
+	final static int renderYRes=(1<<8)*2;
+	
+	BufferedImage fullPlot; //the color spectrum plot of all images
+	BufferedImage curPlot; //the current color spectrum plot shown (may be fullplot, or a separate plot from selected regions)
+	Graphics2D curPlotGraphics;
+	BufferedImage[] compPlots; //an array of plots, one per file (used for quick updates of selected areas) -- drawn together, form curPlot
+	boolean inverted; //normally black background, inverted uses a white background	
+	final static int[] transTemplate=new int[renderXRes*renderYRes]; //!< an array of zeros for quickly blanking out an image
+	//final static DataBufferInt transTemplate=new DataBufferInt(renderXRes*renderYRes);
+	
+	public SpectrumViewer(String title)
+	{
+		super(title,20);
+		init();
+	}
+	public SpectrumViewer(String title,int inset)
+	{
+		super(title,inset);
+		init();
+	}
+	
+	protected void init() {
+		fullPlot=new BufferedImage(renderXRes,renderYRes,BufferedImage.TYPE_INT_ARGB);
+		curPlot=new BufferedImage(renderXRes,renderYRes,BufferedImage.TYPE_INT_ARGB);
+		curPlotGraphics=(Graphics2D)curPlot.getGraphics();
+		compPlots=new BufferedImage[0];
+		//transTemplate=new int[renderXRes*renderYRes];
+		setImage(fullPlot);
+	}
+	
+	public void showFullPlot() {
+		setImage(fullPlot);
+	}
+	
+	public void showCurPlot() {
+		paintCurPlot(); //refresh the image, in case compPlots are all null and fullPlot changed
+		setImage(curPlot);
+	}
+	
+	//plots a number of images into the fullplot, which is retained so it doesn't have to be recalcuated when switching modes
+	public void plotImages(float[][] spec, BufferedImage[] rgbimgs) 
+	{
+		fullPlot.getRaster().setDataElements(0,0,renderXRes,renderYRes,transTemplate);
+		Graphics2D graphics=fullPlot.createGraphics();
+		//graphics.setBackground(getBackground());
+		graphics.setColor(new Color(0,0,0,0));
+		graphics.fillRect(0,0,renderXRes,renderYRes);
+		
+		Rectangle2D.Float r=new Rectangle2D.Float();
+		int pointSize=disp.getHintPointSize();
+		for (int i=0; i<rgbimgs.length; i++) {
+			int[] rgb=rgbimgs[i].getRGB(0,0,rgbimgs[i].getWidth(),rgbimgs[i].getHeight(),null,0,rgbimgs[i].getWidth());
+			for(int p=0; p<rgb.length; p++) {
+				graphics.setColor(new Color(rgb[p]));
+				float x=spec[i][3*p]*(renderXRes-pointSize); //res-pointSize so maximal point is visible
+				float y=spec[i][3*p+1]*(renderYRes-pointSize);
+				r.setRect(Math.round(x),Math.round(y),pointSize,pointSize);
+				graphics.fill(r);
+			}
+		}
+		if(compPlots.length!=rgbimgs.length)
+			compPlots=new BufferedImage[rgbimgs.length];
+		setImage(fullPlot);
+	}
+	
+	public void plotImageAreas(float[][] spec, BufferedImage[] rgbimg, Area[] areas) {
+		if(compPlots.length!=areas.length) {
+			compPlots=new BufferedImage[areas.length];
+			//compPlots elements will be initialized on an as-needed basis
+		}
+		for(int i=0; i<areas.length; i++) {
+			paintImageArea(spec[i],rgbimg[i],areas[i],i);
+		}
+		paintCurPlot();
+		setImage(curPlot);
+	}
+	
+	public void updateImageArea(float[] spec, BufferedImage rgbimg, Area a, int i) {
+		paintImageArea(spec,rgbimg,a,i);
+		paintCurPlot();
+		repaint();
+	}
+	
+	//does computation for compPlot, but doesn't update curPlot
+	protected void paintImageArea(float[] spec, BufferedImage rgbimg, Area a, int i) {
+		if(a==null || a.isEmpty()) {
+			compPlots[i]=null;
+			return;
+		}
+		if(compPlots[i]==null)
+			compPlots[i]=new BufferedImage(renderXRes,renderYRes,BufferedImage.TYPE_INT_ARGB);
+		compPlots[i].getRaster().setDataElements(0,0,renderXRes,renderYRes,transTemplate);
+		Graphics2D graphics=compPlots[i].createGraphics();
+		
+		Rectangle2D.Float r=new Rectangle2D.Float();
+		int pointSize=disp.getHintPointSize();
+		int[] rgb=rgbimg.getRGB(0,0,rgbimg.getWidth(),rgbimg.getHeight(),null,0,rgbimg.getWidth());
+		int p=0;
+		for(int y=0; y<rgbimg.getHeight(); y++) {
+			double yc=y/(double)(rgbimg.getHeight()-1)*.999+.0005;
+			for(int x=0; x<rgbimg.getWidth(); x++) {
+				double xc=x/(double)(rgbimg.getWidth()-1)*.999+.0005;
+				if(a.contains(xc,yc)) {
+					graphics.setColor(new Color(rgb[p/3]));
+					float px=spec[p]*(renderXRes-pointSize); //res-pointSize so maximal point is visible
+					float py=spec[p+1]*(renderYRes-pointSize);
+					r.setRect(Math.round(px),Math.round(py),pointSize,pointSize);
+					graphics.fill(r);
+				}
+				p+=3;
+			}
+		}
+	}
+	
+	protected void paintCurPlot() {
+		curPlot.getRaster().setDataElements(0,0,renderXRes,renderYRes,transTemplate);
+		boolean hasNonNull=false;
+		for(int i=0; i<compPlots.length; i++) {
+			if(compPlots[i]!=null) {
+				curPlotGraphics.drawImage(compPlots[i],null,null);
+				hasNonNull=true;
+			}
+		}
+		if(!hasNonNull)
+			curPlotGraphics.drawImage(fullPlot,null,null);
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/ThresholdMap.java ./tools/easytrain/ThresholdMap.java
--- ../Tekkotsu_2.4.1/tools/easytrain/ThresholdMap.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/easytrain/ThresholdMap.java	2006-09-15 23:18:31.000000000 -0400
@@ -0,0 +1,155 @@
+import java.awt.geom.*;
+import java.awt.Color;
+import java.util.Iterator;
+import java.util.Map;
+import java.util.TreeMap;
+import java.io.File;
+import java.io.FileWriter;
+import java.awt.image.*;
+
+public class ThresholdMap {
+	ColorConverter convert;
+	int yRes,uRes,vRes;
+	short[][][] map; //short because no unsigned byte type :-P
+	byte[] repR;
+	byte[] repG;
+	byte[] repB;
+	TreeMap areas;
+	
+	// these defaults drop the highest and lowest y level, so these
+	// y-values won't map to anything (too desaturated or washed out)
+	final int MIN_Y=1; // minimum y level to be mapped
+	final int MAX_Y=-1; // offset from y res -- maximum saturation to be mapped
+	
+	public ThresholdMap(ColorConverter convert, int yRes, int uRes, int vRes) {
+		this.convert=convert;
+		this.yRes=yRes;
+		this.uRes=uRes;
+		this.vRes=vRes;
+		map=new short[yRes][uRes][vRes];
+		repR=new byte[256];
+		repG=new byte[256];
+		repB=new byte[256];
+		resetMap();
+		areas=new TreeMap();
+	}
+	
+	public Color getRepresentitiveColor(int i) {
+		return new Color((repR[i]<<16)+(repG[i]<<8)+repB[i]);
+	}
+	
+	public void resetMap() {
+		for(int y=0; y<yRes; y++)
+			for(int u=0; u<uRes; u++)
+				for(int v=0; v<vRes; v++)
+					map[y][u][v]=Short.MAX_VALUE;
+	}
+
+	public void changeSpectrum(ColorConverter convert) {
+		this.convert=convert;
+		for(Iterator it=areas.entrySet().iterator(); it.hasNext();) {
+			Map.Entry entry=(Map.Entry)it.next();
+			updateMap((Area)entry.getValue(),((Short)entry.getKey()).shortValue());
+		}
+	}
+	
+	public void updateMap(Area area, short index) {
+		float[] xy=new float[convert.getComponents()];
+		areas.put(new Short(index),area.clone());
+		for(int y=MIN_Y; y<yRes+MAX_Y; y++) {
+			float yc=(y+.5f)/yRes;
+			for(int u=0; u<uRes; u++) {
+				float uc=(u+.5f)/uRes;
+				for(int v=0; v<vRes; v++) {
+					
+					if(map[y][u][v]>index) {
+						//have to test if a new mapping was added
+						float vc=(v+.5f)/vRes;
+						convert.getColor(yc,uc,vc,xy);
+						//ugly hack because points on the area border aren't normally considered hits, but need to be
+						//boolean hit=area.contains(xy[0]*.999+.0005,xy[1]*.999+.0005);
+						boolean hit=area.contains(xy[0],xy[1]);
+						if(hit)
+							map[y][u][v]=index;
+					} else if(map[y][u][v]==index) {
+						//have to test if current mapping was removed
+						float vc=(v+.5f)/vRes;
+						convert.getColor(yc,uc,vc,xy);
+						//ugly hack because points on the area border aren't normally considered hits, but need to be
+						//boolean hit=area.contains(xy[0]*.999+.0005,xy[1]*.999+.0005);
+						boolean hit=area.contains(xy[0],xy[1]);
+						if(!hit) {
+							map[y][u][v]=Short.MAX_VALUE; //mapping went away
+							// but now need to see if it "fell through" to another layer
+							Iterator it=areas.entrySet().iterator();
+							while(it.hasNext()) {
+								Map.Entry entry=(Map.Entry)it.next();
+								short k=((Short)entry.getKey()).shortValue();
+								if(k<=index)
+									continue;
+								Area a=(Area)entry.getValue();
+								if(a.contains(xy[0],xy[1])) {
+									map[y][u][v]=k;
+									break;
+								}
+							}
+						}
+					}
+					//don't have to test if on lower-index layer (they would still override any changes to current index)
+					
+				} // main body, v loop
+			} // u loop
+		}// y loop
+		float repyc=.6f;
+		int repy=(int)(repyc*(yRes-1));
+		float rc=0,gc=0,bc=0;
+		int c=0;
+		ColorConverter YUVtoRGB=new ColorConverter.YUVtoRGB();
+		for(int u=0; u<uRes; u++) {
+			float uc=u/(float)(uRes-1);
+			for(int v=0; v<vRes; v++) {
+				float vc=v/(float)(vRes-1);
+				if(map[repy][u][v]==index) {
+					YUVtoRGB.getColor(repyc,uc,vc,xy);
+					rc+=xy[0];
+					gc+=xy[1];
+					bc+=xy[2];
+					c++;
+				}
+			}
+		}
+		repR[index]=(byte)(255*rc/c);
+		repG[index]=(byte)(255*gc/c);
+		repB[index]=(byte)(255*bc/c);
+	}
+	
+	public BufferedImage segment(float[] img, int width, int height) {
+		IndexColorModel model=new IndexColorModel(8,256,repR,repG,repB,255);
+		BufferedImage out = new BufferedImage(width, height, BufferedImage.TYPE_BYTE_INDEXED,model);
+		byte[] seg=new byte[img.length];
+		int i=0;
+		int j=0;
+		while(i<img.length) {
+			int y=(int)(clip(img[i++])*(yRes-1));
+			int u=(int)(clip(img[i++])*(uRes-1));
+			int v=(int)(clip(img[i++])*(vRes-1));
+			seg[j++]=(byte)map[y][u][v];
+		}
+		out.getRaster().setDataElements(0,0,width,height,seg);//new DataBufferByte(seg,seg.length));
+		return out;
+	}
+	
+	float clip(float x) {
+		return x<=0 ? 0 : (x>=1 ? 1 : x);
+	}
+	
+	public void saveFile(File f) throws java.io.IOException {
+		FileWriter save=new FileWriter(f);
+		save.write("TMAP\nYUV'8\n" + yRes + " " + uRes + " " + vRes + "\n");
+		for(int y=0; y<yRes; y++)
+			for(int u=0; u<uRes; u++)
+				for(int v=0; v<vRes; v++)
+				save.write((byte)(map[y][u][v]+1)); //write out all of v at once
+		save.close();
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/Thumbnail.java ./tools/easytrain/Thumbnail.java
--- ../Tekkotsu_2.4.1/tools/easytrain/Thumbnail.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/easytrain/Thumbnail.java	2005-10-13 12:50:11.000000000 -0400
@@ -0,0 +1,47 @@
+/** @file Thumbnail.java
+ *  @brief 
+ *
+ *  Button Component that contains smaller image of an image loaded by the user.
+ *
+ *	@author editted by: Eric Durback
+ *  @bug No known bugs.
+ */
+
+import java.awt.image.*;
+import java.awt.*;
+import javax.swing.*;
+import javax.swing.event.*;
+import java.awt.event.*;
+import java.io.*;
+import java.util.*;
+import java.awt.geom.*;
+import java.util.prefs.Preferences;
+
+public class Thumbnail extends JToggleButton
+{
+	BufferedImage _image;
+	String[] imglist;
+	
+	ImageData imageData;
+	
+	int curimg;
+	int numImages;
+	boolean isRGB;
+	
+	
+	
+	public Thumbnail (ImageData imageData, int imageNum) 
+	{
+	  	
+		this.imageData = imageData;
+		curimg = imageNum;
+		
+		_image=imageData.getRGBImage(imageNum);
+		double scale = (double)_image.getHeight()/(double)_image.getWidth();
+		ImageIcon i = new ImageIcon(_image.getScaledInstance(72 ,(int)(72*scale), Image.SCALE_SMOOTH));
+		setIcon(i);
+
+		repaint();	
+	}
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/ThumbnailShow.java ./tools/easytrain/ThumbnailShow.java
--- ../Tekkotsu_2.4.1/tools/easytrain/ThumbnailShow.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/easytrain/ThumbnailShow.java	2005-10-22 01:19:32.000000000 -0400
@@ -0,0 +1,397 @@
+/** @file ThumbnailShow.java
+ *  @brief 
+ *
+ *  Frame for showing the Thumbnail objects. each Thumbnail contains a 
+ *  small image of one of the images the user loaded.  4 per row horizontally.
+ *
+ *	@author editted by: Eric Durback
+ *  @bug No known bugs.
+ */
+
+import java.awt.image.*;
+import java.awt.*;
+import javax.swing.*;
+import javax.swing.event.*;
+import java.awt.event.*;
+import java.io.*;
+import java.util.*;
+import java.awt.geom.*;
+import java.util.prefs.Preferences;
+import javax.swing.undo.UndoableEditSupport;
+import javax.swing.undo.AbstractUndoableEdit;
+
+public class ThumbnailShow extends JFrame implements KeyListener, ComponentListener, FocusListener,  ActionListener
+{
+	public static final String CURIMG_PROPERTY="CurrentImage";
+	JScrollPane rootScroll;	
+	JScrollBar scrollbar;
+		
+	int curimg;
+	int numImages;
+	int downAmount;
+	int columns,rows;
+	ArrayList thumbs = new ArrayList();
+	JList colorlist;
+	Container thumbList;
+	DefaultListModel list;
+	ImageData imgData;
+
+	Container root;
+	JPanel thumbRoot;
+	
+	static Preferences prefs = Preferences.userNodeForPackage(ThumbnailShow.class);
+ 
+	UndoableEditSupport undoListeners;
+	
+	class ImageChangeEdit extends AbstractUndoableEdit {
+		ThumbnailShow src;
+		int previous, next;
+		ImageChangeEdit(ThumbnailShow src, int previous, int next) {
+			super();
+			this.src=src;
+			this.previous=previous;
+			this.next=next;
+		}
+		public void redo() {
+			super.redo();
+			src.changeThumb(src.curimg,next);
+		}
+		public void undo() {
+			super.undo();
+			src.changeThumb(src.curimg,previous);
+		}
+		public boolean isSignificant() {
+			return false;
+		}
+	}
+	public void addUndoableEditListener(UndoableEditListener l) { undoListeners.addUndoableEditListener(l); }
+	public void removeUndoableEditListener(UndoableEditListener l) { undoListeners.removeUndoableEditListener(l); }
+
+	public void focusGained(FocusEvent e) {} 
+
+	public void focusLost(FocusEvent e) {}
+
+	public ThumbnailShow(ImageData imgData) 
+	{
+	  	
+		this.imgData=imgData;
+		numImages = imgData.getNumImages();
+		
+		setBackground(Color.GRAY);
+		
+		if(numImages < 3)
+		{
+			setSize(240, 150);
+			columns = 2;
+			rows = 1;
+		}
+		else if(numImages < 5)
+		{		    
+			setSize(450, 180);
+			columns = 2;
+			rows = 2;
+		}
+		else if(numImages<10)
+		{			
+			setSize(450, 300);
+			columns = 3;
+			rows = (numImages-1) / columns + 1;
+		}
+		else
+		{
+			setSize(450, 400);
+			columns = 4;
+			rows = numImages / columns + 1;
+		}
+		/*if( numImages == 5 || numImages == 6 || numImages == 9 || numImages == 12)
+		{
+			downAmount = 3;
+		}
+		else if(numImages == 3 || numImages ==4)
+		{
+			downAmount = 2;
+		}
+		else
+		{
+			downAmount = 4;
+		}*/
+		
+		
+		
+		setTitle("Image Thumbnails");
+		setLocation(prefs.getInt("ThumbnailShow.location.x",50),prefs.getInt("ThumbnailShow.location.y",50));
+		
+		addKeyListener(this);
+		addComponentListener(this);
+		addFocusListener(this); 
+		undoListeners=new UndoableEditSupport();
+		
+		GridLayout g = new GridLayout();
+		
+		g.setColumns(columns);
+		
+		//g.setRows(numImages/4 + 1);
+		g.setRows(rows);
+		
+		root = this.getContentPane();
+		
+		thumbRoot = new JPanel();
+		thumbRoot.setMaximumSize(new Dimension(300,300));
+		thumbRoot.setLayout(g);
+		thumbRoot.setBackground(Color.GRAY);
+		
+		
+		Thumbnail temp;
+		for(int i=0; i<numImages; i++)
+		{
+			temp = new Thumbnail(imgData,i);
+			
+			temp.addActionListener(this);
+			temp.addKeyListener(this);
+			temp.setSelected(true);
+			thumbRoot.add(temp);
+			thumbs.add(temp);		
+		}
+		
+		
+		downAmount = g.getColumns();
+		
+		rootScroll = new JScrollPane(thumbRoot,JScrollPane.VERTICAL_SCROLLBAR_ALWAYS,
+		                    JScrollPane.HORIZONTAL_SCROLLBAR_NEVER);
+		root.add(rootScroll,BorderLayout.CENTER);
+	
+		
+		((Thumbnail)thumbs.get(0)).setSelected(false);
+
+		rootScroll.setLayout(new ScrollPaneLayout());
+	}
+	
+	public int getCurrentImage() {
+		return curimg;
+	}
+
+	public void actionPerformed(ActionEvent e)
+	{
+		
+		
+		for(int i =0; i<numImages; i++)
+		{
+			if (e.getSource()==thumbs.get(i) ) 
+			{			
+				
+				undoListeners.postEdit(new ImageChangeEdit(this, curimg, i));
+				changeThumb(curimg,i);
+				return; //only one should match	
+			}
+			
+		}
+	}
+	
+	public void changeThumb(int last, int pressed)
+	{
+		if (last<0) last+=numImages;
+		if (pressed<0) pressed+=numImages;
+		if (last>=numImages) last-=numImages;
+		if (pressed>=numImages) pressed-=numImages;
+		    
+		
+		((Thumbnail)thumbs.get(last)).setSelected(true);
+		((Thumbnail)thumbs.get(pressed)).setSelected(false);
+		curimg = pressed;	
+
+		firePropertyChange(CURIMG_PROPERTY,last,pressed);
+	}
+	
+	public void keyPressed(KeyEvent e) 
+	{
+		int move;
+		
+		if (e.getKeyCode()==KeyEvent.VK_LEFT ||
+		    e.getKeyCode()==KeyEvent.VK_PAGE_UP ||
+		    e.getKeyCode()==KeyEvent.VK_KP_LEFT) 
+		{
+			curimg--;
+		  
+			if (curimg<0) curimg+=numImages;
+			
+			undoListeners.postEdit(new ImageChangeEdit(this, curimg+1, curimg));
+			changeThumb(curimg+1,curimg);	
+		} 
+		else if (e.getKeyCode()==KeyEvent.VK_RIGHT ||
+		    e.getKeyCode()==KeyEvent.VK_PAGE_DOWN ||
+		    e.getKeyCode()==KeyEvent.VK_KP_RIGHT) 
+		{
+			curimg++;
+			
+			if (curimg>=numImages) curimg-=numImages;
+		    
+			undoListeners.postEdit(new ImageChangeEdit(this, curimg-1, curimg));
+		    changeThumb(curimg-1,curimg);
+		} else if (e.getKeyCode()==KeyEvent.VK_DOWN ||
+		    e.getKeyCode()==KeyEvent.VK_KP_DOWN)
+		{
+			move = getDownMove();
+			curimg+=move;
+		    
+			while(curimg>=numImages)
+				curimg-=numImages;
+		    
+			undoListeners.postEdit(new ImageChangeEdit(this, curimg-move, curimg));
+			changeThumb(curimg-move,curimg);
+		} else if (e.getKeyCode()==KeyEvent.VK_UP ||
+		    e.getKeyCode()==KeyEvent.VK_KP_UP)
+		{
+			move = getUpMove();
+			curimg-=move;
+		  
+			while(curimg<0)
+				curimg+=numImages;
+
+			undoListeners.postEdit(new ImageChangeEdit(this, curimg+move, curimg));
+			changeThumb(curimg+move,curimg);
+		}
+	}
+	
+	public int getDownMove() //change to down and up
+	{
+		int empty = getEmptySpots();
+		
+		if(numImages < 3)
+		{
+			return  1;
+		}
+		else if(lastColumnEndRow())
+		{
+			if(lastRow())
+			{
+				return 1;
+				
+			}
+			else
+			{
+				return (columns - empty+1);
+			}
+		}
+		else if(aboveEmptySpot())//case where not a image underneath
+		{
+			return (2 * columns) - empty + 1;
+		}
+		else if(lastRow())
+		{
+			return (columns-empty+1);
+		}		
+		else
+		{
+			return columns ;
+		}
+			
+			
+	}
+	
+	
+	public int getUpMove() //change to down and up
+	{
+		int empty = getEmptySpots();
+		
+		if(numImages < 3)
+		{
+			return 1;
+		}
+		
+		else if(topLeft())
+		{
+			if(empty == 0)//full grid
+			{
+				return 1;
+			}
+			else
+			{
+				return  columns - empty +1;
+			}
+		}
+		else if(topRight())
+		{
+			if(empty == 0)
+			{
+				return columns + 1;
+			}
+			else if(belowEmpty())
+			{
+				return (2*columns) - empty + 1;
+			}
+			else
+			{
+				return columns - empty + 1;
+			}
+		}		
+		else if(curimg < columns)
+		{
+			return columns -empty + 1;
+		}	
+		else
+		{
+			return columns ;
+		}
+			
+			
+	}
+	
+	public boolean topLeft()
+	{
+		return (curimg == 0);
+	}
+	
+	public boolean topRight()
+	{
+		return (curimg == columns-1);
+	}
+	
+	public boolean belowEmpty()
+	{
+		return (getEmptySpots() > columns - curimg);
+	}
+	
+	public boolean lastColumnEndRow()
+	{
+		return (curimg != 0 && (((curimg+1) % columns) == 0) && (numImages - curimg <= columns));	
+	}
+	
+	public int getEmptySpots()
+	{
+		return (columns * rows) % numImages;
+	}
+	
+	public boolean lastRow()
+	{
+		return(curimg / columns == rows-1); 
+	}
+	
+	public boolean aboveEmptySpot()
+	{
+		return(getEmptySpots() > 0 && (curimg / columns) +1== rows -1  //2nd to last row
+		   && ((rows-1)*columns) - curimg <= getEmptySpots());			
+	}	
+	
+	public void keyReleased(KeyEvent e) { }
+	public void keyTyped(KeyEvent e) { }
+
+	public void componentResized(ComponentEvent e) 
+	{            	
+		repaint();
+		
+	}
+
+	public void componentHidden(ComponentEvent e) { }
+	public void componentMoved(ComponentEvent e)
+	{ 
+	
+		prefs.putInt("ThumbnailShow.location.x",getLocation().x);
+		prefs.putInt("ThumbnailShow.location.y",getLocation().y);
+
+	}
+	public void componentShown(ComponentEvent e) { }
+
+	
+	
+  
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/TrainCanvas.java ./tools/easytrain/TrainCanvas.java
--- ../Tekkotsu_2.4.1/tools/easytrain/TrainCanvas.java	2005-08-04 16:58:05.000000000 -0400
+++ ./tools/easytrain/TrainCanvas.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,1205 +0,0 @@
-/** @file TrainCanvas.java
- *  @brief Canvas for EasyTrain        
- *
- *	@author editted by: Eric Durback
- *  @bug No known bugs.
- */
-
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.util.*;
-import java.awt.geom.*;
-import java.io.*;
-import java.util.prefs.Preferences;
-
-public class TrainCanvas extends Canvas implements MouseListener,
-MouseMotionListener
-{
-	BufferedImage image;
-	BufferedImage cachedplot;
-	
-	ColorControlPanel ControlPanel;
-
-	Graphics2D graphics;
-	Polygon curPoly;
-	int lastx, lasty;
-	float f_width, f_height, f_offset;
-	int numImages, curImage;
-	String [] files;
-	String defaultName;
-
-	Area curColorArea;
-	Area [] curImageArea;
-	Area [] originalImageArea;
-
-	String curColor;
-
-	Point imageHint, imagePlace;
-
-	Hashtable colorAreasHash;
-	Hashtable imageAreasHash;
-	Hashtable originalImageAreasHash;
-
-	Hashtable colorMaskHash;
-
-	boolean inverted, colorshow, autoSelect, dirtyOriginal;
-	
-	public final static int NOTHING = 0;
-	public final static int IMAGE_AREA = 1;
-	public final static int COLOR_AREA = 2;
-	
-	Object undoObj;
-	int lastAction;
-	int uImg;
-	
-	float[] xy;
-	int[] rgb;
-
-	SegmentedImage segImage;
-	ImageShowArea imageShow;
-	ImageData imageData;
-	ImageData YUVimageData;
-	HelpBox helpBox;
-
-	boolean areaInImage = false;
-	
-	static Preferences prefs = Preferences.userNodeForPackage(EasyTrain.class);
-
-
-	public TrainCanvas(SegmentedImage _segImage, ImageShowArea _imageShow, ImageData _imageData, ImageData _YUVimageData, ColorControlPanel c_panel, HelpBox _helpBox, String [] files_ ) 
-	{
-
-		//setBackground(Color.black);
-		addMouseListener(this);
-		addMouseMotionListener(this);
-	
-		colorAreasHash=new Hashtable();
-		imageAreasHash = new Hashtable();
-		colorMaskHash = new Hashtable();
-		originalImageAreasHash = new Hashtable();
-		ControlPanel = c_panel;
-		helpBox = _helpBox;
-		
-		inverted=false;
-		colorshow=false;
-		dirtyOriginal = true;
-		imageHint=null;
-		imagePlace=null;
-		segImage = _segImage;
-		imageShow = _imageShow;
-		imageData = _imageData;
-		YUVimageData = _YUVimageData;
-		numImages = files_.length;
-		curImage = 0;
-		undoObj = null;
-		lastAction = NOTHING;
-		uImg = 0;		
-		
-		curImageArea=new Area[numImages];
-		for(int i=0; i<numImages; i++)
-		{
-			curImageArea[i] = new Area();
-		}
-		originalImageArea = new Area[numImages];
-
-		files = files_;    
-
-	}
-
-	public void setControlPanel(ColorControlPanel c)
-	{
-		ControlPanel = c;
-	}
-
-
-	public void plotImage() 
-	{
-		plotImage(this.xy,this.rgb);
-	}
-
-	public void plotImage(float[] xy, int[] rgb) 
-	{
-		
-		this.xy=xy;
-		this.rgb=rgb;
-		
-		Dimension d=getSize();
-		f_width=(float)d.width-41;
-		f_height=(float)d.height-41;
-		f_offset=20;
-
-		cachedplot=new BufferedImage(d.width, d.height, BufferedImage.TYPE_INT_RGB);
-		graphics=(Graphics2D)cachedplot.getGraphics();
-		
-		if(inverted)
-		{
-			graphics.setColor(Color.white);
-			graphics.fillRect(0,0,d.width, d.height);
-		}
-		
-		for (int i=0; i<rgb.length; i++) 
-		{
-		 
-		  graphics.setColor(new Color(rgb[i]));
-		  graphics.drawRect((int)(xy[i*2]*f_width+f_offset),
-		                    (int)(xy[i*2+1]*f_height+f_offset), 1,1);
-		}
-
-		image=new BufferedImage(d.width, d.height, BufferedImage.TYPE_INT_RGB);
-		graphics=(Graphics2D)image.getGraphics();
-				
-		redrawScene();
-		repaint();
-	}
-
-	public void plotImageArea(Area [] area)
-	{ 
-				
-		float[][] xy = imageData.getAllHS();		
-		int[][] rgb = imageData.getAllPixels();
-		
-		double xMod = imageShow.resizedX;
-		double yMod = imageShow.resizedY;
-
-		double width = imageShow.getSize().getWidth();
-		double height = imageShow.getSize().getHeight();		
-		
-		Rectangle curRect;
-
-		Dimension d=getSize();
-		image = new BufferedImage(d.width, d.height, BufferedImage.TYPE_INT_RGB);
-		Graphics2D graphics = (Graphics2D)image.getGraphics();		
-		
-		if(inverted)
-		{
-			graphics.setColor(Color.white);
-			graphics.fillRect(0,0,d.width, d.height);
-		}
-
-		for(double y=0; y<height; y+=2.0 * yMod)
-		{
-		    for (double x=0; x<width; x+=2.0 * xMod)
-			{
-				for(int k=0; k<numImages; k++)
-				{
-				    if(area[k].contains((int)x,(int)y))
-					{
-					    int i=(int) ((((double)y/yMod)/2.0)*(((double)width/xMod)/2.0)+((double)x/xMod)/2.0);
-					    
-					    int w = (int)(xy[k][i*2]*f_width+f_offset);	//int w = (int)(xy[k][i*2]*f_width+f_offset);
-					    int h = (int)(xy[k][i*2+1]*f_height+f_offset);	//int h = (int)(xy[k][i*2+1]*f_height+f_offset);
-					     
-					    graphics.setColor(new Color(rgb[k][i]));	//graphics.setColor(new Color(rgb[k][i]));
-					    graphics.drawRect(w, h, 1,1);
-						
-						/*if(autoSelect && !curColorArea.contains(w,h))
-						{						
-							curRect=new Rectangle(w -1, h-1,3,3); 								    
-					    	curColorArea.add(new Area(curRect));
-						}*/
-					}
-				}
-			}
-		}
-
-		repaint();
-	}
-
-
-	
-	public void paint(Graphics g) 
-	{
-		update(g);
-	}
-
-	public void update(Graphics g) 
-	{
-		Graphics2D g2d=(Graphics2D) g;
-		if (image!=null) 
-			g.drawImage(image, 0, 0, this);
-
-		if (inverted)
-			g2d.setColor(Color.black);
-		else
-			g2d.setColor(Color.white);
-
-		if (curColorArea!=null)
-			g2d.draw(curColorArea);
-
-		if (curPoly!=null && !areaInImage)
-			g2d.draw(curPoly);
-
-		if (imageHint!=null) 
-		{
-			g2d.drawRect(imageHint.x-2, imageHint.y-2, 5, 5);
-		}
-	}
-
-	public void setCurColor(String color) 
-	{
-
-		if (color==null) 
-		{
-			curImageArea=null;
-			curColorArea = null;
-			return;
-		}
-		
-		undoObj = null;
-		lastAction = NOTHING;
-		ControlPanel.disableUndo();
-
-		curImage = imageShow.getCurImage();
-
-		curColorArea = (Area)colorAreasHash.get(color);
-		curImageArea = (Area[])imageAreasHash.get(color);
-		originalImageArea = (Area[])originalImageAreasHash.get(color);
-
-		if (curImageArea==null) 
-		{
-			curImageArea=new Area[numImages];
-			for(int i=0; i<numImages; i++)
-			{
-				curImageArea[i] = new Area();
-			}
-
-			imageAreasHash.put(color, curImageArea);
-			curColorArea = new Area();
-
-			colorAreasHash.put(color, curColorArea);
-		}
-
-		imageShow.setCurArea(curImageArea[curImage]);
-
-		if(!colorshow)
-		{
-			plotImageArea(curImageArea);
-		}
-		else
-		{
-			plotImage();
-		}
-
-		redrawScene();
-	}
-	
-	public void undo ()
-	{
-	
-		if(lastAction == IMAGE_AREA)
-		{		
-			curImageArea[uImg] = ((Area)undoObj).createTransformedArea(AffineTransform.getScaleInstance(imageShow.resizedX,imageShow.resizedY));
-			imageShow.setCurArea(curImageArea[curImage]);
-			plotImageArea(curImageArea);	
-			dirtyOriginal = true;	
-		}
-		else if(lastAction == COLOR_AREA)
-		{
-			curColorArea.reset();
-			curColorArea.add((Area)((Area)undoObj));
-						
-		}
-		
-		repaint();
-		ControlPanel.disableUndo();
-		segImage.reSegment(makeTmap(), getAverageColors());
-		
-	}
-	
-	public void help()
-	{
-		
-		helpBox.setVisible(true);
-		helpBox.setState(helpBox.NORMAL);
-		
-	}
-	
-	public void clear () 
-	{
-		if (curImageArea==null) return;
-
-		curImage = imageShow.getCurImage();
-		curImageArea[curImage].reset();
-		curColorArea.reset();
-		
-		ControlPanel.disableUndo();
-		
-		
-		imageShow.setCurArea(null);
-		redrawScene();
-		segImage.reSegment(makeTmap(), getAverageColors());		
-		
-		if(colorshow)
-		{
-			plotImage();
-		}
-	}
-
-	public void invert () 
-	{
-		inverted=!inverted;
-		
-		if(inverted)
-		{
-			setBackground(Color.white);
-		}
-		else
-		{
-			setBackground(Color.black);
-		}
-		
-		if(curImageArea != null && !colorshow)
-		{
-			plotImageArea(curImageArea);
-		}
-		else
-		{
-			plotImage();
-		}
-
-	}
-
-	public void showColors () 
-	{
-		colorshow=!colorshow;
-		
-		if(colorshow)
-		{
-			plotImage();
-		}
-		else if(curImageArea != null)
-		{
-			plotImageArea(curImageArea);
-		}		
-		repaint();
-	}
-
-	public void autoSelect () //not being used
-	{
-		autoSelect=true;
-
-		if(autoSelect)
-		{
-			plotImageArea(curImageArea);
-			segImage.reSegment(makeTmap(), getAverageColors());
-		}
-		
-		if(colorshow)
-		{
-			plotImage();
-		}
-
-		autoSelect = false;
-
-	}
-
-	public void remove(String color) 
-	{
-		curColor=null;
-		curColorArea=null;
-		curImageArea=null;
-		colorAreasHash.remove(color);
-		imageAreasHash.remove(color);		
-
-		imageShow.setCurArea(null);
-
-		redrawScene();
-	}
-
-	public void redrawScene()
-	{
-		graphics.drawImage(cachedplot,0,0,this);
-		  		
-		if (curColorArea != null)
-		graphics.draw(curColorArea);
-		
-	}
-
-	
-	public byte[] makeTmap()
-	{
-		ArrayList areas = makeAreas();
-		//boolean maps[][][] = makeMasks();
-
-		int size_y=16, size_u=64, size_v=64;
-		byte[] tmap=new byte[size_y*size_u*size_v];
-
-		float[] hsb=new float[3];
-		int y, u, v, r, g, b, h, s;
-		int iy, iu, iv, i;
-
-		for (iy=0; iy<16; iy++) 
-		{
-			for (iu=0; iu<64; iu++) 
-			{
-				for (iv=0; iv<64; iv++) 
-				{
-				    y=iy<<4; u=iu<<2; v=iv<<2;
-				    u=u*2-255;
-				    v=v*2-255;
-				    r=y+u;
-				    b=y+v;
-				    u=u>>1;
-				    v=(v>>2)-(v>>4);
-				    g=y-u-v;
-				    if (r<0) r=0; 
-				    if (g<0) g=0; 
-				    if (b<0) b=0;
-				    if (r>255) r=255; 
-				    if (g>255) g=255; 
-				    if (b>255) b=255;
-				    
-				    float[] xy=EasyTrain.colorConverter.getColor(r, g, b);
-				    h=(int)(xy[0]*f_width+f_offset);
-				    s=(int)(xy[1]*f_height+f_offset);
-				    Point point=new Point(h, s);
-				    
-				    for (i=0; i<areas.size(); i++) 
-				    {
-						
-						Area area = (Area) areas.get(i);
-						if (area.contains(point)) 
-						{
-						    tmap[(iy*size_u+iu)*size_v+iv]=(byte)(i+1);
-						    break;
-						}
-				    }
-				}
-	    	}
-		}
-
-		return tmap;
-	
-	}   
-	//TODO make a weighted average version
-	public int[][] getAverageColors()
-	{
-		ArrayList areas = makeAreas();
-
-		rgb=imageData.getSpecialPixels();
-
-		int[][] avgcolors=new int[areas.size()][4]; 
-
-		int skip=(rgb.length/10000)+1;
-		
-		for (int i=0; i<rgb.length; i+=skip) 
-		{
-		    for (int a=0; a<areas.size(); a++) 
-		    {
-			
-				Area area=(Area)areas.get(a);
-				Point p=new Point((int)(xy[i*2]*f_width+f_offset),
-						  (int)(xy[i*2+1]*f_height+f_offset));
-				
-				if (area.contains(p)) 
-				{
-				    avgcolors[a][0]+=(rgb[i]>>16)&0xff;
-				    avgcolors[a][1]+=(rgb[i]>>8)&0xff;
-				    avgcolors[a][2]+=rgb[i]&0xff;
-				    avgcolors[a][3]++;
-				    
-				}
-		    }	    
-		}
-
-		for (int i=0; i<avgcolors.length; i++) 
-		{
-		    if (avgcolors[i][3]>0) 
-		    {
-				avgcolors[i][0]=avgcolors[i][0]/avgcolors[i][3];
-				avgcolors[i][1]=avgcolors[i][1]/avgcolors[i][3];
-				avgcolors[i][2]=avgcolors[i][2]/avgcolors[i][3];
-		    } 
-		    else 
-		    {
-				avgcolors[i][0]=0;
-				avgcolors[i][1]=0;
-				avgcolors[i][2]=0;
-		    }
-		}
-		return avgcolors;
-	}
-
-	public ArrayList makeAreas()
-	{
-	
-		Enumeration colors=colorAreasHash.keys();
-		ArrayList colornames=new ArrayList(20);
-
-		while (colors.hasMoreElements()) colornames.add(colors.nextElement());
-
-		Collections.sort(colornames);
-		ArrayList areas=new ArrayList(20);
-
-		for (Iterator i=colornames.iterator(); i.hasNext();
-		     areas.add(colorAreasHash.get(i.next())));
-
-		return areas;
-
-	}	
-
-	public ArrayList makeImageAreas()
-	{
-
-		Enumeration colors=imageAreasHash.keys();
-		ArrayList colornames=new ArrayList(20);
-
-		while (colors.hasMoreElements()) colornames.add(colors.nextElement());
-
-		Collections.sort(colornames);
-		ArrayList areas=new ArrayList(20);
-
-		for (Iterator i=colornames.iterator(); i.hasNext();
-		     areas.add(imageAreasHash.get(i.next())));
-
-		return areas;
-	}
-
-	public boolean[][][] makeMasks()
-	{
-		
-		Enumeration colors=imageAreasHash.keys();
-		ArrayList colornames=new ArrayList(20);
-		while (colors.hasMoreElements()) colornames.add(colors.nextElement());
-		Collections.sort(colornames);
-		ArrayList areas=new ArrayList(20);
-
-		for (Iterator i=colornames.iterator(); i.hasNext();
-		     areas.add(imageAreasHash.get(i.next())));
-
-		boolean[][][] masks = new boolean[areas.size()][(int)f_width+1][(int)f_height+1];
-
-		for (int i=0; i<areas.size(); i++){
-		    for(int x=0; x<f_width; x++){
-				for(int y=0; y<f_height; y++)
-			    {
-					masks[i][x][y]=false;
-			    }
-			}
-		}
-		//something wrong here
-		//xy = hue saturation, this is probably from segmenter
-		float xy[][] = imageData.getAllHS();
-		double imageWidth = imageShow.getSize().getWidth();
-		double imageHeight = imageShow.getSize().getHeight();
-		for (int i=0; i<areas.size(); i++)
-		{
-			for (int y=0; y<imageHeight; y+=2)
-			{
-			    for (int x=0; x<imageWidth; x+=2)
-				{
-				    Area[] a = (Area[])areas.get(i);
-				    for(int k=0; k<numImages; k++)
-					{
-				    	if (a[k].contains(x,y))
-						{
-					    	int j=(y/2)*(((int)imageWidth)/2)+x/2;
-					    	masks[i][(int)(xy[k][2*j]*f_width)][(int)(xy[k][2*j+1]*f_height)] = true;
-					    
-					    	//int j=(y/2)*(((int)imageWidth))+x/2;
-					    	//masks[i][(int)(xy[j]*f_width)][(int)(xy[j+1]*f_height)] = true;
-						}
-					}
-				}	
-			}
-		}
-
-		return masks;
-	}
-
-	public void load (String filename) throws FileNotFoundException, IOException
-	{
-		int dotpos=filename.lastIndexOf('.');
-		if (dotpos>0) filename=filename.substring(0,dotpos);
-
-		colorAreasHash = new Hashtable();
-		imageAreasHash = new Hashtable();
-
-		curImageArea[curImage].reset();
-		curColorArea.reset();
-
-		BufferedReader saveFile=new BufferedReader(new FileReader(filename + ".save"));
-		BufferedReader areaFile;
-
-		saveFile.readLine();
-
-		int numColors = Integer.parseInt(saveFile.readLine());
-		String [] colors = new String[numColors];
-		Polygon curPoly = new Polygon();;
-		StringTokenizer inTok;
-		int x,y;
-
-		for(int j=0; j<numColors; j++)
-		{
-			String s = saveFile.readLine();
-			colors[j] = s;
-		}
-
-		if(!saveFile.readLine().equals("NEXT"))
-		{
-			System.out.println("Error File Format is incorrect");
-			return;
-		}
-
-		for(int i=0; i<numColors; i++)
-		{
-			
-			for(String in = saveFile.readLine(); !((in.equals("NEXT")) || in.equals("")); in = saveFile.readLine())
-			{
-				inTok = new StringTokenizer(in);
-				in = inTok.nextToken();
-				
-				if(in.equals("START"))
-				{
-					curPoly = new Polygon();
-					x = (int)Double.parseDouble(inTok.nextToken());
-					y = (int)Double.parseDouble(inTok.nextToken());
-					curPoly.addPoint(x,y);
-				}
-				else if(in.equals("LINE"))
-				{
-					x = (int)Double.parseDouble(inTok.nextToken());
-					y = (int)Double.parseDouble(inTok.nextToken());
-					curPoly.addPoint(x,y);
-				}
-				else if(in.equals("CLOSE"))
-				{
-					//System.out.println("adding area");	
-					curColorArea.add(new Area(curPoly));
-				}
-				
-				//System.out.println("S");				
-			}
-			
-			colorAreasHash.put(colors[i],curColorArea);
-			curColorArea = new Area();
-		}
-
-			
-		for(int l=0; l<files.length; l++)
-		{
-				
-			try
-			{
-				areaFile = new BufferedReader(new FileReader(filename +"_"+files[l]+ ".area"));
-			
-				areaFile.readLine();
-				for(int k=0; k<numColors; k++)
-				{		
-				
-					curImageArea =(Area[])imageAreasHash.get(colors[k]);
-					
-					if(curImageArea == null)
-					{
-						curImageArea = new Area[numImages];
-						for(int i=0; i<numImages; i++)
-					    {
-					      	curImageArea[i] = new Area();
-					    }
-		    		}
-				    
-				    
-					for(String in = areaFile.readLine(); (!(in.equals("NEXT")) && areaFile.ready()); in = areaFile.readLine())
-					{
-						inTok = new StringTokenizer(in);
-						in = inTok.nextToken();
-						
-						if(in.equals("START"))
-						{
-							curPoly = new Polygon();
-							x = (int)Double.parseDouble(inTok.nextToken());
-							y = (int)Double.parseDouble(inTok.nextToken());
-							curPoly.addPoint(x,y);
-						}
-						else if(in.equals("LINE"))
-						{
-							x = (int)Double.parseDouble(inTok.nextToken());
-							y = (int)Double.parseDouble(inTok.nextToken());
-							curPoly.addPoint(x,y);
-						}
-						else if(in.equals("CLOSE"))
-						{
-							curImageArea[l].add(new Area(curPoly));
-						}
-						
-					}
-					imageAreasHash.put(colors[k],curImageArea);
-				}
-				
-			}
-			catch(Exception e)
-			{
-				for(int k=0; k<numColors; k++)
-				{		
-				
-					curImageArea =(Area[])imageAreasHash.get(colors[k]);
-					
-					if(curImageArea == null)
-					{
-						curImageArea = new Area[numImages];
-						for(int i=0; i<numImages; i++)
-					    {
-					      	curImageArea[i] = new Area();
-					    }
-		    		}
-		    		
-		    		imageAreasHash.put(colors[k],curImageArea);
-		    	}
-							
-			}
-			
-		}
-		segImage.reSegment(makeTmap(), getAverageColors());
-		//setCurColor(null);
-	}
-
-	public void save (String filename) 
-	{
-		int dotpos=filename.lastIndexOf('.');
-		if (dotpos>0) filename=filename.substring(0,dotpos);
-
-		Enumeration colors=colorAreasHash.keys();
-		ArrayList colornames=new ArrayList(20);
-		while (colors.hasMoreElements()) colornames.add(colors.nextElement());
-		Collections.sort(colornames);
-		ArrayList areas=makeAreas();
-		ArrayList imageAreas = makeImageAreas();
-
-		int size_y=16, size_u=64, size_v=64;
-
-		int i;
-		byte[] tmap = makeTmap();
-
-		try 
-		{
-			FileOutputStream file_tm_fos=new FileOutputStream(filename + ".tm");
-			OutputStreamWriter file_tm_osw=new OutputStreamWriter(file_tm_fos);
-			file_tm_osw.write("TMAP\nYUV8\n" +
-			  size_y + " " + size_u + " " + size_v + "\n");
-			file_tm_osw.flush();
-			file_tm_fos.write(tmap);
-			file_tm_osw.close();
-		} 
-		catch (Exception ex) 
-		{
-			System.out.println("Error saving to "+filename +".tm: " + ex);
-		}
-		
-		int [][] avgcolors = getAverageColors();
-
-		try 
-		{
-			FileWriter file_col_fw=new FileWriter(filename + ".col");
-			file_col_fw.write("0 (128 128 128) \"unclassified\" 8 1.00\n");
-			
-			for (i=0; i<areas.size(); i++) 
-			{
-				file_col_fw.write((i+1)+ " (" +
-				              avgcolors[i][0] + " " +
-				              avgcolors[i][1] + " " +
-				              avgcolors[i][2] + ") " +
-				              "\"" + colornames.get(i)+ "\" 8 0.75\n");
-			}
-			
-			file_col_fw.close();
-		} 
-		catch (Exception ex) 
-		{
-			System.out.println("Error saving to "+filename + ".col: " + ex);
-		}
-
-		try 
-		{
-			FileWriter file_save_fw=new FileWriter(filename + ".save");
-			FileWriter file_area_fw;
-			file_save_fw.write(filename + "\n");
-			file_save_fw.write(areas.size() + "\n");
-
-			for(int j=0; j<colornames.size(); j++)
-			{
-				file_save_fw.write(colornames.get(j) + "\n");	
-			}      
-
-			for (i=0; i<areas.size(); i++) 
-			{
-				Area a = (Area)areas.get(i);
-				PathIterator path = a.getPathIterator(null);
-
-				String pathString = createPathString(path);
-				file_save_fw.write(pathString);  
-
-			}
-
-			file_save_fw.write("\n");
-			file_save_fw.close();
-
-
-			for(int l=0; l<files.length; l++)
-			{
-				
-				String areaname = filename + "_"+ files[l];
-	
-				file_area_fw=new FileWriter(areaname + ".area");	
-
-				for (i=0; i<imageAreas.size(); i++) 
-				{
-				    Area [] a = (Area[])imageAreas.get(i);
-				    PathIterator path = a[l].getPathIterator(null);
-				      	
-				    String pathString = createPathString(path);
-				    file_area_fw.write(pathString);  
-				   
-				}
-
-				file_area_fw.write("\n");
-				file_area_fw.close();
-
-			}		  
-
-		} catch (Exception ex) {
-		  System.out.println("Error saving to "+filename + ".area: " + ex);
-		}
-
-
-	}
-
-	String createPathString(PathIterator path)
-	{
-
-		String retPath = "NEXT\n";
-
-		double[] coords = new double[6];
-		int type;	
-
-		while(!path.isDone())
-		{
-		  	type = path.currentSegment(coords); 
-		  	
-		  	
-		  	if( (type == PathIterator.SEG_MOVETO)) //new polygon
-		  	{
-		  		retPath += "START " + coords[0] + " " + coords[1] + "\n";		
-		  	}
-		  	else if( (type == PathIterator.SEG_LINETO)) //line 
-		  	{
-		  		retPath += "LINE " + coords[0] + " " + coords[1] + "\n";
-		  	}
-		  	else if( (type == PathIterator.SEG_CLOSE))  //end of curr polygon
-		  	{
-		  		retPath += "CLOSE\n";
-			}
-			
-			path.next();
-			
-		}
-
-		return retPath;
-
-	}
-
-	byte[] readThresholdMap(String thresholdfile) 
-	{
-		try 
-		{
-			byte[] tmdata=new byte[65536];
-			FileInputStream file_tm_fis=new FileInputStream(thresholdfile);
-			file_tm_fis.read(tmdata,0,19);
-			file_tm_fis.read(tmdata);
-			file_tm_fis.close();
-			return tmdata;
-		} 
-		catch (Exception ex) 
-		{
-			System.out.println("Error reading file "+thresholdfile+": "+ex);
-			return null;
-		}
-	}
-
-
-
-	void resizeAreas(double x, double y, double changeX, double changeY)
-	{
-		if(curImageArea != null)
-		{
-			Area[] curAreaList;
-			Area curArea;
-			
-			updateAreas(x,y,changeX,changeY);			
-			
-			imageShow.setCurArea(curImageArea[curImage]);
-			plotImageArea(curImageArea);
-
-			repaint();
-		}	  
-	}
-	
-	void updateAreas(double x, double y, double changeX, double changeY)
-	{
-		Area[] curAreaList;
-		Area curArea;
-		Area[] origAreaList;
-		Area origArea;
-		Object o;
-		
-		Enumeration colors=imageAreasHash.keys();
-		ArrayList colornames=new ArrayList();
-		while (colors.hasMoreElements()) colornames.add(colors.nextElement());
-		
-		for (int i=0; i<colornames.size(); i++)
-		{
-			curAreaList = (Area[])imageAreasHash.get(colornames.get(i));
-			
-			o = originalImageAreasHash.get(colornames.get(i));
-			
-			if(o == null)
-			{
-				origAreaList = new Area[numImages];
-			}
-			else
-			{
-				origAreaList = (Area[])o;
-			}
-				
-			for(int j = 0; j < numImages; j++)
-			{
-				if(dirtyOriginal == true)
-				{
-					curAreaList[j] = curAreaList[j].createTransformedArea(AffineTransform.getScaleInstance(changeX,changeY));
-					origAreaList[j] = curAreaList[j].createTransformedArea(AffineTransform.getScaleInstance(1.0/x,1.0/y));
-				}
-				else
-				{
-					curAreaList[j] = origAreaList[j].createTransformedArea(AffineTransform.getScaleInstance(x,y));
-				}
-				
-			}
-				
-			originalImageAreasHash.put(colornames.get(i),origAreaList);
-			imageAreasHash.put(colornames.get(i),curAreaList);
-		}	
-		
-		dirtyOriginal = false;
-	}
-	
-	//******* MOUSE CONTROLS ********
-    
-    public void mousePressed(MouseEvent e) 
-	{
-		if (e.getButton()!=MouseEvent.BUTTON1) return;
-
-		if (curImageArea==null || curColorArea==null)
-		{
-			ControlPanel.addDefaultColor();    
-		}
-
-		if (e.getSource() instanceof ImageShowArea)
-		{
-		    areaInImage = true;
-		    curPoly=new Polygon();
-		    lastx=e.getX();
-		    lasty=e.getY();
-		    curPoly.addPoint(e.getX(), e.getY());
-		    imageShow.setCurPoly(curPoly);		    
-		}
-		else
-		{
-		    areaInImage = false;		    
-		    curPoly=new Polygon();
-		    lastx=e.getX();
-		    lasty=e.getY();
-		    curPoly.addPoint(e.getX(), e.getY());
-		    repaint();
-		}
-	}
-
-	public void mouseDragged(MouseEvent e) 
-	{	  
-		if (e.getSource() instanceof ImageShowArea)
-		{   	      
-			int x=e.getX();
-			int y=e.getY();
-
-			if ((Math.abs(x-lastx)+Math.abs(y-lasty))>2) 
-			{
-				curPoly.addPoint(e.getX(), e.getY());
-				lastx=x;
-				lasty=y;
-				imageShow.setCurPoly(curPoly);
-			}
-		}
-		else
-		{	      
-			int x=e.getX();
-			int y=e.getY();
-
-			if ((Math.abs(x-lastx)+Math.abs(y-lasty))>2) 
-			{
-				curPoly.addPoint(e.getX(), e.getY());
-				lastx=x;
-				lasty=y;
-				repaint();
-			}
-		}
-	}
-
-	public void mouseReleased(MouseEvent e) 
-	{
-		if (e.getButton()!=MouseEvent.BUTTON1) return;
-
-		if (e.getSource() instanceof ImageShowArea)
-		{
-		    if (curImageArea==null)
-		    {
-		    	ControlPanel.addDefaultColor();		    
-		    } 
-		    
-		    curImage = imageShow.getCurImage();
-
-		    curPoly.addPoint(e.getX(), e.getY());
-		    
-		    if (curPoly.npoints>=3) 
-		    {
-				
-				if(originalImageArea != null && originalImageArea[curImage] != null)
-				{
-					undoObj = new Area(originalImageArea[curImage]);
-				}
-				else
-				{
-					undoObj = curImageArea[curImage].createTransformedArea(AffineTransform.getScaleInstance(1.0/imageShow.resizedX,1.0/imageShow.resizedY));
-				}
-				
-				ControlPanel.enableUndo();
-				lastAction = IMAGE_AREA;
-				uImg = curImage; 
-				 
-				if (e.isControlDown())
-				{ 
-				    curImageArea[curImage].subtract(new Area(curPoly));
-				}
-				else if (e.isShiftDown())
-				{ 
-					curImageArea[curImage].add(new Area(curPoly));
-				}
-				else
-				{
-					curImageArea[curImage].reset();
-				 	
-					curImageArea[curImage].add(new Area(curPoly));
-				}
-				dirtyOriginal = true;
-		    }
-		    
-		    curPoly=null;
-		    imageShow.setCurArea(curImageArea[curImage]);
-		    imageShow.setCurPoly(null);
-		    
-		    
-
-		    if(!colorshow)
-		    {
-		    	plotImageArea(curImageArea);
-		    }
-		}
-		else //color area
-		{
-		    if (curColorArea==null) return;
-
-		    curPoly.addPoint(e.getX(), e.getY());
-		    
-		    if (curPoly.npoints>=3) 
-		    {
-				
-				undoObj = new Area(curColorArea);
-				ControlPanel.enableUndo();
-				lastAction = COLOR_AREA;
-				
-				
-				if (e.isControlDown())
-				{ 
-				    curColorArea.subtract(new Area(curPoly));
-				}
-				else if (e.isShiftDown())
-				{ 
-				    curColorArea.add(new Area(curPoly));
-				}
-				else
-				{
-					curColorArea.reset();
-					curColorArea.add(new Area(curPoly));
-				}
-			}
-			
-		    curPoly=null;
-		    repaint();
-		}
-		
-		segImage.reSegment(makeTmap(), getAverageColors());
-	}
-
-	public void mouseMoved(MouseEvent e)
-	{
-		Object source=e.getSource();
-		curImage = imageShow.getCurImage();
-		if (source instanceof ImageShowArea) 
-		{
-		  	
-			ImageShowArea imageShow=(ImageShowArea)source;
-			int rgb=imageShow.getPixel(e.getX(), e.getY());
-			float[] xy=EasyTrain.colorConverter.getColor(rgb);
-			int x=(int)(xy[0]*f_width+f_offset);
-			int y=(int)(xy[1]*f_height+f_offset);
-			imageHint=new Point(x,y);
-			
-			segImage.showHint(new Point((int) ((double)e.getX() / imageShow.resizedX),(int) ( (double)e.getY() / imageShow.resizedY)));
-				
-			repaint();
-		}
-		/* this currently is not working
-		else if (source instanceof SegmentedImage) 
-		{
-			SegmentedImage seg=(SegmentedImage)source;
-			int rgb=seg.getPixel(e.getX(), e.getY());
-			float[] xy=TrainingTool.colorConverter.getColor(rgb);
-			int x=(int)(xy[0]*f_width+f_offset);
-			int y=(int)(xy[1]*f_height+f_offset);
-			imageHint=new Point(x,y);
-				
-			segImage.showHint(null);
-			
-			repaint();
-		 
-		}*/
-		else
-		{
-			segImage.showHint(null);
-			imageHint = null;			
-			repaint();
-		}    
-	}
-
-	public void mouseClicked(MouseEvent e){}
-	
-	public void mouseExited(MouseEvent e)
-	{
-		if (e.getSource() instanceof ImageShowArea) 
-		{
-			imageHint=null;
-			repaint();
-		}
-		else if(e.getSource() instanceof SegmentedImage)
-		{
-			imagePlace = null;
-			repaint();
-		}
-	}
-	
-	public void mouseEntered(MouseEvent e){}
-	public void updateLocation(MouseEvent e){}
-
- 	
-
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/easytrain/help.txt ./tools/easytrain/help.txt
--- ../Tekkotsu_2.4.1/tools/easytrain/help.txt	2005-08-03 20:27:38.000000000 -0400
+++ ./tools/easytrain/help.txt	2005-10-29 12:43:16.000000000 -0400
@@ -1,67 +1,113 @@
-EastyTrain instructions:
-
-Usage:
-  java EasyTrain [-isYUV | -isRGB] imagefile...
-
-Image files should be saved from the Tekkotsu RawCam window as PNG
-files with YUV encoding (the default), but the program can also handle
-images in RGB encoding.  EasyTrain displays the images as RGB in
-either case.
-
-1. Raw image window: displays the current image file.  Use the up and
-down arrow keys to cycle through all the image files.
-
-2. Segmented image window: displays the color-segmented version of the
-current image file.  (If no colors are defined yet, it will be all
-black.)
-
-3. Color space window: displays pixels from selected image regions in
-a 2D color space representation.  Draw a bounding region with the
-mouse to select pixel clusters.
-
-4. GUI window: contains buttons to add or remove colors, load or save
-files, etc.
-
-================
-
-Start by entering a color name, say, "pink".  (Type the color name in
-the dialog box at the top of the GUI window, and hit "enter".)
-
-Now use the mouse to circle a pink region in the raw image window.
-This will cause a cloud of pink pixels to appear in the color space
-window.  (Note: if you have a pink object on a green background and
-you just draw a big box around it, so that some green pixels are
-included in the box, that's okay, because the green pixels will be far
-enough away from the pink ones in color space that you can easily
-separate them.)
-
-Use the mouse to circle just the cloud of pink pixels in color space.
-Once you've done that, the pink regions should appear in the color
-segmented image window.
-
-You can add to a region by holding down the shift key and drawing with
-the mouse.  You can subtract from a region by holding down the control
-key and drawing.
-
-You can use the up and down arrow keys in the raw or segmented image
-windows to cycle though the images.  You can circle zero or more
-regions in each image.  Pixels from all the images will be lumped
-together in the color space window.
-
-If no color name is selected, EasyTrain will show you the color space
-with all the pixels from all the images.  If you do have a color name
-selected, you can deselect it by holding down the control key and
-clicking on the color name in the GUI window.
-
-After you've defined all your colors, use the "Save" button to save
-your work.  The area boundary info for each image will be saved, along
-with the .col and .tm files needed by CMVision.  That means if you
-come back later and run the program again, loading in the same image
-files, the program will also load in the boundaries you defined, so
-you can continue to edit them.
-
-================
-
-Note to Linux users: if you're receiving warnings about inability to locate
-a system preferences file, this is because of the way Java was installed.
-See http://java.sun.com/j2se/1.5.0/install-linux.html for a fix.
+EasyTrain instructions:
+
+Usage:
+  java EasyTrain [-isYUV | -isRGB] [-show YUV|HSB|rg|xy|Lab] imagefile...
+
+See additional tutorials at:
+  http://www.cs.cmu.edu/~dst/Tekkotsu/Tutorial/colorsegment.shtml
+  http://www.cs.cmu.edu/~tekkotsu/CameraSetup.html
+
+
+== Command Line Flags: ===========
+
+  -isYUV, -isRGB   Report the mode that input images were saved in.
+
+  -show <mode>     Controls the color space shown in Color Spectrum window:
+                     YUV - displays U,V channels; native space of the AIBO
+                     HSB - [default] displays Hue and Saturation
+                     rg  - R and G contributions of RGB space
+                     xy  - X and Y contributions of XYZ space
+                     Lab - displays a,b channels
+
+  Among the color spaces available for showing, all except HSB distribute
+  hues basically radially, with a white point at the center.  HSB places
+  the hues along the x axis, and saturation along the y; thus the white
+  point is spread out along the top of the plot.
+      YUV might be preferred for its direct control
+      HSB might be preferred for a horizontal view of hue
+      Lab might be preferred for a radial view of hue
+      (rg and xy are mainly side-effects, but made available if desired)
+
+
+== Expected Image Format: ========
+
+  Image files should be saved from the Tekkotsu RawCam window as PNG files
+  with YUV encoding, but the program can also handle images in RGB
+  encoding.  If you do decide to use JPEG images, you should actually save
+  them in 'RGB' mode, because the JPEG format uses YUV internally.
+
+  Pass '-isYUV' if the images were saved in YUV mode, pass '-isRGB' if they
+  were saved in RGB mode.
+
+
+== Window List: ==================
+
+1. RGB Image View: displays the current image file in RGB color space.  Use
+   the arrow keys to cycle through all the image files.
+
+2. Segmented Viewer: displays the color-segmented version of the
+   current image file.  (If no colors are defined yet, it will be all
+   grey.)
+
+3. Color Spectrum Window: displays pixels from selected image regions in a
+   2D color space representation.  Draw a bounding region with the mouse to
+   select pixel clusters.  See discussion of the '-show' option for
+   controlling the color space used
+
+4. Control window: contains buttons to add or remove colors, load or save
+   files, etc.  Hover over items for tooltips.
+
+5. Thumbnail window: shows thumbnails of loaded images, allows you to
+   directly jump to specific images by clicking on them.
+
+
+== Shortcuts: ==============
+
+  In any of the editor windows (1-3 above):
+    Ctrl-A: select all
+    Ctrl-D: deselect
+    Ctrl-Z: undo
+    Shift-Ctrl-Z: redo
+    '+': Increase magnification multiple
+    '-': Decrease magnification multiple
+    '=': Reset magnification to "actual size"
+
+
+== Usage: ==================
+ 
+  Start by entering a color name, say, "pink".  (Type the color name in the
+  dialog box at the top of the GUI window, and hit "enter".)
+
+  Now use the mouse to circle a pink region in the raw image window.  This
+  will cause a cloud of pink pixels to appear in the color space window.
+  (Note: if you have a pink object on a green background and you just draw
+  a big box around it, so that some green pixels are included in the box,
+  that's okay, because the green pixels will be far enough away from the
+  pink ones in color space that you can easily separate them.)
+
+  Use the mouse to circle just the cloud of pink pixels in color space.
+  Once you've done that, the pink regions should appear in the color
+  segmented image window.
+
+  You can add to a region by holding down the shift key and drawing with
+  the mouse.  You can subtract from a region by holding down the control
+  key and drawing.
+
+  You can use the arrow keys in the raw or segmented image windows to cycle
+  though the images.  You can circle zero or more regions in each image.
+  Pixels from all the images will be lumped together in the color space
+  window.  (If no regions are selected, or 'all pixels' control is
+  selected, then the full color spectrum is shown)
+
+  After you've defined all your colors, use the "Save" button to save your
+  work.  The area boundary info for each image will be saved, along with
+  the .col and .tm files needed by CMVision.  That means if you come back
+  later and run the program again, loading in the same image files, the
+  program will also load in the boundaries you defined, so you can continue
+  to edit them.
+
+================
+
+Note to Linux users: if you're receiving warnings about inability to locate
+a system preferences file, this is because of the way Java was installed.
+See http://java.sun.com/j2se/1.5.0/install-linux.html for a fix.
Binary files ../Tekkotsu_2.4.1/tools/easytrain/test1.png and ./tools/easytrain/test1.png differ
Binary files ../Tekkotsu_2.4.1/tools/easytrain/test2.png and ./tools/easytrain/test2.png differ
Binary files ../Tekkotsu_2.4.1/tools/easytrain/test3.png and ./tools/easytrain/test3.png differ
Binary files ../Tekkotsu_2.4.1/tools/easytrain/test4.png and ./tools/easytrain/test4.png differ
Binary files ../Tekkotsu_2.4.1/tools/easytrain/test5.png and ./tools/easytrain/test5.png differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/evenmodtime/Makefile ./tools/evenmodtime/Makefile
--- ../Tekkotsu_2.4.1/tools/evenmodtime/Makefile	2005-08-16 16:48:11.000000000 -0400
+++ ./tools/evenmodtime/Makefile	1969-12-31 19:00:00.000000000 -0500
@@ -1,12 +0,0 @@
-.PHONY: all clean test
-
-all: evenmodtime
-
-evenmodtime: evenmodtime.cc
-	g++ -o evenmodtime -Wall -O2 evenmodtime.cc
-
-clean:
-	rm -f evenmodtime
-
-test:
-
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/evenmodtime/evenmodtime.cc ./tools/evenmodtime/evenmodtime.cc
--- ../Tekkotsu_2.4.1/tools/evenmodtime/evenmodtime.cc	2003-07-28 14:39:19.000000000 -0400
+++ ./tools/evenmodtime/evenmodtime.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,54 +0,0 @@
-#include <stdlib.h>
-#include <unistd.h>
-#include <time.h>
-#include <iostream>
-#include <sys/stat.h>
-#include <utime.h>
-
-using namespace std;
-
-int usage(unsigned int argc, const char* argv[]) {
-	cerr << "Usage: "<<argv[0]<<" filename ... \n"
-			 << "       This will round the modification time of filename up to the\n"
-			 << "       nearest even second.\n"
-			 << "       \n"
-			 << "       This is useful for cleaning up modification times on a PC before\n"
-			 << "       synchronizing with a memory stick, since memory sticks apparently\n"
-			 << "       do not store odd seconds, which causes confusion for programs\n"
-			 << "       such as rsync" << endl;
-	return 2;
-}
-
-
-/*	   << "       This will then output the modification time of filename rounded\n"
-			 << "       up to the nearest even second in the format YYYYMMDDHHMMSS.\n"
-*/
-
-int main(unsigned int argc, const char* argv[]) {
-	int status;
-	if(argc<2)
-		return usage(argc,argv);
-	for(unsigned int i=1; i<argc; i++) {
-		struct stat stat_buf;
-		status=lstat(argv[i],&stat_buf);
-		if(status) {
-			cerr << argv[0] << ": Bad file '" << argv[i] << "'" << endl;
-			return 1;
-		}
-		stat_buf.st_mtime=(stat_buf.st_mtime+1) & ~1;
-		//  struct tm * tm_buf;
-		//	tm_buf=localtime(&stat_buf.st_mtime);
-		//	char out[1024];
-		//	strftime(out,1024,"%Y%m%d%H%M.%S",tm_buf);
-		//	cout << out << endl;
-		struct utimbuf  ut_buf;
-		ut_buf.actime=stat_buf.st_atime;
-		ut_buf.modtime=stat_buf.st_mtime;
-		status=utime(argv[i],&ut_buf);
-		if(status) {
-			cerr << argv[0] << ": Bad file '" << argv[i] << "'" << endl;
-			return 1;
-		}
-	}
-	return 0;
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/filtersyswarn/Makefile ./tools/filtersyswarn/Makefile
--- ../Tekkotsu_2.4.1/tools/filtersyswarn/Makefile	2005-08-16 16:48:15.000000000 -0400
+++ ./tools/filtersyswarn/Makefile	2006-05-09 12:37:58.000000000 -0400
@@ -3,7 +3,7 @@
 all: filtersyswarn
 
 filtersyswarn: filtersyswarn.cc
-	g++ -o filtersyswarn -Wall -O2 filtersyswarn.cc
+	$(CXX) -o filtersyswarn -Wall -O2 filtersyswarn.cc
 
 clean:
 	rm -f filtersyswarn
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/filtersyswarn/filtersyswarn.cc ./tools/filtersyswarn/filtersyswarn.cc
--- ../Tekkotsu_2.4.1/tools/filtersyswarn/filtersyswarn.cc	2005-06-01 01:48:08.000000000 -0400
+++ ./tools/filtersyswarn/filtersyswarn.cc	2006-02-05 19:11:04.000000000 -0500
@@ -12,9 +12,9 @@
 	regex_t sysmsg, instbegin, inststat, ignorebegin, warnstat, inclbegin, inclstat;
 	
 	string OPENR="^";
-	if(argc>1)
+	if(argc>1) {
 		OPENR+=argv[1];
-	else {
+	} else {
 		char* OPENRSDK_ROOT=getenv("OPENRSDK_ROOT");
 		OPENR+=(OPENRSDK_ROOT!=NULL)?OPENRSDK_ROOT:"/usr/local/OPEN_R_SDK/";
 	}
@@ -32,8 +32,9 @@
 	regcomp(&sysmsg,OPENR.c_str(),REG_EXTENDED|REG_NOSUB);
 	regcomp(&instbegin,instbeginstr.c_str(),REG_EXTENDED|REG_NOSUB);
 	regcomp(&inststat,inststatstr.c_str(),REG_EXTENDED|REG_NOSUB);
-	string pliststr_no_vdtor=".*plist.h:[0-9]*: warning: base class";
-	regcomp(&ignorebegin,(OPENR+".*: warning: |"+pliststr_no_vdtor).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);
 	regcomp(&warnstat,"^   ",REG_EXTENDED|REG_NOSUB);
 
 	string file, instant;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/ftpinstall ./tools/ftpinstall
--- ../Tekkotsu_2.4.1/tools/ftpinstall	2004-11-16 18:52:32.000000000 -0500
+++ ./tools/ftpinstall	2006-08-23 16:26:46.000000000 -0400
@@ -21,7 +21,7 @@
 	."\n";
 
 use Getopt::Std;
-getopts('u:p:hHz');
+getopts('a:u:p:hHz');
 die $message if ($opt_h || $opt_H);
 $username = $opt_u if ($opt_u);
 $password = $opt_p if ($opt_p);
@@ -31,6 +31,9 @@
 die $message if @ARGV <= 1;
 $hostname = shift(@ARGV);
 $localdir = shift(@ARGV);
+$numoflist=0;
+
+$copiedtimestamp = ".copied.timestamp.$hostname";
 
 chdir($localdir);
 makecopylist(".");
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/ftpupdate ./tools/ftpupdate
--- ../Tekkotsu_2.4.1/tools/ftpupdate	2004-11-16 18:52:32.000000000 -0500
+++ ./tools/ftpupdate	2006-08-23 16:26:46.000000000 -0400
@@ -21,7 +21,7 @@
 	."\n";
 
 use Getopt::Std;
-getopts('u:p:hHz');
+getopts('u:a:p:hHz');
 die $message if ($opt_h || $opt_H);
 $username = $opt_u if ($opt_u);
 $password = $opt_p if ($opt_p);
@@ -33,11 +33,11 @@
 $localdir = shift(@ARGV);
 $numoflist=0;
 
-$copiedtimestamp = ".copiedtomemstick.timestamp";
-
-makecopylist($localdir);
+$copiedtimestamp = ".copied.timestamp.$hostname";
 
 chdir($localdir);
+makecopylist(".");
+
 login();
 for ($i = 0; $i < $numoflist; $i++) {
 	if ($LIST[$i] =~ /\/$/) {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/genCommonHeader ./tools/genCommonHeader
--- ../Tekkotsu_2.4.1/tools/genCommonHeader	2005-06-01 01:48:08.000000000 -0400
+++ ./tools/genCommonHeader	2006-09-21 19:02:30.000000000 -0400
@@ -2,7 +2,7 @@
 
 dest=common.h;
 src=build;
-thresh=40;
+thresh=0.5;
 root=`cd \`dirname "$0"\`/..; pwd`/
 
 usage="\
@@ -13,7 +13,8 @@
    If unspecified, destination is $dest and builddir is $src, both \n \
    relative to the current directory (`pwd`). \n \
    \n \
-   Threshold defaults to $thresh.\n \
+   Threshold defaults to $thresh.  This specifies the percentage of source\n \
+   files which must include the header for it to be listed.\n \
    \n \
    force and force-pattern allow you to explicitly add files to the \n \
    list, even if  they wouldn't otherwise break the threshold.  You can \n \
@@ -25,6 +26,8 @@
    each of the file names for portability. \n \
    \n";
 
+args="$*"
+
 while [ $# -gt 0 ] ; do
     case "$1" in
 	-r|--root) root="$2"; shift; shift ;;
@@ -39,10 +42,11 @@
 
 rm -f $dest;
 echo "/* This is a file lists the most depended-upon header files used by" >> "$dest"
-echo " * the project.  It is automatically generated by tools/genCommonHeader." >> "$dest"
+echo " * the project.  It is automatically generated by:" >> "$dest"
+echo " *   tools/genCommonHeader $args" >> "$dest"
 echo " * When compiling for PLATFORM_LOCAL, this header will be precompiled. " >> "$dest"
 echo " * It was created at `date` and checked into " >> "$dest"
-echo " * CVS at \$Date: 2006/10/04 04:21:12 $ */" >> "$dest"
+echo " * CVS at \$Date: 2006/10/04 04:21:12 $ */" >> "$dest"
 echo "" >> "$dest"
 
 echo "#ifdef __cplusplus //lets us blindly apply to C files as well" >> "$dest"
@@ -57,14 +61,22 @@
     echo "#ifdef $plat" >> "$dest"
     for modelbuild in "$src/$plat/TGT"* ; do
 	echo "Processing $modelbuild...";
+	srcfiles=`find build/PLATFORM_APERIOS/TGT_ERS7/ -name "*.d" | wc -l`;
+	cutoff=`echo "( $srcfiles * $thresh + .5 ) / 1" | bc`;
 	model=`echo "$modelbuild" | sed "s@$src/$plat/@@"`;
 	echo "#ifdef $model" >> "$dest";
-	( find "$modelbuild" -name "*.d" | xargs sed -n 's/\(.*\.h\):$/\1/p' ) | sed "s@^$root@@" | sort | uniq -c | sort -nr | \
+	( \
+		for x in `find "$modelbuild" -name "*.d"` ; do \
+			sed -n 's/\(.*\.h\):$/\1/p' "$x" | sort | uniq; \
+		done; \
+	) | sed "s@^$root@@" | sort | uniq -c | sort -nr | \
 	while read n file ; do
-	    if [ $n -ge $thresh ] ; then
+	    if [ $n -ge $cutoff ] ; then
 		echo "#include \"$file\" //$n" >> "$dest" ;
-	    elif echo "$file" | grep -q "$pattern" ; then
-		echo "#include \"$file\" //forced (pattern match)" >> "$dest" ;
+	    elif [ "$pattern" ] ; then
+	    	if echo "$file" | grep -q "$pattern" ; then
+		    echo "#include \"$file\" //forced (pattern match)" >> "$dest" ;
+		fi;
 	    fi;
 	done;
 	for f in $forced ; do
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/installXCodeTemplates ./tools/installXCodeTemplates
--- ../Tekkotsu_2.4.1/tools/installXCodeTemplates	2005-06-01 01:48:08.000000000 -0400
+++ ./tools/installXCodeTemplates	2005-10-25 23:56:09.000000000 -0400
@@ -101,6 +101,31 @@
 </plist>
 EOF
 
+CUR="$INSTALL/MotionCommand.pbfiletemplate"
+mkdir "$CUR";
+echo "Made dir $CUR";
+cp "$SOURCE/motioncommand.h" "$SOURCE/implementation.cc" "$CUR";
+cat > "$CUR/$TIFILE" << EOF
+<?xml version="1.0" encoding="UTF-8"?>
+<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyLis
+t-1.0.dtd">
+<plist version="1.0">
+<dict>
+	<key>Description</key>
+	<string>A blank Tekkotsu MotionCommand, with an optional implementation file.</string>
+	<key>MainTemplateFile</key>
+	<string>implementation.cc</string>
+	<key>FileToDisplay</key>
+	<string>%@.h</string>
+	<key>ImplicitCounterpartTemplateFiles</key>
+	<dict>
+		<key>motioncommand.h</key>
+		<string>%@.h</string>
+	</dict>
+</dict>
+</plist>
+EOF
+
 CUR="$INSTALL/Control.pbfiletemplate"
 mkdir "$CUR";
 echo "Made dir $CUR";
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/makelowercase ./tools/makelowercase
--- ../Tekkotsu_2.4.1/tools/makelowercase	2004-11-16 23:48:22.000000000 -0500
+++ ./tools/makelowercase	2006-09-12 15:06:23.000000000 -0400
@@ -9,8 +9,14 @@
 fi;
 
 for x in $* ; do
-	dir=`echo "$x" | sed 's@\(.*\)/.*@\1@'`;
-	file=`echo "$x" | sed 's@\(.*\)/@@'`;
+	dir=`dirname "$x"`;
+	file=`basename "$x"`;
+	if [ "$file" = "CVS" ] ; then
+		continue;
+	fi;
+	if echo "$file" | grep -q '\\..*' ; then
+		continue;
+	fi;
 	if [ ! -r "$x" ] ; then
 		if [ "$file" != "*" ] ; then
 			echo "WARNING: Could not read '$x'";
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/makeuppercase ./tools/makeuppercase
--- ../Tekkotsu_2.4.1/tools/makeuppercase	2004-11-16 23:48:23.000000000 -0500
+++ ./tools/makeuppercase	2006-09-12 15:06:24.000000000 -0400
@@ -9,8 +9,14 @@
 fi;
 
 for x in $* ; do
-	dir=`echo "$x" | sed 's@\(.*\)/.*@\1@'`;
-	file=`echo "$x" | sed 's@\(.*\)/@@'`;
+	dir=`dirname "$x"`;
+	file=`basename "$x"`;
+	if [ "$file" = "CVS" ] ; then
+		continue;
+	fi;
+	if echo "$file" | grep -q '\\..*' ; then
+		continue;
+	fi;
 	if [ ! -r "$x" ] ; then
 		if [ "$file" != "*" ] ; then
 			echo "WARNING: Could not read '$x'";
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mipaltools/Makefile ./tools/mipaltools/Makefile
--- ../Tekkotsu_2.4.1/tools/mipaltools/Makefile	2005-08-16 16:48:15.000000000 -0400
+++ ./tools/mipaltools/Makefile	2006-05-09 12:37:59.000000000 -0400
@@ -3,10 +3,10 @@
 all: StackedIt
 
 StackedIt: src/*.h src/*.cc
-	make -C src
+	$(MAKE) -C src
 
 clean:
-	make -C src clean
+	$(MAKE) -C src clean
 
 test:
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mipaltools/src/Makefile ./tools/mipaltools/src/Makefile
--- ../Tekkotsu_2.4.1/tools/mipaltools/src/Makefile	2003-12-02 02:00:41.000000000 -0500
+++ ./tools/mipaltools/src/Makefile	2006-05-09 12:37:59.000000000 -0400
@@ -1,23 +1,23 @@
 all: EmonLog.o  Function.o  FunctionStore.o  StackAnalyser.o  StackDump.o  main.o
-	g++ -o ../StackedIt EmonLog.o  Function.o  FunctionStore.o  StackAnalyser.o  StackDump.o  main.o 
+	$(CXX) -o ../StackedIt EmonLog.o  Function.o  FunctionStore.o  StackAnalyser.o  StackDump.o  main.o 
 
 Function.o: Function.cc Function.h
-	g++ -c -O3  Function.cc
+	$(CXX) -c -O3  Function.cc
 
 FunctionStore.o: FunctionStore.cc FunctionStore.h Function.h 
-	g++ -c -O3  FunctionStore.cc
+	$(CXX) -c -O3  FunctionStore.cc
 
 StackAnalyser.o: StackAnalyser.cc StackAnalyser.h StackDump.h FunctionStore.h Function.h Trace.h
-	g++ -c -O3  StackAnalyser.cc
+	$(CXX) -c -O3  StackAnalyser.cc
 
 StackDump.o: StackDump.cc StackDump.h 
-	g++ -c -O3  StackDump.cc
+	$(CXX) -c -O3  StackDump.cc
 
 main.o: main.cc StackDump.h FunctionStore.h Function.h StackAnalyser.h
-	g++ -c -O3  main.cc
+	$(CXX) -c -O3  main.cc
 
 EmonLog.o:	EmonLog.h EmonLog.cc
-	g++ -c -O3  EmonLog.cc
+	$(CXX) -c -O3  EmonLog.cc
 
 clean:
 	rm -f *.o ../StackedIt ../StackedIt.exe
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mntmem ./tools/mntmem
--- ../Tekkotsu_2.4.1/tools/mntmem	2003-04-29 17:03:09.000000000 -0400
+++ ./tools/mntmem	2006-03-28 19:48:05.000000000 -0500
@@ -1,12 +1,25 @@
 #!/bin/sh
 
-pt="/mnt/memstick";
+default_pt=false;
 if [ $# -gt 0 ] ; then
 	pt="$1";
+elif [ "$MEMSTICK_ROOT" ] ; then
+	pt="$MEMSTICK_ROOT";
+else
+	default_pt=true;
+	case "`uname`" in
+		CYGWIN*) pt="/cygdrive/e";;
+		Darwin) d="`dirname $0`"; pt="`$d/osx_find_memstick`";;
+		*) pt="/mnt/memstick";;
+	esac
 fi;
 
 case "`uname`" in
-	CYGWIN*|Darwin)
+	Darwin)
+		#osx_find_memstick shouldn't have returned until it was mounted
+		exit 0;
+		;;
+	CYGWIN*)
 		until [ -d "$pt" ] ; do
 			printf "\\a";
 			sleep 1;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/ERS-210.lws ./tools/mon/ERS-210.lws
--- ../Tekkotsu_2.4.1/tools/mon/ERS-210.lws	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/ERS-210.lws	2006-07-25 14:46:10.000000000 -0400
@@ -0,0 +1,386 @@
+LWSC
+1
+
+FirstFrame 1
+LastFrame 60
+FrameStep 1
+PreviewFirstFrame 1
+PreviewLastFrame 60
+PreviewFrameStep 1
+FramesPerSecond 30.000000
+
+LoadObject objects-ERS-210/body2.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0.177 0.014 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ShadowOptions 7
+
+LoadObject objects-ERS-210/tail2.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0.05715 0.08279999 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-210/neck.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0.0627 -0.10004999 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-210/head.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0.02689999 -0.0004500076 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 3
+ShadowOptions 7
+
+LoadObject objects-ERS-210/jaw.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 -0.00475 -0.02945 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 4
+ShadowOptions 7
+
+LoadObject objects-ERS-210/ear-l.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0.02704999 0.06610002 0.006099998 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 6
+ParentObject 4
+ShadowOptions 7
+
+LoadObject objects-ERS-210/ear-r.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  -0.02705 0.06610002 0.006149998 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 7
+ParentObject 4
+ShadowOptions 7
+
+LoadObject objects-ERS-210/leg-b-up-l.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0.07045 0.0033 0.06394999 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 6
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-210/leg-b-low-l.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  -0.001850001 -0.09015001 0.0225 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 6
+ParentObject 8
+ShadowOptions 7
+
+LoadObject objects-ERS-210/foot-b-l.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 -0.07345001 0.02495 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 1
+ParentObject 9
+ShadowOptions 7
+
+LoadObject objects-ERS-210/leg-b-up-r.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  -0.07064998 0.003349999 0.06394999 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 6
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-210/leg-b-low-r.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0.00205 -0.09019998 0.0225 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 6
+ParentObject 11
+ShadowOptions 7
+
+LoadObject objects-ERS-210/foot-b-r.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 -0.0735 0.025 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 1
+ParentObject 12
+ShadowOptions 7
+
+LoadObject objects-ERS-210/leg-f-up-l.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0.07045001 -0.0007499999 -0.07510001 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 6
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-210/leg-f-low-l.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  -0.00165 -0.09469999 -0.01165 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 6
+ParentObject 14
+ShadowOptions 7
+
+LoadObject objects-ERS-210/foot-f-l.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 -0.06485 -0.02929999 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 1
+ParentObject 15
+ShadowOptions 7
+
+LoadObject objects-ERS-210/leg-f-up-r.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  -0.07044999 -0.0006499998 -0.07515001 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 6
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-210/leg-f-low-r.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0.00105 -0.0948 -0.0116 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 6
+ParentObject 17
+ShadowOptions 7
+
+LoadObject objects-ERS-210/foot-f-r.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 -0.0649 -0.0293 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 1
+ParentObject 18
+ShadowOptions 7
+
+LoadObject objects-ERS-210/LED_g01.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 4
+ShadowOptions 7
+
+LoadObject objects-ERS-210/LED_g02.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 4
+ShadowOptions 7
+
+LoadObject objects-ERS-210/LED_g03.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 4
+ShadowOptions 7
+
+LoadObject objects-ERS-210/LED_r01.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 4
+ShadowOptions 7
+
+LoadObject objects-ERS-210/LED_r02.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 4
+ShadowOptions 7
+
+LoadObject objects-ERS-210/LED_r03.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 4
+ShadowOptions 7
+
+LoadObject objects-ERS-210/LED_r04.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 4
+ShadowOptions 7
+
+LoadObject objects-ERS-210/LED_tail.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 2
+ShadowOptions 7
+
+AmbientColor 255 255 255
+AmbIntensity 0.50000
+
+AddLight
+LightName Light
+ShowLight 1 7
+LightMotion (unnamed)
+  9
+  1
+  -2 2 -2 45 35 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LightColor 255 255 255
+LgtIntensity 0.700000
+LightType 0
+ShadowType 1
+
+ShowCamera 1 7
+CameraMotion (unnamed)
+  9
+  1
+  -0.6381658 0.5205013 -0.6771318 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+TargetObject 1
+ZoomFactor 3.200000
+Resolution 1
+PixelAspectRatio 2
+SegmentMemory 2200000
+Antialiasing 0
+AdaptiveSampling 1
+AdaptiveThreshold 16
+FilmSize 2
+FieldRendering 0
+MotionBlur 0
+DepthOfField 0
+
+SolidBackdrop 1
+BackdropColor 80 80 180 
+ZenithColor 0 40 80
+SkyColor 120 180 240
+GroundColor 50 40 30
+NadirColor 100 80 60
+FogType 0
+DitherIntensity 1
+AnimatedDither 0
+
+RenderMode 2
+RayTraceEffects 0
+ClipRayColors 0
+DataOverlayLabel  
+FullSceneParamEval 0
+
+ViewMode 5
+ViewAimpoint -0.006362 0.165064 -0.119767
+ViewDirection 0.300197 -0.314159 0.000000
+ViewZoomFactor 0.526749
+GridNumber 40
+GridSize 0.010000
+ShowMotionPath 1
+ShowBGImage 0
+ShowFogRadius 0
+ShowRedraw 0
+ShowSafeAreas 0
+ShowFieldChart 0
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/ERS-7.lws ./tools/mon/ERS-7.lws
--- ../Tekkotsu_2.4.1/tools/mon/ERS-7.lws	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/ERS-7.lws	2006-08-02 17:15:50.000000000 -0400
@@ -0,0 +1,486 @@
+LWSC
+1
+
+FirstFrame 1
+LastFrame 60
+FrameStep 1
+PreviewFirstFrame 1
+PreviewLastFrame 60
+PreviewFrameStep 1
+FramesPerSecond 30.000000
+
+LoadObject objects-ERS-7/body01.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 5
+ShadowOptions 7
+
+LoadObject objects-ERS-7/body02.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-7/body03.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-7/body04.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-7/body05.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-7/body06.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-7/neck.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0.0195 -0.06749999 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 40
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-7/head01.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0.08 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 45
+ParentObject 7
+ShadowOptions 7
+
+LoadObject objects-ERS-7/head02.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 8
+ShadowOptions 7
+
+LoadObject objects-ERS-7/head03.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 8
+ShadowOptions 7
+
+LoadObject objects-ERS-7/head04.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 8
+ShadowOptions 7
+
+LoadObject objects-ERS-7/head05.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 8
+ShadowOptions 7
+
+LoadObject objects-ERS-7/head06.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 8
+ShadowOptions 7
+
+LoadObject objects-ERS-7/tail01.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0.033 0.102 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 8
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-7/tail02.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 14
+ShadowOptions 7
+
+LoadObject objects-ERS-7/LforefootA.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 -0.06500001 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 43
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-7/LforefootB.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0.0625 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 30
+ParentObject 16
+ShadowOptions 7
+
+LoadObject objects-ERS-7/LforefootC.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0.0047 -0.0695 -0.009 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 46
+ParentObject 17
+ShadowOptions 7
+
+LoadObject objects-ERS-7/LforefootD.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 18
+ShadowOptions 7
+
+LoadObject objects-ERS-7/RforefootA.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 -0.06500001 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 43
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-7/RforefootB.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  -0.06249997 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 30
+ParentObject 20
+ShadowOptions 7
+
+LoadObject objects-ERS-7/RforefootC.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  -0.0047 -0.0695 -0.009 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 41
+ParentObject 21
+ShadowOptions 7
+
+LoadObject objects-ERS-7/RforefootD.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 22
+ShadowOptions 7
+
+LoadObject objects-ERS-7/LhindfootA.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0.065 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 43
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-7/LhindfootB.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0.0625 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 24
+ParentObject 24
+ShadowOptions 7
+
+LoadObject objects-ERS-7/LhindfootC.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0.0047 -0.0695 0.009 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 41
+ParentObject 25
+ShadowOptions 7
+
+LoadObject objects-ERS-7/LhindfootD.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 26
+ShadowOptions 7
+
+LoadObject objects-ERS-7/RhindfootA.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0.065 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 43
+ParentObject 1
+ShadowOptions 7
+
+LoadObject objects-ERS-7/RhindfootB.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  -0.0625 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 24
+ParentObject 28
+ShadowOptions 7
+
+LoadObject objects-ERS-7/RhindfootC.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  -0.0047 -0.0695 0.009 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 41
+ParentObject 29
+ShadowOptions 7
+
+LoadObject objects-ERS-7/RhindfootD.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 30
+ShadowOptions 7
+
+LoadObject objects-ERS-7/chops.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 -0.0175 -0.04 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 40
+ParentObject 8
+ShadowOptions 7
+
+LoadObject objects-ERS-7/Lear01.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0.042 0.0145 0.011 0 0 10 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LockedChannels 11
+ParentObject 8
+ShadowOptions 7
+
+LoadObject objects-ERS-7/Lear02.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 33
+ShadowOptions 7
+
+LoadObject objects-ERS-7/Rear01.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  -0.042 0.0145 0.011 0 0 -10 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 8
+ShadowOptions 7
+
+LoadObject objects-ERS-7/Rear02.lwo
+ShowObject 8 7
+ObjectMotion (unnamed)
+  9
+  1
+  0 0 0 0 0 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ParentObject 35
+ShadowOptions 7
+
+AmbientColor 255 255 255
+AmbIntensity 0.250000
+
+AddLight
+LightName Light
+ShowLight 1 7
+LightMotion (unnamed)
+  9
+  1
+  -2 2 -2 45 35 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+LightColor 255 255 255
+LgtIntensity 1.000000
+LightType 0
+ShadowType 1
+
+ShowCamera 1 7
+CameraMotion (unnamed)
+  9
+  1
+  -0.5484055 0.145 -0.2908995 64.79997 14.8 0 1 1 1
+  0 0 0 0 0
+EndBehavior 1
+ZoomFactor 3.200000
+Resolution 1
+PixelAspectRatio 2
+SegmentMemory 2200000
+Antialiasing 2
+AdaptiveSampling 1
+AdaptiveThreshold 16
+FilmSize 2
+FieldRendering 0
+MotionBlur 0
+DepthOfField 0
+
+SolidBackdrop 1
+BackdropColor 80 80 180
+ZenithColor 0 40 80
+SkyColor 120 180 240
+GroundColor 50 40 30
+NadirColor 100 80 60
+FogType 0
+DitherIntensity 1
+AnimatedDither 0
+
+RenderMode 2
+RayTraceEffects 0
+DataOverlayLabel  
+
+ViewMode 5
+ViewAimpoint 0.017500 0.092000 -0.008500
+ViewDirection -7.611368 -0.191986 0.000000
+ViewZoomFactor 6.000000
+GridNumber 10
+GridSize 0.100000
+ShowMotionPath 1
+ShowBGImage 0
+ShowFogRadius 0
+ShowRedraw 0
+ShowSafeAreas 0
+ShowFieldChart 0
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/Makefile ./tools/mon/Makefile
--- ../Tekkotsu_2.4.1/tools/mon/Makefile	2005-08-16 16:48:15.000000000 -0400
+++ ./tools/mon/Makefile	2006-08-23 15:13:27.000000000 -0400
@@ -7,12 +7,15 @@
 
 OBJS:=${SRCS:.java=.class}
 
-CXX=javac
+JAVAC?=javac
 CURDIR:=$(shell pwd | sed 's/.*\///')
+PROJECT_BUILDDIR?=/tmp
+USER?=$(if $(USERNAME),$(USERNAME),$(shell whoami))
+BUILDLIST:=$(PROJECT_BUILDDIR)/$(CURDIR)_$(USER)_buildlist.txt
 
 # SEP is to use ';' on windows and ':' on unix because windows is mentally deficient
 SEP:=$(shell if [ "`uname`" = "CYGWIN" -o "`uname`" \> "CYGWIN" -a "`uname`" \< "CYGWIO" ] ; then echo ";" ; else echo ":" ; fi )
-CXXFLAGS=-deprecation -classpath ".$(SEP)./ftp.jar$(SEP)./jargs.jar" 
+JAVACFLAGS=-deprecation -classpath ".$(SEP)./ftp.jar$(SEP)./jargs.jar" 
 
 .PHONY: all clean build clearbuildlist test
 
@@ -20,20 +23,23 @@
 
 org/tekkotsu/aibo3d/%.class: org/tekkotsu/aibo3d/%.java
 	@if [ $(AIBO3D) -eq 0 ] ; then \
-		printf " $<" >> tmp_buildList.txt; \
+		printf " $<" >> "$(BUILDLIST)"; \
+		chown $(USER) "$(BUILDLIST)"; \
 	fi;
 
 %.class: %.java
-	@printf " $<" >> tmp_buildList.txt;
+	@printf " $<" >> "$(BUILDLIST)";
+	@chown $(USER) "$(BUILDLIST)";
 
 clearbuildlist:
-	@rm -f tmp_buildList.txt;
+	@rm -f "$(BUILDLIST)";
+
+"$(BUILDLIST)": ${OBJS} ;
 
-tmp_buildList.txt: ${OBJS}
 #	@echo "Build list constructed...";
 
-build: tmp_buildList.txt
-	@if [ -r tmp_buildList.txt ] ; then \
+build: "$(BUILDLIST)"
+	@if [ -r "$(BUILDLIST)" ] ; then \
 		cat README; \
 		if [ $(AIBO3D) -ne 0 ] ; then \
 			echo " *************************************************************************"; \
@@ -43,21 +49,22 @@
 		else \
 			echo " **     (Using cached Java3D status - make clean to clear cache)        **"; \
 		fi;	\
-		$(if $(shell which $(CXX)), \
-			if [ `cat tmp_buildList.txt | wc -c` -gt 400 ] ; then \
+		$(if $(shell which $(JAVAC)), \
+			if [ `cat "$(BUILDLIST)" | wc -c` -gt 400 ] ; then \
 				list=' [...]'; \
 			else \
-				list="`cat tmp_buildList.txt`"; \
+				list="`cat \"$(BUILDLIST)\"`"; \
 			fi; \
-			echo "Compiling$$list ..."; $(CXX) $(CXXFLAGS) `cat tmp_buildList.txt`; , \
-			printf "  ***** WARNING: You don't have java... skipping TekkotsuMon *****\n"; \
+			echo "Compiling$$list ..."; $(JAVAC) $(JAVACFLAGS) `cat "$(BUILDLIST)"` || exit 1; , \
+			printf "  ***** WARNING: You don't have Java SDK... skipping TekkotsuMon *****\n"; \
 		) \
+		rm -f "$(BUILDLIST)"; \
 	else \
 		echo "TekkotsuMon: Nothing to be done."; \
 	fi;
 
 clean:
-	rm -f tmp_buildList.txt "$(AIBO3DCACHE)"
+	rm -f "$(BUILDLIST)" "$(AIBO3DCACHE)"
 	find . -name "*.class" -exec rm \{\} \;
 	find . -name "*~" -exec rm \{\} \;
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/README ./tools/mon/README
--- ../Tekkotsu_2.4.1/tools/mon/README	2003-07-25 16:02:48.000000000 -0400
+++ ./tools/mon/README	2006-07-02 14:50:56.000000000 -0400
@@ -1,3 +1,3 @@
- **     These tools require the JDK 1.4 or higher.  These files         **
+ **     These tools require the JDK 1.5/5.0 or higher.  These files     **
  **     are _not_ necessary for development.  If errors occur, you      **
  **     can remove the tools/mon/Makefile and continue without it.      **
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/SketchGUI ./tools/mon/SketchGUI
--- ../Tekkotsu_2.4.1/tools/mon/SketchGUI	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/SketchGUI	2006-02-20 23:16:10.000000000 -0500
@@ -0,0 +1,50 @@
+#!/bin/sh
+
+cd "`dirname \"$0\"`"
+if [ ! -r org/tekkotsu/sketch/SketchGUI.java ] ; then
+	echo "Cannot access org/tekkotsu/sketch/SketchGUI.java"
+	echo "Make sure this script is located at the root of the java package tree"
+	echo "(i.e. Tekkotsu/tools/mon)"
+	exit 1;
+fi;
+
+if [ ! -r org/tekkotsu/sketch/SketchGUI.class ] ; then
+	echo "Cannot access Java executable."
+	echo "Perhaps the tools need to be compiled.  Go to the Tekkotsu/tools"
+	echo "directory and type 'make'"
+	exit 1;
+fi;
+
+if [ $# -eq 0 -o $# -gt 2 ] ; then
+	echo Usage: $0 hostname [cam/local/world]
+	exit 1;
+fi;
+
+# make sure second argument is one of cam/local/world
+if [ $# -eq 1 ] ; then
+  viewspace="cam"
+else
+  viewspace="$2"
+fi;
+if [ ! "$viewspace" == "cam" -a  ! "$viewspace" == "local" -a  ! "$viewspace" == "world" ] ; then
+      echo Usage: $0 hostname [cam/local/world]
+      exit 1;
+fi;
+
+if uname | grep -iq cygwin ; then
+    # cygwin: don't know how to open a new command window, so run SketchGUI here
+    java -Xmx256M org.tekkotsu.sketch.SketchGUI $*
+elif uname | grep -iq darwin ; then
+    # MacOS: run in a new Terminal window
+    # The 'exit' in the script below closes the window after the command 
+    # completes (otherwise it would stay open).
+    osascript - << EOF
+    tell application "Terminal"
+        do script "cd `pwd`; java -Xmx256M org.tekkotsu.sketch.SketchGUI $1 $viewspace; sleep 5; exit"
+    end tell
+EOF
+else
+    # Linux: run in a new xterm
+    xterm -e "java -Xmx256M org.tekkotsu.sketch.SketchGUI $1 $viewspace" &
+fi;
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/aibo3d.lws ./tools/mon/aibo3d.lws
--- ../Tekkotsu_2.4.1/tools/mon/aibo3d.lws	2003-08-26 22:52:02.000000000 -0400
+++ ./tools/mon/aibo3d.lws	1969-12-31 19:00:00.000000000 -0500
@@ -1,386 +0,0 @@
-LWSC
-1
-
-FirstFrame 1
-LastFrame 60
-FrameStep 1
-PreviewFirstFrame 1
-PreviewLastFrame 60
-PreviewFrameStep 1
-FramesPerSecond 30.000000
-
-LoadObject objects/body2.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 0.177 0.014 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ShadowOptions 7
-
-LoadObject objects/tail2.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 0.05715 0.08279999 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ParentObject 1
-ShadowOptions 7
-
-LoadObject objects/neck.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 0.0627 -0.10004999 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ParentObject 1
-ShadowOptions 7
-
-LoadObject objects/head.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 0.02689999 -0.0004500076 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ParentObject 3
-ShadowOptions 7
-
-LoadObject objects/jaw.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 -0.00475 -0.02945 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ParentObject 4
-ShadowOptions 7
-
-LoadObject objects/ear-l.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0.02704999 0.06610002 0.006099998 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 6
-ParentObject 4
-ShadowOptions 7
-
-LoadObject objects/ear-r.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  -0.02705 0.06610002 0.006149998 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 7
-ParentObject 4
-ShadowOptions 7
-
-LoadObject objects/leg-b-up-l.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0.07045 0.0033 0.06394999 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 6
-ParentObject 1
-ShadowOptions 7
-
-LoadObject objects/leg-b-low-l.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  -0.001850001 -0.09015001 0.0225 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 6
-ParentObject 8
-ShadowOptions 7
-
-LoadObject objects/foot-b-l.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 -0.07345001 0.02495 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 1
-ParentObject 9
-ShadowOptions 7
-
-LoadObject objects/leg-b-up-r.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  -0.07064998 0.003349999 0.06394999 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 6
-ParentObject 1
-ShadowOptions 7
-
-LoadObject objects/leg-b-low-r.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0.00205 -0.09019998 0.0225 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 6
-ParentObject 11
-ShadowOptions 7
-
-LoadObject objects/foot-b-r.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 -0.0735 0.025 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 1
-ParentObject 12
-ShadowOptions 7
-
-LoadObject objects/leg-f-up-l.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0.07045001 -0.0007499999 -0.07510001 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 6
-ParentObject 1
-ShadowOptions 7
-
-LoadObject objects/leg-f-low-l.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  -0.00165 -0.09469999 -0.01165 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 6
-ParentObject 14
-ShadowOptions 7
-
-LoadObject objects/foot-f-l.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 -0.06485 -0.02929999 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 1
-ParentObject 15
-ShadowOptions 7
-
-LoadObject objects/leg-f-up-r.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  -0.07044999 -0.0006499998 -0.07515001 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 6
-ParentObject 1
-ShadowOptions 7
-
-LoadObject objects/leg-f-low-r.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0.00105 -0.0948 -0.0116 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 6
-ParentObject 17
-ShadowOptions 7
-
-LoadObject objects/foot-f-r.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 -0.0649 -0.0293 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LockedChannels 1
-ParentObject 18
-ShadowOptions 7
-
-LoadObject objects/LED_g01.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 0 0 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ParentObject 4
-ShadowOptions 7
-
-LoadObject objects/LED_g02.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 0 0 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ParentObject 4
-ShadowOptions 7
-
-LoadObject objects/LED_g03.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 0 0 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ParentObject 4
-ShadowOptions 7
-
-LoadObject objects/LED_r01.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 0 0 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ParentObject 4
-ShadowOptions 7
-
-LoadObject objects/LED_r02.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 0 0 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ParentObject 4
-ShadowOptions 7
-
-LoadObject objects/LED_r03.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 0 0 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ParentObject 4
-ShadowOptions 7
-
-LoadObject objects/LED_r04.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 0 0 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ParentObject 4
-ShadowOptions 7
-
-LoadObject objects/LED_tail.lwo
-ShowObject 8 7
-ObjectMotion (unnamed)
-  9
-  1
-  0 0 0 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-ParentObject 2
-ShadowOptions 7
-
-AmbientColor 255 255 255
-AmbIntensity 0.50000
-
-AddLight
-LightName Light
-ShowLight 1 7
-LightMotion (unnamed)
-  9
-  1
-  -2 2 -2 45 35 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-LightColor 255 255 255
-LgtIntensity 0.700000
-LightType 0
-ShadowType 1
-
-ShowCamera 1 7
-CameraMotion (unnamed)
-  9
-  1
-  -0.6381658 0.5205013 -0.6771318 0 0 0 1 1 1
-  0 0 0 0 0
-EndBehavior 1
-TargetObject 1
-ZoomFactor 3.200000
-Resolution 1
-PixelAspectRatio 2
-SegmentMemory 2200000
-Antialiasing 0
-AdaptiveSampling 1
-AdaptiveThreshold 16
-FilmSize 2
-FieldRendering 0
-MotionBlur 0
-DepthOfField 0
-
-SolidBackdrop 1
-BackdropColor 80 80 180 
-ZenithColor 0 40 80
-SkyColor 120 180 240
-GroundColor 50 40 30
-NadirColor 100 80 60
-FogType 0
-DitherIntensity 1
-AnimatedDither 0
-
-RenderMode 2
-RayTraceEffects 0
-ClipRayColors 0
-DataOverlayLabel  
-FullSceneParamEval 0
-
-ViewMode 5
-ViewAimpoint -0.006362 0.165064 -0.119767
-ViewDirection 0.300197 -0.314159 0.000000
-ViewZoomFactor 0.526749
-GridNumber 40
-GridSize 0.010000
-ShowMotionPath 1
-ShowBGImage 0
-ShowFogRadius 0
-ShowRedraw 0
-ShowSafeAreas 0
-ShowFieldChart 0
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/LED_g01.lwo and ./tools/mon/objects/LED_g01.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/LED_g02.lwo and ./tools/mon/objects/LED_g02.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/LED_g03.lwo and ./tools/mon/objects/LED_g03.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/LED_r01.lwo and ./tools/mon/objects/LED_r01.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/LED_r02.lwo and ./tools/mon/objects/LED_r02.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/LED_r03.lwo and ./tools/mon/objects/LED_r03.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/LED_r04.lwo and ./tools/mon/objects/LED_r04.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/LED_tail.lwo and ./tools/mon/objects/LED_tail.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/body2.lwo and ./tools/mon/objects/body2.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/ear-l.lwo and ./tools/mon/objects/ear-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/ear-r.lwo and ./tools/mon/objects/ear-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/foot-b-l.lwo and ./tools/mon/objects/foot-b-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/foot-b-r.lwo and ./tools/mon/objects/foot-b-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/foot-f-l.lwo and ./tools/mon/objects/foot-f-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/foot-f-r.lwo and ./tools/mon/objects/foot-f-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/head.lwo and ./tools/mon/objects/head.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/jaw.lwo and ./tools/mon/objects/jaw.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/leg-b-low-l.lwo and ./tools/mon/objects/leg-b-low-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/leg-b-low-r.lwo and ./tools/mon/objects/leg-b-low-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/leg-b-up-l.lwo and ./tools/mon/objects/leg-b-up-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/leg-b-up-r.lwo and ./tools/mon/objects/leg-b-up-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/leg-f-low-l.lwo and ./tools/mon/objects/leg-f-low-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/leg-f-low-r.lwo and ./tools/mon/objects/leg-f-low-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/leg-f-up-l.lwo and ./tools/mon/objects/leg-f-up-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/leg-f-up-r.lwo and ./tools/mon/objects/leg-f-up-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/neck.lwo and ./tools/mon/objects/neck.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects/tail2.lwo and ./tools/mon/objects/tail2.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/LED_g01.lwo and ./tools/mon/objects-ERS-210/LED_g01.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/LED_g02.lwo and ./tools/mon/objects-ERS-210/LED_g02.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/LED_g03.lwo and ./tools/mon/objects-ERS-210/LED_g03.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/LED_r01.lwo and ./tools/mon/objects-ERS-210/LED_r01.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/LED_r02.lwo and ./tools/mon/objects-ERS-210/LED_r02.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/LED_r03.lwo and ./tools/mon/objects-ERS-210/LED_r03.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/LED_r04.lwo and ./tools/mon/objects-ERS-210/LED_r04.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/LED_tail.lwo and ./tools/mon/objects-ERS-210/LED_tail.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/body2.lwo and ./tools/mon/objects-ERS-210/body2.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/ear-l.lwo and ./tools/mon/objects-ERS-210/ear-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/ear-r.lwo and ./tools/mon/objects-ERS-210/ear-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/foot-b-l.lwo and ./tools/mon/objects-ERS-210/foot-b-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/foot-b-r.lwo and ./tools/mon/objects-ERS-210/foot-b-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/foot-f-l.lwo and ./tools/mon/objects-ERS-210/foot-f-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/foot-f-r.lwo and ./tools/mon/objects-ERS-210/foot-f-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/head.lwo and ./tools/mon/objects-ERS-210/head.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/jaw.lwo and ./tools/mon/objects-ERS-210/jaw.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/leg-b-low-l.lwo and ./tools/mon/objects-ERS-210/leg-b-low-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/leg-b-low-r.lwo and ./tools/mon/objects-ERS-210/leg-b-low-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/leg-b-up-l.lwo and ./tools/mon/objects-ERS-210/leg-b-up-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/leg-b-up-r.lwo and ./tools/mon/objects-ERS-210/leg-b-up-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/leg-f-low-l.lwo and ./tools/mon/objects-ERS-210/leg-f-low-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/leg-f-low-r.lwo and ./tools/mon/objects-ERS-210/leg-f-low-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/leg-f-up-l.lwo and ./tools/mon/objects-ERS-210/leg-f-up-l.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/leg-f-up-r.lwo and ./tools/mon/objects-ERS-210/leg-f-up-r.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/neck.lwo and ./tools/mon/objects-ERS-210/neck.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-210/tail2.lwo and ./tools/mon/objects-ERS-210/tail2.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/Lear01.lwo and ./tools/mon/objects-ERS-7/Lear01.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/Lear02.lwo and ./tools/mon/objects-ERS-7/Lear02.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/LforefootA.lwo and ./tools/mon/objects-ERS-7/LforefootA.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/LforefootB.lwo and ./tools/mon/objects-ERS-7/LforefootB.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/LforefootC.lwo and ./tools/mon/objects-ERS-7/LforefootC.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/LforefootD.lwo and ./tools/mon/objects-ERS-7/LforefootD.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/LhindfootA.lwo and ./tools/mon/objects-ERS-7/LhindfootA.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/LhindfootB.lwo and ./tools/mon/objects-ERS-7/LhindfootB.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/LhindfootC.lwo and ./tools/mon/objects-ERS-7/LhindfootC.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/LhindfootD.lwo and ./tools/mon/objects-ERS-7/LhindfootD.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/Rear01.lwo and ./tools/mon/objects-ERS-7/Rear01.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/Rear02.lwo and ./tools/mon/objects-ERS-7/Rear02.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/RforefootA.lwo and ./tools/mon/objects-ERS-7/RforefootA.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/RforefootB.lwo and ./tools/mon/objects-ERS-7/RforefootB.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/RforefootC.lwo and ./tools/mon/objects-ERS-7/RforefootC.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/RforefootD.lwo and ./tools/mon/objects-ERS-7/RforefootD.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/RhindfootA.lwo and ./tools/mon/objects-ERS-7/RhindfootA.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/RhindfootB.lwo and ./tools/mon/objects-ERS-7/RhindfootB.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/RhindfootC.lwo and ./tools/mon/objects-ERS-7/RhindfootC.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/RhindfootD.lwo and ./tools/mon/objects-ERS-7/RhindfootD.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/body01.lwo and ./tools/mon/objects-ERS-7/body01.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/body02.lwo and ./tools/mon/objects-ERS-7/body02.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/body03.lwo and ./tools/mon/objects-ERS-7/body03.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/body04.lwo and ./tools/mon/objects-ERS-7/body04.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/body05.lwo and ./tools/mon/objects-ERS-7/body05.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/body06.lwo and ./tools/mon/objects-ERS-7/body06.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/chops.lwo and ./tools/mon/objects-ERS-7/chops.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/head01.lwo and ./tools/mon/objects-ERS-7/head01.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/head02.lwo and ./tools/mon/objects-ERS-7/head02.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/head03.lwo and ./tools/mon/objects-ERS-7/head03.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/head04.lwo and ./tools/mon/objects-ERS-7/head04.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/head05.lwo and ./tools/mon/objects-ERS-7/head05.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/head06.lwo and ./tools/mon/objects-ERS-7/head06.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/neck.lwo and ./tools/mon/objects-ERS-7/neck.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/tail01.lwo and ./tools/mon/objects-ERS-7/tail01.lwo differ
Binary files ../Tekkotsu_2.4.1/tools/mon/objects-ERS-7/tail02.lwo and ./tools/mon/objects-ERS-7/tail02.lwo differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/aibo3d/Aibo3D.java ./tools/mon/org/tekkotsu/aibo3d/Aibo3D.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/aibo3d/Aibo3D.java	2003-10-09 15:11:26.000000000 -0400
+++ ./tools/mon/org/tekkotsu/aibo3d/Aibo3D.java	2006-09-09 19:27:44.000000000 -0400
@@ -1,6 +1,7 @@
 package org.tekkotsu.aibo3d;
 
 import java.awt.*;
+import javax.swing.*;
 import java.awt.event.*;
 import javax.media.j3d.*;
 import java.io.*;
@@ -19,153 +20,343 @@
 import com.sun.j3d.utils.picking.*;
 
 import org.tekkotsu.mon.Joints;
+import org.tekkotsu.mon.Listener;
 import org.tekkotsu.mon.WorldStateJointsListener;
 
-public class Aibo3D extends Frame {
-  static Preferences prefs = Preferences.userNodeForPackage(Aibo3D.class);
-  Scene scene;
-  Canvas3D canvas3d;
-  Aibo3DForward forward;
-  WorldStateJointsListener wsj;
-
-  public static void main(String args[]) {
+public class Aibo3D extends JFrame implements Listener.ConnectionListener, WorldStateJointsListener.UpdatedListener {
+	static Preferences prefs = Preferences.userNodeForPackage(Aibo3D.class);
+	Scene scene;
+	Canvas3D canvas3d;
+	SimpleUniverse universe;
+	BranchGroup rootgroup;
+	Aibo3DForward forward;
+	WorldStateJointsListener wsj;
+	TransformGroup viewpoint;
+	boolean firstUpdate;
+	JLabel disconnectMsg; 
+	String model;
+	
+	public static void main(String args[]) {
 		if(args.length<1) {
 			System.out.println("Usage: java Aibo3D host [port]");
 			System.out.println("       if port is not specified, it defaults to 10031");
 			System.exit(2);
 		}
-		int port=10031;
+		int port=WorldStateJointsListener.defPort;
 		if(args.length>1)
 			port=Integer.parseInt(args[1]);
-    new Aibo3D(args[0],port,null);
-  }
-
-  public Aibo3D(String host, int port, String args[]) {
-    super("Aibo 3D");
-    setSize(500,500);
-    setLocation(prefs.getInt("Aibo3D.location.x",50), prefs.getInt("Aibo3D.location.y",50));
-
-    setup3DCanvas();
-    loadLW3D("aibo3d.lws");
-    forward=new Aibo3DForward(scene);
-    showScene();
-  
-    wsj=new WorldStateJointsListener(host,port);
-    while (true) {
-      if (wsj.isConnected()) {
-        if (wsj.hasData()) {
-          Joints j=wsj.getData();
-          float[] p=j.positions;
-          forward.knee_fl.setX(-p[2]);
-          forward.thigh_fl.set(-p[0],0.0f,p[1]);
-          forward.knee_fr.setX(-p[5]);
-          forward.thigh_fr.set(-p[3],0.0f,-p[4]);
-          forward.knee_bl.setX(p[8]);
-          forward.thigh_bl.set(p[6],0.0f,p[7]);
-          forward.knee_br.setX(p[11]);
-          forward.thigh_br.set(p[9],0.0f,-p[10]);
-          forward.neck.setX(-p[12]);
-          forward.head.set(0.0f,p[13],p[14]);
-          forward.tail.set(p[15],p[16],0.0f);
-          forward.jaw.setX(-p[17]);
-        }
-      }
-      sleep(10);
-    }
-  
-//    testLimits(forward.thigh_bl,50);
-  }
+		new Aibo3D(args[0],port,null);
+	}
+	
+	public Aibo3D(String host, int port, String args[]) {
+		super("Aibo 3D");
+		getContentPane().setLayout(new BorderLayout());
+		setSize(prefs.getInt("Aibo3D.size.width",500),prefs.getInt("Aibo3D.size.height",500));
+		setLocation(prefs.getInt("Aibo3D.location.x",50), prefs.getInt("Aibo3D.location.y",50));
+		
+		disconnectMsg=new JLabel("Disconnected. trying to reconnect...",SwingConstants.CENTER);
+		add(disconnectMsg,BorderLayout.CENTER);
+		addWindowListener(new WindowAdapter() { // cleans up properly
+			public void windowClosing(WindowEvent e) {
+				close();
+			}
+		});
+		
+		wsj=WorldStateJointsListener.getCommonInstance(host,port);
+		firstUpdate=true;
+		wsj.addConnectionListener(this);
+		wsj.addUpdatedListener(this);
+		
+		setVisible(true);
+		
+		/*
+		BufferedReader in = new BufferedReader(new InputStreamReader(System.in));
+		String lastS="";
+		ArrayList lastC=null;
+		while(true) {
+			try {
+				String s=in.readLine();
+				if(model!=null) {
+					if(lastC!=null)
+						highlight(lastS,lastC);
+					lastC=highlight(s,new Color3f(1,0,0));
+					lastS=s;
+				}
+			} catch(Exception e) {
+				e.printStackTrace();
+				break;
+			}
+		}
+		 */
+		
+		//    testLimits(forward.thigh_bl,50);
+	}
+	
+	void highlight(String s, ArrayList c) {
+		TransformGroup tg=forward.getTG("objects-"+model+"/"+s+".lwo");
+		if(tg==null) {
+			System.out.println("invalid: "+s);
+			return;
+		}
+		for(Enumeration e=tg.getAllChildren(); e.hasMoreElements();) {
+			Node n=(Node)e.nextElement();
+			if(n instanceof TransformGroup) {
+				//flipNormals((TransformGroup)n); // don't recurse
+			} else {
+				if(n instanceof Shape3D) {
+					Appearance app=((Shape3D)n).getAppearance();
+					app.getMaterial().setDiffuseColor((Color3f)c.get(0));
+					c.remove(0);
+				} else {
+					System.out.println("unhandled in flip: "+n.getClass());
+				}
+			}
+		}
+	}
+	ArrayList highlight(String s, Color3f c) {
+		TransformGroup tg=forward.getTG("objects-"+model+"/"+s+".lwo");
+		if(tg==null) {
+			System.out.println("invalid: "+s);
+			return null;
+		}
+		ArrayList l=new ArrayList();
+		for(Enumeration e=tg.getAllChildren(); e.hasMoreElements();) {
+			Node n=(Node)e.nextElement();
+			if(n instanceof TransformGroup) {
+				//flipNormals((TransformGroup)n); // don't recurse
+			} else {
+				if(n instanceof Shape3D) {
+					Appearance app=((Shape3D)n).getAppearance();
+					Color3f ans=new Color3f();
+					app.getMaterial().getDiffuseColor(ans);
+					l.add(ans);
+					app.getMaterial().setDiffuseColor(1.f,0,0);
+				} else {
+					System.out.println("unhandled in flip: "+n.getClass());
+				}
+			}
+		}
+		return l;
+	}
 
-	void close() {
-    prefs.putInt("Aibo3D.location.x",getLocation().x+getInsets().left);
-    prefs.putInt("Aibo3D.location.y",getLocation().y+getInsets().top);
+	public void onConnected() {
+		firstUpdate=true;
+	}
+	public void onDisconnected() {
+		firstUpdate=true;
+		getContentPane().removeAll();
+		add(disconnectMsg,BorderLayout.CENTER);
+		((JComponent)getContentPane()).revalidate();
+		model=null;
+	}
+	
+	public void worldStateUpdated(WorldStateJointsListener mc) {
+		Joints j=wsj.getData();
+		if(firstUpdate) {
+			getContentPane().removeAll();
+			firstUpdate=false;
+			setup3DCanvas();
+			loadLW3D(j.model+".lws");
+			model=j.model;
+			forward=new Aibo3DForward(model,scene);
+			createSceneGraph(scene);
+			((JComponent)getContentPane()).revalidate();
+			canvas3d.getView().setFrontClipDistance(0.025);
+			recursivePrintGroup(scene);
+		}
+		float[] p=j.positions;
+		forward.knee_fl.setX(-p[2]);
+		forward.thigh_fl.set(-p[0],0.0f,p[1]);
+		forward.knee_fr.setX(-p[5]);
+		forward.thigh_fr.set(-p[3],0.0f,-p[4]);
+		forward.knee_bl.setX(p[8]);
+		forward.thigh_bl.set(p[6],0.0f,p[7]);
+		forward.knee_br.setX(p[11]);
+		forward.thigh_br.set(p[9],0.0f,-p[10]);
+		forward.neck.setX(p[12]);
+		forward.head.set(0.0f,p[13],p[14]);
+		if(model.equals("ERS-7")) {
+			forward.tail.set(p[15],0.0f,p[16]);
+		} else {
+			forward.tail.set(p[15],p[16],0.0f);
+		}
+		forward.jaw.setX(-p[17]);
+	}
+	
+	
+	public void close() {
+		prefs.putInt("Aibo3D.location.x",getLocation().x/*+getInsets().left*/);
+		prefs.putInt("Aibo3D.location.y",getLocation().y/*+getInsets().top*/);
+		prefs.putInt("Aibo3D.size.width",getSize().width);
+		prefs.putInt("Aibo3D.size.height",getSize().height);
+		float[] trans = new float[16];
+		Transform3D t3d=new Transform3D();
+		if(viewpoint!=null) {
+			viewpoint.getTransform(t3d);
+			t3d.get(trans);
+			for(int i=0; i<4; ++i)
+				for(int j=0; j<4; ++j)
+					prefs.putFloat("Aibo3D.viewpoint."+i+"."+j,trans[i*4+j]);
+		}
+		wsj.removeUpdatedListener(this);
+		wsj.removeConnectionListener(this);
 		dispose();
 	}
+	
+	void testLimits(AiboJoint j) {
+		float step;
+		step=(j.maxX-j.minX)/100;
+		for (float x=j.minX; x<j.maxX; x+=step) { j.setX(x); sleep(10); }
+		for (float x=j.maxX; x>j.minX; x-=step) { j.setX(x); sleep(10); }
+		j.setX(0.0f);
+		step=(j.maxY-j.minY)/100;
+		for (float y=j.minY; y<j.maxY; y+=step) { j.setY(y); sleep(10); }
+		for (float y=j.maxY; y>j.minY; y-=step) { j.setY(y); sleep(10); }
+		j.setY(0.0f);
+		step=(j.maxZ-j.minZ)/100;
+		for (float z=j.minZ; z<j.maxZ; z+=step) { j.setZ(z); sleep(10); }
+		for (float z=j.maxZ; z>j.minZ; z-=step) { j.setZ(z); sleep(10); }
+		j.setZ(0.0f);
+	}
+	
+	void testLimits(AiboJoint j, int n) {
+		for (int i=0; i<n; i++) {
+			testLimits(j);
+		}
+	}
+	
+	void sleep(long ms) {
+		try { Thread.sleep(ms); } catch (Exception e) {}
+	}
+	
+	void loadLW3D(String filename) {
+		Loader loader=new Lw3dLoader(Loader.LOAD_ALL);
+		try {
+			scene=loader.load(filename);
+		} catch (Exception ex) {
+			System.out.println("error loading "+filename);
+			System.exit(1);
+		}
+	}
+	
+	void setup3DCanvas() {
+		canvas3d=new Canvas3D(SimpleUniverse.getPreferredConfiguration());
+		add(canvas3d,BorderLayout.CENTER);
+		universe = new SimpleUniverse(canvas3d);
+		universe.getViewingPlatform().setNominalViewingTransform();
+	}
+	
+	
+	void createSceneGraph(Scene scene) {
+		rootgroup = new BranchGroup();
+		
+		TransformGroup trans = viewpoint = new TransformGroup();
+		trans.setCapability(TransformGroup.ALLOW_TRANSFORM_READ);
+		trans.setCapability(TransformGroup.ALLOW_TRANSFORM_WRITE);
+		
+		Transform3D t3d=new Transform3D();
+		float[] preftrans = new float[16];
+		for(int i=0; i<4; ++i)
+			for(int j=0; j<4; ++j)
+				preftrans[i*4+j]=prefs.getFloat("Aibo3D.viewpoint."+i+"."+j,i==j?1:0);
+		t3d.set(preftrans);
+		viewpoint.setTransform(t3d);
+		
+		BoundingSphere bounds = new BoundingSphere(new Point3d(), 100.0);
+		
+		MouseRotate rotator = new MouseRotate(trans);
+		rotator.setSchedulingBounds(bounds);
+		rootgroup.addChild(rotator);
+		
+		MouseTranslate translator = new MouseTranslate(trans);
+		translator.setSchedulingBounds(bounds);
+		rootgroup.addChild(translator);
+		
+		MouseZoom zoomer = new MouseZoom(trans);
+		zoomer.setSchedulingBounds(bounds);
+		rootgroup.addChild(zoomer); 
+		
+		if (scene.getSceneGroup() != null) {
+			trans.addChild(scene.getSceneGroup());
+			rootgroup.addChild(trans);
+		}
+		setFlags(rootgroup);
+		moveLights(scene.getSceneGroup(), rootgroup);
+		universe.addBranchGraph(rootgroup);
+	}
+	
+	void setFlags(Group g) {
+		g.setCapability(Group.ALLOW_CHILDREN_READ);
+		//g.setCapability(Group.ALLOW_CHILDREN_WRITE);
+		for(Enumeration e=g.getAllChildren(); e.hasMoreElements(); ) {
+			Object o=e.nextElement();
+			if(o instanceof Group) {
+				setFlags((Group)o);
+			} else if(o instanceof Shape3D) {
+				((Shape3D)o).setCapability(Shape3D.ALLOW_APPEARANCE_READ);
+				//((Shape3D)o).setCapability(Shape3D.ALLOW_APPEARANCE_WRITE);
+				//((Shape3D)o).getAppearance().setCapability(Appearance.ALLOW_POLYGON_ATTRIBUTES_READ);
+				//((Shape3D)o).getAppearance().setCapability(Appearance.ALLOW_POLYGON_ATTRIBUTES_WRITE);
+				//((Shape3D)o).getAppearance().getPolygonAttributes().setCapability(PolygonAttributes.ALLOW_CULL_FACE_READ);
+				//((Shape3D)o).getAppearance().getPolygonAttributes().setCapability(PolygonAttributes.ALLOW_CULL_FACE_WRITE);
+				((Shape3D)o).getAppearance().setCapability(Appearance.ALLOW_MATERIAL_READ);
+				((Shape3D)o).getAppearance().getMaterial().setCapability(Material.ALLOW_COMPONENT_READ);
+				((Shape3D)o).getAppearance().getMaterial().setCapability(Material.ALLOW_COMPONENT_WRITE);
+			}
+		}
+	}
+	
+	void moveLights(Group from, Group to) {
+		//from.setCapability(Group.ALLOW_CHILDREN_READ);
+		
+		java.util.Enumeration enumKids = from.getAllChildren();
+		while( enumKids.hasMoreElements( ) != false ) {
+			Object o = enumKids.nextElement();
+			if (o instanceof Group) {
+				moveLights((Group)o, to);
+			} else if (o instanceof DirectionalLight || o instanceof PointLight) {
+				//from.setCapability(Group.ALLOW_CHILDREN_WRITE);
+				//to.setCapability(Group.ALLOW_CHILDREN_READ);
+				//to.setCapability(Group.ALLOW_CHILDREN_WRITE);
+				from.removeChild((Node)o);
+				to.addChild((Node)o);
+			}
+		}
+		
+	}
 
-  void testLimits(AiboJoint j) {
-    float step;
-    step=(j.maxX-j.minX)/100;
-    for (float x=j.minX; x<j.maxX; x+=step) { j.setX(x); sleep(10); }
-    for (float x=j.maxX; x>j.minX; x-=step) { j.setX(x); sleep(10); }
-    j.setX(0.0f);
-    step=(j.maxY-j.minY)/100;
-    for (float y=j.minY; y<j.maxY; y+=step) { j.setY(y); sleep(10); }
-    for (float y=j.maxY; y>j.minY; y-=step) { j.setY(y); sleep(10); }
-    j.setY(0.0f);
-    step=(j.maxZ-j.minZ)/100;
-    for (float z=j.minZ; z<j.maxZ; z+=step) { j.setZ(z); sleep(10); }
-    for (float z=j.maxZ; z>j.minZ; z-=step) { j.setZ(z); sleep(10); }
-    j.setZ(0.0f);
-  }
-
-  void testLimits(AiboJoint j, int n) {
-    for (int i=0; i<n; i++) {
-      testLimits(j);
-    }
-  }
-
-  void sleep(long ms) {
-    try { Thread.sleep(ms); } catch (Exception e) {}
-  }
-
-  void loadLW3D(String filename) {
-    Loader loader=new Lw3dLoader(Loader.LOAD_ALL);
-    try {
-      scene=loader.load(filename);
-    } catch (Exception ex) {
-      System.out.println("error loading "+filename);
-      System.exit(1);
-    }
-  }
-
-  void setup3DCanvas() {
-    canvas3d=new Canvas3D(SimpleUniverse.getPreferredConfiguration());
-    add("Center",canvas3d);
-    setVisible(true);
-    addWindowListener(new WindowAdapter()         // cleans up properly
-      { public void windowClosing(WindowEvent e)
-          { dispose(); System.exit(0); } });
-  }
-
-
-  void showScene() {
-    GraphicsConfiguration config =
-      SimpleUniverse.getPreferredConfiguration();
-
-
-    SimpleUniverse universe = new SimpleUniverse(canvas3d);
-    universe.getViewingPlatform().setNominalViewingTransform();
-
-    BranchGroup bg = createSceneGraph(scene);
-    universe.addBranchGraph(bg);
-  }
-
-  BranchGroup createSceneGraph(Scene scene) {
-    BranchGroup root = new BranchGroup();
-
-    TransformGroup trans = new TransformGroup();
-    trans.setCapability(TransformGroup.ALLOW_TRANSFORM_READ);
-    trans.setCapability(TransformGroup.ALLOW_TRANSFORM_WRITE);
-
-    BoundingSphere bounds = new BoundingSphere(new Point3d(), 100.0);
-
-    MouseRotate rotator = new MouseRotate(trans);
-    rotator.setSchedulingBounds(bounds);
-    root.addChild(rotator);
-
-    MouseTranslate translator = new MouseTranslate(trans);
-    translator.setSchedulingBounds(bounds);
-    root.addChild(translator);
-
-    MouseZoom zoomer = new MouseZoom(trans);
-    zoomer.setSchedulingBounds(bounds);
-    root.addChild(zoomer); 
-
-    if (scene.getSceneGroup() != null) {
-      trans.addChild(scene.getSceneGroup());
-      root.addChild(trans);
-    }
+	
+	void recursivePrintGroup(Object sgo) {
+		recursivePrintGroup(sgo,"");
+	}
 
-    return root;
-  }
+	void recursivePrintGroup(Object sgo, String indent) {
+		if( sgo instanceof SceneGraphObject != false )
+		{
+			SceneGraphObject sg = (SceneGraphObject) sgo;
+			
+			// recursively process group
+			if( sg instanceof Group )
+			{
+				Group g = (Group) sg;
+				//g.setCapability(Group.ALLOW_CHILDREN_READ);
+				
+				// recurse on child nodes
+				java.util.Enumeration enumKids = g.getAllChildren( );
+				
+				System.out.println(indent+sg.getClass()+" {");
+				while( enumKids.hasMoreElements( ) != false )
+					recursivePrintGroup( enumKids.nextElement( ), indent+"  ");
+				System.out.println(indent+"}");
+			}
+			else if ( sg instanceof Node || sg instanceof NodeComponent)
+			{
+				System.out.println(indent+sg);
+			} else {
+				System.out.println(indent+sg.getClass());
+			}
+		}
+		
+	}
+	
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/aibo3d/Aibo3DForward.java ./tools/mon/org/tekkotsu/aibo3d/Aibo3DForward.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/aibo3d/Aibo3DForward.java	2003-09-26 00:36:17.000000000 -0400
+++ ./tools/mon/org/tekkotsu/aibo3d/Aibo3DForward.java	2006-08-30 18:26:46.000000000 -0400
@@ -8,133 +8,290 @@
 import com.sun.j3d.loaders.Scene;
 
 public class Aibo3DForward {
-  Scene _scene;
-  Hashtable _namedObjects;
-  boolean lock;
-
-  AiboJoint head;
-  AiboJoint neck;
-  AiboJoint jaw;
-  AiboJoint tail;
-  AiboJoint thigh_fl;
-  AiboJoint knee_fl;
-  AiboJoint thigh_fr;
-  AiboJoint knee_fr;
-  AiboJoint thigh_bl;
-  AiboJoint knee_bl;
-  AiboJoint thigh_br;
-  AiboJoint knee_br;
-  List aiboJoints;
-  
-  public Aibo3DForward(Scene scene) {
-    _scene=scene;
-    _namedObjects=scene.getNamedObjects();
-    lock=false;
-
-    makeSceneTransformable();
-    initERS210();
-  }
-
-  public List getAiboJoints() {
-    return aiboJoints;    
-  }
-
-  void makeSceneTransformable() {
-    for (Enumeration e=_namedObjects.keys(); e.hasMoreElements();)
-      makeObjectTransformable(e.nextElement());
-  }
-
-  void makeObjectTransformable(Object key) {
-    TransformGroup objtg=getTG(key);
-    objtg.setCapability(TransformGroup.ALLOW_TRANSFORM_READ);
-    objtg.setCapability(TransformGroup.ALLOW_TRANSFORM_WRITE);
-  }
-
-  void printNamedObjects() {
-    for (Enumeration e=_namedObjects.keys(); e.hasMoreElements();)
-      System.out.println(e.nextElement());
-  }
-
-  void printNamedObjectTransformationMatrices() {
-    for (Enumeration e=_namedObjects.keys(); e.hasMoreElements();) {
-      System.out.println(e.nextElement()+": ");
-      printNamedObjectTransformationMatrix(e.nextElement());
-    }
-  }
-
-  void printNamedObjectTransformationMatrix(Object key) {
-    TransformGroup objtg=getTG(key);
-    Transform3D t3d=new Transform3D();
-    objtg.getTransform(t3d);
-    System.out.println(t3d);
-  }
+	Scene _scene;
+	Hashtable _namedObjects;
+	boolean lock;
+	
+	AiboJoint head;
+	AiboJoint neck;
+	AiboJoint jaw;
+	AiboJoint tail;
+	AiboJoint thigh_fl;
+	AiboJoint knee_fl;
+	AiboJoint thigh_fr;
+	AiboJoint knee_fr;
+	AiboJoint thigh_bl;
+	AiboJoint knee_bl;
+	AiboJoint thigh_br;
+	AiboJoint knee_br;
+	List aiboJoints;
+	
+	public Aibo3DForward(String model, Scene scene) {
+		_scene=scene;
+		_namedObjects=scene.getNamedObjects();
+		lock=false;
+		
+		makeSceneTransformable();
+		if(model.equals("ERS-210"))
+			initERS210();
+		else if(model.equals("ERS-7")) {
+			 initERS7();
+		}
+	}
+	
+	public List getAiboJoints() {
+		return aiboJoints;    
+	}
+	
+	void makeSceneTransformable() {
+		for (Enumeration e=_namedObjects.keys(); e.hasMoreElements();)
+			makeObjectTransformable(e.nextElement());
+	}
+	
+	void makeObjectTransformable(Object key) {
+		TransformGroup objtg=getTG(key);
+		objtg.setCapability(TransformGroup.ALLOW_TRANSFORM_READ);
+		objtg.setCapability(TransformGroup.ALLOW_TRANSFORM_WRITE);
+	}
+	
+	void printNamedObjects() {
+		for (Enumeration e=_namedObjects.keys(); e.hasMoreElements();)
+			System.out.println(e.nextElement());
+	}
+	
+	void printNamedObjectTransformationMatrices() {
+		for (Enumeration e=_namedObjects.keys(); e.hasMoreElements();) {
+			System.out.println(e.nextElement()+": ");
+			printNamedObjectTransformationMatrix(e.nextElement());
+		}
+	}
+	
+	void printNamedObjectTransformationMatrix(Object key) {
+		TransformGroup objtg=getTG(key);
+		Transform3D t3d=new Transform3D();
+		objtg.getTransform(t3d);
+		System.out.println(t3d);
+	}
+	
+	public TransformGroup getTG(Object key) {
+		return (TransformGroup)_namedObjects.get(key);
+	}
+	
+	TransformGroup flipNormals(TransformGroup tg) {
+		return flipNormals(tg,false);
+	}
+	
+	TransformGroup flipNormals(TransformGroup tg, boolean highlight) {
+		for(Enumeration e=tg.getAllChildren(); e.hasMoreElements();) {
+			Node n=(Node)e.nextElement();
+			if(n instanceof TransformGroup) {
+				//flipNormals((TransformGroup)n); // don't recurse
+			} else {
+				if(n instanceof Shape3D) {
+					Appearance app=((Shape3D)n).getAppearance();
+					PolygonAttributes papp=app.getPolygonAttributes();
+					if(papp==null)
+						app.setPolygonAttributes(papp=new PolygonAttributes());
+					papp.setBackFaceNormalFlip(!papp.getBackFaceNormalFlip());
+					papp.setCullFace(PolygonAttributes.CULL_FRONT);
+					if(highlight)
+						app.getMaterial().setDiffuseColor(1.f,0,0);
+				} else {
+					System.out.println("unhandled in flip: "+n.getClass());
+				}
+			}
+		}
+		return tg;
+	}
+		
+	
+	
+	void initERS210 () {
+		neck=new AiboJoint(getTG("objects-ERS-210/neck.lwo"), "neck",
+			-46.0f,   85.0f,
+			0.0f,     0.0f,
+			0.0f,     0.0f);
+		head=new AiboJoint(getTG("objects-ERS-210/head.lwo"), "head",
+			0.0f,     0.0f,
+			-92.6f,   92.6f,
+			-32.0f,   32.0f);
+		jaw=new AiboJoint(getTG("objects-ERS-210/jaw.lwo"), "jaw",
+			0.0f,     50.0f,
+			0.0f,     0.0f,
+			0.0f,     0.0f);
+		tail=new AiboJoint(getTG("objects-ERS-210/tail2.lwo"), "tail",
+			-25.0f,   25.0f,
+			-25.0f,   25.0f,
+			0.0f,     0.0f);
+		thigh_fl=new AiboJoint(getTG("objects-ERS-210/leg-f-up-l.lwo"), "thigh_fl",
+			-120.0f,  120.0f,
+			0.0f,     0.0f,
+			-15.0f,   92.0f);
+		thigh_fr=new AiboJoint(getTG("objects-ERS-210/leg-f-up-r.lwo"), "thigh_fr",
+			-120.0f,  120.0f,
+			0.0f,     0.0f,
+			-92.0f,   15.0f);
+		thigh_bl=new AiboJoint(getTG("objects-ERS-210/leg-b-up-l.lwo"), "thigh_bl",
+			-120.0f,  120.0f,
+			0.0f,     0.0f,
+			-15.0f,   92.0f);
+		thigh_br=new AiboJoint(getTG("objects-ERS-210/leg-b-up-r.lwo"), "thigh_br",
+			-120.0f,  120.0f,
+			0.0f,     0.0f,
+			-92.0f,   15.0f);
+		knee_fl=new AiboJoint(getTG("objects-ERS-210/leg-f-low-l.lwo"), "knee_fl",
+			-150.0f,  30.0f,
+			0.0f,     0.0f,
+			0.0f,     0.0f);
+		knee_fl.setRotationalPreOffset(35*(float)Math.PI/180,0.f,0.f);
+		knee_fr=new AiboJoint(getTG("objects-ERS-210/leg-f-low-r.lwo"), "knee_fr",
+			-150.0f,  30.0f,
+			0.0f,     0.0f,
+			0.0f,     0.0f);
+		knee_fr.setRotationalPreOffset(35*(float)Math.PI/180,0.f,0.f);
+		knee_bl=new AiboJoint(getTG("objects-ERS-210/leg-b-low-l.lwo"), "knee_bl",
+			-30.0f,   150.0f,
+			0.0f,     0.0f,
+			0.0f,     0.0f);
+		knee_bl.setRotationalPreOffset(-35*(float)Math.PI/180,0.f,0.f);
+		knee_br=new AiboJoint(getTG("objects-ERS-210/leg-b-low-r.lwo"), "knee_br",
+			-30.0f,   150.0f,
+			0.0f,     0.0f,
+			0.0f,     0.0f);
+		knee_br.setRotationalPreOffset(-35*(float)Math.PI/180,0.f,0.f);
+		aiboJoints=new ArrayList(20);
+		
+		aiboJoints.add(head);
+		aiboJoints.add(neck);
+		aiboJoints.add(jaw);
+		aiboJoints.add(tail);
+		aiboJoints.add(thigh_fl);
+		aiboJoints.add(knee_fl);
+		aiboJoints.add(thigh_fr);
+		aiboJoints.add(knee_fr);
+		aiboJoints.add(thigh_bl);
+		aiboJoints.add(knee_bl);
+		aiboJoints.add(thigh_br);
+		aiboJoints.add(knee_br);
+	}
 
-  public TransformGroup getTG(Object key) {
-    return (TransformGroup)_namedObjects.get(key);
-  }
+	void initERS7 () {
+		flipNormals(getTG("objects-ERS-7/body01.lwo")); // main body
+		flipNormals(getTG("objects-ERS-7/body02.lwo")); // chest IR
+		flipNormals(getTG("objects-ERS-7/body03.lwo")); // throat plate
+		flipNormals(getTG("objects-ERS-7/body04.lwo")); // back
+		//flipNormals(getTG("objects-ERS-7/body05.lwo"),true); // back buttons
+		flipNormals(getTG("objects-ERS-7/body06.lwo")); //underbelly
+		
+		//flipNormals(getTG("objects-ERS-7/chops.lwo"),true); //mouth
+		
+		//flipNormals(getTG("objects-ERS-7/head01.lwo"),true); // chin
+		//flipNormals(getTG("objects-ERS-7/head02.lwo"),true); // camera
+		//flipNormals(getTG("objects-ERS-7/head03.lwo"),true); // face
+		//flipNormals(getTG("objects-ERS-7/head04.lwo"),true); // face panel LEDs
+		//flipNormals(getTG("objects-ERS-7/head05.lwo"),true); // right ear mount
+		//flipNormals(getTG("objects-ERS-7/head06.lwo"),true); // left ear mount
 
-  void initERS210 () {
-    neck=new AiboJoint(getTG("objects/neck.lwo"), "neck",
-                       -46.0f,   85.0f,
-                       0.0f,     0.0f,
-                       0.0f,     0.0f);
-    head=new AiboJoint(getTG("objects/head.lwo"), "head",
-                       0.0f,     0.0f,
-                       -92.6f,   92.6f,
-                       -32.0f,   32.0f);
-    jaw=new AiboJoint(getTG("objects/jaw.lwo"), "jaw",
-                       0.0f,     50.0f,
-                       0.0f,     0.0f,
-                       0.0f,     0.0f);
-    tail=new AiboJoint(getTG("objects/tail2.lwo"), "tail",
-                       -25.0f,   25.0f,
-                       -25.0f,   25.0f,
-                       0.0f,     0.0f);
-    thigh_fl=new AiboJoint(getTG("objects/leg-f-up-l.lwo"), "thigh_fl",
-                       -120.0f,  120.0f,
-                       0.0f,     0.0f,
-                       -15.0f,   92.0f);
-    thigh_fr=new AiboJoint(getTG("objects/leg-f-up-r.lwo"), "thigh_fr",
-                       -120.0f,  120.0f,
-                       0.0f,     0.0f,
-                       -92.0f,   15.0f);
-    thigh_bl=new AiboJoint(getTG("objects/leg-b-up-l.lwo"), "thigh_bl",
-                       -120.0f,  120.0f,
-                       0.0f,     0.0f,
-                       -15.0f,   92.0f);
-    thigh_br=new AiboJoint(getTG("objects/leg-b-up-r.lwo"), "thigh_br",
-                       -120.0f,  120.0f,
-                       0.0f,     0.0f,
-                       -92.0f,   15.0f);
-    knee_fl=new AiboJoint(getTG("objects/leg-f-low-l.lwo"), "knee_fl",
-                       -115.0f,  65.0f,
-                       0.0f,     0.0f,
-                       0.0f,     0.0f);
-    knee_fr=new AiboJoint(getTG("objects/leg-f-low-r.lwo"), "knee_fr",
-                       -115.0f,  65.0f,
-                       0.0f,     0.0f,
-                       0.0f,     0.0f);
-    knee_bl=new AiboJoint(getTG("objects/leg-b-low-l.lwo"), "knee_bl",
-                       -65.0f,   115.0f,
-                       0.0f,     0.0f,
-                       0.0f,     0.0f);
-    knee_br=new AiboJoint(getTG("objects/leg-b-low-r.lwo"), "knee_br",
-                       -65.0f,   115.0f,
-                       0.0f,     0.0f,
-                       0.0f,     0.0f);
-    aiboJoints=new ArrayList(20);
+		flipNormals(getTG("objects-ERS-7/Lear01.lwo")); // left microphone
+		//flipNormals(getTG("objects-ERS-7/Lear02.lwo"),true); // left ear
 
-    aiboJoints.add(head);
-    aiboJoints.add(neck);
-    aiboJoints.add(jaw);
-    aiboJoints.add(tail);
-    aiboJoints.add(thigh_fl);
-    aiboJoints.add(knee_fl);
-    aiboJoints.add(thigh_fr);
-    aiboJoints.add(knee_fr);
-    aiboJoints.add(thigh_bl);
-    aiboJoints.add(knee_bl);
-    aiboJoints.add(thigh_br);
-    aiboJoints.add(knee_br);
-  }
+		flipNormals(getTG("objects-ERS-7/LforefootA.lwo")); // left front shoulder
+		//flipNormals(getTG("objects-ERS-7/LforefootB.lwo"),true); // left front thigh
+		//flipNormals(getTG("objects-ERS-7/LforefootC.lwo"),true); // left front shin
+		//flipNormals(getTG("objects-ERS-7/LforefootD.lwo"),true); // left front foot
+		
+		flipNormals(getTG("objects-ERS-7/LhindfootA.lwo")); // left hind shoulder
+		//flipNormals(getTG("objects-ERS-7/LhindfootB.lwo"),true); // left hind thigh
+		//flipNormals(getTG("objects-ERS-7/LhindfootC.lwo"),true); // left hind shin
+		//flipNormals(getTG("objects-ERS-7/LhindfootD.lwo"),true); // left hind foot
+		
+		//flipNormals(getTG("objects-ERS-7/neck.lwo"),true); //neck
+		
+		//flipNormals(getTG("objects-ERS-7/Rear01.lwo")); // right microphone
+		flipNormals(getTG("objects-ERS-7/Rear02.lwo")); // right ear
+		
+		//flipNormals(getTG("objects-ERS-7/RforefootA.lwo")); // right front shoulder
+		flipNormals(getTG("objects-ERS-7/RforefootB.lwo")); // right front thigh
+		flipNormals(getTG("objects-ERS-7/RforefootC.lwo")); // right front shin
+		flipNormals(getTG("objects-ERS-7/RforefootD.lwo")); // right front foot
+		
+		//flipNormals(getTG("objects-ERS-7/RhindfootA.lwo")); // right hind shoulder
+		flipNormals(getTG("objects-ERS-7/RhindfootB.lwo")); // right hind thigh
+		flipNormals(getTG("objects-ERS-7/RhindfootC.lwo")); // right hind shin
+		flipNormals(getTG("objects-ERS-7/RhindfootD.lwo")); // right hind foot
+		
+		flipNormals(getTG("objects-ERS-7/tail01.lwo")); // tail "bone"
+		flipNormals(getTG("objects-ERS-7/tail02.lwo")); // tail itself
+		
+		neck=new AiboJoint(getTG("objects-ERS-7/neck.lwo"), "neck",
+			-80.0f,   3.f,
+			0.0f,     0.0f,
+			0.0f,     0.0f);
+		neck.setRotationalPreOffset(0.f,-(float)Math.PI,0.f);
+		neck.setRotationalPostOffset(0.f,(float)Math.PI,0.f);
+		head=new AiboJoint(getTG("objects-ERS-7/head01.lwo"), "head",
+			0.0f,      0.0f,
+			-93.0f,   93.0f,
+			-20.0f,    50.0f);
+		head.setRotationalPreOffset(0.f,-(float)Math.PI/2,0.f);
+		head.setRotationalPostOffset(0.f,(float)Math.PI/2,0.f);
+		jaw=new AiboJoint(getTG("objects-ERS-7/chops.lwo"), "jaw",
+			0.0f,     55.0f,
+			0.0f,     0.0f,
+			0.0f,     0.0f);
+		tail=new AiboJoint(getTG("objects-ERS-7/tail01.lwo"), "tail",
+			0.0f,   63.0f,
+			0.0f,     0.0f,
+			-60.0f,   60.0f);
+		thigh_fl=new AiboJoint(getTG("objects-ERS-7/LforefootB.lwo"), "thigh_fl",
+			-120.0f,  135.0f,
+			0.0f,     0.0f,
+			-15.0f,   93.0f);
+		thigh_fr=new AiboJoint(getTG("objects-ERS-7/RforefootB.lwo"), "thigh_fr",
+			-120.0f,  135.0f,
+			0.0f,     0.0f,
+			-93.0f,   15.0f);
+		thigh_bl=new AiboJoint(getTG("objects-ERS-7/LhindfootB.lwo"), "thigh_bl",
+			-135.0f,  120.0f,
+			0.0f,     0.0f,
+			-15.0f,   93.0f);
+		thigh_br=new AiboJoint(getTG("objects-ERS-7/RhindfootB.lwo"), "thigh_br",
+			-135.0f,  120.0f,
+			0.0f,     0.0f,
+			-93.0f,   15.0f);
+		knee_fl=new AiboJoint(getTG("objects-ERS-7/LforefootC.lwo"), "knee_fl",
+			-127.0f,  30.0f,
+			0.0f,     0.0f,
+			0.0f,     0.0f);
+		knee_fl.setRotationalPreOffset(30*(float)Math.PI/180,0.f,0.f);
+		knee_fr=new AiboJoint(getTG("objects-ERS-7/RforefootC.lwo"), "knee_fr",
+			-127.0f,  30.0f,
+			0.0f,     0.0f,
+			0.0f,     0.0f);
+		knee_fr.setRotationalPreOffset(30*(float)Math.PI/180,0.f,0.f);
+		knee_bl=new AiboJoint(getTG("objects-ERS-7/LhindfootC.lwo"), "knee_bl",
+			-30.0f,   127.0f,
+			0.0f,     0.0f,
+			0.0f,     0.0f);
+		knee_bl.setRotationalPreOffset(-30*(float)Math.PI/180,0.f,0.f);
+		knee_br=new AiboJoint(getTG("objects-ERS-7/RhindfootC.lwo"), "knee_br",
+			-30.0f,   127.0f,
+			0.0f,     0.0f,
+			0.0f,     0.0f);
+		knee_br.setRotationalPreOffset(-30*(float)Math.PI/180,0.f,0.f);
+		aiboJoints=new ArrayList(20);
+		
+		aiboJoints.add(head);
+		aiboJoints.add(neck);
+		aiboJoints.add(jaw);
+		aiboJoints.add(tail);
+		aiboJoints.add(thigh_fl);
+		aiboJoints.add(knee_fl);
+		aiboJoints.add(thigh_fr);
+		aiboJoints.add(knee_fr);
+		aiboJoints.add(thigh_bl);
+		aiboJoints.add(knee_bl);
+		aiboJoints.add(thigh_br);
+		aiboJoints.add(knee_br);
+	}
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/aibo3d/Aibo3DPick.java ./tools/mon/org/tekkotsu/aibo3d/Aibo3DPick.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/aibo3d/Aibo3DPick.java	2003-10-01 22:07:33.000000000 -0400
+++ ./tools/mon/org/tekkotsu/aibo3d/Aibo3DPick.java	2006-08-03 17:22:26.000000000 -0400
@@ -22,7 +22,7 @@
 import org.tekkotsu.mon.WorldStateJointsListener;
 import org.tekkotsu.mon.Joints;
 
-public class Aibo3DPick extends Frame {
+public class Aibo3DPick extends Frame implements WorldStateJointsListener.UpdatedListener {
   Canvas3D canvas3d;
   Scene scene;
   Aibo3DForward forward;
@@ -31,7 +31,7 @@
   SimpleUniverse universe;
   BranchGroup root;
   static Preferences prefs = Preferences.userNodeForPackage(Aibo3DPick.class);
-	Thread mirror;
+	//Thread mirror;
 	WorldStateJointsListener wsjl;
 	WorldStateJointsWriter wsjw;
   
@@ -53,19 +53,25 @@
     setLocation(prefs.getInt("Aibo3DPick.location.x",50),prefs.getInt("Aibo3DPick.location.y",50));
 
     setup3DCanvas();
-    loadLW3D("aibo3d.lws");
-    forward=new Aibo3DForward(scene);
+    loadLW3D("ERS-210.lws");
+    forward=new Aibo3DForward("ERS-210",scene);
     showScene();
 
     picker.createPicker();
-    wsjl=new WorldStateJointsListener(host, 10031);
+    wsjl=WorldStateJointsListener.getCommonInstance(host);
+		wsjl.addUpdatedListener(this);
 		wsjw=new WorldStateJointsWriter(host, port);
 
-		mirror=new mirrorThread(this);
-		mirror.start();
+		//mirror=new mirrorThread(this);
+		//mirror.start();
     addWindowListener(new CloseAdapter(this));
   }
 
+	public void worldStateUpdated(WorldStateJointsListener mc) {
+		mirrorListener(mc);
+	}
+
+
 	class mirrorThread extends Thread {
 		Aibo3DPick gui;
 		mirrorThread(Aibo3DPick gui) { this.gui=gui; }
@@ -94,31 +100,31 @@
 	public void close() {
     prefs.putInt("Aibo3DPick.location.x",getLocation().x+getInsets().left);
     prefs.putInt("Aibo3DPick.location.y",getLocation().y+getInsets().top);
-		wsjl.kill();
+		wsjl.removeUpdatedListener(this);
 		if(wsjw!=null)
 			wsjw.kill();
-		mirror.interrupt();
+		//mirror.interrupt();
 		dispose();
 	}
 
   void mirrorListener (WorldStateJointsListener wsj) {
     if (wsj.isConnected()) {
-      if (wsj.hasData()) {
-        Joints j=wsj.getData();
-        float[] p=j.positions;
-        forward.knee_fl.setX(-p[2]);
-        forward.thigh_fl.set(-p[0],0.0f,p[1]);
-        forward.knee_fr.setX(-p[5]);
-        forward.thigh_fr.set(-p[3],0.0f,-p[4]);
-        forward.knee_bl.setX(p[8]);
-        forward.thigh_bl.set(p[6],0.0f,p[7]);
-        forward.knee_br.setX(p[11]);
-        forward.thigh_br.set(p[9],0.0f,-p[10]);
-        forward.neck.setX(-p[12]);
-        forward.head.set(0.0f,p[13],p[14]);
-        forward.tail.set(p[15],p[16],0.0f);
-        forward.jaw.setX(-p[17]);
-      }
+      //if (wsj.hasData()) {
+			Joints j=wsj.getData();
+			float[] p=j.positions;
+			forward.knee_fl.setX(-p[2]);
+			forward.thigh_fl.set(-p[0],0.0f,p[1]);
+			forward.knee_fr.setX(-p[5]);
+			forward.thigh_fr.set(-p[3],0.0f,-p[4]);
+			forward.knee_bl.setX(p[8]);
+			forward.thigh_bl.set(p[6],0.0f,p[7]);
+			forward.knee_br.setX(p[11]);
+			forward.thigh_br.set(p[9],0.0f,-p[10]);
+			forward.neck.setX(-p[12]);
+			forward.head.set(0.0f,p[13],p[14]);
+			forward.tail.set(p[15],p[16],0.0f);
+			forward.jaw.setX(-p[17]);
+			//}
     }
   }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/aibo3d/AiboJoint.java ./tools/mon/org/tekkotsu/aibo3d/AiboJoint.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/aibo3d/AiboJoint.java	2003-09-26 00:36:17.000000000 -0400
+++ ./tools/mon/org/tekkotsu/aibo3d/AiboJoint.java	2006-08-03 17:16:05.000000000 -0400
@@ -6,126 +6,180 @@
 import java.lang.*;
 
 public class AiboJoint {
-  public static final int RADIANS=0;
-  public static final int DEGREES=1;
-
-  public String name;
-  public TransformGroup obj;
-  public float minX;
-  public float maxX;
-  public float minY;
-  public float maxY;
-  public float minZ;
-  public float maxZ;
-  public float x;
-  public float y;
-  public float z;
-
-  float bound(float n, float l, float h) {
-    return Math.max(Math.min(h, n),l);
-  }
-
-  public void setX(float X) {
-    x=bound(X, minX, maxX);
-    setJoints();
-  }
-
-  public void setY(float Y) {
-    y=bound(Y, minY, maxY);
-    setJoints();
-  }
-
-  public void setZ(float Z) {
-    z=bound(Z, minZ, maxZ);
-    setJoints();
-  }
-
-  public void setX(double X) {
-    setX((float)X);
-  }
-
-  public void setY(double Y) {
-    setY((float)Y);
-  }
-
-  public void setZ(double Z) {
-    setZ((float)Z);
-  }
-
-  public void setXDiff(int X) {
-    setX(x+((float)X*0.03f));
-  }
-
-  public void setYDiff(int Y) {
-    setY(y+((float)Y*0.03f));
-  }
-  
-  public void setZDiff(int Z) {
-    setZ(z+((float)Z*0.03f));
-  }
-
-  public void set(float X, float Y, float Z) {
-    x=bound(X, minX, maxX);
-    y=bound(Y, minY, maxY);
-    z=bound(Z, minZ, maxZ);
-    setJoints();
-  }
-
-  // TODO: Lots of crazy speedups possible
-  void setJoints() {
-    Transform3D t3d=new Transform3D();
-    Matrix3f accum=new Matrix3f();
-    Matrix3f rot=new Matrix3f();
-    obj.getTransform(t3d);
-    accum.setIdentity();
-    rot.rotX(x);
-    accum.mul(rot);
-    rot.rotY(y);
-    accum.mul(rot);
-    rot.rotZ(z);
-    accum.mul(rot);
-    t3d.setRotation(accum);
-    obj.setTransform(t3d);
-  }
-
-  public AiboJoint (TransformGroup tg, String n, float minx, float maxx,
-                    float miny, float maxy, float minz, float maxz) {
-    this(tg, n, minx, maxx, miny, maxy, minz, maxz, DEGREES);
-  }
- 
-  public AiboJoint (TransformGroup tg, String n, float minx, float maxx,
-                    float miny, float maxy, float minz, float maxz, int units) {
-    if (units==RADIANS) {
-      obj=tg;
-      minX=minx;
-      maxX=maxx;
-      minY=miny;
-      maxY=maxy;
-      minZ=minz;
-      maxZ=maxz;
-    } else if (units==DEGREES) {
-      obj=tg;
-      minX=deg2rad(minx);
-      maxX=deg2rad(maxx);
-      minY=deg2rad(miny);
-      maxY=deg2rad(maxy);
-      minZ=deg2rad(minz);
-      maxZ=deg2rad(maxz);
-    } else {
-      System.out.println("error: unknown units");
-      System.exit(1);
-    }
-    x=0.0f;
-    y=0.0f;
-    z=0.0f;
-    name=n;
-  }
-
-  public float deg2rad (float deg) {
-    return (deg*(float)Math.PI)/180.0f;
-  }
-
-  public String toString () {
-    return name;
-  }
+	public static final int RADIANS=0;
+	public static final int DEGREES=1;
+	
+	public String name;
+	public TransformGroup obj;
+	public Matrix3f rotPreOffset,rotPostOffset;
+	public Matrix3f mul;
+	Matrix3f rot;
+	public float minX;
+	public float maxX;
+	public float minY;
+	public float maxY;
+	public float minZ;
+	public float maxZ;
+	public float x;
+	public float y;
+	public float z;
+	
+	float bound(float n, float l, float h) {
+		return Math.max(Math.min(h, n),l);
+	}
+	
+	public void setX(float X) {
+		x=bound(X, minX, maxX);
+		setJoints();
+	}
+	
+	public void setY(float Y) {
+		y=bound(Y, minY, maxY);
+		setJoints();
+	}
+	
+	public void setZ(float Z) {
+		z=bound(Z, minZ, maxZ);
+		setJoints();
+	}
+	
+	public void setX(double X) {
+		setX((float)X);
+	}
+	
+	public void setY(double Y) {
+		setY((float)Y);
+	}
+	
+	public void setZ(double Z) {
+		setZ((float)Z);
+	}
+	
+	public void setXDiff(int X) {
+		setX(x+((float)X*0.03f));
+	}
+	
+	public void setYDiff(int Y) {
+		setY(y+((float)Y*0.03f));
+	}
+	
+	public void setZDiff(int Z) {
+		setZ(z+((float)Z*0.03f));
+	}
+	
+	public void set(float X, float Y, float Z) {
+		x=bound(X, minX, maxX);
+		y=bound(Y, minY, maxY);
+		z=bound(Z, minZ, maxZ);
+		setJoints();
+	}
+	
+	
+	public AiboJoint mulX(float X) {
+		x=bound(X, minX, maxX);
+		rot.rotX(x);
+		mul.mul(rot);
+		return this;
+	}
+	public AiboJoint mulY(float Y) {
+		y=bound(Y, minY, maxY);
+		rot.rotY(y);
+		mul.mul(rot);
+		return this;
+	}
+	public AiboJoint mulZ(float Z) {
+		z=bound(Z, minZ, maxZ);
+		rot.rotZ(z);
+		mul.mul(rot);
+		return this;
+	}
+	public void apply() {
+		mul.mul(rotPostOffset);
+		Transform3D t3d=new Transform3D();
+		obj.getTransform(t3d);
+		t3d.setRotation(mul);
+		obj.setTransform(t3d);
+		mul.set(rotPreOffset);
+	}
+	
+	void setJoints() {
+		Matrix3f accum=new Matrix3f(rotPreOffset);
+		rot.rotX(x);
+		accum.mul(rot);
+		rot.rotY(y);
+		accum.mul(rot);
+		rot.rotZ(z);
+		accum.mul(rot);
+		accum.mul(rotPostOffset);
+		Transform3D t3d=new Transform3D();
+		obj.getTransform(t3d);
+		t3d.setRotation(accum);
+		obj.setTransform(t3d);
+		mul.set(rotPreOffset);
+	}
+	
+	public AiboJoint (TransformGroup tg, String n, float minx, float maxx,float miny, float maxy, float minz, float maxz) {
+		this(tg, n, minx, maxx, miny, maxy, minz, maxz, DEGREES);
+	}
+	
+	public AiboJoint (TransformGroup tg, String n, float minx, float maxx, float miny, float maxy, float minz, float maxz, int units) {
+		if (units==RADIANS) {
+			obj=tg;
+			minX=minx;
+			maxX=maxx;
+			minY=miny;
+			maxY=maxy;
+			minZ=minz;
+			maxZ=maxz;
+		} else if (units==DEGREES) {
+			obj=tg;
+			minX=deg2rad(minx);
+			maxX=deg2rad(maxx);
+			minY=deg2rad(miny);
+			maxY=deg2rad(maxy);
+			minZ=deg2rad(minz);
+			maxZ=deg2rad(maxz);
+		} else {
+			System.out.println("error: unknown units");
+			System.exit(1);
+		}
+		x=0.0f;
+		y=0.0f;
+		z=0.0f;
+		name=n;
+		rotPreOffset = new Matrix3f();
+		rotPreOffset.setIdentity();
+		rotPostOffset = new Matrix3f();
+		rotPostOffset.setIdentity();
+		mul = new Matrix3f();
+		mul.setIdentity();
+		rot=new Matrix3f();
+	}
+	
+	public void setRotationalPreOffset(float x, float y, float z) {
+		rotPreOffset.rotX(x);
+		Matrix3f rot=new Matrix3f();
+		rot.rotY(y);
+		rotPreOffset.mul(rot);
+		rot.rotZ(z);
+		rotPreOffset.mul(rot);
+		mul.set(rotPreOffset);
+	}
+	
+	public void setRotationalPostOffset(float x, float y, float z) {
+		rotPostOffset.rotX(x);
+		Matrix3f rot=new Matrix3f();
+		rot.rotY(y);
+		rotPostOffset.mul(rot);
+		rot.rotZ(z);
+		rotPostOffset.mul(rot);
+	}
+	
+	public float deg2rad (float deg) {
+		return (deg*(float)Math.PI)/180.0f;
+	}
+	
+	public String toString () {
+		return name;
+	}
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/aibo3d/AiboPicker.java ./tools/mon/org/tekkotsu/aibo3d/AiboPicker.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/aibo3d/AiboPicker.java	2003-09-26 00:36:17.000000000 -0400
+++ ./tools/mon/org/tekkotsu/aibo3d/AiboPicker.java	2006-07-25 14:46:17.000000000 -0400
@@ -52,36 +52,36 @@
   }
 
   void initERS210() {
-    addShapesFor(getTG("objects/neck.lwo"), head);
-    addShapesFor(getTG("objects/head.lwo"), head);
-    addShapesFor(getTG("objects/LED_g01.lwo"), head);
-    addShapesFor(getTG("objects/LED_g02.lwo"), head);
-    addShapesFor(getTG("objects/LED_g03.lwo"), head);
-    addShapesFor(getTG("objects/LED_r01.lwo"), head);
-    addShapesFor(getTG("objects/LED_r02.lwo"), head);
-    addShapesFor(getTG("objects/LED_r03.lwo"), head);
-    addShapesFor(getTG("objects/ear-l.lwo"), head);
-    addShapesFor(getTG("objects/ear-r.lwo"), head);
+    addShapesFor(getTG("objects-ERS-210/neck.lwo"), head);
+    addShapesFor(getTG("objects-ERS-210/head.lwo"), head);
+    addShapesFor(getTG("objects-ERS-210/LED_g01.lwo"), head);
+    addShapesFor(getTG("objects-ERS-210/LED_g02.lwo"), head);
+    addShapesFor(getTG("objects-ERS-210/LED_g03.lwo"), head);
+    addShapesFor(getTG("objects-ERS-210/LED_r01.lwo"), head);
+    addShapesFor(getTG("objects-ERS-210/LED_r02.lwo"), head);
+    addShapesFor(getTG("objects-ERS-210/LED_r03.lwo"), head);
+    addShapesFor(getTG("objects-ERS-210/ear-l.lwo"), head);
+    addShapesFor(getTG("objects-ERS-210/ear-r.lwo"), head);
 
-    addShapesFor(getTG("objects/jaw.lwo"), jaw);
-    addShapesFor(getTG("objects/body2.lwo"), body);
-    addShapesFor(getTG("objects/tail2.lwo"), tail);
+    addShapesFor(getTG("objects-ERS-210/jaw.lwo"), jaw);
+    addShapesFor(getTG("objects-ERS-210/body2.lwo"), body);
+    addShapesFor(getTG("objects-ERS-210/tail2.lwo"), tail);
    
-    addShapesFor(getTG("objects/foot-b-r.lwo"), foot_br);
-    addShapesFor(getTG("objects/leg-b-low-r.lwo"), knee_br);
-    addShapesFor(getTG("objects/leg-b-up-r.lwo"), leg_br);
+    addShapesFor(getTG("objects-ERS-210/foot-b-r.lwo"), foot_br);
+    addShapesFor(getTG("objects-ERS-210/leg-b-low-r.lwo"), knee_br);
+    addShapesFor(getTG("objects-ERS-210/leg-b-up-r.lwo"), leg_br);
 
-    addShapesFor(getTG("objects/foot-b-l.lwo"), foot_bl);
-    addShapesFor(getTG("objects/leg-b-low-l.lwo"), knee_bl);
-    addShapesFor(getTG("objects/leg-b-up-l.lwo"), leg_bl);
+    addShapesFor(getTG("objects-ERS-210/foot-b-l.lwo"), foot_bl);
+    addShapesFor(getTG("objects-ERS-210/leg-b-low-l.lwo"), knee_bl);
+    addShapesFor(getTG("objects-ERS-210/leg-b-up-l.lwo"), leg_bl);
 
-    addShapesFor(getTG("objects/foot-f-r.lwo"), foot_fr);
-    addShapesFor(getTG("objects/leg-f-low-r.lwo"), knee_fr);
-    addShapesFor(getTG("objects/leg-f-up-r.lwo"), leg_fr);
+    addShapesFor(getTG("objects-ERS-210/foot-f-r.lwo"), foot_fr);
+    addShapesFor(getTG("objects-ERS-210/leg-f-low-r.lwo"), knee_fr);
+    addShapesFor(getTG("objects-ERS-210/leg-f-up-r.lwo"), leg_fr);
 
-    addShapesFor(getTG("objects/foot-f-l.lwo"), foot_fl);
-    addShapesFor(getTG("objects/leg-f-low-l.lwo"), knee_fl);
-    addShapesFor(getTG("objects/leg-f-up-l.lwo"), leg_fl);
+    addShapesFor(getTG("objects-ERS-210/foot-f-l.lwo"), foot_fl);
+    addShapesFor(getTG("objects-ERS-210/leg-f-low-l.lwo"), knee_fl);
+    addShapesFor(getTG("objects-ERS-210/leg-f-up-l.lwo"), leg_fl);
     for (Enumeration e=_shapeToTG.keys(); e.hasMoreElements();) {
       Object o=e.nextElement();
       // System.out.println(o + "->" + _shapeToTG.get(o));
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/ControllerGUI.java ./tools/mon/org/tekkotsu/mon/ControllerGUI.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/ControllerGUI.java	2005-08-05 15:44:23.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/ControllerGUI.java	2006-09-20 16:22:17.000000000 -0400
@@ -13,6 +13,7 @@
 //Admittedly a little sloppy, but I don't want to spend forever on this...
 
 public class ControllerGUI extends JFrame implements ActionListener, KeyListener, EStopListener.UpdatedListener {
+	org.tekkotsu.sketch.SketchGUI cameraSkGUI=null, localSkGUI=null, worldSkGUI=null;
 	JList menu;
 	JScrollPane menuScroll;
 	JComboBox title;
@@ -28,16 +29,17 @@
 	JTextField inputField;
 	boolean isUpdating=false;
 	DefaultListModel scriptsModel=new DefaultListModel();
-  Vector inputFieldHistory;
-  int inputFieldLocation;
+	Vector inputFieldHistory;
+	int inputFieldLocation;
 	static Preferences prefs = Preferences.userNodeForPackage(ControllerGUI.class);
 	final static int MAX_STORE_INPUT_HIST=20;
 	
 	ControllerGUI(String addr, int port) {
 		super();
+		setTitle("TekkotsuMon: Controller ("+addr+")");
 		comm = new ControllerListener(addr,port);
-		comm.listener=this;
 		init();
+		comm.listener=this;
 		comm.needConnection();
 	}
 
@@ -203,8 +205,14 @@
 							comm.sendInput(((ScriptEntry)scriptsModel.get(i)).cmd);
 					//restart servers for any windows we still have open
 					Iterator mons=comm.dynObjSrcs.values().iterator();
-					while(mons.hasNext())
-						comm.sendInput("!root "+(String)mons.next());
+					LinkedList started=new LinkedList(); //only start each entry once (may open multiple items)
+					while(mons.hasNext()) {
+						String c=(String)mons.next();
+						if(!started.contains(c)) {
+							comm.sendInput("!root "+c);
+							started.add(c);
+						}
+					}
 					//Set focus to the main menu
 					menu.requestFocus();
 				}
@@ -301,7 +309,8 @@
 		} else if(evt.getSource()==inputField) {
 			//System.out.println("input: "+inputField.getText());
 			int[] sel=menu.getSelectedIndices();
-      if (inputField.getText().length()==0) {
+			if (inputField.getText().length()==0) {
+				return;
 			} else if(sel.length==0 || inputField.getText().charAt(0)=='!')
 				comm.sendInput(inputField.getText());
 			else
@@ -313,8 +322,11 @@
 				for(int i=0; i<sel.length; i++)
 					comm.sendInput(inputField.getText(),comm.buildSelectionPath(sel[i]));
 			*/
-      inputFieldHistory.add(inputField.getText());
-      inputFieldLocation=inputFieldHistory.size();
+			
+			if(!inputFieldHistory.get(inputFieldHistory.size()-1).equals(inputField.getText())) {
+				inputFieldHistory.add(inputField.getText());
+			}
+			inputFieldLocation=inputFieldHistory.size();
 			inputField.setText("");
 		} else if(evt.getSource()==reconnectBut) {
 			int port=comm._port;
@@ -331,6 +343,42 @@
 			comm.needConnection();
 			estop.close();
 			estop.open();
+		} else if(evt.getActionCommand().equals("CameraSketchSpace")) {
+			if(cameraSkGUI==null || !cameraSkGUI.isDisplayable()) {
+				org.tekkotsu.sketch.SketchGUI.Space _space = org.tekkotsu.sketch.SketchGUI.Space.cam;
+				int _listingPort = 5800;
+				int _sketchPort = 5801;
+				cameraSkGUI = new org.tekkotsu.sketch.SketchGUI(comm._host, _listingPort, _sketchPort, _space);
+				cameraSkGUI.setDefaultCloseOperation(DISPOSE_ON_CLOSE);
+				cameraSkGUI.setVisible(true);
+			} else {
+				cameraSkGUI.close();
+				cameraSkGUI=null;
+			}
+		} else if(evt.getActionCommand().equals("LocalSketchSpace")) {
+			if(localSkGUI==null || !localSkGUI.isDisplayable()) {
+				org.tekkotsu.sketch.SketchGUI.Space _space = org.tekkotsu.sketch.SketchGUI.Space.local;
+				int _listingPort = 5802;
+				int _sketchPort = 5803;
+				localSkGUI = new org.tekkotsu.sketch.SketchGUI(comm._host, _listingPort, _sketchPort, _space);
+				localSkGUI.setDefaultCloseOperation(DISPOSE_ON_CLOSE);
+				localSkGUI.setVisible(true);
+			} else {
+				localSkGUI.close();
+				localSkGUI=null;
+			}
+		} else if(evt.getActionCommand().equals("WorldSketchSpace")) {
+			if(worldSkGUI==null || !worldSkGUI.isDisplayable()) {
+				org.tekkotsu.sketch.SketchGUI.Space _space = org.tekkotsu.sketch.SketchGUI.Space.world;
+				int _listingPort = 5804;
+				int _sketchPort = 5805;
+				worldSkGUI = new org.tekkotsu.sketch.SketchGUI(comm._host, _listingPort, _sketchPort, _space);
+				worldSkGUI.setDefaultCloseOperation(DISPOSE_ON_CLOSE);
+				worldSkGUI.setVisible(true);
+			} else {
+				worldSkGUI.close();
+				worldSkGUI=null;
+			}
 		} else if(evt.getActionCommand().equals("raw") || evt.getActionCommand().equals("rle") || evt.getActionCommand().equals("reg")) {
 			if(evt.getActionCommand().equals("raw")) {
 				comm.sendInput("!root \"TekkotsuMon\" \"Raw Cam Server\"");
@@ -416,7 +464,6 @@
 	protected void init() {
 		int spacer_size=10;
 	
-		setTitle("TekkotsuMon: Controller Menus");
 		getContentPane().setLayout(new BorderLayout());
 		getContentPane().add(Box.createHorizontalStrut(spacer_size),BorderLayout.WEST);
 		getContentPane().add(Box.createHorizontalStrut(spacer_size),BorderLayout.EAST);
@@ -546,6 +593,33 @@
 		
 		p.add(Box.createVerticalStrut(spacer_size));
 		{
+			Box tmp=Box.createHorizontalBox();
+			tmp.add(new JLabel("Sketch: "));
+			JButton but;
+		 	but=new JButton("C");
+			but.setToolTipText("Display Camera Sketch Space");
+			but.addActionListener(this);
+			but.setActionCommand("CameraSketchSpace");
+			but.setPreferredSize(new Dimension(35,22));
+			tmp.add(but);
+		 	but=new JButton("L");
+			but.setToolTipText("Display Local Sketch Space");
+			but.addActionListener(this);
+			but.setActionCommand("LocalSketchSpace");
+			but.setPreferredSize(new Dimension(35,22));
+			tmp.add(but);
+		 	but=new JButton("W");
+			but.setToolTipText("Display World Sketch Space");
+			but.addActionListener(this);
+			but.setActionCommand("WorldSketchSpace");
+			but.setPreferredSize(new Dimension(35,22));
+			tmp.add(but);
+			tmp.setAlignmentX(0.0f);
+			p.add(tmp);
+		}
+		
+		p.add(Box.createVerticalStrut(spacer_size));
+		{
 			JSeparator sep=new JSeparator(SwingConstants.HORIZONTAL);
 			sep.setMaximumSize(new Dimension(sep.getMaximumSize().width,spacer_size));
 			p.add(sep);
@@ -599,10 +673,17 @@
 		addWindowListener(new CloseVisionAdapter(this));
 
 		setLocation(prefs.getInt("ControllerGUI.location.x",50),prefs.getInt("ControllerGUI.location.y",50));
-		int numScripts=prefs.getInt("ControllerGUI.numScripts",0);
-		for(int i=0; i<numScripts; i++)
-			scriptsModel.addElement(new ScriptEntry(prefs.get("ControllerGUI.script"+i+".title","unknown"),prefs.get("ControllerGUI.script"+i+".cmd","")));
-
+		int numScripts=prefs.getInt("ControllerGUI.numScripts",-1);
+		if(numScripts>-1) {
+			for(int i=0; i<numScripts; i++)
+				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("Head Remote Control","!root \"TekkotsuMon\" \"Head Remote Control\""));
+			scriptsModel.addElement(new ScriptEntry("Walk Remote Control","!root \"TekkotsuMon\" \"Walk Remote Control\""));
+		}
 		pack();
 		title.setMaximumSize(new Dimension(15+25,title.getHeight()));
 		setVisible(true);
@@ -680,14 +761,20 @@
       int key=e.getKeyCode();
       if (key==KeyEvent.VK_UP || key==KeyEvent.VK_KP_UP) {
         inputFieldLocation--;
-        if (inputFieldLocation < 0)
-          inputFieldLocation+=inputFieldHistory.size();
+        if (inputFieldLocation < 0) {
+          java.awt.Toolkit.getDefaultToolkit().beep();
+          inputFieldLocation=0;
+        }
         inputField.setText((String)inputFieldHistory.get(inputFieldLocation));
       } else if (key==KeyEvent.VK_DOWN || key==KeyEvent.VK_KP_DOWN) {
         inputFieldLocation++;
-        if (inputFieldLocation >= inputFieldHistory.size())
-          inputFieldLocation-=inputFieldHistory.size();
-        inputField.setText((String)inputFieldHistory.get(inputFieldLocation));
+        if (inputFieldLocation == inputFieldHistory.size()) {
+          inputField.setText("");
+        } else if (inputFieldLocation > inputFieldHistory.size()) {
+          java.awt.Toolkit.getDefaultToolkit().beep();
+          inputFieldLocation=inputFieldHistory.size();
+        } else
+          inputField.setText((String)inputFieldHistory.get(inputFieldLocation));
       }
     }
   }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/ControllerListener.java ./tools/mon/org/tekkotsu/mon/ControllerListener.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/ControllerListener.java	2005-06-10 15:15:25.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/ControllerListener.java	2006-08-08 16:12:54.000000000 -0400
@@ -205,7 +205,7 @@
 							_titles.add(readLine(sin));
 						if(!_isConnected) break;
 					} else if(msgtype.equals("goodbye")) {
-						//removeDynObjs();
+						//closeDynObjs();
 						System.out.println("Remote is shutting down.");
 					} else if(msgtype.equals("reset")) {
 						_menus.clear();
@@ -248,20 +248,22 @@
 							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;
-								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(_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);
+								}
 							}
 						}
 					} else if(msgtype.equals("close")) {
@@ -329,7 +331,20 @@
 		dynObjPorts.clear();
 		dynObjSrcs.clear();
 	}
- 
+	
+	public void closeDynObjs() {
+		Iterator it=dynObjs.values().iterator();
+		while(it.hasNext()) {
+			Object obj=it.next();
+			try {
+				Method m=obj.getClass().getMethod("close",(java.lang.Class[])null);
+				m.invoke(obj,(java.lang.Object[])null);
+			} catch(Exception ex) {}
+		}
+		dynObjs.clear();
+		dynObjPorts.clear();
+	}
+	
 	public boolean hasData() {
 		return _updatedFlag;
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/EStopButton.java ./tools/mon/org/tekkotsu/mon/EStopButton.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/EStopButton.java	2005-08-02 17:33:36.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/EStopButton.java	2006-03-03 13:21:04.000000000 -0500
@@ -53,7 +53,7 @@
 		setEnabled(mode!=DISABLED_MODE);
 		comm.addUpdatedListener(this);
 		
-		setToolTipText("Toggle Emergency Stop; alt-click to open new window");
+		setToolTipText("Toggle Emergency Stop; middle-click (or alt-click) to open into new window");
 		enableEvents(AWTEvent.MOUSE_EVENT_MASK);
 
 		updateStatus();
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/EStopPanel.java ./tools/mon/org/tekkotsu/mon/EStopPanel.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/EStopPanel.java	2005-08-02 17:33:36.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/EStopPanel.java	2006-02-28 13:00:49.000000000 -0500
@@ -10,7 +10,7 @@
 import java.awt.event.MouseEvent;
 import java.awt.event.InputEvent;
 
-public class EStopPanel extends JPanel implements EStopListener.UpdatedListener {
+public class EStopPanel extends JPanel implements EStopListener.UpdatedListener, Listener.ConnectionListener {
 	EStopListener comm;
 	int mode;
 	static final int STOPPED_MODE=0;
@@ -148,7 +148,7 @@
 	}
 	
 	public void close() {
-		comm.kill();
+		comm.close();
 		remove();
 	}
 	
@@ -158,7 +158,6 @@
 	
 	public void open() {
 		comm.addUpdatedListener(this);
-		comm.startThread();
 	}
 
 	public void estopUpdated(EStopListener l) {
@@ -173,6 +172,13 @@
 		repaint();
 	}
 	
+	public void onConnected() {
+		estopUpdated(comm);
+	}
+	public void onDisconnected() {
+		estopUpdated(comm);
+	}
+
 	public void processMouseEvent(MouseEvent e) {
 		if(e.getID()==MouseEvent.MOUSE_RELEASED) {
 			if((e.getModifiersEx()&InputEvent.ALT_DOWN_MASK)!=0) {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/HeadPointGUI.java ./tools/mon/org/tekkotsu/mon/HeadPointGUI.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/HeadPointGUI.java	2005-01-21 18:31:39.000000000 -0500
+++ ./tools/mon/org/tekkotsu/mon/HeadPointGUI.java	2006-08-30 18:17:10.000000000 -0400
@@ -14,9 +14,9 @@
 	JSlider pslide;
 	JSlider rslide;
 	JButton stopBut;
-	JRadioButton horizRollBut;
-	JRadioButton horizPanBut;
-	boolean horizButFake=false;
+	JRadioButton vertNodBut;
+	JRadioButton vertTiltBut;
+	boolean vertButFake=false;
 	JCheckBox resetOnRelease;
 	JLabel status;
 	JButton reconnectBut;
@@ -77,18 +77,18 @@
 
 	public void pointPicked(Point2D.Float p, MouseEvent e, PointPick pp) {
 		boolean isBut2=(e.getModifiersEx()&MouseEvent.BUTTON3_DOWN_MASK)==MouseEvent.BUTTON3_DOWN_MASK;
-		if(!horizButFake && isBut2) {
-			if(horizPanBut.isSelected())
-				horizRollBut.setSelected(true);
+		if(!vertButFake && isBut2) {
+			if(vertTiltBut.isSelected())
+				vertNodBut.setSelected(true);
 			else
-				horizPanBut.setSelected(true);
-			horizButFake=isBut2;
+				vertTiltBut.setSelected(true);
+			vertButFake=isBut2;
 		}
-		if(horizRollBut.isSelected())
-			rslide.setValue((int)(slidermax*p.x));
-		if(horizPanBut.isSelected())
-			pslide.setValue((int)(slidermax*p.x));
-		tslide.setValue((int)(slidermax*p.y));
+		if(vertNodBut.isSelected())
+			rslide.setValue((int)(slidermax*p.y));
+		if(vertTiltBut.isSelected())
+			tslide.setValue((int)(slidermax*p.y));
+		pslide.setValue((int)(slidermax*p.x));
 	}
 
 	public void headPointUpdated(HeadPointListener comm) {
@@ -110,24 +110,24 @@
 	public void mouseExited(MouseEvent e) {}
 	public void mousePressed(MouseEvent e) {
 		boolean isBut2=(e.getModifiersEx()&MouseEvent.BUTTON3_DOWN_MASK)==MouseEvent.BUTTON3_DOWN_MASK;
-		if(!horizButFake && isBut2) {
-			if(horizPanBut.isSelected())
-				horizRollBut.setSelected(true);
+		if(!vertButFake && isBut2) {
+			if(vertTiltBut.isSelected())
+				vertNodBut.setSelected(true);
 			else
-				horizPanBut.setSelected(true);
-			horizButFake=isBut2;
+				vertTiltBut.setSelected(true);
+			vertButFake=isBut2;
 			updatePP();
 		}
 	}
 	public void mouseReleased(MouseEvent e) {
 		boolean isBut1=(e.getModifiersEx()&MouseEvent.BUTTON1_DOWN_MASK)==MouseEvent.BUTTON1_DOWN_MASK;
 		boolean isBut2=(e.getModifiersEx()&MouseEvent.BUTTON3_DOWN_MASK)==MouseEvent.BUTTON3_DOWN_MASK;
-		if(horizButFake && !isBut2) {
-			if(horizPanBut.isSelected())
-				horizRollBut.setSelected(true);
+		if(vertButFake && !isBut2) {
+			if(vertTiltBut.isSelected())
+				vertNodBut.setSelected(true);
 			else
-				horizPanBut.setSelected(true);
-			horizButFake=isBut2;
+				vertTiltBut.setSelected(true);
+			vertButFake=isBut2;
 			updatePP();
 		}
 		if(!isBut1 && !isBut2) {
@@ -139,18 +139,18 @@
 	public void stateChanged(ChangeEvent e) {
 		if(e.getSource()==tslide) {
 			comm.sendCommand("t",tslide.getValue()/(float)slidermax);
-			pp.doSetPoint(pp.getXValue(),tslide.getValue()/(float)slidermax);
+			if(vertTiltBut.isSelected())
+				pp.doSetPoint(pp.getXValue(),tslide.getValue()/(float)slidermax);
 		} else if(e.getSource()==pslide) {
 			comm.sendCommand("p",-pslide.getValue()/(float)slidermax);
-			if(horizPanBut.isSelected())
-				pp.doSetPoint(pslide.getValue()/(float)slidermax,pp.getYValue());
+			pp.doSetPoint(pslide.getValue()/(float)slidermax,pp.getYValue());
 		} else if(e.getSource()==rslide) {
 			// Rotation is both fast and sensitive, so we'll exponentiate it to
 			// drag out the low end without sacrificing the high end
 			comm.sendCommand("r",rslide.getValue()/(float)slidermax);
 			float tmp=pp.getYValue();
-			if(horizRollBut.isSelected())
-				pp.doSetPoint(rslide.getValue()/(float)slidermax,pp.getYValue());
+			if(vertNodBut.isSelected())
+				pp.doSetPoint(pp.getXValue(),rslide.getValue()/(float)slidermax);
 		}
 	}
 
@@ -159,9 +159,9 @@
 			tslide.setValue(0);
 			pslide.setValue(0);
 			rslide.setValue(0);
-		} else if(e.getSource()==horizRollBut) {
+		} else if(e.getSource()==vertNodBut) {
 			updatePP();
-		} else if(e.getSource()==horizPanBut) {
+		} else if(e.getSource()==vertTiltBut) {
 			updatePP();
 		} else if(e.getSource()==reconnectBut) {
 			int port=comm._port;
@@ -174,12 +174,12 @@
 	}
 	
 	public void updatePP() {
-		float x=0;
-		if(horizPanBut.isSelected())
-			x=pslide.getValue()/(float)slidermax;
-		else if(horizRollBut.isSelected())
-			x=rslide.getValue()/(float)slidermax;
-		pp.doSetPoint(x,tslide.getValue()/(float)slidermax);
+		float y=0;
+		if(vertTiltBut.isSelected())
+			y=tslide.getValue()/(float)slidermax;
+		else if(vertNodBut.isSelected())
+			y=rslide.getValue()/(float)slidermax;
+		pp.doSetPoint(pslide.getValue()/(float)slidermax,y);
 	}
 
 	public void frameInit() {
@@ -252,19 +252,19 @@
 				tmp2.add(tmp3);
 			}
 			tmp2.add(Box.createVerticalStrut(strutsize));
-			tmp2.add(new JLabel("Roll:"));
+			tmp2.add(new JLabel("Nod:"));
 			{
 				Box tmp3=Box.createHorizontalBox();
 				rslide=new JSlider(-slidermax,slidermax,0);
 				rslide.addChangeListener(this);
 				JLabel lab;
-				lab=new JLabel("Counter");
+				lab=new JLabel("Down");
 				lab.setFont(lab.getFont().deriveFont(lab.getFont().getSize2D()-2));
 				lab.setHorizontalAlignment(SwingConstants.RIGHT);
 				lab.setPreferredSize(new Dimension(labwidth,lab.getFont().getSize()));
 				tmp3.add(lab);
 				tmp3.add(rslide);
-				lab=new JLabel("Clock");
+				lab=new JLabel("Up");
 				lab.setFont(lab.getFont().deriveFont(lab.getFont().getSize2D()-2));
 				lab.setHorizontalAlignment(SwingConstants.LEFT);
 				lab.setPreferredSize(new Dimension(labwidth,lab.getFont().getSize()));
@@ -287,15 +287,15 @@
 			}
 			tmp2.add(Box.createVerticalStrut(strutsize));
 			ButtonGroup bg = new ButtonGroup();
-			horizPanBut=new JRadioButton("Horizontal is Pan");
-			horizPanBut.addActionListener(this);
-			horizPanBut.setSelected(true);
-			bg.add(horizPanBut);
-			tmp2.add(horizPanBut);
-			horizRollBut=new JRadioButton("Horizontal is Roll");
-			horizRollBut.addActionListener(this);
-			bg.add(horizRollBut);
-			tmp2.add(horizRollBut);
+			vertTiltBut=new JRadioButton("Vertical is Tilt");
+			vertTiltBut.addActionListener(this);
+			bg.add(vertTiltBut);
+			tmp2.add(vertTiltBut);
+			vertNodBut=new JRadioButton("Vertical is Nod");
+			vertNodBut.addActionListener(this);
+			bg.add(vertNodBut);
+			tmp2.add(vertNodBut);
+			vertNodBut.setSelected(true);
 			tmp2.add(Box.createVerticalStrut(strutsize));
 			tmp2.add(resetOnRelease=new JCheckBox("Center on release")); 
 			tmp2.add(Box.createVerticalGlue());
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/HeadPointListener.java ./tools/mon/org/tekkotsu/mon/HeadPointListener.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/HeadPointListener.java	2005-06-22 16:06:17.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/HeadPointListener.java	2006-03-31 13:50:41.000000000 -0500
@@ -40,8 +40,10 @@
     mysock = socket;
     try {
 			mysock.setTcpNoDelay(true);
+		 try {
 			mysock.setTrafficClass(0x10);
-      out = mysock.getOutputStream();
+		 } catch(SocketException e) {}
+			out = mysock.getOutputStream();
 			InputStream sin=socket.getInputStream();
 			fireHeadPointUpdated();
 			fireConnected();
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/ImageSequenceWriterThread.java ./tools/mon/org/tekkotsu/mon/ImageSequenceWriterThread.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/ImageSequenceWriterThread.java	2004-01-20 15:05:31.000000000 -0500
+++ ./tools/mon/org/tekkotsu/mon/ImageSequenceWriterThread.java	2006-06-26 12:32:50.000000000 -0400
@@ -26,14 +26,21 @@
 	boolean stopping=false;
 	JButton but;
 	boolean isYUVMode;
+	boolean savePositions;
 
-	public ImageSequenceWriterThread(VisionListener l, JButton reenableBut, boolean YUVmode) {
+	final static int JPEG_ENTRY=1;
+	final static int IMGBUF_ENTRY=2;
+	final static int POSITION_ENTRY=3;
+
+	public ImageSequenceWriterThread(VisionListener l, JButton reenableBut, boolean YUVmode, boolean positions) {
 		super("ImageSequenceWriter");
 		isYUVMode=YUVmode;
-		int initbufsize=250;
+		int initbufsize=50;
 		but=reenableBut;
+		savePositions=positions;
 		listen=l;
 		l.addListener(this);
+		l.startSensors();
 		BufferedImage i=l.getImage();
 		if(i.getColorModel().getTransferType()!=DataBuffer.TYPE_BYTE)
 			for(int j=0;j<initbufsize;j++)
@@ -65,13 +72,74 @@
 		else
 			push(l.getImage(),l.getTimeStamp(),l.getFrameNum());
 	}
+	public void sensorsUpdated(VisionListener l) {
+		//System.out.println("Sensors: "+savePositions);
+		if(savePositions) {
+			synchronized(q) {
+				String s=new String(l.getSensors());
+				Date t;
+				long frameNum;
+				if(!s.startsWith("#POS")) {
+					System.err.println("Malformed sensor reading");
+					return;
+				}
+				//want to extract the timestamp and frame number,
+				//but I don't really want to rewrite the file parsing in Java...
+				//so this is a bit hackish, but should be reasonable
+				int metaoff=s.lastIndexOf("<meta-info>"); //verbose mode
+				if(metaoff!=-1) {
+					int timeoff=s.indexOf("timestamp",metaoff);
+					if(timeoff==-1) {
+						System.err.println("Could not read meta-info timestamp in sensor dump");
+						return;
+					}
+					timeoff+=9;
+					int timeend=timeoff;
+					while(s.charAt(timeend)!='\r' && s.charAt(timeend)!='\n')
+						timeend++;
+					t=new Date(Long.parseLong(s.substring(timeoff,timeend).trim()));
+					
+					int frameoff=s.indexOf("framenumber",metaoff);
+					if(frameoff==-1) {
+						System.err.println("Could not read meta-info frame info in sensor dump");
+						return;
+					}
+					frameoff+=11;
+					int frameend=frameoff;
+					while(s.charAt(frameend)!='\r' && s.charAt(frameend)!='\n')
+						frameend++;
+					frameNum=Long.parseLong(s.substring(frameoff,frameend).trim());
+				} else {
+					metaoff=s.lastIndexOf("meta-info"); //condensed mode
+					if(metaoff==-1) {
+						System.err.println("Could not find meta-info section in sensor dump");
+						return;
+					}
+					metaoff+=9;
+					while(s.charAt(metaoff)!='=')
+						metaoff++;
+					metaoff++;
+					int metaend=metaoff;
+					while(s.charAt(metaend)!='\r' && s.charAt(metaend)!='\n')
+						metaend++;
+					String[] sa=s.substring(metaoff,metaend).trim().split(" ");
+					t=new Date(Long.parseLong(sa[0]));
+					frameNum=Long.parseLong(sa[1]);
+				}
+				q.addLast(new Integer(POSITION_ENTRY));
+				q.addLast(s);
+				q.addLast(t);
+				q.addLast(new Long(frameNum));
+			}
+		}
+	}
 
 	public void push(byte[] jpeg, int len, Date t, long frameNum) {
 		byte[] jpegcopy = new byte[len];
 		for(int i=0; i<len; i++)
 			jpegcopy[i]=jpeg[i];
 		synchronized(q) {
-			q.addLast(new Boolean(true));
+			q.addLast(new Integer(JPEG_ENTRY));
 			q.addLast(jpegcopy);
 			q.addLast(t);
 			q.addLast(new Long(frameNum));
@@ -88,9 +156,11 @@
 			else
 				i2=new BufferedImage(i.getWidth(),i.getHeight(),i.getType(),(IndexColorModel)i.getColorModel());
 		}
-		i.copyData(i2.getRaster());
+		synchronized(i) {
+			i.copyData(i2.getRaster());
+		}
 		synchronized(q) {
-			q.addLast(new Boolean(false));
+			q.addLast(new Integer(IMGBUF_ENTRY));
 			q.addLast(i2);
 			q.addLast(t);
 			q.addLast(new Long(frameNum));
@@ -105,6 +175,7 @@
 		} catch(Exception ex) { ex.printStackTrace(); return; }
 		Date start=null;
 		long startFrame=0;
+		long startSensor=0;
 		try {
 			while(true) {
 				while(q.size()>0) {
@@ -121,29 +192,36 @@
 							break;
 						}
 					}
-					BufferedImage i;
-					byte[] jpeg;
+					BufferedImage i=null;
+					byte[] jpeg=null;
+					String sensors=null;
 					Date t;
 					long num;
+					int entryType;
 					synchronized(q) {
-						if(((Boolean)q.removeFirst()).booleanValue()) { //is a jpeg
+						entryType=((Integer)q.removeFirst()).intValue();
+						if(entryType==JPEG_ENTRY) { //is a jpeg
 							jpeg=(byte[])q.removeFirst();
-							i=null;
-						} else {
+						} else if(entryType==IMGBUF_ENTRY) { //is a BufferedImage
 							i=(BufferedImage)q.removeFirst();
-							jpeg=null;
+						} else if(entryType==POSITION_ENTRY) { //is a sensor reading
+							sensors=(String)q.removeFirst();;
 						}
 						t=(Date)q.removeFirst();
 						num=((Long)q.removeFirst()).longValue();
 					}
 					if(start==null) {
+						if(entryType==POSITION_ENTRY)
+							continue;
 						start=t;
 						startFrame=num;
 						log.println("First frame "+startFrame+" timestamp: "+start.getTime());
 					}
+					if(startSensor==0 && entryType==POSITION_ENTRY)
+						startSensor=num;
 					long dt=t.getTime()-start.getTime();
-					long df=num-startFrame;
-					String name=getFileName(dt,df);
+					long df=num-(entryType==POSITION_ENTRY?startSensor:startFrame);
+					String name=getFileName(dt,df,sensors!=null);
 					if(log!=null)
 						log.println(name+"\t"+count+"\t"+df+"\t"+dt);
 					FileOutputStream fileout=new FileOutputStream(dir+name);
@@ -152,6 +230,8 @@
 						imgBufs.addLast(i);
 					} else if(jpeg!=null) {
 						fileout.write(jpeg);
+					} else if(sensors!=null) {
+						fileout.write(sensors.getBytes());
 					}
 					count++;
 				}
@@ -161,9 +241,10 @@
 			}
 		} catch(Exception ex) {
 			listen.removeListener(this);
-			if((InterruptedException)ex==null)
+			if(!(ex instanceof InterruptedException))
 				ex.printStackTrace();
 		}
+		listen.stopSensors();
 		if(log!=null)
 			log.close();
 		if(but!=null && tmp!=null) {
@@ -173,7 +254,7 @@
 		}
 	}
 
-	protected String getFileName(long dt,long num) {
+	protected String getFileName(long dt,long num,boolean isSensor) {
 		String ans=pre;
 		long c=num;
 		int digits=dig;
@@ -185,7 +266,7 @@
 			ans+=c/s;
 			c-=(c/s)*s;
 		}
-		ans+=post+"."+fmt;
+		ans+=post+"."+(isSensor?"pos":fmt);
 		return ans;
 	}
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/Joints.java ./tools/mon/org/tekkotsu/mon/Joints.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/Joints.java	2004-04-16 01:51:29.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/Joints.java	2005-09-13 18:09:54.000000000 -0400
@@ -1,14 +1,19 @@
 package org.tekkotsu.mon;
 
+//'Joints' is something of a misnomer -- also stores sensor and button information as well
 public class Joints {
+	public String model;
   public float[] positions;
   public float[] duties;
   public float[] sensors;
   public float[] buttons;
-  int timestamp;
+  public long timestamp;
+	public long frame;
 
   Joints() {
-      //note: this is old and for the ers2xx, but, eh. doesn't hurt to leave like this
+		//note: this is old and for the ers2xx, but, eh. doesn't hurt to leave like this
+		//each packet holds correct number of items for each category, so these
+		//can be reassigned with the correct number of items for the model in question
     positions=new float[18];
     duties=new float[18];
     sensors=new float[10];
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/LGClient.java ./tools/mon/org/tekkotsu/mon/LGClient.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/LGClient.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/org/tekkotsu/mon/LGClient.java	2006-04-06 16:55:55.000000000 -0400
@@ -0,0 +1,218 @@
+package org.tekkotsu.mon;
+
+import java.io.*;
+import java.net.*;
+import java.util.*;
+import javax.swing.*;
+import java.awt.*;
+import javax.swing.text.*; 
+import java.awt.event.*; 
+import java.io.File; 
+import java.lang.*;
+import java.lang.Object.*;
+import sun.audio.*;
+import javax.sound.sampled.*;
+import javax.sound.sampled.spi.*;
+//import javax.sound.sampled.spi.AudioFileReader.*;
+//import javax.sound.sampled.spi.AudioFileWriter.*;
+
+public class LGClient extends JFrame {
+	private static JEditorPane jep;	   
+	final static JLabel statusBar = new JLabel(" ");
+	final static String tmpPath="/tmp/LGwww-"+System.getProperty("user.name","unknown_user");
+
+	public LGClient(){
+
+	}
+
+	public LGClient(String file){
+		super("LGClient");
+		setSize(1280,1024); 
+		setDefaultCloseOperation(EXIT_ON_CLOSE); 
+		JPanel urlPanel = new JPanel(); 
+		urlPanel.setLayout(new BorderLayout()); 
+		JTextField urlField = new JTextField(file);
+		urlPanel.add(new JLabel("Site: "), BorderLayout.WEST); 
+		urlPanel.add(urlField, BorderLayout.CENTER); 
+		
+		jep = new JEditorPane(); 
+		jep.setEditable(false); 
+		jep.setContentType("text/html");
+		 
+		try { 
+			jep.setPage(file);
+		} 
+		catch(Exception e) { 
+			statusBar.setText("Could not open starting page.  Using a blank."); 
+		} 
+
+		JScrollPane jsp = new JScrollPane(jep); 
+		getContentPane().add(jsp, BorderLayout.CENTER); 
+		getContentPane().add(urlPanel, BorderLayout.NORTH); 
+		getContentPane().add(statusBar, BorderLayout.SOUTH); 
+	
+		// and last but not least, hook up our event handlers 
+		urlField.addActionListener(new ActionListener() { 
+				public void actionPerformed(ActionEvent ae) { 
+					try { 
+						jep.setPage(ae.getActionCommand()); 
+					} 
+					catch(Exception e) { 
+						statusBar.setText("Error: " + e.getMessage()); 
+					} 
+				} 
+			}); 
+		jep.addHyperlinkListener(new SimpleLinkListener1(jep, urlField, 
+														 statusBar));	 
+	}
+	
+	public StringBuffer readLine(InputStream inputS){
+		StringBuffer lineReader = new StringBuffer();
+		int curr;
+		try{
+			while((curr = inputS.read()) != '\n'){
+				if(curr == -1)
+					return null;
+				else
+					lineReader.append((char)curr);
+			}
+		}
+		catch(IOException e){
+			System.exit(-1);
+		}
+		return lineReader;
+	}
+
+	public static void main(String[] args) throws IOException {
+		
+		Socket sock = null;
+		PrintWriter out = null;
+		InputStream in = null;
+		boolean test = true;
+		InputStream fis=  null;
+		AudioStream as = null;
+
+		try {
+			sock = new Socket(args[0], 10100);
+			out = new PrintWriter(sock.getOutputStream(), true);
+			in = sock.getInputStream();
+		} catch (UnknownHostException e) {
+			System.err.println("Don't know about host: "+args[0]);
+			System.exit(1);
+		} catch (IOException e) {
+			System.err.println("Couldn't get I/O for the connection to: "+args[0]);
+			System.exit(1);
+		}
+		BufferedReader stdIn = new BufferedReader(new InputStreamReader(System.in));
+		BufferedWriter bw = null;
+		StringBuffer line;
+		(new File(tmpPath)).mkdir();
+		LGClient lgc = new LGClient();
+		
+		while ((line = lgc.readLine(in)) != null) {
+			StringTokenizer t = new StringTokenizer(line.toString());
+			try{
+				if(t.hasMoreTokens()){
+					String st = t.nextToken();
+					if(st.equals("UPLOAD_HTML")){
+						String filename = t.nextToken();
+						StringBuffer line2 = null;
+						bw = new BufferedWriter(new FileWriter(tmpPath+"/" + filename));
+						while(!((line2 = lgc.readLine(in)).toString()).toUpperCase().equals("</HTML>")){
+							bw.write(line2.toString(),0,(line2.toString()).length());
+							bw.newLine();
+						}
+						if((line2.toString()).toUpperCase().equals("<HTML>"))
+							bw.write(line2.toString(),0,(line2.toString()).length());
+						bw.close();
+					}
+					if(st.equals("UPLOAD_AUDIO")){
+						String filename = t.nextToken();
+						String newFilename = t.nextToken();
+						
+						try{
+							File f = new File(tmpPath+"/" + newFilename);
+							URL url = new URL(filename);
+							AudioInputStream ais = AudioSystem.getAudioInputStream(url);
+							AudioSystem.write(ais,AudioFileFormat.Type.WAVE,f);
+							ais.close();
+						}
+						catch(UnsupportedAudioFileException e){
+							System.err.println("Unsupported Audio File: "+ filename);
+							System.exit(1);
+						}
+						
+					}
+					if(st.equals("UPLOAD_BINARY")){
+						String filename = t.nextToken();
+						int bytecount=Integer.parseInt(t.nextToken());
+						FileOutputStream os = new FileOutputStream(tmpPath+"/" + filename);
+						byte[] bytes = new byte[bytecount];
+														
+						for(int i=0; i<bytecount; i++) {
+							int b = in.read(); 
+							bytes[i]= (byte)b;
+						}
+						os.write(bytes,0,bytecount);
+						os.close();
+					}
+					if(st.equals("DISPLAY")){
+						String filename = t.nextToken();
+						if (!(filename.startsWith("file:"))) {
+							// If it's not a fully qualified url, assume it's a file
+							if (filename.startsWith("/")) {
+								// Absolute path, so just prepend "file:"
+								filename = "file:" + filename;
+							}
+							else {
+								try {
+									// assume it's relative to the starting point...
+									File f = new File(tmpPath+"/" + filename);
+									filename = f.toURL().toString();
+								}
+								catch (Exception e) {
+									filename = "http://www-2.cs.cmu.edu/afs/cs.cmu.edu/project/skinnerbots/LookingGlass/";
+								}
+							}
+						}
+						else {
+							filename = "http://www-2.cs.cmu.edu/afs/cs.cmu.edu/project/skinnerbots/LookingGlass/";
+						}
+						try { 
+							if(test)
+								new LGClient(filename).setVisible(true);
+							else {
+								jep.setText("<html><head> <title> blank </title> </head> <body> </body> </html>");
+								jep.setPage(filename); 
+							}
+						} 
+						catch(Exception e) { 
+							statusBar.setText("Could not open starting page.  Using a blank."); 
+						}		
+						test = false;
+					}
+					if(st.equals("PLAY")){
+						File f = new File(t.nextToken());
+						fis = new FileInputStream(tmpPath+"/" + f);
+						as = new AudioStream(fis);
+						AudioPlayer.player.start(as);
+					}
+					if(st.equals("STOP")){
+						File f = new File(t.nextToken());
+						if(as != null)
+							AudioPlayer.player.stop(as);
+						else
+							System.out.println("Cannot close file:" + f.toString());
+					}
+				}
+			}
+			catch(NumberFormatException e){
+				System.out.println("Corrupted data. "+line + " is ignored...");
+			} 
+		}
+		out.close();
+		in.close();
+		stdIn.close();
+		sock.close();
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/Listener.java ./tools/mon/org/tekkotsu/mon/Listener.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/Listener.java	2005-08-05 15:44:23.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/Listener.java	2006-08-02 17:15:53.000000000 -0400
@@ -149,6 +149,7 @@
 		} else {
 			System.out.println("can't start Listener without [host],port");
 		}
+		_listenerThread=null;
 	}
 
 	public void kill() {
@@ -210,6 +211,13 @@
 		return (b2i(buf[3])<<24) | (b2i(buf[2])<<16) |
 					 (b2i(buf[1])<< 8) | b2i(buf[0]);
 	}
+
+	public long readUnsignedInt(InputStream in) throws IOException {
+		long ans=readInt(in);
+		if(ans<0)
+			ans+=(1L<<32);
+		return ans;
+	}
 	
 	public short readShort(InputStream in) throws IOException {
 		int read=0;
@@ -285,7 +293,10 @@
 		if (isReadWriteCountersEnabled()) {
 			bytesRead++;
 		}
-		return (char)in.read();
+		int c=in.read();
+		if(c==-1)
+			_isConnected=false;
+		return (char)c;
 	}
 
 	public void writeChar(OutputStream out, char c) throws IOException {
@@ -306,13 +317,13 @@
 		while(c!='\n') {
 			sbuf.append(c);
 			x=in.read();
-			if (isReadWriteCountersEnabled()) {
-				bytesRead++;
-			}
 			if(x==-1) {
 				_isConnected=false;
 				return sbuf.toString();
 			}
+			if (isReadWriteCountersEnabled()) {
+				bytesRead++;
+			}
 			c=(char)x;
 		}
 		return sbuf.toString();
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/SimpleLinkListener1.java ./tools/mon/org/tekkotsu/mon/SimpleLinkListener1.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/SimpleLinkListener1.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/org/tekkotsu/mon/SimpleLinkListener1.java	2006-03-30 13:00:06.000000000 -0500
@@ -0,0 +1,68 @@
+package org.tekkotsu.mon;
+
+import java.awt.*;
+import java.awt.event.*;
+import java.io.*;
+import java.util.*;
+import javax.swing.*;
+import javax.swing.event.*;
+import javax.swing.text.*;
+import javax.swing.text.html.*;
+
+
+public class SimpleLinkListener1 implements HyperlinkListener {
+    private JEditorPane pane;        // The pane we're using to display HTML
+    private JTextField urlField;     // An optional text field for showing
+    // the current URL being displayed
+    private JLabel statusBar;        // An optional label for showing where
+    // a link would take you
+    public SimpleLinkListener1(JEditorPane jep, JTextField jtf, JLabel jl) {
+	pane = jep;
+	urlField = jtf;
+	statusBar = jl;
+    }
+    public SimpleLinkListener1(JEditorPane jep) {
+    this(jep, null, null);
+    }
+    public void hyperlinkUpdate(HyperlinkEvent he) {
+	HyperlinkEvent.EventType type = he.getEventType();
+    if (type == HyperlinkEvent.EventType.ENTERED) {
+	// Enter event. Fill in the status bar
+	if (statusBar != null) {
+	    statusBar.setText(he.getURL().toString());
+	}
+    }
+    else if (type == HyperlinkEvent.EventType.EXITED) {
+	// Exit event. Clear the status bar
+	if (statusBar != null) {
+	    statusBar.setText(" "); // must be a space or it disappears
+	}
+    }
+    else {
+	// Jump event. Get the url, and if it's not null, switch to that
+	// page in the main editor pane and update the "site url" label.
+	if (he instanceof HTMLFrameHyperlinkEvent) {
+	    // ahh, frame event, handle this separately
+	    HTMLFrameHyperlinkEvent evt = (HTMLFrameHyperlinkEvent)he;
+	    HTMLDocument doc = (HTMLDocument)pane.getDocument();
+	    doc.processHTMLFrameHyperlinkEvent(evt);
+	} else {
+	    try {
+		pane.setPage(he.getURL());
+		if (urlField != null) {
+		    urlField.setText(he.getURL().toString());
+		}
+	    }
+	    
+	    catch (FileNotFoundException fnfe) {
+		pane.setText("Could not open file: <tt>" + he.getURL() +
+			     "</tt>.<hr>");
+	    }
+	    catch (Exception e) {
+		e.printStackTrace();
+	    }
+	}
+    }
+    }
+}
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/TCPListener.java ./tools/mon/org/tekkotsu/mon/TCPListener.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/TCPListener.java	2005-06-08 17:05:01.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/TCPListener.java	2006-10-02 16:38:23.000000000 -0400
@@ -54,9 +54,9 @@
 	public void close() {
 		_listenerThread=null;
 		_isConnected=false;
-		try { _socket.close(); } catch (Exception ex) { }
+		try { _socket.close(); } catch (Exception ex) {System.out.println("Got exception during closing socket "+ex); }
 		if (_isServer)
-			try { _serverSocket.close(); } catch (Exception ex) { }
+			try { _serverSocket.close(); } catch (Exception ex) {System.out.println("Got exception during closing server socket "+ex); }
 	}
 
 	public TCPListener() { super(); }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/TCPVisionListener.java ./tools/mon/org/tekkotsu/mon/TCPVisionListener.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/TCPVisionListener.java	2005-08-05 15:44:23.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/TCPVisionListener.java	2006-10-02 16:38:23.000000000 -0400
@@ -18,60 +18,75 @@
 import java.awt.Color;
 
 public class TCPVisionListener extends TCPListener implements VisionListener {
-	boolean updatedFlag;
-	Date timestamp;
-	long frameNum=0;
-
-	protected Vector listeners = new Vector();
-	protected boolean updating;
+    boolean updatedFlag;
+    Date timestamp;
+    long frameNum=0;
 
-	public void addListener(VisionUpdatedListener l) { listeners.add(l); needConnection(); }
-	public void removeListener(VisionUpdatedListener l) { listeners.remove(l); }
-	public void fireVisionUpdate() {
-		updating=true;
-		for(int i=0; i<listeners.size() && updating; i++)
-			((VisionUpdatedListener)listeners.get(i)).visionUpdated(this);
-		updating=false;
-	}
+    protected Vector listeners = new Vector();
+    protected boolean updating;
 
-	public Date getTimeStamp() { return timestamp; }
-	public long getFrameNum() { return frameNum; }
-	public IndexColorModel getColorModel() { return cmodel; }
+    public void addListener(VisionUpdatedListener l) { listeners.add(l); needConnection(); }
+    public void removeListener(VisionUpdatedListener l) { listeners.remove(l); }
+    public void fireVisionUpdate() {
+	updating=true;
+	for(int i=0; i<listeners.size() && updating; i++)
+		((VisionUpdatedListener)listeners.get(i)).visionUpdated(this);
+	updating=false;
+    }
+    public void fireSensorUpdate() {
+	updating=true;
+	for(int i=0; i<listeners.size() && updating; i++)
+	    ((VisionUpdatedListener)listeners.get(i)).sensorsUpdated(this);
+	updating=false;
+    }
+	
+    public Date getTimeStamp() { return timestamp; }
+    public long getFrameNum() { return frameNum; }
+    public IndexColorModel getColorModel() { return cmodel; }
 
-	public boolean hasData() {
-		return updatedFlag;
-	}
+    public boolean hasData() {
+	return updatedFlag;
+    }
  
-	public boolean isConnected() {
-		return _isConnected;
-	}
+    public boolean isConnected() {
+	return _isConnected;
+    }
 
-	int channels=3;
-	int width=DEFAULT_WIDTH;
-	int height=DEFAULT_HEIGHT;
-	int pktSize=width*height*channels;
-	int oldformat=PACKET_VISIONRAW_FULL;
-	int format;
-	int compression;
-	int chan_id;
+    int channels=3;
+    int width=DEFAULT_WIDTH;
+    int height=DEFAULT_HEIGHT;
+    int pktSize=width*height*channels;
+    int oldformat=PACKET_VISIONRAW_FULL;
+    int format;
+    int compression;
+    int chan_id;
 
-	byte[] _data=new byte[pktSize];
-	byte[] _outd=new byte[pktSize];
-	byte[] _tmp=new byte[pktSize*2];
-	byte[] _jpeg=new byte[pktSize*2];
-	byte[] _newjpeg=new byte[pktSize*2];
-	boolean isJPEG=false;
-	int jpegLen=0;
-	int newjpegLen=0;
-	boolean isIndex=false;
-	boolean badCompressWarn=false;
-	int[] _pixels=new int[width*height];
-	BufferedImage img=new BufferedImage(width,height,BufferedImage.TYPE_INT_RGB);
-	int bytesRead;
-	boolean convertRGB=true;
-	IndexColorModel cmodel;
+    byte[] _data=new byte[pktSize];
+    byte[] _outd=new byte[pktSize];
+    byte[] _tmp=new byte[pktSize*2];
+    byte[] _jpeg=new byte[pktSize*2];
+    byte[] _newjpeg=new byte[pktSize*2];
+    String sensors;
+    boolean isJPEG=false;
+    int jpegLen=0;
+    int newjpegLen=0;
+    boolean isIndex=false;
+    boolean badCompressWarn=false;
+    int[] _pixels=new int[width*height];
+    BufferedImage img=new BufferedImage(width,height,BufferedImage.TYPE_INT_RGB);
+    int bytesRead;
+    boolean convertRGB=true;
+    IndexColorModel cmodel;
+    int pixel_size = 1;
 
-	Object packetFormatChangeLock=new Object();
+    public static final int SKETCH_BOOL_TYPE  = 1;
+    public static final int SKETCH_UCHAR_TYPE  = 2;
+    public static final int SKETCH_USINT_TYPE   = 3;
+    public static final int SKETCH_FLOAT_TYPE = 4;
+
+    public String getSensors() { return sensors; }
+
+    Object packetFormatChangeLock=new Object();
 
 
     boolean readingImage;
@@ -79,6 +94,7 @@
     public void setReadingImage()
     {
 	readingImage = true;
+	System.out.println("Now reading an image");
     }
 
     public boolean isReadingImage()
@@ -86,275 +102,278 @@
 	return readingImage;
     }
 
-	public boolean hasRawJPEG() { return isJPEG; }
-	public byte[] getJPEG() { return _jpeg; }
-	public int getJPEGLen() { return jpegLen; }
+    public boolean hasRawJPEG() { return isJPEG; }
+    public byte[] getJPEG() { return _jpeg; }
+    public int getJPEGLen() { return jpegLen; }
 	
-	public String readLoadSaveString(InputStream in) throws java.io.IOException {
-		int creatorLen=readInt(in);
-		if(!_isConnected) return ""; 
-		String creator=new String(readBytes(in,creatorLen));
-		if(!_isConnected) return "";
-		if(readChar(in)!='\0')
-			System.err.println("Misread LoadSave string? "+creator);
-		return creator;
+    public String readLoadSaveString(InputStream in) throws java.io.IOException {
+	int creatorLen=readInt(in);
+	if(!_isConnected) return ""; 
+	String creator=new String(readBytes(in,creatorLen));
+	if(!_isConnected) return "";
+	if(readChar(in)!='\0') {
+		System.err.println("Misread LoadSave string? len="+creatorLen+" str="+creator);
+		Throwable th=new Throwable();
+		th.printStackTrace();
 	}
+	return creator;
+    }
 
-	public boolean readChannel(InputStream in, int c, int chanW, int chanH) throws java.io.IOException {
-		readBytes(_tmp,in,chanW*chanH);
-		if(!_isConnected) return false;
-		return upsampleData(c,chanW,chanH);
+    public boolean readChannel(InputStream in, int c, int chanW, int chanH) throws java.io.IOException {
+	readBytes(_tmp,in,chanW*chanH);
+	if(!_isConnected) return false;
+	return upsampleData(c,chanW,chanH);
+    }
+    public boolean upsampleData(int c, int chanW, int chanH) {
+	if(chanW==width && chanH==height) {
+	    //special case: straight copy if image and channel are same size
+	    for(int y=0;y<height;y++) {
+		int datarowstart=y*width*channels+c;
+		int tmprowstart=y*chanW;
+		for(int x=0;x<width;x++)
+		    _data[datarowstart+x*channels]=_tmp[tmprowstart+x];
+	    }
+	    return true;
 	}
-	public boolean upsampleData(int c, int chanW, int chanH) {
-		if(chanW==width && chanH==height) {
-			//special case: straight copy if image and channel are same size
-			for(int y=0;y<height;y++) {
-				int datarowstart=y*width*channels+c;
-				int tmprowstart=y*chanW;
-				for(int x=0;x<width;x++)
-					_data[datarowstart+x*channels]=_tmp[tmprowstart+x];
-			}
-			return true;
-		}
-		//otherwise this channel is subsampled, need to blow it up
-		//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=(chanW-1)/(float)(width-1);
-		float ysc=(chanH-1)/(float)(height-1);
-		for(int y=0;y<height-1;y++) {
-			int datarowstart=y*width*channels+c;
-			float ty=y*ysc;
-			int ly=(int)ty; //lower pixel index
-			float fy=ty-ly; //upper pixel weight
-			int tmprowstart=ly*chanW;
-			for(int x=0;x<width-1;x++) {
-				float tx=x*xsc;
-				int lx=(int)tx; //lower pixel index
-				float fx=tx-lx; //upper pixel weight
+	//otherwise this channel is subsampled, need to blow it up
+	//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=(chanW-1)/(float)(width-1);
+	  float ysc=(chanH-1)/(float)(height-1);
+	  for(int y=0;y<height-1;y++) {
+	  int datarowstart=y*width*channels+c;
+	  float ty=y*ysc;
+	  int ly=(int)ty; //lower pixel index
+	  float fy=ty-ly; //upper pixel weight
+	  int tmprowstart=ly*chanW;
+	  for(int x=0;x<width-1;x++) {
+	  float tx=x*xsc;
+	  int lx=(int)tx; //lower pixel index
+	  float fx=tx-lx; //upper pixel weight
 
-				float lv=((int)_tmp[tmprowstart+lx]&0xFF)*(1-fx)+((int)_tmp[tmprowstart+lx+1]&0xFF)*fx;
-				float uv=((int)_tmp[tmprowstart+lx+chanW]&0xFF)*(1-fx)+((int)_tmp[tmprowstart+lx+1+chanW]&0xFF)*fx;
-				_data[datarowstart+x*channels]=(byte)(lv*(1-fy)+uv*fy);
-			}
-			_data[datarowstart+(width-1)*channels]=_tmp[tmprowstart+chanW-1];
-		}
-		int datarowstart=width*(height-1)*channels+c;
-		int tmprowstart=chanW*(chanH-1);
-		for(int x=0;x<width-1;x++) {
-			float tx=x*xsc;
-			int lx=(int)tx; //lower pixel index
-			float fx=tx-lx; //upper pixel weight
-			_data[datarowstart+x*channels]=(byte)(((int)_tmp[tmprowstart+lx]&0xFF)*(1-fx)+((int)_tmp[tmprowstart+lx+1]&0xFF)*fx);
-		}
-		_data[datarowstart+(width-1)*channels]=_tmp[tmprowstart+chanW-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);
-		int xgap=Math.round(1.0f/xsc);
-		int ygap=Math.round(1.0f/ysc);
-		for(int y=0;y<height-ygap;y++) {
-			int datarowstart=y*width*channels+c;
-			float ty=y*ysc;
-			int ly=(int)ty; //lower pixel index
-			float fy=ty-ly; //upper pixel weight
-			int tmprowstart=ly*chanW;
-			for(int x=0;x<width-xgap;x++) {
-				float tx=x*xsc;
-				int lx=(int)tx; //lower pixel index
-				float fx=tx-lx; //upper pixel weight
+	  float lv=((int)_tmp[tmprowstart+lx]&0xFF)*(1-fx)+((int)_tmp[tmprowstart+lx+1]&0xFF)*fx;
+	  float uv=((int)_tmp[tmprowstart+lx+chanW]&0xFF)*(1-fx)+((int)_tmp[tmprowstart+lx+1+chanW]&0xFF)*fx;
+	  _data[datarowstart+x*channels]=(byte)(lv*(1-fy)+uv*fy);
+	  }
+	  _data[datarowstart+(width-1)*channels]=_tmp[tmprowstart+chanW-1];
+	  }
+	  int datarowstart=width*(height-1)*channels+c;
+	  int tmprowstart=chanW*(chanH-1);
+	  for(int x=0;x<width-1;x++) {
+	  float tx=x*xsc;
+	  int lx=(int)tx; //lower pixel index
+	  float fx=tx-lx; //upper pixel weight
+	  _data[datarowstart+x*channels]=(byte)(((int)_tmp[tmprowstart+lx]&0xFF)*(1-fx)+((int)_tmp[tmprowstart+lx+1]&0xFF)*fx);
+	  }
+	  _data[datarowstart+(width-1)*channels]=_tmp[tmprowstart+chanW-1];
+	*/
 
-				float lv=(_tmp[tmprowstart+lx]&0xFF)*(1-fx)+(_tmp[tmprowstart+lx+1]&0xFF)*fx;
-				float uv=(_tmp[tmprowstart+lx+chanW]&0xFF)*(1-fx)+(_tmp[tmprowstart+lx+1+chanW]&0xFF)*fx;
-				_data[datarowstart+x*channels]=(byte)(lv*(1-fy)+uv*fy);
-			}
-			for(int x=width-xgap;x<width;x++) {
-				float lv=(_tmp[tmprowstart+chanW-1]&0xFF);
-				float uv=(_tmp[tmprowstart+chanW-1+chanW]&0xFF);
-				_data[datarowstart+x*channels]=(byte)(lv*(1-fy)+uv*fy);
-			}
-		}
-		for(int y=height-ygap;y<height;y++) {
-			int datarowstart=y*width*channels+c;
-			int tmprowstart=chanW*(chanH-1);
-			for(int x=0;x<width-xgap;x++) {
-				float tx=x*xsc;
-				int lx=(int)tx; //lower pixel index
-				float fx=tx-lx; //upper pixel weight
+	//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);
+	int xgap=Math.round(1.0f/xsc);
+	int ygap=Math.round(1.0f/ysc);
+	for(int y=0;y<height-ygap;y++) {
+	    int datarowstart=y*width*channels+c;
+	    float ty=y*ysc;
+	    int ly=(int)ty; //lower pixel index
+	    float fy=ty-ly; //upper pixel weight
+	    int tmprowstart=ly*chanW;
+	    for(int x=0;x<width-xgap;x++) {
+		float tx=x*xsc;
+		int lx=(int)tx; //lower pixel index
+		float fx=tx-lx; //upper pixel weight
 
-				float lv=(_tmp[tmprowstart+lx]&0xFF)*(1-fx)+(_tmp[tmprowstart+lx+1]&0xFF)*fx;
-				_data[datarowstart+x*channels]=(byte)(lv);
-			}
-			for(int x=width-xgap;x<width;x++)
-				_data[datarowstart+x*channels]=_tmp[tmprowstart+chanW-1];
-		}
-		
-		return true;
+		float lv=(_tmp[tmprowstart+lx]&0xFF)*(1-fx)+(_tmp[tmprowstart+lx+1]&0xFF)*fx;
+		float uv=(_tmp[tmprowstart+lx+chanW]&0xFF)*(1-fx)+(_tmp[tmprowstart+lx+1+chanW]&0xFF)*fx;
+		_data[datarowstart+x*channels]=(byte)(lv*(1-fy)+uv*fy);
+	    }
+	    for(int x=width-xgap;x<width;x++) {
+		float lv=(_tmp[tmprowstart+chanW-1]&0xFF);
+		float uv=(_tmp[tmprowstart+chanW-1+chanW]&0xFF);
+		_data[datarowstart+x*channels]=(byte)(lv*(1-fy)+uv*fy);
+	    }
 	}
+	for(int y=height-ygap;y<height;y++) {
+	    int datarowstart=y*width*channels+c;
+	    int tmprowstart=chanW*(chanH-1);
+	    for(int x=0;x<width-xgap;x++) {
+		float tx=x*xsc;
+		int lx=(int)tx; //lower pixel index
+		float fx=tx-lx; //upper pixel weight
 
-	public boolean readJPEGChannel(InputStream in, int c, int chanW, int chanH) throws java.io.IOException {
-		int len=readInt(in);
-		newjpegLen=len;
-		//System.out.println("len="+len);
-		if(!_isConnected) return false;
-		if(len>=_newjpeg.length) {
-			System.out.println("Not enough tmp room");
-			return false;
-		}
-		readBytes(_newjpeg,in,len);
-		if(!_isConnected) return false;
-		if(len>chanW*chanH*channels) {
-			if(!badCompressWarn) {
-				badCompressWarn=true;
-				System.out.println("Compressed image is larger than raw would be... :(");
-			}
-		} else {
-			if(badCompressWarn) {
-				badCompressWarn=false;
-				System.out.println("...ok, compressed image is smaller than raw now... :)");
-			}
-		}
+		float lv=(_tmp[tmprowstart+lx]&0xFF)*(1-fx)+(_tmp[tmprowstart+lx+1]&0xFF)*fx;
+		_data[datarowstart+x*channels]=(byte)(lv);
+	    }
+	    for(int x=width-xgap;x<width;x++)
+		_data[datarowstart+x*channels]=_tmp[tmprowstart+chanW-1];
+	}
+		
+	return true;
+    }
 
-		try {
-			ImageInputStream jpegStream=new MemoryCacheImageInputStream(new ByteArrayInputStream(_newjpeg));
-			jpegReader.setInput(jpegStream); 
-			Raster decoded=jpegReader.readRaster(0,null);
-			int off=c;
-			for(int y=0; y<chanH; y++)
-				for(int x=0; x<chanW; x++) {
-					_data[off]=(byte)decoded.getSample(x,y,0);
-					off+=channels;
-				}
-		} catch(Exception ex) { ex.printStackTrace(); }
-		return true;
+    public boolean readJPEGChannel(InputStream in, int c, int chanW, int chanH) throws java.io.IOException {
+	int len=readInt(in);
+	newjpegLen=len;
+	//System.out.println("len="+len);
+	if(!_isConnected) return false;
+	if(len>=_newjpeg.length) {
+	    System.out.println("Not enough tmp room");
+	    return false;
+	}
+	readBytes(_newjpeg,in,len);
+	if(!_isConnected) return false;
+	if(len>chanW*chanH*channels) {
+	    if(!badCompressWarn) {
+		badCompressWarn=true;
+		System.out.println("Compressed image is larger than raw would be... :(");
+	    }
+	} else {
+	    if(badCompressWarn) {
+		badCompressWarn=false;
+		System.out.println("...ok, compressed image is smaller than raw now... :)");
+	    }
 	}
 
-	public boolean readJPEG(InputStream in, int chanW, int chanH) throws java.io.IOException {
-		int len=readInt(in);
-		newjpegLen=len;
-		//System.out.println("len="+len);
-		if(!_isConnected) return false;
-		if(len>=_newjpeg.length) {
-			System.out.println("Not enough tmp room");
-			return false;
-		}
-		readBytes(_newjpeg,in,len);
-		if(!_isConnected) return false;
-		if(len>chanW*chanH*channels) {
-			if(!badCompressWarn) {
-				badCompressWarn=true;
-				System.out.println("Compressed image is larger than raw would be... :(");
-			}
-		} else {
-			if(badCompressWarn) {
-				badCompressWarn=false;
-				System.out.println("...ok, compressed image is smaller than raw now... :)");
-			}
+	try {
+	    ImageInputStream jpegStream=new MemoryCacheImageInputStream(new ByteArrayInputStream(_newjpeg));
+	    jpegReader.setInput(jpegStream); 
+	    Raster decoded=jpegReader.readRaster(0,null);
+	    int off=c;
+	    for(int y=0; y<chanH; y++)
+		for(int x=0; x<chanW; x++) {
+		    _data[off]=(byte)decoded.getSample(x,y,0);
+		    off+=channels;
 		}
+	} catch(Exception ex) { ex.printStackTrace(); }
+	return true;
+    }
 
-		try {
-			ImageInputStream jpegStream=new MemoryCacheImageInputStream(new ByteArrayInputStream(_newjpeg));
-			jpegReader.setInput(jpegStream); 
-			Raster decoded=jpegReader.readRaster(0,null);
-			int off=0;
-			for(int y=0; y<chanH; y++)
-				for(int x=0; x<chanW; x++) {
-					_data[off++]=(byte)decoded.getSample(x,y,0);
-					_data[off++]=(byte)decoded.getSample(x,y,2);
-					_data[off++]=(byte)decoded.getSample(x,y,1);
-				}
-		} catch(Exception ex) { ex.printStackTrace(); }
-		return true;
+    public boolean readJPEG(InputStream in, int chanW, int chanH) throws java.io.IOException {
+	int len=readInt(in);
+	newjpegLen=len;
+	//System.out.println("len="+len);
+	if(!_isConnected) return false;
+	if(len>=_newjpeg.length) {
+	    System.out.println("Not enough tmp room");
+	    return false;
+	}
+	readBytes(_newjpeg,in,len);
+	if(!_isConnected) return false;
+	if(len>chanW*chanH*channels) {
+	    if(!badCompressWarn) {
+		badCompressWarn=true;
+		System.out.println("Compressed image is larger than raw would be... :(");
+	    }
+	} else {
+	    if(badCompressWarn) {
+		badCompressWarn=false;
+		System.out.println("...ok, compressed image is smaller than raw now... :)");
+	    }
 	}
 
-	byte[] colormap = new byte[256*3];
-	public boolean readColorModel(InputStream in) throws java.io.IOException {
-		int len=readInt(in);
-		//System.out.println("len="+len);
-		if(!_isConnected) return false;
-		readBytes(colormap,in,len*3);
-		if(!_isConnected) return false;
-		//we'll do this stupid thing because we can't change an existing color model, and we don't want to make a new one for each frame
-		// (btw, java is stupid)
-		boolean makeNew=false;
-		if(cmodel==null || len!=cmodel.getMapSize()) {
-			makeNew=true;
-		} else {
-			int off=0;
-			for(int i=0; i<len; i++) {
-				if((byte)cmodel.getRed(i)!=colormap[off++] || (byte)cmodel.getGreen(i)!=colormap[off++] || (byte)cmodel.getBlue(i)!=colormap[off++]) {
-					makeNew=true;
-					break;
-				}
-			}
+	try {
+	    ImageInputStream jpegStream=new MemoryCacheImageInputStream(new ByteArrayInputStream(_newjpeg));
+	    jpegReader.setInput(jpegStream); 
+	    Raster decoded=jpegReader.readRaster(0,null);
+	    int off=0;
+	    for(int y=0; y<chanH; y++)
+		for(int x=0; x<chanW; x++) {
+		    _data[off++]=(byte)decoded.getSample(x,y,0);
+		    _data[off++]=(byte)decoded.getSample(x,y,1);
+		    _data[off++]=(byte)decoded.getSample(x,y,2);
 		}
-		if(makeNew) {
-			//System.out.println("new color model");
-			cmodel=new IndexColorModel(7,len,colormap,0,false);
+	} catch(Exception ex) { ex.printStackTrace(); }
+	return true;
+    }
+
+    byte[] colormap = new byte[256*3];
+    public boolean readColorModel(InputStream in) throws java.io.IOException {
+	int len=readInt(in);
+	//System.out.println("len="+len);
+	if(!_isConnected) return false;
+	readBytes(colormap,in,len*3);
+	if(!_isConnected) return false;
+	//we'll do this stupid thing because we can't change an existing color model, and we don't want to make a new one for each frame
+	// (btw, java is stupid)
+	boolean makeNew=false;
+	if(cmodel==null || len!=cmodel.getMapSize()) {
+	    makeNew=true;
+	} else {
+	    int off=0;
+	    for(int i=0; i<len; i++) {
+		if((byte)cmodel.getRed(i)!=colormap[off++] || (byte)cmodel.getGreen(i)!=colormap[off++] || (byte)cmodel.getBlue(i)!=colormap[off++]) {
+		    makeNew=true;
+		    break;
 		}
-		return true;
+	    }
 	}
-	
-	public boolean readIndexedColor(InputStream in, int chanW, int chanH) throws java.io.IOException {
-		readBytes(_data,in,chanW*chanH);
-		if(!_isConnected) return false;
-		if(!readColorModel(in)) return false;
-		if(!_isConnected) return false;
-		isIndex=true;
-		return true;
+	if(makeNew) {
+	    //System.out.println("new color model");
+	    cmodel=new IndexColorModel(7,len,colormap,0,false);
 	}
+	return true;
+    }
+	
+    public boolean readIndexedColor(InputStream in, int chanW, int chanH) throws java.io.IOException {
+	readBytes(_data,in,chanW*chanH);
+	if(!_isConnected) return false;
+	if(!readColorModel(in)) return false;
+	if(!_isConnected) return false;
+	isIndex=true;
+	return true;
+    }
 
-	public boolean readRLE(InputStream in, int chanW, int chanH) throws java.io.IOException {
-		int len=readInt(in);
-		if(!_isConnected) return false;
-		readBytes(_tmp,in,len*5);
-		if(!_isConnected) return false;
+    public boolean readRLE(InputStream in, int chanW, int chanH) throws java.io.IOException {
+	int len=readInt(in);
+	if(!_isConnected) return false;
+	readBytes(_tmp,in,len*5);
+	if(!_isConnected) return false;
 
-		int dpos=0;
-		int curx=0, cury=0;
-		for (; len>0 && cury<chanH;) {
-			byte color=_tmp[dpos++];
-			int x=((int)_tmp[dpos++]&0xFF);
-			x|=((int)_tmp[dpos++]&0xFF)<<8;
-			int rlen=((int)_tmp[dpos++]&0xFF);
-			rlen|=((int)_tmp[dpos++]&0xFF)<<8;
-			//System.out.println(color + " "+x + " "+rlen);
-			len--;
-			if (x < curx)
-				return false;
+	int dpos=0;
+	int curx=0, cury=0;
+	for (; len>0 && cury<chanH;) {
+	    byte color=_tmp[dpos++];
+	    int x=((int)_tmp[dpos++]&0xFF);
+	    x|=((int)_tmp[dpos++]&0xFF)<<8;
+	    int rlen=((int)_tmp[dpos++]&0xFF);
+	    rlen|=((int)_tmp[dpos++]&0xFF)<<8;
+	    //System.out.println(color + " "+x + " "+rlen);
+	    len--;
+	    if (x < curx)
+		return false;
 			
-			for (; curx < x; curx++)
-				_data[cury*width+curx]=0;
+	    for (; curx < x; curx++)
+		_data[cury*width+curx]=0;
 			
-			if (curx+rlen>width)
-				return false;
+	    if (curx+rlen>width)
+		return false;
 			
-			for (; rlen>0; rlen--, curx++)
-				_data[cury*width+curx]=color;
-			if (curx==width) {
-				cury++;
-				curx=0;
-			}
-		}
-		if(!readColorModel(in)) return false;
-		if(!_isConnected) return false;
-		isIndex=true;
-		return true;
+	    for (; rlen>0; rlen--, curx++)
+		_data[cury*width+curx]=color;
+	    if (curx==width) {
+		cury++;
+		curx=0;
+	    }
 	}
+	if(!readColorModel(in)) return false;
+	if(!_isConnected) return false;
+	isIndex=true;
+	return true;
+    }
     
     public boolean readRegions(InputStream in, int chanW, int chanH) throws java.io.IOException {
         //clear the _data array
@@ -370,339 +389,443 @@
             int numRegions = readInt(in);
             if(!_isConnected) return false;
             
-        	readBytes(_tmp,in,36*numRegions);
-			if(!_isConnected) return false;
+	    readBytes(_tmp,in,36*numRegions);
+	    if(!_isConnected) return false;
             	
-			int dpos=0;
-			for (int i = 0; i<numRegions; i++) {
-				byte color= _tmp[dpos];
-	            dpos +=4;
-	            int x1 = byteToInt(_tmp,dpos);
-	            dpos +=4;
-	            int y1 = byteToInt(_tmp,dpos);
-	            dpos +=4;
-	            int x2 = byteToInt(_tmp,dpos);
-	            dpos +=4;
-	            int y2 = byteToInt(_tmp,dpos);
+	    int dpos=0;
+	    for (int i = 0; i<numRegions; i++) {
+		byte color= _tmp[dpos];
+		dpos +=4;
+		int x1 = byteToInt(_tmp,dpos);
+		dpos +=4;
+		int y1 = byteToInt(_tmp,dpos);
+		dpos +=4;
+		int x2 = byteToInt(_tmp,dpos);
+		dpos +=4;
+		int y2 = byteToInt(_tmp,dpos);
                 //The  data of the centroid, area and run_start are ignored
-	            dpos +=20; //isn't nessescary, but now it nicely adds up to 36
+		dpos +=20; //isn't nessescary, but now it nicely adds up to 36
                 if (  x1 > chanW || y1 > chanH || x2 > chanW || y2 > chanH
-                   || x1 > x2 || y1 > y2
-                   || x1 < 0 || x2 < 0 || y1 < 0 || y2 < 0
-                   )
-					return false;
+		      || x1 > x2 || y1 > y2
+		      || x1 < 0 || x2 < 0 || y1 < 0 || y2 < 0
+		      )
+		    return false;
 				
                 //Fill the data array with the bounding boxes..
                 //..the top and bottom lines
-				for (int tb = x1; tb <= x2; tb++) {
-	                _data[y1*width+tb]=color;
-	                _data[y2*width+tb]=color;
-	            }
-	            //..the left and right lines
-				for (int lr = y1; lr <= y2; lr++) {
-	                _data[lr*width+x1]=color;
-	                _data[lr*width+x2]=color;
-	            }
-			}
+		for (int tb = x1; tb <= x2; tb++) {
+		    _data[y1*width+tb]=color;
+		    _data[y2*width+tb]=color;
+		}
+		//..the left and right lines
+		for (int lr = y1; lr <= y2; lr++) {
+		    _data[lr*width+x1]=color;
+		    _data[lr*width+x2]=color;
+		}
+	    }
             readBytes(_tmp,in,12); //read out the min_area, total_area and merge_threshhold and ignore them:)
         }
         if(!readColorModel(in)) return false;
-		if(!_isConnected) return false;
-		isIndex=true;
-		return true;
-	}
+	if(!_isConnected) return false;
+	isIndex=true;
+	return true;
+    }
 
-	public void connected(Socket socket) {
-		_isConnected=true;
-		while(listeners==null) {
-			System.out.println("Assert: Bad race condition -- shouldn't be happening");
-			Thread.yield();
-		}
-		fireVisionUpdate();
-		try {
-			InputStream in=socket.getInputStream();
-			_isConnected=true;
-			while (true) {
-				String type = readLoadSaveString(in);
-				if(!_isConnected) break; //System.out.println("Got type="+type);
-				if(!type.equals("TekkotsuImage")) {
-					if(!type.equals("CloseConnection"))
-						System.err.println("Unrecognized type: "+type);
+    public boolean readSketchImage(InputStream in, int chanW, int chanH) throws java.io.IOException {
+	byte sketchType = readByte(in);
+	pixel_size = 1;
+	if (sketchType == SKETCH_UCHAR_TYPE || sketchType == SKETCH_BOOL_TYPE)
+	    pixel_size = 1;
+	else if (sketchType == SKETCH_USINT_TYPE)
+	    pixel_size = 2;
+	else
+	    System.err.println("Formats with greater than 2 bytes not yet supported");
+	readBytes(_data,in,chanW*chanH*pixel_size);
+	if(!_isConnected) return false;
+	if(!readColorModel(in)) return false;
+	if(!_isConnected) return false;
+	isIndex=true;
+	return true;
+    }
+
+
+    public void connected(Socket socket) {
+	_isConnected=true;
+	while(listeners==null) {
+	    System.out.println("Assert: Bad race condition -- shouldn't be happening");
+	    Thread.yield();
+	}
+	try {
+	    fireConnected();
+	    InputStream in=socket.getInputStream();
+	    _isConnected=true;
+	    while (true) {  // Handle one image request
+		//System.out.println("Waiting to read image");
+		String type = readLoadSaveString(in);
+		if(!_isConnected) break; 
+		//System.out.println("Reading image");
+		//System.out.println("Got type="+type);
+		if(!type.equals("TekkotsuImage")) {
+		    if(type.startsWith("#POS\n")) {
+				sensors=type;
+				//System.out.println("got sensors");
+				fireSensorUpdate();
+				if(destroy)
 					break;
-				}
-				fireConnected();
-				format=readInt(in);
-				if(!_isConnected) break; //System.out.println("Got format="+format);
-				compression=readInt(in);
-				if(!_isConnected) break; //System.out.println("Got compression="+compression);
-				int newWidth=readInt(in);
-				if(!_isConnected) break; //System.out.println("Got newWidth="+newWidth);
-				int newHeight=readInt(in);
-				if(!_isConnected) break; //System.out.println("Got newHeight="+newHeight);
-				long timest=readInt(in);
-				if(timest<0)
-					timest+=(1L<<32);
-				if(!_isConnected) break; //System.out.println("Got timest="+timest);
-				frameNum=readInt(in);
-				if(frameNum<0)
-					frameNum+=(1L<<32);
-				if(!_isConnected) break; //System.out.println("Got frameNum="+frameNum);
+				continue;
+		    } else if(!type.equals("CloseConnection"))
+				System.err.println("Unrecognized type: "+type);
+			else {
+				System.out.println("Got Close connection packet");
+				_isConnected=false;
+			}
+		    break;
+		}
+		format=readInt(in);
+		if(!_isConnected) break; //System.out.println("Got format="+format);
+		compression=readInt(in);
+		if(!_isConnected) break; //System.out.println("Got compression="+compression);
+		int newWidth=readInt(in);
+		if(!_isConnected) break; //System.out.println("Got newWidth="+newWidth);
+		int newHeight=readInt(in);
+		if(!_isConnected) break; //System.out.println("Got newHeight="+newHeight);
+		long timest=readInt(in);
+		if(timest<0)
+		    timest+=(1L<<32);
+		if(!_isConnected) break; //System.out.println("Got timest="+timest);
+		frameNum=readInt(in);
+		if(frameNum<0)
+		    frameNum+=(1L<<32);
+		if(!_isConnected) break; //System.out.println("Got frameNum="+frameNum);
+		pixel_size = 1;
 				
-				if (format!=oldformat || newWidth!=width || newHeight!=height) {
-					width=newWidth;
-					height=newHeight;
-					synchronized (packetFormatChangeLock) {
-						switch (format) {
-						case ENCODE_COLOR:
-							channels=3;
-							pktSize=width*height*channels;
-							break;
-						case ENCODE_SINGLE_CHANNEL:
-							channels=1;
-							pktSize=width*height*channels;
-							break;
-						default:
-							System.err.println("VisionRawListener: unknown packet type "+format);
-							throw new java.lang.NoSuchFieldException("fake exception");
-						}
-						_data=new byte[pktSize];
-						_outd=new byte[pktSize];
-						_tmp=new byte[pktSize];
-						_jpeg=new byte[pktSize*2<2000?2000:pktSize*2];
-						_newjpeg=new byte[pktSize*2<2000?2000:pktSize*2];
-						_pixels=new int[width*height];;
-						img=new BufferedImage(width,height,BufferedImage.TYPE_INT_RGB);
-						oldformat=format;
-					}
-				}
+		if (format!=oldformat || newWidth!=width || newHeight!=height) {
+		    width=newWidth;
+		    height=newHeight;
+		    synchronized (packetFormatChangeLock) {
+			switch (format) {
+			case ENCODE_COLOR:
+			    channels=3;
+			    pktSize=width*height*channels;
+			    break;
+			case ENCODE_SINGLE_CHANNEL:
+			    channels=1;
+			    pktSize=width*height*channels*2; // *** DIRTY HACK TO MAKE Sketch<usint> work
+			    break;
+			default:
+			    System.err.println("VisionRawListener: unknown packet type "+format);
+			    throw new java.lang.NoSuchFieldException("fake exception");
+			}
+			_data=new byte[pktSize];
+			_outd=new byte[pktSize];
+			_tmp=new byte[pktSize];
+			_jpeg=new byte[pktSize*2<2000?2000:pktSize*2];
+			_newjpeg=new byte[pktSize*2<2000?2000:pktSize*2];
+			_pixels=new int[width*height];;
+			img=new BufferedImage(width,height,BufferedImage.TYPE_INT_RGB);
+			oldformat=format;
+		    }
+		}
 				
-				boolean failed=false;
-				for(int i=0; i<channels; i++) {
-					String creator = readLoadSaveString(in);
-					if(!_isConnected) break; //System.out.println("Got creator="+creator);
-					if(!creator.equals("FbkImage")) {
-						System.err.println("Unrecognized creator: "+creator);
-						failed=true; break;
-					} else {
-						int chanwidth=readInt(in);
-						if(!_isConnected) break; //System.out.println("Got chanwidth="+chanwidth);
-						int chanheight=readInt(in);
-						if(!_isConnected) break; //System.out.println("Got chanheight="+chanheight);
+		boolean failed=false;
+		for(int i=0; i<channels; i++) {
+		    String creator = readLoadSaveString(in);
+		    if(!_isConnected) break; //System.out.println("Got creator="+creator);
+		    if(!creator.equals("FbkImage")) {
+			System.err.println("Unrecognized creator: "+creator);
+			failed=true; break;
+		    } else {
+			int chanwidth=readInt(in);
+			if(!_isConnected) break; //System.out.println("Got chanwidth="+chanwidth);
+			int chanheight=readInt(in);
+			if(!_isConnected) break; //System.out.println("Got chanheight="+chanheight);
 						
-						if(chanwidth>width || chanheight>height) {
-							System.err.println("channel dimensions exceed image dimensions");
-							failed=true; break;
-						}
+			if(chanwidth>width || chanheight>height) {
+			    System.err.println("channel dimensions exceed image dimensions");
+			    failed=true; break;
+			}
 						
-						int layer=readInt(in);
-						if(!_isConnected) break; //System.out.println("Got layer="+layer);
-						chan_id=readInt(in);
-						if(!_isConnected) break; //System.out.println("Got chan_id="+chan_id);
-				
-						String fmt=readLoadSaveString(in);
-						if(!_isConnected) break; //System.out.println("Got fmt="+fmt);
-						if(fmt.equals("blank")) {
-							isJPEG=false;
-							isIndex=false;
-							int useChan=(channels==1)?i:chan_id;
-							int off=useChan;
-							for(int y=0; y<height; y++)
-								for(int x=0; x<width; x++) {
-									_data[off]=(byte)(convertRGB?0x80:0);
-									off+=channels;
-								}
-						} else if(fmt.equals("RawImage")) {
-							isJPEG=false;
-							isIndex=false;
-							int useChan=(channels==1)?i:chan_id;
-							if(!readChannel(in,useChan,chanwidth,chanheight)) { failed=true; System.err.println("TCPVisionListener channel read failed"); break; }
-						} else if(fmt.equals("JPEGGrayscale")) {
-							isIndex=false;
-							int useChan=(channels==1)?i:chan_id;
-							if(!readJPEGChannel(in,useChan,chanwidth,chanheight)) { failed=true; System.err.println("TCPVisionListener JPEGGreyscale channel read failed"); break; }
-							isJPEG=(channels==1);
-						} else if(fmt.equals("JPEGColor")) {
-							isIndex=false;
-							if(format==ENCODE_SINGLE_CHANNEL)
-								System.err.println("WTF? ");
-							if(!readJPEG(in,chanwidth,chanheight)) { failed=true; System.err.println("TCPVisionListener JPEGColor channel read failed"); break; }
-							i=channels;
-							isJPEG=true;
-						} else if(fmt.equals("SegColorImage")) {
-							isJPEG=false;
-							isIndex=true;
-							if(!readIndexedColor(in,chanwidth,chanheight)) { 
-							    failed=true; 
-							    System.err.println("TCPVisionListener SegColor read failed"); 
-							    break; 
-							}
-						} else if(fmt.equals("RLEImage")) {
-							isJPEG=false;
-							isIndex=true;
-							if(!readRLE(in,chanwidth,chanheight)) { failed=true; System.err.println("TCPVisionListener RLEImage read failed"); break; }
-						} else if(fmt.equals("RegionImage")) {
-							isJPEG=false;
-							isIndex=true;
-							if(!readRegions(in,chanwidth,chanheight)) { failed=true; System.err.println("TCPVisionListener RegionImage read failed"); break; }
-						} else {
-							isJPEG=false;
-							isIndex=false;
-							System.err.println("Unrecognized format: "+fmt);
-							failed=true; break;
-						}
-						//System.out.println("Done reading");
-						readingImage = false;
-					}
-				}
-				if(failed || !_isConnected) {
-					System.err.println("TCPVisionListener connection lost");
-					break;
-				}
+			int layer=readInt(in);
+			if(!_isConnected) break; //System.out.println("Got layer="+layer);
+			chan_id=readInt(in);
+			if(!_isConnected) break; //System.out.println("Got chan_id="+chan_id);
 				
-				synchronized(_outd) {
-					byte[] temp=_data;
-					_data=_outd;
-					_outd=temp;
-					if(isJPEG) {
-						temp=_newjpeg;
-						_newjpeg=_jpeg;
-						_jpeg=temp;
-						int tempi=newjpegLen;
-						newjpegLen=jpegLen;
-						jpegLen=tempi;
-					}
-					timestamp=new Date(timest);
+			String fmt=readLoadSaveString(in);
+			if(!_isConnected) break; //System.out.println("Got fmt="+fmt);
+			if(fmt.equals("blank")) {
+			    isJPEG=false;
+			    isIndex=false;
+			    int useChan=(channels==1)?i:chan_id;
+			    int off=useChan;
+			    for(int y=0; y<height; y++)
+				for(int x=0; x<width; x++) {
+				    _data[off]=(byte)(convertRGB?0x80:0);
+				    off+=channels;
 				}
-				updatedFlag = true;
-				fireVisionUpdate();
+			} else if(fmt.equals("RawImage")) {
+			    isJPEG=false;
+			    isIndex=false;
+			    int useChan=(channels==1)?i:chan_id;
+			    if(!readChannel(in,useChan,chanwidth,chanheight)) { 
+				failed=true; 
+				System.err.println("TCPVisionListener channel read failed"); 
+				break; 
+			    }
+			} else if(fmt.equals("JPEGGrayscale")) {
+			    isIndex=false;
+			    int useChan=(channels==1)?i:chan_id;
+			    if(!readJPEGChannel(in,useChan,chanwidth,chanheight)) { 
+				failed=true; 
+				System.err.println("TCPVisionListener JPEGGreyscale channel read failed"); 
+				break; 
+			    }
+			    isJPEG=(channels==1);
+			} else if(fmt.equals("JPEGColor")) {
+			    isIndex=false;
+			    if(format==ENCODE_SINGLE_CHANNEL)
+				System.err.println("WTF? ");
+			    if(!readJPEG(in,chanwidth,chanheight)) { 
+				failed=true; 
+				System.err.println("TCPVisionListener JPEGColor channel read failed"); 
+				break; 
+			    }
+			    i=channels;
+			    isJPEG=true;
+			} else if(fmt.equals("SegColorImage")) {
+			    isJPEG=false;
+			    isIndex=true;
+			    if(!readIndexedColor(in,chanwidth,chanheight)) { 
+				failed=true; 
+				System.err.println("TCPVisionListener SegColor read failed"); 
+				break; 
+			    }
+			} else if(fmt.equals("RLEImage")) {
+			    isJPEG=false;
+			    isIndex=true;
+			    if(!readRLE(in,chanwidth,chanheight)) { 
+				failed=true; 
+				System.err.println("TCPVisionListener RLEImage read failed"); 
+				break; 
+			    }
+			} else if(fmt.equals("RegionImage")) {
+			    isJPEG=false;
+			    isIndex=true;
+			    if(!readRegions(in,chanwidth,chanheight)) { 
+				failed=true; 
+				System.err.println("TCPVisionListener RegionImage read failed"); 
+				break; 
+			    }
+			} else if (fmt.equals("SketchImage")) {
+			    isJPEG = false;
+			    isIndex = false;
+			    if (!readSketchImage(in,chanwidth,chanheight)) {
+				failed=true; 
+				System.err.println("TCPVisionListener SketchImage read failed"); 
+				break; 
+			    }
+			} else {
+			    isJPEG=false;
+			    isIndex=false;
+			    System.err.println("Unrecognized format: "+fmt);
+			    failed=true; break;
 			}
-		} catch (Exception ex) {
-		} finally {
-			fireDisconnected();
+		    }
 		}
-		
-		try { socket.close(); } catch (Exception ex) { }
-		_isConnected=false;
-		fireVisionUpdate();
-	}
-	
-	public byte[] getData() {
-//		frameTimer();		
-	    synchronized (_outd) {
-			updatedFlag=false;
-			return _outd;
+		if(failed || !_isConnected) {
+		    System.err.println("TCPVisionListener connection lost");
+		    break;
 		}
-	}
-
-	public void setConvertRGB(boolean b) { 
-		if(b!=convertRGB) {
-			convertRGB=b;
-			updatedFlag=true;
+				
+		synchronized(_outd) {
+		    byte[] temp=_data;
+		    _data=_outd;
+		    _outd=temp;
+		    if(isJPEG) {
+			temp=_newjpeg;
+			_newjpeg=_jpeg;
+			_jpeg=temp;
+			int tempi=newjpegLen;
+			newjpegLen=jpegLen;
+			jpegLen=tempi;
+		    }
+		    timestamp=new Date(timest);
 		}
+		readingImage = false;
+		updatedFlag = true;
+		fireVisionUpdate();
+	    }
+	} catch (Exception ex) {
+		//System.out.println("Got exception during reading "+ex);
+	} finally {
+	    fireDisconnected();
 	}
-	public boolean getConvertRGB() { return convertRGB; }
+		
+	try { socket.close(); } catch (Exception ex) { System.out.println("TCPVisionListener got exception during closing "+ex);}
+	_isConnected=false;
+	fireVisionUpdate();
+    }
+	
+    public byte[] getData() {
+	//		frameTimer();		
+	//synchronized (_outd) {
+	    updatedFlag=false;
+	    return _outd;
+	//}
+    }
 
-	public int[] getYUVPixels() {
-		synchronized(packetFormatChangeLock) {
-			byte[] data=getData();
-			int offset=0;
-			for (int i=0; i<width*height; i++) {
-				int y=(int)data[offset++]&0xFF;
-				int u=(int)data[offset++]&0xFF;
-				int v=(int)data[offset++]&0xFF;
-				_pixels[i]=(255<<24) | (y<<16) | (u<<8) | v;
-			}
-		}
-		return _pixels;
+    public void setConvertRGB(boolean b) { 
+	if(b!=convertRGB) {
+	    convertRGB=b;
+	    updatedFlag=true;
 	}
+    }
+    public boolean getConvertRGB() { return convertRGB; }
 
-	//This still uses RGB pixels just in case you want to display the
-	//intensity value into hues instead of black/white
-	public int[] getIntensityPixels() {
-		synchronized(packetFormatChangeLock) {
-			byte[] data=getData();
-			int offset=0;
-			if(!getConvertRGB()) {
-				for (int i=0; i<width*height; i++) {
-					int z=(int)data[offset++]&0xFF;
-					_pixels[i]=(255<<24) | (z<<16) | (z<<8) | z;
-				}
-			} else if(chan_id==CHAN_Y || chan_id==CHAN_Y_DY || chan_id==CHAN_Y_DX || chan_id==CHAN_Y_DXDY ) {
-				for (int i=0; i<width*height; i++) {
-					int z=(int)data[offset++]&0xFF;
-					_pixels[i]=pixelYUV2RGB(z,0x80,0x80);
-				}
-			} else if(chan_id==CHAN_U) {
-				for (int i=0; i<width*height; i++) {
-					int z=(int)data[offset++]&0xFF;
-					_pixels[i]=pixelYUV2RGB(0x80,z,0x80);
-				}
-			} else if(chan_id==CHAN_V) {
-				for (int i=0; i<width*height; i++) {
-					int z=(int)data[offset++]&0xFF;
-					_pixels[i]=pixelYUV2RGB(0x80,0x80,z);
-				}
-			}
-		}		
-		return _pixels;
+    public int[] getYUVPixels() {
+	synchronized(packetFormatChangeLock) {
+	    byte[] data=getData();
+	    int offset=0;
+	    for (int i=0; i<width*height; i++) {
+		int y=(int)data[offset++]&0xFF;
+		int u=(int)data[offset++]&0xFF;
+		int v=(int)data[offset++]&0xFF;
+		_pixels[i]=(255<<24) | (y<<16) | (u<<8) | v;
+	    }
 	}
+	return _pixels;
+    }
 
-	public int[] getRGBPixels() {
-		synchronized(packetFormatChangeLock) {
-			byte[] data=getData();
-			int offset=0;
-			for (int i=0; i<width*height; i++) {
-				int y=(int)data[offset++]&0xFF;
-				int u=(int)data[offset++]&0xFF;
-				int v=(int)data[offset++]&0xFF;
-				_pixels[i]=pixelYUV2RGB(y, u, v);
-			}
+    //This still uses RGB pixels just in case you want to display the
+    //intensity value into hues instead of black/white
+    public int[] getIntensityPixels() {
+	synchronized(packetFormatChangeLock) {
+	    byte[] data=getData();
+	    int offset=0;
+	    if(!getConvertRGB()) {
+		for (int i=0; i<width*height; i++) {
+		    int z=(int)data[offset++]&0xFF;
+		    _pixels[i]=(255<<24) | (z<<16) | (z<<8) | z;
 		}
-		return _pixels;
+	    } else if(chan_id==CHAN_Y || chan_id==CHAN_Y_DY || chan_id==CHAN_Y_DX || chan_id==CHAN_Y_DXDY ) {
+		for (int i=0; i<width*height; i++) {
+		    int z=(int)data[offset++]&0xFF;
+		    _pixels[i]=pixelYUV2RGB(z,0x80,0x80);
+		}
+	    } else if(chan_id==CHAN_U) {
+		for (int i=0; i<width*height; i++) {
+		    int z=(int)data[offset++]&0xFF;
+		    _pixels[i]=pixelYUV2RGB(0x80,z,0x80);
+		}
+	    } else if(chan_id==CHAN_V) {
+		for (int i=0; i<width*height; i++) {
+		    int z=(int)data[offset++]&0xFF;
+		    _pixels[i]=pixelYUV2RGB(0x80,0x80,z);
+		}
+	    }
+	}		
+	return _pixels;
+    }
+
+    public int[] getRGBPixels() {
+	synchronized(packetFormatChangeLock) {
+	    byte[] data=getData();
+	    int offset=0;
+	    for (int i=0; i<width*height; i++) {
+		int y=(int)data[offset++]&0xFF;
+		int u=(int)data[offset++]&0xFF;
+		int v=(int)data[offset++]&0xFF;
+		_pixels[i]=pixelYUV2RGB(y, u, v);
+	    }
 	}
+	return _pixels;
+    }
 
-	static final int pixelYUV2RGB(int y, int u, int v) {
-		u=u*2-255;
-		v=v*2-255;
-		int r=y+u;
-		int b=y+v;
-		u=u>>1;
-		v=(v>>2)-(v>>4);
+    static final int pixelYUV2RGB(int y, int u, int v) {
+		u=u*2-256;
+		v=v-128;
+		int b=y+u;
+		int r=y+v;
+		v=v>>1;
+		u=(u>>2)-(u>>4);
 		int g=y-u-v;
 		if (r<0) r=0; if (g<0) g=0; if (b<0) b=0;
 		if (r>255) r=255; if (g>255) g=255; if (b>255) b=255;
-
 		return (255<<24) | (r<<16) | (g<<8) | b;
-	}
+    }
 
-	public BufferedImage getImage() {
-		if(!updatedFlag)
-			return img;
-		if(isIndex) {
-			byte[] data=getData();
-			if(cmodel==null)
-				return img;
-			if(img.getWidth()!=width || img.getHeight()!=height || img.getType()!=BufferedImage.TYPE_BYTE_INDEXED)
+    public BufferedImage getImage() {
+	if(!updatedFlag)
+	    return img;
+	if(isIndex) {
+	    byte[] data=getData();
+	    if(cmodel==null)
+		return img;
+	    //System.out.println("Pixel size = "+pixel_size);
+	    if (pixel_size == 2) {
+			if(img.getWidth()!=width || img.getHeight()!=height || img.getType()!=BufferedImage.TYPE_USHORT_GRAY)
+				img = new BufferedImage(width,height,BufferedImage.TYPE_USHORT_GRAY);
+			// Hack to get usint data out of byte[] and into TYPE_USHORT image
+			int j=0;
+			for (int i=0; i<img.getWidth()*img.getHeight(); i++) {
+				img.getRaster().setSample(i%img.getWidth(),i/img.getWidth(),0,((int)data[j]&0xFF) +  (((int)data[j+1]&0xFF)<<8));
+				j+=2;
+			}
+		} else {
+			if(img.getWidth()!=width || img.getHeight()!=height || img.getType()!=BufferedImage.TYPE_BYTE_INDEXED) {
+				//System.out.println("Allocating new image");
 				img=new BufferedImage(width,height,BufferedImage.TYPE_BYTE_INDEXED,cmodel);
+			}
 			img.getRaster().setDataElements(0,0,width,height,data);
-		} else {
-			updatedFlag=false;
-			int[] pix;
-			if(img.getWidth()!=width || img.getHeight()!=height || img.getType()!=BufferedImage.TYPE_BYTE_INDEXED)
-				img=new BufferedImage(width,height,BufferedImage.TYPE_INT_RGB);
+		}
+	} else {
+		int[] pix;
+		if(img.getWidth()!=width || img.getHeight()!=height || img.getType()!=BufferedImage.TYPE_INT_RGB)
+			img=new BufferedImage(width,height,BufferedImage.TYPE_INT_RGB);
+		synchronized(_outd) {
 			if(format==ENCODE_COLOR)
 				pix=getConvertRGB()?getRGBPixels():getYUVPixels();
 			else
 				pix=getIntensityPixels();
-			img.setRGB(0,0,width,height,pix,0,width);
+			synchronized(img) {
+				img.setRGB(0,0,width,height,pix,0,width);
+			}
 		}
-		return img;
 	}
+	return img;
+    }
 
+    public void close() {
+		if(destroy) {
+			super.close();
+			return;
+		}
+	if(_socket==null || _socket.isClosed())
+	    return;
+	destroy=true;
+	byte[] buf = (new String("refreshSensors\n")).getBytes();
+	try {
+	    _socket.getOutputStream().write(buf);
+	} catch(Exception e) { e.printStackTrace(); }
+	//wait until the final sensors comes in so if user hits save image we can save the corresponding sensors too
+    }
 
-
-	public TCPVisionListener() { super(); }
-	public TCPVisionListener(int port) { super(port); }
-	public TCPVisionListener(String host, int port) { super(host,port); }
+    public void startSensors() {
+	byte[] buf = (new String("startSensors\n")).getBytes();
+	try {
+	    _socket.getOutputStream().write(buf);
+	} catch(Exception e) { e.printStackTrace(); }
+    }
+	
+    public void stopSensors() {
+	byte[] buf = (new String("stopSensors\n")).getBytes();
+	try {
+	    _socket.getOutputStream().write(buf);
+	} catch(Exception e) { e.printStackTrace(); }
+    }
+	
+	
+    public TCPVisionListener() { super(); }
+    public TCPVisionListener(int port) { super(port); }
+    public TCPVisionListener(String host, int port) { super(host,port); }
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/UDPListener.java ./tools/mon/org/tekkotsu/mon/UDPListener.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/UDPListener.java	2005-07-29 19:08:03.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/UDPListener.java	2005-09-08 19:44:48.000000000 -0400
@@ -1 +1 @@
-package org.tekkotsu.mon;import java.net.DatagramSocket;import java.net.*;public abstract class UDPListener extends Listener {  protected abstract void connected(DatagramSocket socket, DatagramPacket firstPacket);  byte[] incomingbuf = new byte[1<<16];  DatagramPacket incoming = new DatagramPacket(incomingbuf, incomingbuf.length);  byte[] buf = (new String("connection request")).getBytes();	int _lastPort=-1; // keep track of previously used port number so we can resume connections  protected void runServer() {		System.out.println("ERROR: UDP server listener is not implemented");    try {      //_socket=new DatagramSocket(_port);      try {        //_socket.connect(InetAddress.getByName(_host), _port);        //_socket.setSoTimeout(10000); // block for 10 seconds at most (if infinite, we can't automatically detect a closed connection & then reconnect      } catch (Exception ex) { }      // send a dummy message so that the AIBO can see what      // address to connect it's UDP socket to			/*      DatagramPacket message = new DatagramPacket(buf, buf.length,                                                  InetAddress.getByName(_host),                                                  _port);      _socket.send(message);			*/      //connected(_socket);    } catch (Exception ex) {      System.out.println("port "+_port+": "+ex);    }  }  protected void runConnect() {		int attempts=0;		Thread me = Thread.currentThread();		while (me==_listenerThread && !destroy) {			if(attempts==0) {				System.out.println("["+_port+"] connecting ...");			}			try {				if(_lastPort==-1)					_socket=new DatagramSocket();				else					_socket=new DatagramSocket(_lastPort);				_lastPort=_socket.getLocalPort();				_socket.connect(InetAddress.getByName(_host), _port);				// send a dummy message so that the AIBO can see what				// address to connect it's UDP socket to				DatagramPacket message = new DatagramPacket(buf, buf.length);				_socket.send(message);				_socket.setSoTimeout(500);				_socket.receive(incoming);				_socket.setSoTimeout(0); //set to be blocking				System.out.println("["+_port+"] connected ...");				attempts=0;				_isConnected=true;			} catch (Exception ex) {}			if(_isConnected) {				connected(_socket,incoming);				if(!destroy)					System.out.println("["+_port+"] disconnected, attempting to reestablish ..");			}			attempts++;			if(destroy) {				System.out.println("["+_port+"] connection closed");				break;			}			try {				Thread.sleep(500);			} catch (Exception ex) {}		}  }  public void close() {	_listenerThread=null;	_isConnected=false;		try{_socket.close();}	catch(Exception e){}  }  public UDPListener() { super(); }  public UDPListener(int port) { super(port); }  public UDPListener(String host, int port) { super(host, port); }  DatagramSocket _socket;}
\ No newline at end of file
+package org.tekkotsu.mon;import java.net.DatagramSocket;import java.net.*;public abstract class UDPListener extends Listener {  protected abstract void connected(DatagramSocket socket, DatagramPacket firstPacket);  byte[] incomingbuf = new byte[1<<16];  DatagramPacket incoming = new DatagramPacket(incomingbuf, incomingbuf.length);  byte[] buf = (new String("connection request")).getBytes();	int _lastPort=-1; // keep track of previously used port number so we can resume connections  protected void runServer() {		System.out.println("ERROR: UDP server listener is not implemented");    try {      //_socket=new DatagramSocket(_port);      try {        //_socket.connect(InetAddress.getByName(_host), _port);        //_socket.setSoTimeout(10000); // block for 10 seconds at most (if infinite, we can't automatically detect a closed connection & then reconnect      } catch (Exception ex) { }      // send a dummy message so that the AIBO can see what      // address to connect it's UDP socket to			/*      DatagramPacket message = new DatagramPacket(buf, buf.length,                                                  InetAddress.getByName(_host),                                                  _port);      _socket.send(message);			*/      //connected(_socket);    } catch (Exception ex) {      System.out.println("port "+_port+": "+ex);    }  }  protected void runConnect() {		int attempts=0;		Thread me = Thread.currentThread();		while (me==_listenerThread && !destroy) {			if(attempts==0) {				System.out.println("["+_port+"] connecting ...");			}			try {				if(_lastPort==-1)					_socket=new DatagramSocket();				else					_socket=new DatagramSocket(_lastPort);				_lastPort=_socket.getLocalPort();				_socket.connect(InetAddress.getByName(_host), _port);				// send a dummy message so that the AIBO can see what				// address to connect its UDP socket to				DatagramPacket message = new DatagramPacket(buf, buf.length);				_socket.setSoTimeout(500);				while(!destroy) {					try {						_socket.send(message);						_socket.receive(incoming);						break;					} catch (SocketTimeoutException ex) { }					catch (SocketException ex) { Thread.sleep(500); }				}				_socket.setSoTimeout(0); //set to be blocking again				System.out.println("["+_port+"] connected ...");				attempts=0;				_isConnected=true;			} catch (Exception ex) { ex.printStackTrace(); }			if(_isConnected) {				connected(_socket,incoming);				if(!destroy)					System.out.println("["+_port+"] disconnected, attempting to reestablish ..");			}			attempts++;			if(destroy) {				System.out.println("["+_port+"] connection closed");				_socket.close();				break;			}			try {				Thread.sleep(500);			} catch (Exception ex) {}		}  }  public void close() {	_listenerThread=null;	_isConnected=false;		try{_socket.close();}	catch(Exception e){}  }  public UDPListener() { super(); }  public UDPListener(int port) { super(port); }  public UDPListener(String host, int port) { super(host, port); }  DatagramSocket _socket;}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/UDPVisionListener.java ./tools/mon/org/tekkotsu/mon/UDPVisionListener.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/UDPVisionListener.java	2005-08-05 15:44:23.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/UDPVisionListener.java	2006-07-02 14:50:56.000000000 -0400
@@ -1 +1,743 @@
-package org.tekkotsu.mon;import java.awt.image.BufferedImage;import java.util.Vector;import java.util.Date;import java.io.*;import java.net.*;import java.awt.image.BufferedImage;import java.awt.image.Raster;import java.awt.image.IndexColorModel;import java.util.Date;import javax.imageio.ImageIO;import javax.imageio.ImageReader;import javax.imageio.stream.ImageInputStream;import javax.imageio.stream.MemoryCacheImageInputStream;public class UDPVisionListener extends UDPListener implements VisionListener {  DatagramSocket mysock;	  InputStream in;	boolean updatedFlag;	Date timestamp;	long frameNum=0;	protected Vector listeners = new Vector();	protected boolean updating;		public void addListener(VisionUpdatedListener l) { listeners.add(l); needConnection(); }	public void removeListener(VisionUpdatedListener l) { listeners.remove(l); }	public void fireVisionUpdate() {		updating=true;		for(int i=0; i<listeners.size() && updating; i++)			((VisionUpdatedListener)listeners.get(i)).visionUpdated(this);		updating=false;	}	public Date getTimeStamp() { return timestamp; }	public long getFrameNum() { return frameNum; }	public IndexColorModel getColorModel() { return cmodel; }	public boolean hasData() {		return updatedFlag;	} 	public boolean isConnected() {		return _isConnected;	}	int channels=3;	int width=DEFAULT_WIDTH;	int height=DEFAULT_HEIGHT;	int pktSize=width*height*channels;	int oldformat=PACKET_VISIONRAW_FULL;	int format;	int compression;	int chan_id;	byte[] _data=new byte[pktSize];	byte[] _outd=new byte[pktSize];	byte[] _tmp=new byte[pktSize*2];	byte[] _jpeg=new byte[pktSize*2];	byte[] _newjpeg=new byte[pktSize*2];	boolean isJPEG=false;	int jpegLen=0;	int newjpegLen=0;	boolean isIndex=false;	boolean badCompressWarn=false;	int[] _pixels=new int[width*height];	BufferedImage img=new BufferedImage(width,height,BufferedImage.TYPE_INT_RGB);	int bytesRead;	boolean convertRGB=true;	IndexColorModel cmodel;	public boolean hasRawJPEG() { return isJPEG; }	public byte[] getJPEG() { return _jpeg; }	public int getJPEGLen() { return jpegLen; }		public String readLoadSaveString(InputStream in) throws java.io.IOException {		int creatorLen=readInt(in);		if(!_isConnected) return ""; //System.out.println("creatorLen=="+creatorLen);		String creator=new String(readBytes(in,creatorLen));		if(!_isConnected) return "";		if(readChar(in)!='\0')			System.err.println("Misread LoadSave string? "+creator);		return creator;	}	public boolean readChannel(InputStream in, int c, int chanW, int chanH) throws java.io.IOException {		readBytes(_tmp,in,chanW*chanH);		if(!_isConnected) return false;		return upsampleData(c,chanW,chanH);	}	public boolean upsampleData(int c, int chanW, int chanH) {		if(chanW==width && chanH==height) {			//special case: straight copy if image and channel are same size			for(int y=0;y<height;y++) {				int datarowstart=y*width*channels+c;				int tmprowstart=y*chanW;				for(int x=0;x<width;x++)					_data[datarowstart+x*channels]=_tmp[tmprowstart+x];			}			return true;		}		//otherwise this channel is subsampled, need to blow it up		//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=(chanW-1)/(float)(width-1);		float ysc=(chanH-1)/(float)(height-1);		for(int y=0;y<height-1;y++) {			int datarowstart=y*width*channels+c;			float ty=y*ysc;			int ly=(int)ty; //lower pixel index			float fy=ty-ly; //upper pixel weight			int tmprowstart=ly*chanW;			for(int x=0;x<width-1;x++) {				float tx=x*xsc;				int lx=(int)tx; //lower pixel index				float fx=tx-lx; //upper pixel weight				float lv=((int)_tmp[tmprowstart+lx]&0xFF)*(1-fx)+((int)_tmp[tmprowstart+lx+1]&0xFF)*fx;				float uv=((int)_tmp[tmprowstart+lx+chanW]&0xFF)*(1-fx)+((int)_tmp[tmprowstart+lx+1+chanW]&0xFF)*fx;				_data[datarowstart+x*channels]=(byte)(lv*(1-fy)+uv*fy);			}			_data[datarowstart+(width-1)*channels]=_tmp[tmprowstart+chanW-1];		}		int datarowstart=width*(height-1)*channels+c;		int tmprowstart=chanW*(chanH-1);		for(int x=0;x<width-1;x++) {			float tx=x*xsc;			int lx=(int)tx; //lower pixel index			float fx=tx-lx; //upper pixel weight			_data[datarowstart+x*channels]=(byte)(((int)_tmp[tmprowstart+lx]&0xFF)*(1-fx)+((int)_tmp[tmprowstart+lx+1]&0xFF)*fx);		}		_data[datarowstart+(width-1)*channels]=_tmp[tmprowstart+chanW-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);		int xgap=Math.round(1.0f/xsc);		int ygap=Math.round(1.0f/ysc);		for(int y=0;y<height-ygap;y++) {			int datarowstart=y*width*channels+c;			float ty=y*ysc;			int ly=(int)ty; //lower pixel index			float fy=ty-ly; //upper pixel weight			int tmprowstart=ly*chanW;			for(int x=0;x<width-xgap;x++) {				float tx=x*xsc;				int lx=(int)tx; //lower pixel index				float fx=tx-lx; //upper pixel weight				float lv=(_tmp[tmprowstart+lx]&0xFF)*(1-fx)+(_tmp[tmprowstart+lx+1]&0xFF)*fx;				float uv=(_tmp[tmprowstart+lx+chanW]&0xFF)*(1-fx)+(_tmp[tmprowstart+lx+1+chanW]&0xFF)*fx;				_data[datarowstart+x*channels]=(byte)(lv*(1-fy)+uv*fy);			}			for(int x=width-xgap;x<width;x++) {				float lv=(_tmp[tmprowstart+chanW-1]&0xFF);				float uv=(_tmp[tmprowstart+chanW-1+chanW]&0xFF);				_data[datarowstart+x*channels]=(byte)(lv*(1-fy)+uv*fy);			}		}		for(int y=height-ygap;y<height;y++) {			int datarowstart=y*width*channels+c;			int tmprowstart=chanW*(chanH-1);			for(int x=0;x<width-xgap;x++) {				float tx=x*xsc;				int lx=(int)tx; //lower pixel index				float fx=tx-lx; //upper pixel weight				float lv=(_tmp[tmprowstart+lx]&0xFF)*(1-fx)+(_tmp[tmprowstart+lx+1]&0xFF)*fx;				_data[datarowstart+x*channels]=(byte)(lv);			}			for(int x=width-xgap;x<width;x++)				_data[datarowstart+x*channels]=_tmp[tmprowstart+chanW-1];		}				return true;	}	public boolean readJPEGChannel(InputStream in, int c, int chanW, int chanH) throws java.io.IOException {		int len=readInt(in);		newjpegLen=len;		//System.out.println("len="+len);		if(!_isConnected) return false;		if(len>=_newjpeg.length) {			System.out.println("Not enough tmp room");			return false;		}		readBytes(_newjpeg,in,len);		if(!_isConnected) return false;		if(len>chanW*chanH*channels) {			if(!badCompressWarn) {				badCompressWarn=true;				System.out.println("Compressed image is larger than raw would be... :(");			}		} else {			if(badCompressWarn) {				badCompressWarn=false;				System.out.println("...ok, compressed image is smaller than raw now... :)");			}		}		try {			ImageInputStream jpegStream=new MemoryCacheImageInputStream(new ByteArrayInputStream(_newjpeg));			jpegReader.setInput(jpegStream); 			Raster decoded=jpegReader.readRaster(0,null);			int off=c;			for(int y=0; y<chanH; y++)				for(int x=0; x<chanW; x++) {					_data[off]=(byte)decoded.getSample(x,y,0);					off+=channels;				}		} catch(Exception ex) { ex.printStackTrace(); }		return true;	}	public boolean readJPEG(InputStream in, int chanW, int chanH) throws java.io.IOException {		int len=readInt(in);		newjpegLen=len;		//System.out.println("len="+len);		if(!_isConnected) return false;		if(len>=_newjpeg.length) {			System.out.println("Not enough tmp room");			return false;		}		readBytes(_newjpeg,in,len);		if(!_isConnected) return false;		if(len>chanW*chanH*channels) {			if(!badCompressWarn) {				badCompressWarn=true;				System.out.println("Compressed image is larger than raw would be... :(");			}		} else {			if(badCompressWarn) {				badCompressWarn=false;				System.out.println("...ok, compressed image is smaller than raw now... :)");			}		}		try {			ImageInputStream jpegStream=new MemoryCacheImageInputStream(new ByteArrayInputStream(_newjpeg));			jpegReader.setInput(jpegStream); 			Raster decoded=jpegReader.readRaster(0,null);			int off=0;			for(int y=0; y<chanH; y++)				for(int x=0; x<chanW; x++) {					_data[off++]=(byte)decoded.getSample(x,y,0);					_data[off++]=(byte)decoded.getSample(x,y,2);					_data[off++]=(byte)decoded.getSample(x,y,1);				}		} catch(Exception ex) { ex.printStackTrace(); }		return true;	}	byte[] colormap = new byte[256*3];	public boolean readColorModel(InputStream in) throws java.io.IOException {		int len=readInt(in);		//System.out.println("len="+len);		if(!_isConnected) return false;		readBytes(colormap,in,len*3);		if(!_isConnected) return false;		//we'll do this stupid thing because we can't change an existing color model, and we don't want to make a new one for each frame		// (btw, java is stupid)		boolean makeNew=false;		if(cmodel==null || len!=cmodel.getMapSize()) {			makeNew=true;		} else {			int off=0;			for(int i=0; i<len; i++) {				if((byte)cmodel.getRed(i)!=colormap[off++] || (byte)cmodel.getGreen(i)!=colormap[off++] || (byte)cmodel.getBlue(i)!=colormap[off++]) {					makeNew=true;					break;				}			}		}		if(makeNew) {			//System.out.println("new color model");			cmodel=new IndexColorModel(7,len,colormap,0,false);		}		return true;	}		public boolean readIndexedColor(InputStream in, int chanW, int chanH) throws java.io.IOException {		readBytes(_data,in,chanW*chanH);		if(!_isConnected) return false;		if(!readColorModel(in)) return false;		if(!_isConnected) return false;		isIndex=true;		return true;	}	public boolean readRLE(InputStream in, int chanW, int chanH) throws java.io.IOException {		int len=readInt(in);		if(!_isConnected) return false;		readBytes(_tmp,in,len*5);		if(!_isConnected) return false;		int dpos=0;		int curx=0, cury=0;		for (; len>0 && cury<chanH;) {			byte color=_tmp[dpos++];			int x=((int)_tmp[dpos++]&0xFF);			x|=((int)_tmp[dpos++]&0xFF)<<8;			int rlen=((int)_tmp[dpos++]&0xFF);			rlen|=((int)_tmp[dpos++]&0xFF)<<8;			//System.out.println(color + " "+x + " "+rlen);			len--;			if (x < curx)				return false;						for (; curx < x; curx++)				_data[cury*width+curx]=0;						if (curx+rlen>width)				return false;						for (; rlen>0; rlen--, curx++)				_data[cury*width+curx]=color;			if (curx==width) {				cury++;				curx=0;			}		}		if(!readColorModel(in)) return false;		if(!_isConnected) return false;		isIndex=true;		return true;	}		public boolean readRegions(InputStream in, int chanW, int chanH) throws java.io.IOException {		//clear the _data array		for(int h=0; h<chanH; h++) {			for(int w =0; w<chanW; w++) {				_data[chanW*h+w]=0;			}		}  		int numColors=readInt(in);		if(!_isConnected) return false;		for(int curColor = 0; curColor < numColors; curColor++) {			int numRegions = readInt(in);			if(!_isConnected) return false;            			readBytes(_tmp,in,36*numRegions);			if(!_isConnected) return false;            				int dpos=0;			for (int i = 0; i<numRegions; i++) {				byte color= _tmp[dpos];				dpos +=4;				int x1 = byteToInt(_tmp,dpos);				dpos +=4;				int y1 = byteToInt(_tmp,dpos);				dpos +=4;				int x2 = byteToInt(_tmp,dpos);				dpos +=4;				int y2 = byteToInt(_tmp,dpos);				//The  data of the centroid, area and run_start are ignored				dpos +=20; //isn't nessescary, but now it nicely adds up to 36				if (  x1 > chanW || y1 > chanH || x2 > chanW || y2 > chanH							|| x1 > x2 || y1 > y2							|| x1 < 0 || x2 < 0 || y1 < 0 || y2 < 0							)					return false;								//Fill the data array with the bounding boxes..				//..the top and bottom lines				for (int tb = x1; tb <= x2; tb++) {					_data[y1*width+tb]=color;					_data[y2*width+tb]=color;				}				//..the left and right lines				for (int lr = y1; lr <= y2; lr++) {					_data[lr*width+x1]=color;					_data[lr*width+x2]=color;				}			}			readBytes(_tmp,in,12); //read out the min_area, total_area and merge_threshhold and ignore them:)		}		if(!readColorModel(in)) return false;		if(!_isConnected) return false;		isIndex=true;		return true;	}	public void connected(DatagramSocket UDPsocket, DatagramPacket incoming) {		_isConnected=true;		mysock = UDPsocket;		while(listeners==null) {			System.out.println("Assert: Bad race condition -- shouldn't be happening");			Thread.yield();		}		fireVisionUpdate();		try {			while(!mysock.isClosed()) {				in = new ByteArrayInputStream(incoming.getData());				String type = readLoadSaveString(in);				if(!_isConnected) break; //System.out.println("Got type="+type);				if(!type.equals("TekkotsuImage")) {					if(!type.equals("CloseConnection"))						System.err.println("Unrecognized type: "+type);					else {						System.out.println("Got Close connection packet");						_isConnected=false;					}					break;				}        fireConnected();				format=readInt(in);				if(!_isConnected) break; //System.out.println("Got format="+format);				compression=readInt(in);				if(!_isConnected) break; //System.out.println("Got compression="+compression);				int newWidth=readInt(in);				if(!_isConnected) break; //System.out.println("Got newWidth="+newWidth);				int newHeight=readInt(in);				if(!_isConnected) break; //System.out.println("Got newHeight="+newHeight);				long timest=readInt(in);				if(timest<0)					timest+=(1L<<32);				if(!_isConnected) break; //System.out.println("Got timest="+timest);				frameNum=readInt(in);				if(frameNum<0)					frameNum+=(1L<<32);				if(!_isConnected) break; //System.out.println("Got frameNum="+frameNum);								if (format!=oldformat || newWidth!=width || newHeight!=height) {					width=newWidth;					height=newHeight;					synchronized (_outd) {						switch (format) {						case ENCODE_COLOR:							channels=3;							pktSize=width*height*channels;							break;						case ENCODE_SINGLE_CHANNEL:							channels=1;							pktSize=width*height*channels;							break;						default:							System.err.println("VisionRawListener: unknown packet type "+format);							throw new java.lang.NoSuchFieldException("fake exception");						}						_data=new byte[pktSize];						_outd=new byte[pktSize];						_tmp=new byte[pktSize];						_jpeg=new byte[pktSize*2<2000?2000:pktSize*2];						_newjpeg=new byte[pktSize*2<2000?2000:pktSize*2];						_pixels=new int[width*height];;						img=new BufferedImage(width,height,BufferedImage.TYPE_INT_RGB);						oldformat=format;					}				}								boolean failed=false;				for(int i=0; i<channels; i++) {					String creator = readLoadSaveString(in);					if(!_isConnected) break; //System.out.println("Got creator="+creator);					if(!creator.equals("FbkImage")) {						System.err.println("Unrecognized creator: "+creator);						failed=true; break;					} else {						int chanwidth=readInt(in);						if(!_isConnected) break; //System.out.println("Got chanwidth="+chanwidth);						int chanheight=readInt(in);						if(!_isConnected) break; //System.out.println("Got chanheight="+chanheight);												if(chanwidth>width || chanheight>height) {							System.err.println("channel dimensions exceed image dimensions");							failed=true; break;						}												int layer=readInt(in);						if(!_isConnected) break; //System.out.println("Got layer="+layer);						chan_id=readInt(in);						if(!_isConnected) break; //System.out.println("Got chan_id="+chan_id);										String fmt=readLoadSaveString(in);						if(!_isConnected) break; //System.out.println("Got fmt="+fmt);						if(fmt.equals("blank")) {							isJPEG=false;							isIndex=false;							int useChan=(channels==1)?i:chan_id;							int off=useChan;							for(int y=0; y<height; y++)								for(int x=0; x<width; x++) {									_data[off]=(byte)(convertRGB?0x80:0);									off+=channels;								}						} else if(fmt.equals("RawImage")) {							isJPEG=false;							isIndex=false;							int useChan=(channels==1)?i:chan_id;							if(!readChannel(in,useChan,chanwidth,chanheight)) { failed=true; System.err.println("UDPVisionListener channel read failed"); break; }						} else if(fmt.equals("JPEGGrayscale")) {							isIndex=false;							int useChan=(channels==1)?i:chan_id;							if(!readJPEGChannel(in,useChan,chanwidth,chanheight)) { failed=true; System.err.println("UDPVisionListener JPEGGreyscale channel read failed"); break; }							isJPEG=(channels==1);						} else if(fmt.equals("JPEGColor")) {							isIndex=false;							if(format==ENCODE_SINGLE_CHANNEL)								System.err.println("WTF? ");							if(!readJPEG(in,chanwidth,chanheight)) { failed=true; System.err.println("UDPVisionListener JPEGColor channel read failed"); break; }							i=channels;							isJPEG=true;						} else if(fmt.equals("SegColorImage")) {							isJPEG=false;							isIndex=true;							if(!readIndexedColor(in,chanwidth,chanheight)) { failed=true; System.err.println("UDPVisionListener SegColor read failed"); break; }						} else if(fmt.equals("RLEImage")) {							isJPEG=false;							isIndex=true;							if(!readRLE(in,chanwidth,chanheight)) { failed=true; System.err.println("UDPVisionListener RLEImage read failed"); break; }						} else if(fmt.equals("RegionImage")) {							isJPEG=false;							isIndex=true;							if(!readRegions(in,chanwidth,chanheight)) { failed=true; System.err.println("UDPVisionListener RegionImage read failed"); break; }						} else {							isJPEG=false;							isIndex=false;							System.err.println("Unrecognized format: "+fmt);							failed=true; break;						}					}				}				if(failed || !_isConnected) {					System.err.println("UDPVisionListener connection lost");					break;				}								synchronized(_outd) {					byte[] temp=_data;					_data=_outd;					_outd=temp;					if(isJPEG) {						temp=_newjpeg;						_newjpeg=_jpeg;						_jpeg=temp;						int tempi=newjpegLen;						newjpegLen=jpegLen;						jpegLen=tempi;					}					timestamp=new Date(timest);				}				updatedFlag=true;				fireVisionUpdate();				mysock.receive(incoming);			}		} catch (Exception ex) {    } finally {      fireDisconnected();    }				try { mysock.close(); } catch (Exception ex) { }		if(!_isConnected) {			if(!destroy)				System.out.println("Waiting 5 seconds to reconnect");			try { Thread.sleep(5000); } catch (Exception ex) {}		}		_isConnected=false;		fireVisionUpdate();	}		public byte[] getData() {		synchronized (_outd) {			updatedFlag=false;			return _outd;		}	}	public void setConvertRGB(boolean b) { 		if(b!=convertRGB) {			convertRGB=b;			updatedFlag=true;		}	}	public boolean getConvertRGB() { return convertRGB; }	public int[] getYUVPixels() {		synchronized(_outd) {			byte[] data=getData();			int offset=0;			for (int i=0; i<width*height; i++) {				int y=(int)data[offset++]&0xFF;				int u=(int)data[offset++]&0xFF;				int v=(int)data[offset++]&0xFF;				_pixels[i]=(255<<24) | (y<<16) | (u<<8) | v;			}		}		return _pixels;	}	//This still uses RGB pixels just in case you want to display the	//intensity value into hues instead of black/white	public int[] getIntensityPixels() {		synchronized(_outd) {			byte[] data=getData();			int offset=0;			if(!getConvertRGB()) {				for (int i=0; i<width*height; i++) {					int z=(int)data[offset++]&0xFF;					_pixels[i]=(255<<24) | (z<<16) | (z<<8) | z;				}			} else if(chan_id==CHAN_Y || chan_id==CHAN_Y_DY || chan_id==CHAN_Y_DX || chan_id==CHAN_Y_DXDY ) {				for (int i=0; i<width*height; i++) {					int z=(int)data[offset++]&0xFF;					_pixels[i]=pixelYUV2RGB(z,0x80,0x80);				}			} else if(chan_id==CHAN_U) {				for (int i=0; i<width*height; i++) {					int z=(int)data[offset++]&0xFF;					_pixels[i]=pixelYUV2RGB(0x80,z,0x80);				}			} else if(chan_id==CHAN_V) {				for (int i=0; i<width*height; i++) {					int z=(int)data[offset++]&0xFF;					_pixels[i]=pixelYUV2RGB(0x80,0x80,z);				}			}		}				return _pixels;	}	public int[] getRGBPixels() {		synchronized(_outd) {			byte[] data=getData();			int offset=0;			for (int i=0; i<width*height; i++) {				int y=(int)data[offset++]&0xFF;				int u=(int)data[offset++]&0xFF;				int v=(int)data[offset++]&0xFF;				_pixels[i]=pixelYUV2RGB(y, u, v);			}		}		return _pixels;	}	static final int pixelYUV2RGB(int y, int u, int v) {		u=u*2-255;		v=v*2-255;		int r=y+u;		int b=y+v;		u=u>>1;		v=(v>>2)-(v>>4);		int g=y-u-v;		if (r<0) r=0; if (g<0) g=0; if (b<0) b=0;		if (r>255) r=255; if (g>255) g=255; if (b>255) b=255;		return (255<<24) | (r<<16) | (g<<8) | b;	}	public BufferedImage getImage() {		if(!updatedFlag)			return img;		if(isIndex) {			byte[] data=getData();			if(cmodel==null)				return img;			if(img.getWidth()!=width || img.getHeight()!=height || img.getType()!=BufferedImage.TYPE_BYTE_INDEXED)				img=new BufferedImage(width,height,BufferedImage.TYPE_BYTE_INDEXED,cmodel);			img.getRaster().setDataElements(0,0,width,height,data);		} else {			updatedFlag=false;			int[] pix;			if(img.getWidth()!=width || img.getHeight()!=height || img.getType()!=BufferedImage.TYPE_BYTE_INDEXED)				img=new BufferedImage(width,height,BufferedImage.TYPE_INT_RGB);			if(format==ENCODE_COLOR)				pix=getConvertRGB()?getRGBPixels():getYUVPixels();			else				pix=getIntensityPixels();			img.setRGB(0,0,width,height,pix,0,width);		}		return img;	}	public UDPVisionListener() { super(); }	public UDPVisionListener(int port) { super(port); }	public UDPVisionListener(String host, int port) { super(host,port); }}
\ No newline at end of file
+package org.tekkotsu.mon;
+
+import java.awt.image.BufferedImage;
+import java.util.Vector;
+import java.util.Date;
+
+import java.io.*;
+import java.net.*;
+import java.awt.image.BufferedImage;
+import java.awt.image.Raster;
+import java.awt.image.IndexColorModel;
+import java.util.Date;
+import javax.imageio.ImageIO;
+import javax.imageio.ImageReader;
+import javax.imageio.stream.ImageInputStream;
+import javax.imageio.stream.MemoryCacheImageInputStream;
+
+public class UDPVisionListener extends UDPListener implements VisionListener {
+  DatagramSocket mysock;
+	
+  InputStream in;
+
+	boolean updatedFlag;
+	Date timestamp;
+	long frameNum=0;
+
+	protected Vector listeners = new Vector();
+	protected boolean updating;
+	
+	public void addListener(VisionUpdatedListener l) { listeners.add(l); needConnection(); }
+	public void removeListener(VisionUpdatedListener l) { listeners.remove(l); }
+	public void fireVisionUpdate() {
+		updating=true;
+		for(int i=0; i<listeners.size() && updating; i++)
+			((VisionUpdatedListener)listeners.get(i)).visionUpdated(this);
+		updating=false;
+	}
+	public void fireSensorUpdate() {
+		updating=true;
+		for(int i=0; i<listeners.size() && updating; i++)
+			((VisionUpdatedListener)listeners.get(i)).sensorsUpdated(this);
+		updating=false;
+	}
+
+	public Date getTimeStamp() { return timestamp; }
+	public long getFrameNum() { return frameNum; }
+	public IndexColorModel getColorModel() { return cmodel; }
+
+	public boolean hasData() {
+		return updatedFlag;
+	}
+ 
+	public boolean isConnected() {
+		return _isConnected;
+	}
+
+	int channels=3;
+	int width=DEFAULT_WIDTH;
+	int height=DEFAULT_HEIGHT;
+	int pktSize=width*height*channels;
+	int oldformat=PACKET_VISIONRAW_FULL;
+	int format;
+	int compression;
+	int chan_id;
+
+	byte[] _data=new byte[pktSize];
+	byte[] _outd=new byte[pktSize];
+	byte[] _tmp=new byte[pktSize*2];
+	byte[] _jpeg=new byte[pktSize*2];
+	byte[] _newjpeg=new byte[pktSize*2];
+	String sensors;
+	boolean isJPEG=false;
+	int jpegLen=0;
+	int newjpegLen=0;
+	boolean isIndex=false;
+	boolean badCompressWarn=false;
+	int[] _pixels=new int[width*height];
+	BufferedImage img=new BufferedImage(width,height,BufferedImage.TYPE_INT_RGB);
+	int bytesRead;
+	boolean convertRGB=true;
+	IndexColorModel cmodel;
+
+	public String getSensors() { return sensors; }
+
+	public boolean hasRawJPEG() { return isJPEG; }
+	public byte[] getJPEG() { return _jpeg; }
+	public int getJPEGLen() { return jpegLen; }
+	
+	public String readLoadSaveString(InputStream in) throws java.io.IOException {
+		int creatorLen=readInt(in);
+		if(!_isConnected) return ""; //System.out.println("creatorLen=="+creatorLen);
+		String creator=new String(readBytes(in,creatorLen));
+		if(!_isConnected) return "";
+		if(readChar(in)!='\0') {
+			System.err.println("Misread LoadSave string? len="+creatorLen+" str="+creator);
+			Throwable th=new Throwable();
+			th.printStackTrace();
+		}
+		return creator;
+	}
+
+	public boolean readChannel(InputStream in, int c, int chanW, int chanH) throws java.io.IOException {
+		readBytes(_tmp,in,chanW*chanH);
+		if(!_isConnected) return false;
+		return upsampleData(c,chanW,chanH);
+	}
+	public boolean upsampleData(int c, int chanW, int chanH) {
+		if(chanW==width && chanH==height) {
+			//special case: straight copy if image and channel are same size
+			for(int y=0;y<height;y++) {
+				int datarowstart=y*width*channels+c;
+				int tmprowstart=y*chanW;
+				for(int x=0;x<width;x++)
+					_data[datarowstart+x*channels]=_tmp[tmprowstart+x];
+			}
+			return true;
+		}
+		//otherwise this channel is subsampled, need to blow it up
+		//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=(chanW-1)/(float)(width-1);
+		float ysc=(chanH-1)/(float)(height-1);
+		for(int y=0;y<height-1;y++) {
+			int datarowstart=y*width*channels+c;
+			float ty=y*ysc;
+			int ly=(int)ty; //lower pixel index
+			float fy=ty-ly; //upper pixel weight
+			int tmprowstart=ly*chanW;
+			for(int x=0;x<width-1;x++) {
+				float tx=x*xsc;
+				int lx=(int)tx; //lower pixel index
+				float fx=tx-lx; //upper pixel weight
+
+				float lv=((int)_tmp[tmprowstart+lx]&0xFF)*(1-fx)+((int)_tmp[tmprowstart+lx+1]&0xFF)*fx;
+				float uv=((int)_tmp[tmprowstart+lx+chanW]&0xFF)*(1-fx)+((int)_tmp[tmprowstart+lx+1+chanW]&0xFF)*fx;
+				_data[datarowstart+x*channels]=(byte)(lv*(1-fy)+uv*fy);
+			}
+			_data[datarowstart+(width-1)*channels]=_tmp[tmprowstart+chanW-1];
+		}
+		int datarowstart=width*(height-1)*channels+c;
+		int tmprowstart=chanW*(chanH-1);
+		for(int x=0;x<width-1;x++) {
+			float tx=x*xsc;
+			int lx=(int)tx; //lower pixel index
+			float fx=tx-lx; //upper pixel weight
+			_data[datarowstart+x*channels]=(byte)(((int)_tmp[tmprowstart+lx]&0xFF)*(1-fx)+((int)_tmp[tmprowstart+lx+1]&0xFF)*fx);
+		}
+		_data[datarowstart+(width-1)*channels]=_tmp[tmprowstart+chanW-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);
+		int xgap=Math.round(1.0f/xsc);
+		int ygap=Math.round(1.0f/ysc);
+		for(int y=0;y<height-ygap;y++) {
+			int datarowstart=y*width*channels+c;
+			float ty=y*ysc;
+			int ly=(int)ty; //lower pixel index
+			float fy=ty-ly; //upper pixel weight
+			int tmprowstart=ly*chanW;
+			for(int x=0;x<width-xgap;x++) {
+				float tx=x*xsc;
+				int lx=(int)tx; //lower pixel index
+				float fx=tx-lx; //upper pixel weight
+
+				float lv=(_tmp[tmprowstart+lx]&0xFF)*(1-fx)+(_tmp[tmprowstart+lx+1]&0xFF)*fx;
+				float uv=(_tmp[tmprowstart+lx+chanW]&0xFF)*(1-fx)+(_tmp[tmprowstart+lx+1+chanW]&0xFF)*fx;
+				_data[datarowstart+x*channels]=(byte)(lv*(1-fy)+uv*fy);
+			}
+			for(int x=width-xgap;x<width;x++) {
+				float lv=(_tmp[tmprowstart+chanW-1]&0xFF);
+				float uv=(_tmp[tmprowstart+chanW-1+chanW]&0xFF);
+				_data[datarowstart+x*channels]=(byte)(lv*(1-fy)+uv*fy);
+			}
+		}
+		for(int y=height-ygap;y<height;y++) {
+			int datarowstart=y*width*channels+c;
+			int tmprowstart=chanW*(chanH-1);
+			for(int x=0;x<width-xgap;x++) {
+				float tx=x*xsc;
+				int lx=(int)tx; //lower pixel index
+				float fx=tx-lx; //upper pixel weight
+
+				float lv=(_tmp[tmprowstart+lx]&0xFF)*(1-fx)+(_tmp[tmprowstart+lx+1]&0xFF)*fx;
+				_data[datarowstart+x*channels]=(byte)(lv);
+			}
+			for(int x=width-xgap;x<width;x++)
+				_data[datarowstart+x*channels]=_tmp[tmprowstart+chanW-1];
+		}
+		
+		return true;
+	}
+
+	public boolean readJPEGChannel(InputStream in, int c, int chanW, int chanH) throws java.io.IOException {
+		int len=readInt(in);
+		newjpegLen=len;
+		//System.out.println("len="+len);
+		if(!_isConnected) return false;
+		if(len>=_newjpeg.length) {
+			System.out.println("Not enough tmp room");
+			return false;
+		}
+		readBytes(_newjpeg,in,len);
+		if(!_isConnected) return false;
+		if(len>chanW*chanH*channels) {
+			if(!badCompressWarn) {
+				badCompressWarn=true;
+				System.out.println("Compressed image is larger than raw would be... :(");
+			}
+		} else {
+			if(badCompressWarn) {
+				badCompressWarn=false;
+				System.out.println("...ok, compressed image is smaller than raw now... :)");
+			}
+		}
+
+		try {
+			ImageInputStream jpegStream=new MemoryCacheImageInputStream(new ByteArrayInputStream(_newjpeg));
+			jpegReader.setInput(jpegStream); 
+			Raster decoded=jpegReader.readRaster(0,null);
+			int off=c;
+			for(int y=0; y<chanH; y++)
+				for(int x=0; x<chanW; x++) {
+					_data[off]=(byte)decoded.getSample(x,y,0);
+					off+=channels;
+				}
+		} catch(Exception ex) { ex.printStackTrace(); }
+		return true;
+	}
+
+	public boolean readJPEG(InputStream in, int chanW, int chanH) throws java.io.IOException {
+		int len=readInt(in);
+		newjpegLen=len;
+		//System.out.println("len="+len);
+		if(!_isConnected) return false;
+		if(len>=_newjpeg.length) {
+			System.out.println("Not enough tmp room");
+			return false;
+		}
+		readBytes(_newjpeg,in,len);
+		if(!_isConnected) return false;
+		if(len>chanW*chanH*channels) {
+			if(!badCompressWarn) {
+				badCompressWarn=true;
+				System.out.println("Compressed image is larger than raw would be... :(");
+			}
+		} else {
+			if(badCompressWarn) {
+				badCompressWarn=false;
+				System.out.println("...ok, compressed image is smaller than raw now... :)");
+			}
+		}
+
+		try {
+			ImageInputStream jpegStream=new MemoryCacheImageInputStream(new ByteArrayInputStream(_newjpeg));
+			jpegReader.setInput(jpegStream); 
+			Raster decoded=jpegReader.readRaster(0,null);
+			int off=0;
+			for(int y=0; y<chanH; y++)
+				for(int x=0; x<chanW; x++) {
+					_data[off++]=(byte)decoded.getSample(x,y,0);
+					_data[off++]=(byte)decoded.getSample(x,y,1);
+					_data[off++]=(byte)decoded.getSample(x,y,2);
+				}
+		} catch(Exception ex) { ex.printStackTrace(); }
+		return true;
+	}
+
+	byte[] colormap = new byte[256*3];
+	public boolean readColorModel(InputStream in) throws java.io.IOException {
+		int len=readInt(in);
+		//System.out.println("len="+len);
+		if(!_isConnected) return false;
+		readBytes(colormap,in,len*3);
+		if(!_isConnected) return false;
+		//we'll do this stupid thing because we can't change an existing color model, and we don't want to make a new one for each frame
+		// (btw, java is stupid)
+		boolean makeNew=false;
+		if(cmodel==null || len!=cmodel.getMapSize()) {
+			makeNew=true;
+		} else {
+			int off=0;
+			for(int i=0; i<len; i++) {
+				if((byte)cmodel.getRed(i)!=colormap[off++] || (byte)cmodel.getGreen(i)!=colormap[off++] || (byte)cmodel.getBlue(i)!=colormap[off++]) {
+					makeNew=true;
+					break;
+				}
+			}
+		}
+		if(makeNew) {
+			//System.out.println("new color model");
+			cmodel=new IndexColorModel(7,len,colormap,0,false);
+		}
+		return true;
+	}
+	
+	public boolean readIndexedColor(InputStream in, int chanW, int chanH) throws java.io.IOException {
+		readBytes(_data,in,chanW*chanH);
+		if(!_isConnected) return false;
+		if(!readColorModel(in)) return false;
+		if(!_isConnected) return false;
+		isIndex=true;
+		return true;
+	}
+
+	public boolean readRLE(InputStream in, int chanW, int chanH) throws java.io.IOException {
+		int len=readInt(in);
+		if(!_isConnected) return false;
+		readBytes(_tmp,in,len*5);
+		if(!_isConnected) return false;
+
+		int dpos=0;
+		int curx=0, cury=0;
+		for (; len>0 && cury<chanH;) {
+			byte color=_tmp[dpos++];
+			int x=((int)_tmp[dpos++]&0xFF);
+			x|=((int)_tmp[dpos++]&0xFF)<<8;
+			int rlen=((int)_tmp[dpos++]&0xFF);
+			rlen|=((int)_tmp[dpos++]&0xFF)<<8;
+			//System.out.println(color + " "+x + " "+rlen);
+			len--;
+			if (x < curx)
+				return false;
+			
+			for (; curx < x; curx++)
+				_data[cury*width+curx]=0;
+			
+			if (curx+rlen>width)
+				return false;
+			
+			for (; rlen>0; rlen--, curx++)
+				_data[cury*width+curx]=color;
+			if (curx==width) {
+				cury++;
+				curx=0;
+			}
+		}
+		if(!readColorModel(in)) return false;
+		if(!_isConnected) return false;
+		isIndex=true;
+		return true;
+	}
+
+	
+	public boolean readRegions(InputStream in, int chanW, int chanH) throws java.io.IOException {
+		//clear the _data array
+		for(int h=0; h<chanH; h++) {
+			for(int w =0; w<chanW; w++) {
+				_data[chanW*h+w]=0;
+			}
+		}
+  
+		int numColors=readInt(in);
+		if(!_isConnected) return false;
+		for(int curColor = 0; curColor < numColors; curColor++) {
+			int numRegions = readInt(in);
+			if(!_isConnected) return false;
+            
+			readBytes(_tmp,in,36*numRegions);
+			if(!_isConnected) return false;
+            	
+			int dpos=0;
+			for (int i = 0; i<numRegions; i++) {
+				byte color= _tmp[dpos];
+				dpos +=4;
+				int x1 = byteToInt(_tmp,dpos);
+				dpos +=4;
+				int y1 = byteToInt(_tmp,dpos);
+				dpos +=4;
+				int x2 = byteToInt(_tmp,dpos);
+				dpos +=4;
+				int y2 = byteToInt(_tmp,dpos);
+				//The  data of the centroid, area and run_start are ignored
+				dpos +=20; //isn't nessescary, but now it nicely adds up to 36
+				if (  x1 > chanW || y1 > chanH || x2 > chanW || y2 > chanH
+							|| x1 > x2 || y1 > y2
+							|| x1 < 0 || x2 < 0 || y1 < 0 || y2 < 0
+							)
+					return false;
+				
+				//Fill the data array with the bounding boxes..
+				//..the top and bottom lines
+				for (int tb = x1; tb <= x2; tb++) {
+					_data[y1*width+tb]=color;
+					_data[y2*width+tb]=color;
+				}
+				//..the left and right lines
+				for (int lr = y1; lr <= y2; lr++) {
+					_data[lr*width+x1]=color;
+					_data[lr*width+x2]=color;
+				}
+			}
+			readBytes(_tmp,in,12); //read out the min_area, total_area and merge_threshhold and ignore them:)
+		}
+		if(!readColorModel(in)) return false;
+		if(!_isConnected) return false;
+		isIndex=true;
+		return true;
+	}
+
+
+	public void connected(DatagramSocket UDPsocket, DatagramPacket incoming) {
+		_isConnected=true;
+		mysock = UDPsocket;
+		while(listeners==null) {
+			System.out.println("Assert: Bad race condition -- shouldn't be happening");
+			Thread.yield();
+		}
+		try {
+			fireConnected();
+			while(!mysock.isClosed()) {
+				in = new ByteArrayInputStream(incoming.getData());
+				String type = readLoadSaveString(in);
+				if(!_isConnected) break; //System.out.println("Got type="+type);
+				if(!type.equals("TekkotsuImage")) {
+					if(type.startsWith("#POS\n")) {
+						sensors=type;
+						//System.out.println("got sensors");
+						fireSensorUpdate();
+						if(destroy)
+							break;
+						mysock.receive(incoming);
+						continue;
+					} else if(!type.equals("CloseConnection"))
+						System.err.println("Unrecognized type: "+type);
+					else {
+						System.out.println("Got Close connection packet");
+						_isConnected=false;
+					}
+					break;
+				}
+				format=readInt(in);
+				if(!_isConnected) break; //System.out.println("Got format="+format);
+				compression=readInt(in);
+				if(!_isConnected) break; //System.out.println("Got compression="+compression);
+				int newWidth=readInt(in);
+				if(!_isConnected) break; //System.out.println("Got newWidth="+newWidth);
+				int newHeight=readInt(in);
+				if(!_isConnected) break; //System.out.println("Got newHeight="+newHeight);
+				long timest=readInt(in);
+				if(timest<0)
+					timest+=(1L<<32);
+				if(!_isConnected) break; //System.out.println("Got timest="+timest);
+				frameNum=readInt(in);
+				if(frameNum<0)
+					frameNum+=(1L<<32);
+				if(!_isConnected) break; //System.out.println("Got frameNum="+frameNum);
+				
+				if (format!=oldformat || newWidth!=width || newHeight!=height) {
+					width=newWidth;
+					height=newHeight;
+					synchronized (_outd) {
+						switch (format) {
+						case ENCODE_COLOR:
+							channels=3;
+							pktSize=width*height*channels;
+							break;
+						case ENCODE_SINGLE_CHANNEL:
+							channels=1;
+							pktSize=width*height*channels;
+							break;
+						default:
+							System.err.println("VisionRawListener: unknown packet type "+format);
+							throw new java.lang.NoSuchFieldException("fake exception");
+						}
+						_data=new byte[pktSize];
+						_outd=new byte[pktSize];
+						_tmp=new byte[pktSize];
+						_jpeg=new byte[pktSize*2<2000?2000:pktSize*2];
+						_newjpeg=new byte[pktSize*2<2000?2000:pktSize*2];
+						_pixels=new int[width*height];;
+						img=new BufferedImage(width,height,BufferedImage.TYPE_INT_RGB);
+						oldformat=format;
+					}
+				}
+				
+				boolean failed=false;
+				for(int i=0; i<channels; i++) {
+					String creator = readLoadSaveString(in);
+					if(!_isConnected) break; //System.out.println("Got creator="+creator);
+					if(!creator.equals("FbkImage")) {
+						System.err.println("Unrecognized creator: "+creator);
+						failed=true; break;
+					} else {
+						int chanwidth=readInt(in);
+						if(!_isConnected) break; //System.out.println("Got chanwidth="+chanwidth);
+						int chanheight=readInt(in);
+						if(!_isConnected) break; //System.out.println("Got chanheight="+chanheight);
+						
+						if(chanwidth>width || chanheight>height) {
+							System.err.println("channel dimensions exceed image dimensions");
+							failed=true; break;
+						}
+						
+						int layer=readInt(in);
+						if(!_isConnected) break; //System.out.println("Got layer="+layer);
+						chan_id=readInt(in);
+						if(!_isConnected) break; //System.out.println("Got chan_id="+chan_id);
+				
+						String fmt=readLoadSaveString(in);
+						if(!_isConnected) break; //System.out.println("Got fmt="+fmt);
+						if(fmt.equals("blank")) {
+							isJPEG=false;
+							isIndex=false;
+							int useChan=(channels==1)?i:chan_id;
+							int off=useChan;
+							for(int y=0; y<height; y++)
+								for(int x=0; x<width; x++) {
+									_data[off]=(byte)(convertRGB?0x80:0);
+									off+=channels;
+								}
+						} else if(fmt.equals("RawImage")) {
+							isJPEG=false;
+							isIndex=false;
+							int useChan=(channels==1)?i:chan_id;
+							if(!readChannel(in,useChan,chanwidth,chanheight)) { failed=true; System.err.println("UDPVisionListener channel read failed"); break; }
+						} else if(fmt.equals("JPEGGrayscale")) {
+							isIndex=false;
+							int useChan=(channels==1)?i:chan_id;
+							if(!readJPEGChannel(in,useChan,chanwidth,chanheight)) { failed=true; System.err.println("UDPVisionListener JPEGGreyscale channel read failed"); break; }
+							isJPEG=(channels==1);
+						} else if(fmt.equals("JPEGColor")) {
+							isIndex=false;
+							if(format==ENCODE_SINGLE_CHANNEL)
+								System.err.println("WTF? ");
+							if(!readJPEG(in,chanwidth,chanheight)) { failed=true; System.err.println("UDPVisionListener JPEGColor channel read failed"); break; }
+							i=channels;
+							isJPEG=true;
+						} else if(fmt.equals("SegColorImage")) {
+							isJPEG=false;
+							isIndex=true;
+							if(!readIndexedColor(in,chanwidth,chanheight)) { failed=true; System.err.println("UDPVisionListener SegColor read failed"); break; }
+						} else if(fmt.equals("RLEImage")) {
+							isJPEG=false;
+							isIndex=true;
+							if(!readRLE(in,chanwidth,chanheight)) { failed=true; System.err.println("UDPVisionListener RLEImage read failed"); break; }
+						} else if(fmt.equals("RegionImage")) {
+							isJPEG=false;
+							isIndex=true;
+							if(!readRegions(in,chanwidth,chanheight)) { failed=true; System.err.println("UDPVisionListener RegionImage read failed"); break; }
+						} else {
+							isJPEG=false;
+							isIndex=false;
+							System.err.println("Unrecognized format: "+fmt);
+							failed=true; break;
+						}
+					}
+				}
+				if(failed || !_isConnected) {
+					System.err.println("UDPVisionListener connection lost");
+					break;
+				}
+				
+				synchronized(_outd) {
+					byte[] temp=_data;
+					_data=_outd;
+					_outd=temp;
+					if(isJPEG) {
+						temp=_newjpeg;
+						_newjpeg=_jpeg;
+						_jpeg=temp;
+						int tempi=newjpegLen;
+						newjpegLen=jpegLen;
+						jpegLen=tempi;
+					}
+					timestamp=new Date(timest);
+				}
+				updatedFlag=true;
+				fireVisionUpdate();
+				if(destroy) //close requested
+					close(); //try to request final sensor frame again (might've dropped packet)
+				mysock.receive(incoming);
+			}
+		} catch (Exception ex) {
+    } finally {
+      fireDisconnected();
+    }
+		
+		try { mysock.close(); } catch (Exception ex) { }
+		if(!_isConnected) {
+			if(!destroy)
+				System.out.println("Waiting 5 seconds to reconnect");
+			try { Thread.sleep(5000); } catch (Exception ex) {}
+		}
+		_isConnected=false;
+		fireVisionUpdate();
+	}
+	
+	public byte[] getData() {
+		synchronized (_outd) {
+			updatedFlag=false;
+			return _outd;
+		}
+	}
+
+	public void setConvertRGB(boolean b) { 
+		if(b!=convertRGB) {
+			convertRGB=b;
+			updatedFlag=true;
+		}
+	}
+	public boolean getConvertRGB() { return convertRGB; }
+
+	public int[] getYUVPixels() {
+		synchronized(_outd) {
+			byte[] data=getData();
+			int offset=0;
+			for (int i=0; i<width*height; i++) {
+				int y=(int)data[offset++]&0xFF;
+				int u=(int)data[offset++]&0xFF;
+				int v=(int)data[offset++]&0xFF;
+				_pixels[i]=(255<<24) | (y<<16) | (u<<8) | v;
+			}
+		}
+		return _pixels;
+	}
+
+	//This still uses RGB pixels just in case you want to display the
+	//intensity value into hues instead of black/white
+	public int[] getIntensityPixels() {
+		synchronized(_outd) {
+			byte[] data=getData();
+			int offset=0;
+			if(!getConvertRGB()) {
+				for (int i=0; i<width*height; i++) {
+					int z=(int)data[offset++]&0xFF;
+					_pixels[i]=(255<<24) | (z<<16) | (z<<8) | z;
+				}
+			} else if(chan_id==CHAN_Y || chan_id==CHAN_Y_DY || chan_id==CHAN_Y_DX || chan_id==CHAN_Y_DXDY ) {
+				for (int i=0; i<width*height; i++) {
+					int z=(int)data[offset++]&0xFF;
+					_pixels[i]=pixelYUV2RGB(z,0x80,0x80);
+				}
+			} else if(chan_id==CHAN_U) {
+				for (int i=0; i<width*height; i++) {
+					int z=(int)data[offset++]&0xFF;
+					_pixels[i]=pixelYUV2RGB(0x80,z,0x80);
+				}
+			} else if(chan_id==CHAN_V) {
+				for (int i=0; i<width*height; i++) {
+					int z=(int)data[offset++]&0xFF;
+					_pixels[i]=pixelYUV2RGB(0x80,0x80,z);
+				}
+			}
+		}		
+		return _pixels;
+	}
+
+	public int[] getRGBPixels() {
+		synchronized(_outd) {
+			byte[] data=getData();
+			int offset=0;
+			for (int i=0; i<width*height; i++) {
+				int y=(int)data[offset++]&0xFF;
+				int u=(int)data[offset++]&0xFF;
+				int v=(int)data[offset++]&0xFF;
+				_pixels[i]=pixelYUV2RGB(y, u, v);
+			}
+		}
+		return _pixels;
+	}
+
+	static final int pixelYUV2RGB(int y, int u, int v) {
+		u=u*2-255;
+		v=v-128;
+		int b=y+u;
+		int r=y+v;
+		v=v>>1;
+		u=(u>>2)-(u>>4);
+		int g=y-u-v;
+		if (r<0) r=0; if (g<0) g=0; if (b<0) b=0;
+		if (r>255) r=255; if (g>255) g=255; if (b>255) b=255;
+		return (255<<24) | (r<<16) | (g<<8) | b;
+	}
+
+	public BufferedImage getImage() {
+		if(!updatedFlag)
+			return img;
+		if(isIndex) {
+			byte[] data=getData();
+			if(cmodel==null)
+				return img;
+			if(img.getWidth()!=width || img.getHeight()!=height || img.getType()!=BufferedImage.TYPE_BYTE_INDEXED)
+				img=new BufferedImage(width,height,BufferedImage.TYPE_BYTE_INDEXED,cmodel);
+			img.getRaster().setDataElements(0,0,width,height,data);
+		} else {
+			int[] pix;
+			if(img.getWidth()!=width || img.getHeight()!=height || img.getType()!=BufferedImage.TYPE_INT_RGB)
+				img=new BufferedImage(width,height,BufferedImage.TYPE_INT_RGB);
+			synchronized(_outd) {
+				if(format==ENCODE_COLOR)
+					pix=getConvertRGB()?getRGBPixels():getYUVPixels();
+				else
+					pix=getIntensityPixels();
+				img.setRGB(0,0,width,height,pix,0,width);
+			}
+		}
+		return img;
+	}
+
+	public void close() {
+		if(mysock==null || mysock.isClosed())
+			return;
+		destroy=true;
+		byte[] buf = (new String("refreshSensors\n")).getBytes();
+		try {
+			mysock.send(new DatagramPacket(buf,buf.length));
+		} catch(Exception e) { e.printStackTrace(); }
+		//wait until the final sensors comes in so if user hits save image we can save the corresponding sensors too
+	}
+
+	public void startSensors() {
+		byte[] buf = (new String("startSensors\n")).getBytes();
+		try {
+			mysock.send(new DatagramPacket(buf,buf.length));
+		} catch(Exception e) { e.printStackTrace(); }
+	}
+
+	public void stopSensors() {
+		byte[] buf = (new String("stopSensors\n")).getBytes();
+		try {
+			mysock.send(new DatagramPacket(buf,buf.length));
+		} catch(Exception e) { e.printStackTrace(); }
+	}
+
+	public UDPVisionListener() { super(); }
+	public UDPVisionListener(int port) { super(port); }
+	public UDPVisionListener(String host, int port) { super(host,port); }
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/VisionGUI.java ./tools/mon/org/tekkotsu/mon/VisionGUI.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/VisionGUI.java	2005-08-05 15:44:23.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/VisionGUI.java	2006-06-26 12:31:34.000000000 -0400
@@ -2,6 +2,7 @@
 
 import java.awt.event.*;
 import javax.swing.*;
+import javax.swing.filechooser.FileFilter;
 import java.lang.String;
 import java.util.LinkedList;
 import java.awt.*;
@@ -11,6 +12,7 @@
 import java.util.Date;
 import java.io.PrintWriter;
 import java.io.FileOutputStream;
+import java.io.FileWriter;
 import java.util.prefs.Preferences;
 import java.io.File;
 
@@ -29,6 +31,7 @@
 	boolean isRLE=false;
 	boolean connected=false;
 	boolean isFreezeFrame=false;
+	JRadioButton rgbMode,yuvMode;
 	final static ImageIcon carrows = new ImageIcon("images/chasingarrows.png");
 	ImageSequenceWriterThread imgWrite=null;
 	String state="Connecting...";
@@ -64,7 +67,7 @@
 						ans+="Free="+imgWrite.imgBufs.size();
 				} else
 					ans="Writing";
-				ans+=" Queue="+imgWrite.q.size();
+				ans+=" Queue="+imgWrite.q.size()/4;
 				return ans;
 			} else
 				return "";
@@ -77,6 +80,104 @@
 					return "";
 		}
 	}
+
+	public class SaveSequenceDialog extends JDialog implements ActionListener {
+		JFileChooser dia;
+		boolean success;
+		JCheckBox positionsBut;
+		JButton saveBut;
+		JButton cancelBut;
+		VisionGUI gui;
+		SaveSequenceDialog(VisionGUI vg, File curpath) {
+			super(vg,"Save Image Sequence...");
+			gui=vg;
+			{
+				Box tmp=Box.createVerticalBox();
+				dia=new JFileChooser(curpath);
+				//dia.setControlButtonsAreShown(false);
+				dia.setApproveButtonText("Save Here");
+				dia.setDialogType(JFileChooser.SAVE_DIALOG);
+				dia.addActionListener(this);
+				tmp.add(dia);
+				{
+					Box tmp2=Box.createHorizontalBox();
+					tmp2.add(Box.createHorizontalStrut(10));
+					positionsBut=new JCheckBox("Save joint positions as well",!VisionGUI.prefs.get("save_positions","0").equals("0"));
+					positionsBut.addActionListener(this);
+					tmp2.add(positionsBut);
+					tmp2.add(Box.createHorizontalGlue());
+					tmp.add(tmp2);
+				}
+				/*
+				tmp.add(Box.createVerticalStrut(5));
+				{
+					Box tmp2=Box.createHorizontalBox();
+					tmp2.add(Box.createHorizontalGlue());
+					saveBut=new JButton("Save Here");
+					saveBut.addActionListener(this);
+					tmp2.add(saveBut);
+					tmp2.add(Box.createHorizontalStrut(5));
+					cancelBut=new JButton("Cancel");
+					cancelBut.addActionListener(this);
+					tmp2.add(cancelBut);
+					tmp2.add(Box.createHorizontalStrut(10));
+					tmp.add(tmp2);
+					}*/
+				tmp.add(Box.createVerticalStrut(10));
+				getContentPane().add(tmp,BorderLayout.CENTER);
+				getRootPane().setDefaultButton(saveBut);
+			}
+			pack();
+			success=false;
+		}
+		public void actionPerformed(ActionEvent e) {
+			/*if(e.getSource()==saveBut) {
+				success=true;
+				dia.approveSelection();
+				dispose();
+			} else if(e.getActionCommand().equals("Cancel")) {
+				dia.cancelSelection();
+				dispose();
+				} else */
+			if(e.getSource()==positionsBut) {
+				VisionGUI.prefs.put("save_positions",positionsBut.isSelected()?"1":"0");
+			} else if(e.getSource()==dia) {
+				if(e.getActionCommand().equals("ApproveSelection")) {
+					boolean isRGB=gui.vision.getConvertRGB(); 
+					boolean haveJPEGs=gui.vision.getListener().hasRawJPEG();
+					String name=dia.getSelectedFile().getName();
+					boolean hasExtension=name.lastIndexOf(".")!=-1;
+					boolean toJPEG=name.endsWith(".jpeg") || name.endsWith(".jpg");
+					if(!toJPEG && haveJPEGs) {
+						if(hasExtension) {
+							int n=JOptionPane.showConfirmDialog(this,"The original data stream consists of JPEG images, are you sure you\nwant to save in a different format?","Convert formats?",JOptionPane.OK_CANCEL_OPTION);
+							if(n!=JOptionPane.OK_OPTION)
+								return;
+						} else {
+							//silently default to JPEG if left unspecified
+							dia.setSelectedFile(new File(dia.getSelectedFile().getPath()+".jpg"));
+							hasExtension=toJPEG=true;
+						}
+					}
+					if(toJPEG) {
+						if(!isRGB) {
+							int n=JOptionPane.showConfirmDialog(this,"JPEGs store YUV data internally, so it is recommended to save JPEGs as\n\"RGB\" images so the YUV data can be extracted directly from the\ninternal storage, avoiding color space conversions.\n\nDo you want to switch to \"RGB\" mode? (recommended)\n","Save 'RGB' jpeg?",JOptionPane.YES_NO_CANCEL_OPTION);
+							if(n==JOptionPane.YES_OPTION)
+								gui.rgbMode.doClick();
+							if(n==JOptionPane.CANCEL_OPTION)
+								return;
+						}
+					}
+					success=true;
+					dispose();
+				} else if(e.getActionCommand().equals("CancelSelection")) {
+					dispose();
+				}
+			}
+		}
+		public File getCurrentDirectory() { return dia.getCurrentDirectory(); }
+		public File getSelectedFile() { return dia.getSelectedFile(); }
+	}
 	
 	public static void main(String s[]) {
 		int port=-1;
@@ -108,36 +209,17 @@
 			vision.setLockAspectRatio(((JCheckBox)e.getSource()).isSelected());
 		} else if(e.getActionCommand().compareTo("seq")==0) {
 			File cursavepath = new File(prefs.get("cursavepath",""));
-			JFileChooser dia=new JFileChooser(cursavepath);
-			dia.setDialogTitle("Save Image Sequence...");
-			Component cur=this;
-			while(cur.getParent()!=null)
-				cur=cur.getParent();
-			if(dia.showSaveDialog(cur)==JFileChooser.APPROVE_OPTION) {
-				prefs.put("cursavepath",dia.getCurrentDirectory().getPath());
-				imgWrite=new ImageSequenceWriterThread(vision.getListener(), saveImageBut, !vision.getConvertRGB());
-				saveImageBut.setText("Stop Saving Sequence");
-				saveImageBut.setToolTipText("Click to stop buffering new frames - already captured frames will continue to be written (unless you close the window)");
-				saveImageBut.setActionCommand("stopseq");
-				String base=dia.getSelectedFile().getName();
-				String format;
-				if(base.lastIndexOf('.')==-1) {
-					format="png";
-				} else {
-					int i=base.lastIndexOf(".");
-					format=base.substring(i+1);
-					base=base.substring(0,i);
-				}
-				int first=base.indexOf('#');
-				int last=base.lastIndexOf('#');
-				boolean appendTime=(first==-1);
-				imgWrite.setDirectory(dia.getSelectedFile().getParent());
-				if(first!=-1)
-					imgWrite.setName(base.substring(0,first),last-first+1,base.substring(last+1),format);
-				else
-					imgWrite.setName(base,0,"",format);
-				imgWrite.start();
-			}
+			SaveSequenceDialog dia = new SaveSequenceDialog(this,cursavepath);
+			dia.setVisible(true);
+			dia.addWindowListener(new WindowAdapter() {
+					public void windowClosed(WindowEvent e) {
+						SaveSequenceDialog dia=(SaveSequenceDialog)e.getWindow();
+						dia.removeWindowListener(this);
+						prefs.put("cursavepath",dia.getCurrentDirectory().getPath());
+						if(dia.success)
+							dia.gui.startSaveSequence(dia.getSelectedFile(),dia.positionsBut.isSelected());
+					}
+				});
 		} else if(e.getActionCommand().compareTo("stopseq")==0) {
 			saveImageBut.setText("Save Image Sequence");
 			saveImageBut.setToolTipText("Saves to a series of files - use .jpg or .png extension to choose format; #'s will be replaced with index, otherwise timecode is appended");
@@ -146,39 +228,77 @@
 				imgWrite.interrupt();
 		} else if(e.getActionCommand().compareTo("img")==0) {
 			File cursavepath = new File(prefs.get("cursavepath",""));
-			JFileChooser dia=new JFileChooser(cursavepath);
-			dia.setDialogTitle("Save Image...");
-			Component cur=this;
-			while(cur.getParent()!=null)
-				cur=cur.getParent();
-			if(dia.showSaveDialog(cur)==JFileChooser.APPROVE_OPTION) {
-				prefs.put("cursavepath",dia.getCurrentDirectory().getPath());
-				String base=dia.getSelectedFile().getName();
-				String format;
-				if(base.lastIndexOf('.')==-1) {
-					format="png";
-				} else {
-					int i=base.lastIndexOf(".");
-					format=base.substring(i+1);
-					base=base.substring(0,i);
-				}
-				try {
-					FileOutputStream fileout=new FileOutputStream(dia.getSelectedFile().getParent()+File.separator+base+"."+format);
-					if(vision.getConvertRGB() && vision.getListener().hasRawJPEG() && (format.equalsIgnoreCase("jpg") || format.equalsIgnoreCase("jpeg"))) {
-						byte[] jpeg=vision.getListener().getJPEG();
-						int len=vision.getListener().getJPEGLen();
-						fileout.write(jpeg,0,len);
-					} else {
-						ImageIO.write(vision.getListener().getImage(),format,fileout);
+			SaveSequenceDialog dia = new SaveSequenceDialog(this,cursavepath);
+			dia.setVisible(true);
+			dia.addWindowListener(new WindowAdapter() {
+					public void windowClosed(WindowEvent e) {
+						SaveSequenceDialog dia=(SaveSequenceDialog)e.getWindow();
+						dia.removeWindowListener(this);
+						prefs.put("cursavepath",dia.getCurrentDirectory().getPath());
+						if(dia.success)
+							dia.gui.saveImage(dia.getSelectedFile(),dia.positionsBut.isSelected());
 					}
-				} catch(Exception ex) {ex.printStackTrace();}
-			}
+				});
 		} else if(e.getSource()==reconnectBut) {
-			vision.close();
+			vision.kill();
 			vision.open();
 		}
 	}
 
+	void startSaveSequence(File file, boolean positions) {
+		imgWrite=new ImageSequenceWriterThread(vision.getListener(), saveImageBut, !vision.getConvertRGB(), positions);
+		saveImageBut.setText("Stop Saving Sequence");
+		saveImageBut.setToolTipText("Click to stop buffering new frames - already captured frames will continue to be written (unless you close the window)");
+		saveImageBut.setActionCommand("stopseq");
+		String base=file.getName();
+		String format;
+		if(base.lastIndexOf('.')==-1) {
+			format="png";
+		} else {
+			int i=base.lastIndexOf(".");
+			format=base.substring(i+1);
+			base=base.substring(0,i);
+		}
+		int first=base.indexOf('#');
+		int last=base.lastIndexOf('#');
+		boolean appendTime=(first==-1);
+		imgWrite.setDirectory(file.getParent());
+		if(first!=-1)
+			imgWrite.setName(base.substring(0,first),last-first+1,base.substring(last+1),format);
+		else
+			imgWrite.setName(base,0,"",format);
+		imgWrite.start();
+	}
+
+	void saveImage(File file, boolean savePose) {
+		String base=file.getName();
+		String format;
+		if(base.lastIndexOf('.')==-1) {
+			format="png";
+		} else {
+			int i=base.lastIndexOf(".");
+			format=base.substring(i+1);
+			base=base.substring(0,i);
+		}
+		try {
+			FileOutputStream fileout=new FileOutputStream(file.getParent()+File.separator+base+"."+format);
+			if(vision.getConvertRGB() && vision.getListener().hasRawJPEG() && (format.equalsIgnoreCase("jpg") || format.equalsIgnoreCase("jpeg"))) {
+				byte[] jpeg=vision.getListener().getJPEG();
+				int len=vision.getListener().getJPEGLen();
+				fileout.write(jpeg,0,len);
+			} else {
+				ImageIO.write(vision.getListener().getImage(),format,fileout);
+			}
+		} catch(Exception ex) {ex.printStackTrace();}
+		if(savePose) {
+			format="pos";
+			try {
+				FileOutputStream fileout=new FileOutputStream(file.getParent()+File.separator+base+"."+format);
+				fileout.write(vision.getListener().getSensors().getBytes());
+			} catch(Exception ex) {ex.printStackTrace();}
+		}
+	}
+
 	class CloseVisionAdapter extends WindowAdapter {
 		VisionGUI gui;
 		CloseVisionAdapter(VisionGUI gui) {this.gui=gui;}
@@ -194,7 +314,7 @@
 		//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(name+".x",getLocation().x+getInsets().left);
 		//prefs.putInt(name+".y",getLocation().y+getInsets().top);
-		this.vision.close();
+		this.vision.kill();
 		if(this.imgWrite!=null && this.imgWrite.isAlive()) {
 			if(!this.imgWrite.isInterrupted() && !this.imgWrite.stopping)
 				this.imgWrite.interrupt();
@@ -254,6 +374,7 @@
 			lastFrameTime=0;
 		}
 	}
+	public void sensorsUpdated(VisionListener l) {}
 	
 	public VisionGUI(String host, String[] args) {
 		super();
@@ -302,18 +423,17 @@
 				if(!isRLE) {
 					Box tmp4=Box.createHorizontalBox();
 					ButtonGroup group=new ButtonGroup();
-					JRadioButton tmpRad;
-					tmpRad=new JRadioButton("RGB");
-					tmpRad.setSelected(true);
-					tmpRad.addActionListener(this);
-					tmpRad.setToolTipText("Shows RGB colorspace");
-					group.add(tmpRad);
-					tmp4.add(tmpRad);
-					tmpRad=new JRadioButton("YUV");
-					tmpRad.addActionListener(this);
-					tmpRad.setToolTipText("Shows YUV colorspace");
-					group.add(tmpRad);
-					tmp4.add(tmpRad);
+					rgbMode=new JRadioButton("RGB");
+					rgbMode.setSelected(true);
+					rgbMode.addActionListener(this);
+					rgbMode.setToolTipText("Shows RGB colorspace");
+					group.add(rgbMode);
+					tmp4.add(rgbMode);
+					yuvMode=new JRadioButton("YUV");
+					yuvMode.addActionListener(this);
+					yuvMode.setToolTipText("Shows YUV colorspace");
+					group.add(yuvMode);
+					tmp4.add(yuvMode);
 					tmp3.add(tmp4);
 				}
 				aspectBut=new JCheckBox("Lock Aspect Ratio");
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/VisionListener.java ./tools/mon/org/tekkotsu/mon/VisionListener.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/VisionListener.java	2005-08-05 15:44:23.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/VisionListener.java	2005-08-31 17:59:27.000000000 -0400
@@ -45,6 +45,9 @@
 	void fireVisionUpdate();
 	public boolean isConnected();
 
+	public void startSensors();
+	public void stopSensors();
+
 	public Date getTimeStamp();
 	public long getFrameNum();
 	public IndexColorModel getColorModel();
@@ -53,7 +56,8 @@
 	public byte[] getJPEG();
 	public int getJPEGLen();
 	
-    public byte[] getData();
+	public byte[] getData();
+	public String getSensors();
 	public void setConvertRGB(boolean b);
 	public boolean getConvertRGB();
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/VisionPanel.java ./tools/mon/org/tekkotsu/mon/VisionPanel.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/VisionPanel.java	2005-08-05 17:25:42.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/VisionPanel.java	2006-10-02 16:38:23.000000000 -0400
@@ -26,7 +26,7 @@
                                                    MouseListener,
 						   MouseMotionListener
 {
-    boolean usingSketchGUI;
+    boolean usingSketchGUI=false;
 
     protected boolean windowHasFocus;
     protected boolean crosshairsEnabled=false;
@@ -38,8 +38,8 @@
     float tgtAspect=-1;
 
     SketchGUI gui;
-    //    boolean isCam;
-    int space;
+    protected SketchGUI.Space space;
+    //    public int space;
 
     int drawX, drawY, drawHeight, drawWidth;
 
@@ -77,15 +77,13 @@
 	public void setConvertRGB(boolean b) { _listener.setConvertRGB(b); }
 	public boolean getConvertRGB() { return _listener.getConvertRGB(); }
 
-    //	public VisionPanel(VisionListener listener, SketchGUI _gui, boolean _isCam) {
-	public VisionPanel(VisionListener listener, SketchGUI _gui, int _space) {
-		super();
-		init(listener);
-		gui = _gui;
-		//isCam = _isCam;
-		space = _space;
+    //	public VisionPanel(VisionListener listener, SketchGUI _gui, int _space) {
+        public VisionPanel(VisionListener listener, SketchGUI _gui, SketchGUI.Space _space) {
+	    super();
 		usingSketchGUI = true;
-		_listener.removeListener(this);
+	    init(listener);
+	    gui = _gui;
+	    space = _space;
 	}
 	
 	public VisionPanel(String host, String[] args) {
@@ -136,7 +134,6 @@
 	}
 	
 	public void init(VisionListener listener) {
-	    usingSketchGUI = false;
 	    setBackground(Color.BLACK);
 	    setForeground(Color.WHITE);
 	    setOpaque(!lockAspect);
@@ -145,14 +142,16 @@
 	    windowHasFocus = true;
 	    crosshairsEnabled = false;
 	    _listener=listener;
-	    _listener.addListener(this);
+		_listener.addListener(this);
 	}
 
    
 	public VisionListener getListener() { return _listener; }
-	public void close() { _listener.kill();	}
+	public void close() { _listener.close();	}
+	public void kill() { _listener.kill(); }
 	public void open() { _listener.needConnection(); }
 	public void visionUpdated(VisionListener l) { repaint(); }
+	public void sensorsUpdated(VisionListener l) {}
 	
 	public void setLockAspectRatio(boolean b) {
 		if(b!=lockAspect) {
@@ -180,63 +179,63 @@
 		setAspectRatio(asp);
 	}
 	
-  public void paint(Graphics graphics) {
-      if (!usingSketchGUI) { _image=_listener.getImage(); }
-      super.paint(graphics);
-      Dimension sz=getSize();
-      drawX = 0;
-      drawY = 0;
-      drawWidth = sz.width;
-      drawHeight = sz.height;
-      // Scale image to fit the window size while maintaining aspect ratio.
-      // Center the image in the unused space if window width or height too large.
-      // Note: this only makes sense for cam space.
-      //      if (_image != null && getLockAspectRatio() && (!usingSketchGUI || isCam)) {
-      if (_image != null && getLockAspectRatio() && (!usingSketchGUI || space==1)) {
-	  float curasp=sz.width/(float)sz.height;
-	  float tgtasp=getAspectRatio();
-	  if(tgtasp<0)
-	      tgtasp=_image.getWidth()/(float)_image.getHeight();
-	  if(curasp>tgtasp) {
-	      drawWidth = (int)(sz.height*tgtasp);
-	      drawX = (sz.width-drawWidth)/2;
-	  } else if(curasp<tgtasp) {
-	      drawHeight = (int)(sz.width/tgtasp);
-	      drawY = (sz.height-drawHeight)/2;
-	  } else {
-	  }
-      }
-      drawImage(graphics, _image, drawX, drawY, drawWidth, drawHeight);
-      
-      // If requested, draw crosshairs for RawCam, SegCam, or cam sketchspace.
-      // Crosshairs for world sketchspace are handled in SketchPanel.java.
-      //      if (crosshairsEnabled && (!usingSketchGUI || isCam))
-      if (crosshairsEnabled && (!usingSketchGUI || space==1))
-	  {
-	      graphics.setXORMode(Color.GRAY);
-	      graphics.setColor(Color.WHITE);
-	      ((Graphics2D)graphics).setStroke(new BasicStroke(1.0f));
-	      graphics.drawLine(drawX+drawWidth/2,drawY, drawX+drawWidth/2, drawY+drawHeight);
-	      graphics.drawLine(drawX, drawY+drawHeight/2, drawX+drawWidth, drawY+drawHeight/2);
-	      graphics.setPaintMode();
-	  }
-  }
-
-    protected void drawImage(Graphics g, BufferedImage img, int x, int y, int w, int h) {
-	if(img!=null)
-	    g.drawImage(img,x,y,w,h,null);
-	else {
-	    g.setColor(getBackground());
-	    g.fillRect(x,y,w,h);
-	    FontMetrics tmp=g.getFontMetrics();
-	    String msg="No image";
-	    int strw=tmp.stringWidth(msg);
-	    int strh=tmp.getHeight();
-	    g.setColor(getForeground());
-	    g.drawString(msg,(getSize().width-strw)/2,(getSize().height-strh)/2+tmp.getAscent());
+	public void paint(Graphics graphics) {
+		if (!usingSketchGUI) { _image=_listener.getImage(); }
+		super.paint(graphics);
+		Dimension sz=getSize();
+		drawX = 0;
+		drawY = 0;
+		drawWidth = sz.width;
+		drawHeight = sz.height;
+		// Scale image to fit the window size while maintaining aspect ratio.
+		// Center the image in the unused space if window width or height too large.
+		// Note: this only makes sense for cam space.
+		if (_image != null && getLockAspectRatio() && (!usingSketchGUI || space==SketchGUI.Space.cam)) {
+			float curasp=sz.width/(float)sz.height;
+			float tgtasp=getAspectRatio();
+			if(tgtasp<0)
+				tgtasp=_image.getWidth()/(float)_image.getHeight();
+			if(curasp>tgtasp) {
+				drawWidth = (int)(sz.height*tgtasp);
+				drawX = (sz.width-drawWidth)/2;
+			} else if(curasp<tgtasp) {
+				drawHeight = (int)(sz.width/tgtasp);
+				drawY = (sz.height-drawHeight)/2;
+			} else {
+			}
+		}
+		drawImage(graphics, _image, drawX, drawY, drawWidth, drawHeight);
+		
+		// If requested, draw crosshairs for RawCam, SegCam.
+		// Crosshairs for SketchGUI are handled in SketchPanel.java.
+		if (crosshairsEnabled && !usingSketchGUI)
+		{
+			graphics.setXORMode(Color.GRAY);
+			graphics.setColor(Color.WHITE);
+			((Graphics2D)graphics).setStroke(new BasicStroke(1.0f));
+			graphics.drawLine(drawX+drawWidth/2,drawY, drawX+drawWidth/2, drawY+drawHeight);
+			graphics.drawLine(drawX, drawY+drawHeight/2, drawX+drawWidth, drawY+drawHeight/2);
+			graphics.setPaintMode();
+		}
 	}
-    }
-
+	
+	protected void drawImage(Graphics g, BufferedImage img, int x, int y, int w, int h) {
+		if(img!=null) {
+			synchronized(img) {
+				g.drawImage(img,x,y,w,h,null);
+			}
+		} else {
+			g.setColor(getBackground());
+			g.fillRect(x,y,w,h);
+			FontMetrics tmp=g.getFontMetrics();
+			String msg="No image";
+			int strw=tmp.stringWidth(msg);
+			int strh=tmp.getHeight();
+			g.setColor(getForeground());
+			g.drawString(msg,(getSize().width-strw)/2,(getSize().height-strh)/2+tmp.getAscent());
+		}
+	}
+	
     public void mouseDragged(MouseEvent e){}
 
     public void mouseMoved(MouseEvent e)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/VisionUpdatedListener.java ./tools/mon/org/tekkotsu/mon/VisionUpdatedListener.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/VisionUpdatedListener.java	2005-03-03 17:53:54.000000000 -0500
+++ ./tools/mon/org/tekkotsu/mon/VisionUpdatedListener.java	2005-08-31 17:59:27.000000000 -0400
@@ -1,7 +1,6 @@
 package org.tekkotsu.mon;
-
-public interface VisionUpdatedListener {
-	public void visionUpdated(VisionListener comm);
-}
-
-
+
+public interface VisionUpdatedListener {
+	public void visionUpdated(VisionListener comm);
+	public void sensorsUpdated(VisionListener comm);
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/WorldStateJointsListener.java ./tools/mon/org/tekkotsu/mon/WorldStateJointsListener.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/WorldStateJointsListener.java	2005-06-08 17:05:01.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/WorldStateJointsListener.java	2006-08-02 17:15:53.000000000 -0400
@@ -2,73 +2,146 @@
 
 import java.io.InputStream;
 import java.net.Socket;
+import java.util.Vector;
+import java.util.Map;
+import java.util.HashMap;
+import java.net.SocketException;
 
 public class WorldStateJointsListener extends TCPListener {
-  boolean _updatedFlag=false;
-  Joints _data;
-  Joints _outd;
-
-  public void connected(Socket socket) {
-    _isConnected=true;
-    _data=new Joints();
-    _outd=new Joints();
-    try {
-      InputStream in=socket.getInputStream();
-      fireConnected();
-      while (true) {
-        _data.timestamp=readInt(in);
-				//System.out.println("time="+_data.timestamp);
-				int NumPIDJoints=readInt(in);
-				_data.positions=new float[NumPIDJoints];
-				_data.duties=new float[NumPIDJoints];
-				//System.out.println("pid="+NumPIDJoints);
-        for (int i=0; i<NumPIDJoints; i++)
-          _data.positions[i]=readFloat(in);
+	boolean _updatedFlag=false;
+	Joints _data;
+	Joints _outd;
+	static final public int defPort=10031;
+	
+	Vector listeners=new Vector();
+	public interface UpdatedListener {
+		public void worldStateUpdated(WorldStateJointsListener mc);
+	}
+	public void addUpdatedListener(UpdatedListener mcl) { listeners.add(mcl); needConnection(); }
+	public void removeUpdatedListener(UpdatedListener mcl) {
+		listeners.remove(mcl);
+		if(listeners.size()==0)
+			kill();
+	}
+	void fireUpdated() {
+		_updatedFlag=true;
+		if(listeners==null) {
+			System.out.println("wtf?");
+			listeners=new Vector();
+		}
+		for(int i=0;i<listeners.size();i++)
+			((UpdatedListener)listeners.get(i)).worldStateUpdated(this);
+	}
+	
+	static Map commonListeners=new HashMap();
+	static public WorldStateJointsListener getCommonInstance(String host) {
+		return getCommonInstance(host,defPort);
+	}
+	static public WorldStateJointsListener getCommonInstance(String host, int port) {
+		WorldStateJointsListener wsjl=(WorldStateJointsListener)commonListeners.get(host+":"+port);
+		if(wsjl!=null)
+			return wsjl;
+		//not found, need new connection
+		commonListeners.put(host+":"+port,wsjl=new WorldStateJointsListener(host,port));
+		return wsjl;
+	}
+	
+	public void connected(Socket socket) {
+		_isConnected=true;
+		_data=new Joints();
+		_outd=new Joints();
+		try {
+			InputStream in=socket.getInputStream();
+			fireConnected();
+			StringBuffer model=new StringBuffer();
+			while (true) {
+				//System.out.print("reading...");
+				model.delete(0,model.length());
+				char c;
+				while((c=readChar(in))!='\0') {
+					if(!_isConnected)
+						break;
+					model.append(c);
+				}
+				_data.model=model.toString();
+				//System.out.print(_data.model+"...");
+				
+				if(!_isConnected) break; //System.out.println("got packet from "+model);
+				_data.timestamp=readUnsignedInt(in);
+				if(!_isConnected) break; //System.out.println("time="+_data.timestamp);
+				_data.frame=readUnsignedInt(in);
+				if(!_isConnected) break; //System.out.println("frame="+_data.frame);
+				
+				int NumOutputs=readInt(in);
+				if(!_isConnected) break; //System.out.println("outputs="+NumOutputs);
+				if(_data.positions.length!=NumOutputs)
+					_data.positions=new float[NumOutputs];
+				for (int i=0; i<_data.positions.length; i++)
+					_data.positions[i]=readFloat(in);
+				if(!_isConnected) break;
+				
 				int NumSensors=readInt(in);
-				_data.sensors=new float[NumSensors];
-				//System.out.println("sensor="+NumSensors);
-        for (int i=0; i<NumSensors; i++)
-          _data.sensors[i]=readFloat(in);
+				if(!_isConnected) break; //System.out.println("sensors="+NumSensors);
+				if(_data.sensors.length!=NumSensors)
+					_data.sensors=new float[NumSensors];
+				for (int i=0; i<_data.sensors.length; i++)
+					_data.sensors[i]=readFloat(in);
+				if(!_isConnected) break;
+				
 				int NumButtons=readInt(in);
-				_data.buttons=new float[NumButtons];
-				//System.out.println("button="+NumButtons);
-        for (int i=0; i<NumButtons; i++)
-          _data.buttons[i]=readFloat(in);
-        for (int i=0; i<NumPIDJoints; i++)
-          _data.duties[i]=readFloat(in);
-
-        synchronized(_outd) {
-          Joints temp=_data;
-          _data=_outd;
-          _outd=temp;
-          _updatedFlag=true;
-        }
-      }
-    } catch (Exception ex) {
-    } finally {
-      fireDisconnected();
-    }
-
-    try { socket.close(); } catch (Exception ex) { }
-    _isConnected=false;
-  }
- 
-  public boolean hasData() {
-    return _updatedFlag;
-  }
-
-  public Joints getData() {
-    synchronized (_outd) {
-      _updatedFlag=false;
-      return _outd;
-    }
-  }
-
-  public boolean isConnected() {
-    return _isConnected;
-  }
-
-  public WorldStateJointsListener() { super(); needConnection(); }
-  public WorldStateJointsListener(int port) { super(port); needConnection(); }
-  public WorldStateJointsListener(String host, int port) { super(host,port); needConnection(); }
+				if(!_isConnected) break; //System.out.println("buttons="+NumButtons);
+				if(_data.buttons.length!=NumButtons)
+					_data.buttons=new float[NumButtons];
+				for (int i=0; i<_data.buttons.length; i++)
+					_data.buttons[i]=readFloat(in);
+				if(!_isConnected) break;
+				
+				int NumPIDJoints=readInt(in);
+				if(!_isConnected) break; //System.out.println("pids="+NumPIDJoints);
+				if(_data.duties.length!=NumPIDJoints)
+					_data.duties=new float[NumPIDJoints];
+				for (int i=0; i<_data.duties.length; i++)
+					_data.duties[i]=readFloat(in);
+				if(!_isConnected) break;
+				
+				//System.out.print("updating...");
+				synchronized(_outd) {
+					Joints temp=_data;
+					_data=_outd;
+					_outd=temp;
+					fireUpdated();
+				}
+				//System.out.println("done");
+			}
+			//System.out.print("closing...");
+		} catch (SocketException e) {
+		} catch (Exception e) {
+			e.printStackTrace();
+		} finally {
+			fireDisconnected();
+		}
+		
+		try { socket.close(); } catch (Exception ex) { }
+		_isConnected=false;
+		//System.out.println("closed");
+	}
+	
+	public boolean hasData() {
+		return _updatedFlag;
+	}
+	
+	public Joints getData() {
+		synchronized (_outd) {
+			_updatedFlag=false;
+			return _outd;
+		}
+	}
+	
+	public boolean isConnected() {
+		return _isConnected;
+	}
+	
+	public WorldStateJointsListener() { super(); }
+	public WorldStateJointsListener(int port) { super(port); }
+	public WorldStateJointsListener(String host, int port) { super(host,port); }
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/WorldStateRecordGUI.java ./tools/mon/org/tekkotsu/mon/WorldStateRecordGUI.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/mon/WorldStateRecordGUI.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/org/tekkotsu/mon/WorldStateRecordGUI.java	2005-09-13 18:09:54.000000000 -0400
@@ -0,0 +1,244 @@
+package org.tekkotsu.mon;
+
+import javax.swing.*;
+import java.awt.*;
+import java.awt.event.WindowAdapter;
+import java.awt.event.WindowEvent;
+import java.awt.event.ActionListener;
+import java.awt.event.ActionEvent;
+import java.util.prefs.Preferences;
+import java.io.*;
+
+public class WorldStateRecordGUI extends JFrame implements ActionListener, Listener.ConnectionListener, WorldStateJointsListener.UpdatedListener {
+	JLabel status;
+	JButton reconnectBut,recordBut,stopBut;
+	final static ImageIcon carrows = new ImageIcon("images/chasingarrows.png");
+	static Preferences prefs = Preferences.userNodeForPackage(WorldStateRecordGUI.class);
+	WorldStateJointsListener comm;
+	String saveBaseName;
+	String savePath;
+	long firstFrameTime=-1;
+
+	static public void main(String s[]) {
+		int port=WorldStateJointsListener.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 WorldStateRecordGUI(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 WorldStateRecordGUI host [port]");
+		System.out.println("			 if port is not specified, it defaults to "+WorldStateJointsListener.defPort);
+		System.exit(2);
+	}
+
+	public WorldStateRecordGUI(String host, int port, String args[]) {
+		super("TekkotsuMon: WorldState Recorder");
+		init(WorldStateJointsListener.getCommonInstance(host,port));
+	}
+
+	public WorldStateRecordGUI(WorldStateJointsListener comm) {
+		super();
+		init(comm);
+	}
+
+	class RecordButton extends JButton {
+		public void paint(Graphics g) {
+			super.paint(g);
+			Rectangle r=new Rectangle(0,0,getSize().width,getSize().height);
+			if(isEnabled())
+				g.setColor(new Color(255,0,0,255));
+			else
+				g.setColor(new Color(255,0,0,64));
+			float margin=.15f;
+			int hgap=(int)(r.width*margin);
+			int vgap=(int)(r.height*margin);
+			g.fillOval(r.x+hgap,r.y+vgap,r.width-hgap*2,r.height-vgap*2);
+		}
+	}
+
+	class StopButton extends JButton {
+		public void paint(Graphics g) {
+			super.paint(g);
+			Rectangle r=new Rectangle(0,0,getSize().width,getSize().height);
+			if(isEnabled())
+				g.setColor(new Color(0,0,0,255));
+			else
+				g.setColor(new Color(0,0,0,64));
+			float margin=.25f;
+			int hgap=(int)(r.width*margin);
+			int vgap=(int)(r.height*margin);
+			g.fillRect(r.x+hgap,r.y+vgap,r.width-hgap*2,r.height-vgap*2);
+		}
+	}
+
+	protected void init(WorldStateJointsListener comm) {
+		this.comm=comm;
+		int spacer_size=10;
+		Container root = getContentPane();
+		root.setLayout(new BorderLayout());
+		root.add(Box.createVerticalStrut(spacer_size),BorderLayout.NORTH);
+		root.add(Box.createHorizontalStrut(spacer_size),BorderLayout.EAST);
+		root.add(Box.createHorizontalStrut(spacer_size),BorderLayout.WEST);
+		
+		{
+			GridLayout gl=new GridLayout(1,2);
+			gl.setHgap(spacer_size);
+			gl.setVgap(spacer_size);
+			JPanel tmp=new JPanel(gl);
+			recordBut=new RecordButton();
+			recordBut.setPreferredSize(new Dimension(96,96));
+			recordBut.setToolTipText("Connect and begin recording data stream");
+			recordBut.addActionListener(this);
+			tmp.add(recordBut);
+			stopBut=new StopButton();
+			stopBut.setPreferredSize(new Dimension(96,96));
+			stopBut.setEnabled(false);
+			stopBut.setToolTipText("Stop recording data stream");
+			stopBut.addActionListener(this);
+			tmp.add(stopBut);
+			root.add(tmp,BorderLayout.CENTER);
+		}
+
+		{
+			Box statusbox=Box.createVerticalBox();
+			statusbox.add(Box.createVerticalStrut(spacer_size));
+			{
+				JSeparator sep=new JSeparator(SwingConstants.HORIZONTAL);
+				statusbox.add(sep);
+			}
+			statusbox.add(Box.createVerticalStrut(spacer_size-2));
+			{
+				JPanel tmp=new JPanel(new BorderLayout());
+				status=new JLabel("Waiting to record...");
+				worldStateUpdated(comm);
+				tmp.add(Box.createHorizontalStrut(spacer_size),BorderLayout.WEST);
+				tmp.add(status,BorderLayout.CENTER);
+				{
+					Box tmp2=Box.createHorizontalBox();
+					reconnectBut=new JButton(carrows);
+					reconnectBut.setPreferredSize(new Dimension(carrows.getIconWidth(),carrows.getIconHeight()));
+					reconnectBut.addActionListener(this);
+					reconnectBut.setToolTipText("Drop current connection and try again.");
+					tmp2.add(reconnectBut);
+					tmp2.add(Box.createHorizontalStrut(spacer_size));
+					tmp.add(tmp2,BorderLayout.EAST);
+				}
+				statusbox.add(tmp);
+			}
+			statusbox.add(Box.createVerticalStrut(spacer_size));
+			root.add(statusbox, BorderLayout.SOUTH);
+		}
+		addWindowListener(new CloseWorldStateAdapter(this));
+		//worldState.setPreferredSize(new Dimension(150,150));
+		pack();
+		//worldState.setPreferredSize(null);
+		setLocation(prefs.getInt("WorldStateRecordGUI.location.x",50),prefs.getInt("WorldStateRecordGUI.location.y",50));
+		setVisible(true);
+	}
+
+	public void actionPerformed(ActionEvent evt) {
+		if(evt.getSource()==reconnectBut) {
+			//worldState.close();
+			//worldState.open();
+		} else if(evt.getSource()==recordBut) {
+			File cursavepath = new File(prefs.get("cursavepath",""));
+			JFileChooser dia=new JFileChooser(cursavepath);
+			dia.setDialogTitle("Save Sensor Data Sequence...");
+			Component cur=this;
+			while(cur.getParent()!=null)
+				cur=cur.getParent();
+			status.setText("Waiting for destination...");
+			if(dia.showSaveDialog(cur)==JFileChooser.APPROVE_OPTION) {
+				prefs.put("cursavepath",dia.getCurrentDirectory().getPath());
+				saveBaseName=dia.getSelectedFile().getName();
+				savePath=dia.getSelectedFile().getParent();
+				firstFrameTime=-1;
+				recordBut.setEnabled(false);
+				stopBut.setEnabled(true);
+				status.setText("Connecting...");
+				comm.addConnectionListener(this);
+				comm.addUpdatedListener(this);
+			}
+		} else if(evt.getSource()==stopBut) {
+			stopBut.setEnabled(false);
+			recordBut.setEnabled(true);
+			status.setText("Waiting to record...");
+			comm.removeUpdatedListener(this);
+			comm.removeConnectionListener(this);
+			saveBaseName=null;
+			firstFrameTime=-1;
+		}
+	}
+	class CloseWorldStateAdapter extends WindowAdapter {
+		WorldStateRecordGUI gui;
+		CloseWorldStateAdapter(WorldStateRecordGUI gui) {this.gui=gui;}
+		public void windowClosing(WindowEvent e) {
+			gui.close();
+		}
+	}
+	public void close() {
+		prefs.putInt("WorldStateRecordGUI.location.x",getLocation().x);
+		prefs.putInt("WorldStateRecordGUI.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("WorldStateRecordGUI.location.x",getLocation().x+getInsets().left);
+		//prefs.putInt("WorldStateRecordGUI.location.y",getLocation().y+getInsets().top);
+		//worldState.remove();
+		comm.removeConnectionListener(this);
+		comm.removeUpdatedListener(this);
+		dispose();
+	}
+	public void onConnected() {
+		status.setText("Connected.");
+	}
+	public void onDisconnected() {
+		status.setText("Waiting to record...");
+	}
+	public void worldStateUpdated(WorldStateJointsListener l) {
+		if(!l.isConnected()) {
+			status.setText("Waiting to record...");
+		} else {
+			status.setText("Recording...");
+			Joints j=comm.getData();
+			if(firstFrameTime==-1)
+				firstFrameTime=j.timestamp;
+			StringBuffer base=new StringBuffer(saveBaseName);
+			long c=j.timestamp-firstFrameTime;
+			int digits=6;
+			for(int s=(int)Math.pow(10,digits-1); s>=1; s/=10) {
+				base.append(c/s);
+				c-=(c/s)*s;
+			}
+			try {
+				PrintStream ps=new PrintStream(new FileOutputStream(savePath+File.separator+base+".pos"));
+				ps.println("#POS");
+				ps.println("condensed "+j.model);
+				ps.println("meta-info = "+j.timestamp+" "+j.frame);
+				ps.print("outputs =");
+				for(int i=0; i<j.positions.length; i++)
+					ps.print(" "+j.positions[i]);
+				ps.print("\nbuttons =");
+				for(int i=0; i<j.buttons.length; i++)
+					ps.print(" "+j.buttons[i]);
+				ps.print("\nsensors =");
+				for(int i=0; i<j.sensors.length; i++)
+					ps.print(" "+j.sensors[i]);
+				ps.print("\npidduties =");
+				for(int i=0; i<j.duties.length; i++)
+					ps.print(" "+j.duties[i]);
+				ps.println("\n#END");
+				ps.close();
+			} catch(Exception e) {
+				e.printStackTrace();
+			}
+		}
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/AgentShapeInfo.java ./tools/mon/org/tekkotsu/sketch/AgentShapeInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/AgentShapeInfo.java	2005-06-21 05:16:10.000000000 -0400
+++ ./tools/mon/org/tekkotsu/sketch/AgentShapeInfo.java	2006-03-02 13:28:03.000000000 -0500
@@ -6,10 +6,10 @@
 import javax.swing.ImageIcon;
 
 public class AgentShapeInfo extends ShapeInfo {
-	static Icon icon = new ImageIcon("org/tekkotsu/mon/icons/agent.png");
+	static Icon icon = new ImageIcon(icon_path+"agent.png");
 	float orientation; // orientation of agent
 
-	public AgentShapeInfo(int _id, int _parentId, String _name, Color _color,
+    public AgentShapeInfo(int _id, int _parentId, String _name, Color _color,
 			float _centroidx, float _centroidy, float _centroidz,
 			float _orientation) {
 		super(_id, _parentId, _name, _color, _centroidx,_centroidy, _centroidz);
@@ -31,9 +31,27 @@
 	
 	public Icon getIcon() { return icon; }
 
-	public void renderTo(Graphics2D graphics) {
-		graphics.drawOval((int)(getCentroidX()+1),
-			(int)(getCentroidY()+1), 5, 5);
+    public void renderTo(Graphics2D graphics, float scaling) {
+	    //		graphics.drawOval((int)(getCentroidX()+1),
+	    //	(int)(getCentroidY()+1), 5, 5);
+		int [] coordsX, coordsY;
+		coordsX = new int[3];
+		coordsY = new int[3];
+		
+		//represent the dog as a triangle which has base length of 10cm, height of 20cm
+		//top
+		coordsX[0] = (int) (centroidx + 100 * Math.cos(orientation));
+		coordsY[0] = (int) (centroidy + 100 * Math.sin(orientation));
+
+		//left
+		coordsX[1] = (int) (centroidx + 120 * Math.cos(-2.618+orientation));
+		coordsY[1] = (int) (centroidy + 120 * Math.sin(-2.618+orientation));
+
+		//right
+		coordsX[2] = (int) (centroidx + 120 * Math.cos(2.618+orientation));
+		coordsY[2] = (int) (centroidy + 120 * Math.sin(2.618+orientation));
+		graphics.drawPolygon(coordsX,coordsY, 3);
+
 	}
 
 	public float getOrientation() { return orientation; }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/BlobShapeInfo.java ./tools/mon/org/tekkotsu/sketch/BlobShapeInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/BlobShapeInfo.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/org/tekkotsu/sketch/BlobShapeInfo.java	2006-03-23 14:38:32.000000000 -0500
@@ -0,0 +1,89 @@
+package org.tekkotsu.sketch;
+
+import java.awt.Color;
+import java.awt.Font;
+import java.awt.Graphics2D;
+import java.awt.Graphics;
+import javax.swing.Icon;
+import javax.swing.ImageIcon;
+import java.awt.Rectangle;
+import java.awt.geom.*;
+import java.awt.BasicStroke;
+
+// stores info for a BlobShape
+public class BlobShapeInfo extends ShapeInfo {
+    static Icon icon = new ImageIcon(icon_path+"blob.png");
+    static Icon inv_icon = new ImageIcon(icon_path+"blobinv.png");
+
+    float area;
+    int orient;
+    float topLeft_x, topLeft_y, topLeft_z,
+	  topRight_x, topRight_y, topRight_z,
+	  bottomLeft_x, bottomLeft_y, bottomLeft_z,
+	  bottomRight_x, bottomRight_y, bottomRight_z;
+
+
+    public BlobShapeInfo(int _id, int _parentId, String _name, Color _color,
+			 float _centroidx, float _centroidy, float _centroidz,
+			 float _area, int _orient,
+			 float _topLeft_x, float _topLeft_y, float _topLeft_z,
+			 float _topRight_x, float _topRight_y, float _topRight_z,
+			 float _bottomLeft_x, float _bottomLeft_y, float _bottomLeft_z,
+			 float _bottomRight_x, float _bottomRight_y, float _bottomRight_z) {
+	super(_id, _parentId, _name, _color, _centroidx, _centroidy, _centroidz);
+	area = _area;
+	orient = _orient;
+	topLeft_x = _topLeft_x;
+	topLeft_y = _topLeft_y;
+	topLeft_z = _topLeft_z;
+	topRight_x = _topRight_x;
+	topRight_y = _topRight_y;
+	topRight_z = _topRight_z;
+	bottomLeft_x = _bottomLeft_x;
+	bottomLeft_y = _bottomLeft_y;
+	bottomLeft_z = _bottomLeft_z;
+	bottomRight_x = _bottomRight_x;
+	bottomRight_y = _bottomRight_y;
+	bottomRight_z = _bottomRight_z;
+    }
+
+	// should adjust these to take into account the crossbar height for pillar/pinata 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); }
+	public float getBottom() { return java.lang.Math.max(bottomLeft_y,bottomRight_y); }
+
+
+	public String toString() {
+	    String _orient = (orient==0) ? "ground" : (orient==1) ? "pillar" : "pinata";
+	    String _center = "center=(" + centroidx + " " + centroidy + " " + centroidz + ")";
+	    return super.toString() + " " + _orient + " area=" + area + " " + _center;
+	}
+
+	public Icon getIcon() { 
+	    if (inverted)
+		return inv_icon;
+	    else
+		return icon; 
+	}
+
+    public void renderTo(Graphics2D graphics, float scaling) {
+	if (orient == 0 || SketchGUI.gui.space == SketchGUI.Space.cam) { // always render camspace blobs in the camera plane
+	    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);
+	    graphics.drawLine((int)topLeft_x,(int)topLeft_y,(int)bottomLeft_x,(int)bottomLeft_y);
+	    graphics.drawLine((int)topRight_x,(int)topRight_y,(int)bottomRight_x,(int)bottomRight_y);
+	}
+	else {
+	    graphics.setStroke(new BasicStroke(3.0f));
+	    graphics.drawLine((int)bottomLeft_x,(int)bottomLeft_y,(int)bottomRight_x,(int)bottomRight_y);
+	    int w = java.lang.Math.max(12,(int)java.lang.Math.abs(bottomRight_y - bottomLeft_y));
+	    int midx = (int)((bottomLeft_x + bottomRight_x) / 2);
+	    int midy = (int)((bottomLeft_y + bottomRight_y) / 2);
+	    graphics.setStroke(new BasicStroke(3.0f));
+	    graphics.drawLine(midx-w/4,midy,midx+w/4,midy);
+	};
+    }
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/BrickShapeInfo.java ./tools/mon/org/tekkotsu/sketch/BrickShapeInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/BrickShapeInfo.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/org/tekkotsu/sketch/BrickShapeInfo.java	2006-03-02 13:28:03.000000000 -0500
@@ -0,0 +1,86 @@
+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 BrickShape
+public class BrickShapeInfo extends ShapeInfo {
+    static Icon icon = new ImageIcon(icon_path+"brick.png");
+    static Icon inv_icon = new ImageIcon(icon_path+"brickinv.png");
+    
+    float GFLx, GFLy;
+    float GFRx, GFRy;
+    float GBLx, GBLy;
+    float GBRx, GBRy;
+    float TFLx, TFLy;
+    float TFRx, TFRy;
+    float TBLx, TBLy;
+    float TBRx, TBRy;
+    
+    public BrickShapeInfo(int _id, int _parentId, String _name, Color _color,
+			  float _centroidx, float _centroidy, float _centroidz,
+			  float _GFLx, float _GFLy,
+			  float _GFRx, float _GFRy,
+			  float _GBLx, float _GBLy,
+			  float _GBRx, float _GBRy,
+			  float _TFLx, float _TFLy,
+			  float _TFRx, float _TFRy,
+			  float _TBLx, float _TBLy,
+			  float _TBRx, float _TBRy) {
+	super(_id, _parentId, _name, _color, _centroidx, _centroidy, _centroidz);
+	
+	GFLx = _GFLx; GFLy = _GFLy;
+	GFRx = _GFRx; GFRy = _GFRy;
+	GBLx = _GBLx; GBLy = _GBLy;
+	GBRx = _GBRx; GBRy = _GBRy;
+	TFLx = _TFLx; TFLy = _TFLy;
+	TFRx = _TFRx; TFRy = _TFRy;
+	TBLx = _TBLx; TBLy = _TBLy;
+	TBRx = _TBRx; TBRy = _TBRy;
+    }
+	
+    // 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 _brick = "brick=(" + centroidx + " " + centroidy + " " + centroidz + ")";
+	return (super.toString() + " " + _brick); }
+
+    public Icon getIcon() { 
+	if (inverted)
+	    return inv_icon;
+	else
+	    return icon; 
+    }
+
+    public void renderTo(Graphics2D graphics, float scaling) {
+	Rectangle bounds = graphics.getClipBounds();
+	graphics.drawLine((int)GFLx, (int)GFLy, (int)GFRx, (int)GFRy);
+	graphics.drawLine((int)GBLx, (int)GBLy, (int)GBRx, (int)GBRy);
+	graphics.drawLine((int)TFLx, (int)TFLy, (int)TFRx, (int)TFRy);
+	graphics.drawLine((int)TBLx, (int)TBLy, (int)TBRx, (int)TBRy);
+	graphics.drawLine((int)GFLx, (int)GFLy, (int)GBLx, (int)GBLy);
+	graphics.drawLine((int)GFRx, (int)GFRy, (int)GBRx, (int)GBRy);
+	graphics.drawLine((int)TFLx, (int)TFLy, (int)TBLx, (int)TBLy);
+	graphics.drawLine((int)TFRx, (int)TFRy, (int)TBRx, (int)TBRy);
+	graphics.drawLine((int)GFLx, (int)GFLy, (int)TFLx, (int)TFLy);
+	graphics.drawLine((int)GFRx, (int)GFRy, (int)TFRx, (int)TFRy);
+	graphics.drawLine((int)GBLx, (int)GBLy, (int)TBLx, (int)TBLy);
+	graphics.drawLine((int)GBRx, (int)GBRy, (int)TBRx, (int)TBRy);
+    }
+
+}
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/EllipseShapeInfo.java ./tools/mon/org/tekkotsu/sketch/EllipseShapeInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/EllipseShapeInfo.java	2005-08-05 21:07:38.000000000 -0400
+++ ./tools/mon/org/tekkotsu/sketch/EllipseShapeInfo.java	2006-03-04 14:51:23.000000000 -0500
@@ -13,13 +13,12 @@
 // stores info for a EllipseShape
 // note that ellipse center is same as centroid
 public class EllipseShapeInfo extends ShapeInfo {
-    static Icon icon = new ImageIcon("org/tekkotsu/mon/icons/ellipse.png");
-    static Icon inv_icon = new ImageIcon("org/tekkotsu/mon/icons/ellipseinv.png");
+    static Icon icon = new ImageIcon(icon_path+"ellipse.png");
+    static Icon inv_icon = new ImageIcon(icon_path+"ellipseinv.png");
     float semimajor, semiminor; // length of semimajor axes
     float orientation; // orientation of principal axis
-    int id;
 
-	public EllipseShapeInfo(int _id, int _parentId, String _name, Color _color,
+    public EllipseShapeInfo(int _id, int _parentId, String _name, Color _color,
 			float _centroidx, float _centroidy, float _centroidz,
 			float _semimajor, float _semiminor,
 			float _orientation) {
@@ -27,7 +26,6 @@
 		semimajor = _semimajor;
 		semiminor = _semiminor;
 		orientation = _orientation;
-		id = _id;
 	}
 
 	// returns left-most coordinate of object
@@ -41,7 +39,7 @@
 
 
 	public String toString() {
-		return (super.toString() + " center=(" + centroidx + "," + centroidy + "," + centroidz + ")"
+		return (super.toString() + " center=(" + centroidx + " " + centroidy + " " + centroidz + ")"
 			+ " smaj=" + semimajor 
 			+ ", smin=" + semiminor 
 			+ ", orient=" + orientation);
@@ -55,7 +53,7 @@
 
 	// rough rendering which doesn't take ellipse orientation into account
         // maybe do a hack-ish check if abs(orientation) more than pi/4?
-    public void renderTo(Graphics2D graphics) {
+    public void renderTo(Graphics2D graphics, float scaling) {
 	// System.out.println("Drawing ellipse");
 
 	graphics.setStroke(new BasicStroke(1.0f));
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/LineShapeInfo.java ./tools/mon/org/tekkotsu/sketch/LineShapeInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/LineShapeInfo.java	2005-08-05 21:07:38.000000000 -0400
+++ ./tools/mon/org/tekkotsu/sketch/LineShapeInfo.java	2006-04-14 19:54:13.000000000 -0400
@@ -12,67 +12,119 @@
 
 // stores info for a LineShape
 public class LineShapeInfo extends ShapeInfo {
-	static Icon icon = new ImageIcon("org/tekkotsu/mon/icons/line.png");
-	static Icon inv_icon = new ImageIcon("org/tekkotsu/mon/icons/lineinv.png");
-	// x/y coordinates of endpoints, with variances
-	float e1x, e1y, e1v;
-	float e2x, e2y, e2v;
-	float r, theta;
-
-	public LineShapeInfo(int _id, int _parentId, String _name, Color _color,
-			float _centroidx, float _centroidy, float _centroidz,
-			float _e1x, float _e1y, float _e1v, 
-			float _e2x, float _e2y, float _e2v,
-			float _r, float _theta) {
+    static Icon icon = new ImageIcon(icon_path+"line.png");
+    static Icon inv_icon = new ImageIcon(icon_path+"lineinv.png");
+    // x/y coordinates of endpoints, with variances
+    float e1x, e1y, e1v;
+    float e2x, e2y, e2v;
+    float r, theta;
+    boolean end1_valid, end1_active, end2_valid, end2_active;
+    
+    public LineShapeInfo(int _id, int _parentId, String _name, Color _color,
+			 float _centroidx, float _centroidy, float _centroidz,
+			 float _e1x, float _e1y, float _e1v, 
+			 float _e2x, float _e2y, float _e2v,
+			 float _r, float _theta, 
+			 boolean _end1_valid, boolean _end1_active,
+			 boolean _end2_valid, boolean _end2_active) {
 		
-		super(_id, _parentId, _name, _color, _centroidx, _centroidy, _centroidz);
-		e1x = _e1x;
-		e1y = _e1y;
-		e1v = _e1v;
-		e2x = _e2x;
-		e2y = _e2y;
-		e2v = _e2v;
-		r = _r;
-		theta = _theta;
-	}
+	super(_id, _parentId, _name, _color, _centroidx, _centroidy, _centroidz);
+	e1x = _e1x;
+	e1y = _e1y;
+	e1v = _e1v;
+	e2x = _e2x;
+	e2y = _e2y;
+	e2v = _e2v;
+	r = _r;
+	theta = _theta;
+	end1_valid = _end1_valid;
+	end1_active = _end1_active;
+	end2_valid = _end2_valid;
+	end2_active = _end2_active;
+    }
 	
-	// returns left-most coordinate of object
-	public float getLeft() { return java.lang.Math.min(e1x,e2x); }
-	// returns right-most coordinate of object
-	public float getRight() { return java.lang.Math.max(e1x,e2x); }
-	// returns top-most coordinate of object
-	public float getTop() { return java.lang.Math.min(e1y,e2y); }
-	// returns bottom-most coordinate of object
-	public float getBottom() { return java.lang.Math.max(e1y,e2y); }
+    // returns left-most coordinate of object
+    public float getLeft() { return java.lang.Math.min(e1x,e2x); }
+    // returns right-most coordinate of object
+    public float getRight() { return java.lang.Math.max(e1x,e2x); }
+    // returns top-most coordinate of object
+    public float getTop() { return java.lang.Math.min(e1y,e2y); }
+    // returns bottom-most coordinate of object
+    public float getBottom() { return java.lang.Math.max(e1y,e2y); }
 
-	public String toString() {
-		return (super.toString()
-			+ " (" + e1x + "," + e1y + "," + e1v + ")---(" + e2x + "," + e2y + "," + e2v + ")  "
-			+ "r=" + r + " theta=" + theta); }
-			//				+ "(e1x " +e1x + ", e1y " + e1y + ", e1v " + e1v 
-			//+ ", e2x " +e2x + ", e2y " + e2y + ", e2v " + e2v 
-			//+ ", r " + r + ", theta " + theta + ")");	}
+    public String toString() {
+	return (super.toString()
+		+ " (" + e1x + " " + e1y + " " + e1v + ")---(" + e2x + " " + e2y + " " + e2v + ")  "
+		+ "r=" + r + " theta=" + theta); }
 
-	public Icon getIcon() { 
-	    if (inverted)
-		return inv_icon;
-	    return icon; 
-	}
+    public Icon getIcon() { 
+	if (inverted)
+	    return inv_icon;
+	return icon; 
+    }
 
-	public void renderTo(Graphics2D graphics) {
-		graphics.drawLine((int)e1x,(int)e1y,(int)e2x,(int)e2y);
-		// 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));
-	}
+    public void renderTo(Graphics2D graphics, float scaling) {
+	final int radius = (int) (10/scaling);
+	    final float big_slope = (float)1e5;
+	    if ( e1x > e2x ) {
+		boolean t_valid = end1_valid;
+		boolean t_active = end1_active;
+		end1_valid = end2_valid;
+		end1_active = end2_active;
+		end2_valid = t_valid;
+		end2_active = t_active;
+		float tx=e1x;
+		float ty=e1y;
+		e1x=e2x;
+		e1y=e2y;
+		e2x=tx;
+		e2y=ty;}
+	    float m, b;
+	    if ( e2x-e1x > 1/big_slope ) {
+		m = (e2y-e1y)/(e2x-e1x);
+		b = e1y-e1x*m;
+	    } else {
+		m = big_slope;
+		b = 0;
+	    }
+	    int e1xi, e1yi, e2xi, e2yi;
+	    if (end1_active) {
+		e1xi = (int)e1x; e1yi = (int)e1y;
+	    } else {
+		e1xi = -10000; e1yi = (int)(e1xi*m+b);
+	    };
+	    if (end2_active) {
+		e2xi = (int)e2x; e2yi = (int)e2y;
+	    } else {
+		e2xi = 10000; e2yi = (int)(e2xi*m+b);
+	    };
+	    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);
 
-	public float getE1X() { return e1x; }
-	public float getE1Y() { return e1y; }
-	public float getE1V() { return e1v; }
-	public float getE2X() { return e2x; }
-	public float getE2Y() { return e2y; }
-	public float getE2V() { return e2v; }
-	public float getR() { return r; }
-	public float getTheta() { return theta; }
+	// 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));
+    }
+
+    public float getE1X() { return e1x; }
+    public float getE1Y() { return e1y; }
+    public float getE1V() { return e1v; }
+    public float getE2X() { return e2x; }
+    public float getE2Y() { return e2y; }
+    public float getE2V() { return e2v; }
+    public float getR() { return r; }
+    public float getTheta() { return theta; }
+
+    public float getIdX() { return getE1X(); }
+    public float getIdY() { return getE1Y(); }
+    
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/PointShapeInfo.java ./tools/mon/org/tekkotsu/sketch/PointShapeInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/PointShapeInfo.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/org/tekkotsu/sketch/PointShapeInfo.java	2006-07-21 13:59:03.000000000 -0400
@@ -0,0 +1,54 @@
+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 LineShape
+public class PointShapeInfo extends ShapeInfo {
+    static Icon icon = new ImageIcon(icon_path+"point.png");
+    static Icon inv_icon = new ImageIcon(icon_path+"pointinv.png");
+    
+    public PointShapeInfo(int _id, int _parentId, String _name, Color _color,
+			float _centroidx, float _centroidy, float _centroidz) {
+	super(_id, _parentId, _name, _color, _centroidx, _centroidy, _centroidz);
+    }
+	
+    // 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 _point = "point=(" + centroidx + " " + centroidy + " " + centroidz + ")";
+	return (super.toString() + " " + _point); }
+
+    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.fillOval((int)centroidx-radius/2, (int)centroidy-radius/2, radius, radius);
+    }
+
+}
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/PolygonShapeInfo.java ./tools/mon/org/tekkotsu/sketch/PolygonShapeInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/PolygonShapeInfo.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/org/tekkotsu/sketch/PolygonShapeInfo.java	2006-03-23 14:38:32.000000000 -0500
@@ -0,0 +1,96 @@
+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 PolygonShape
+public class PolygonShapeInfo extends ShapeInfo {
+	static Icon icon = new ImageIcon(icon_path+"poly.png");
+	static Icon inv_icon = new ImageIcon(icon_path+"polyinv.png");
+	// x/y coordinates of endpoints, with variances
+    int num_vertices;
+    float[][] vertices;
+    boolean end1_valid, end2_valid;
+    
+    public PolygonShapeInfo(int _id, int _parentId, String _name, Color _color,
+			    float _centroidx, float _centroidy, float _centroidz,
+			    int _num_vertices, float[][] _vertices,
+			    boolean _end1_valid, boolean _end2_valid) {			
+	super(_id, _parentId, _name, _color, _centroidx, _centroidy, _centroidz);
+	num_vertices = _num_vertices;
+	vertices = _vertices;
+	end1_valid = _end1_valid;
+	end2_valid = _end2_valid;
+    }
+	
+    // returns left-most coordinate of object
+    public float getLeft() { 
+	float min_x = vertices[0][0];
+	for (int i = 1; i < num_vertices; i++)
+	    if (min_x > vertices[i][0])
+		min_x = vertices[i][0];
+	return min_x; 
+    }
+    // returns right-most coordinate of object
+    public float getRight() {
+	float max_x = vertices[0][0];
+	for (int i = 1; i < num_vertices; i++)
+	    if (max_x < vertices[i][0])
+		max_x = vertices[i][0];
+	return max_x; 
+    }
+    // returns top-most coordinate of object
+    public float getTop() { 
+	float min_y = vertices[0][1];
+	for (int i = 1; i < num_vertices; i++)
+	    if (min_y > vertices[i][1])
+		min_y = vertices[i][1];
+	return min_y;     
+    }
+    // returns bottom-most coordinate of object
+    public float getBottom() { 
+	float max_y = vertices[0][1];
+	for (int i = 1; i < num_vertices; i++)
+	    if (max_y < vertices[i][1])
+		max_y = vertices[i][1];
+	return max_y; 
+    }
+    public String toString() {
+	String vtx_coords = "(" + vertices[0][0] + "," + vertices[0][1] + ")";
+	for (int i = 1; i < num_vertices; i++)
+	    vtx_coords += "->(" + vertices[i][0] + "," + vertices[i][1] + ")";
+	return (super.toString() + " " +  vtx_coords);
+    }    
+    public Icon getIcon() { 
+	if (inverted)
+	    return inv_icon;
+	return icon; 
+    }
+    
+    public void renderTo(Graphics2D graphics, float scaling) {
+	final int radius = (int) (10.0/scaling);
+	for (int i = 0; i < num_vertices-1; i++)
+	    graphics.drawLine((int)vertices[i][0],(int)vertices[i][1],(int)vertices[i+1][0],(int)vertices[i+1][1]);
+
+	if (end1_valid)
+	    graphics.fillOval((int)vertices[0][0]-radius/2, (int)vertices[0][1]-radius/2, radius, radius);
+
+	if (end2_valid)
+	    graphics.fillOval((int)vertices[num_vertices-1][0]-radius/2, (int)vertices[num_vertices-1][1]-radius/2, radius, radius);
+    }
+
+    public float[] getFirstVertex() {
+	return vertices[0];
+    }
+    
+    public float getIdX() { return vertices[0][0]; }
+    public float getIdY() { return vertices[0][1]; }
+}
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/PyramidShapeInfo.java ./tools/mon/org/tekkotsu/sketch/PyramidShapeInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/PyramidShapeInfo.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/org/tekkotsu/sketch/PyramidShapeInfo.java	2006-07-21 13:59:05.000000000 -0400
@@ -0,0 +1,73 @@
+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 PyramidShape
+public class PyramidShapeInfo extends ShapeInfo {
+    static Icon icon = new ImageIcon(icon_path+"pyramid.png");
+    static Icon inv_icon = new ImageIcon(icon_path+"pyramidinv.png");
+    
+    float FLx, FLy;
+    float FRx, FRy;
+    float BLx, BLy;
+    float BRx, BRy;
+    float Topx, Topy;
+    
+    public PyramidShapeInfo(int _id, int _parentId, String _name, Color _color,
+			  float _centroidx, float _centroidy, float _centroidz,
+			  float _FLx, float _FLy,
+			  float _FRx, float _FRy,
+			  float _BLx, float _BLy,
+			  float _BRx, float _BRy,
+			  float _Topx, float _Topy) {
+	super(_id, _parentId, _name, _color, _centroidx, _centroidy, _centroidz);
+	
+	FLx = _FLx; FLy = _FLy;
+	FRx = _FRx; FRy = _FRy;
+	BLx = _BLx; BLy = _BLy;
+	BRx = _BRx; BRy = _BRy;
+	Topx = _Topx; Topy = _Topy;
+    }
+	
+    // 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 _pyramid = "pyramid=(" + centroidx + " " + centroidy + " " + centroidz + ")";
+	return (super.toString() + " " + _pyramid); }
+
+    public Icon getIcon() { 
+	if (inverted)
+	    return inv_icon;
+	else
+	    return icon; 
+    }
+
+    public void renderTo(Graphics2D graphics, float scaling) {
+	Rectangle bounds = graphics.getClipBounds();
+	graphics.drawLine((int)FLx, (int)FLy, (int)FRx, (int)FRy);
+	graphics.drawLine((int)BLx, (int)BLy, (int)BRx, (int)BRy);
+	graphics.drawLine((int)FLx, (int)FLy, (int)BLx, (int)BLy);
+	graphics.drawLine((int)FRx, (int)FRy, (int)BRx, (int)BRy);
+	graphics.drawLine((int)Topx, (int)Topy, (int)BLx, (int)BLy);
+	graphics.drawLine((int)Topx, (int)Topy, (int)BRx, (int)BRy);
+	graphics.drawLine((int)Topx, (int)Topy, (int)FLx, (int)FLy);
+	graphics.drawLine((int)Topx, (int)Topy, (int)FRx, (int)FRy);
+    }
+
+}
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/ShapeInfo.java ./tools/mon/org/tekkotsu/sketch/ShapeInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/ShapeInfo.java	2005-06-18 04:48:20.000000000 -0400
+++ ./tools/mon/org/tekkotsu/sketch/ShapeInfo.java	2006-04-14 19:54:13.000000000 -0400
@@ -8,40 +8,48 @@
 
 // stores info for a Shape, to use as UserObject for DefaultMutableTreeNode
 
-public class ShapeInfo extends VisualObjectInfo {
-	float centroidx, centroidy, centroidz;
-
+public class ShapeInfo extends SketchOrShapeInfo {
+    float centroidx, centroidy, centroidz;
+    boolean useDefaultSelection, useDefaultInversion;
+    final static String icon_path = "org/tekkotsu/sketch/icons/";
+    
     public ShapeInfo(int _id, int _parentId, String _name, Color _color,
-			float _centroidx, float _centroidy, float _centroidz) {
-		super(_id, _parentId, _name, _color);
-		centroidx = _centroidx;
-		centroidy = _centroidy;
-		centroidz = _centroidz;
-	}
+		     float _centroidx, float _centroidy, float _centroidz) {
+	super(_id, _parentId, _name, _color);
+	centroidx = _centroidx;
+	centroidy = _centroidy;
+	centroidz = _centroidz;
+	useDefaultSelection = true;
+	useDefaultInversion = true;
+    }
 
-	public String toString() {
-	    //		return (super.toString() + "(color " + color + ",cx " + centroidx + ", cy " + centroidy
-	    //			+ ", cz " + centroidz + ")");
-	    return (super.toString() + "[" + color.getRed() + "," + color.getGreen() + "," + color.getBlue() + "]");
-	}
 
-	// if no specific renderer defined, just plot a point at centroid
-	public void renderTo(Graphics2D graphics) {
-    		graphics.setColor(color);
-		graphics.drawOval((int)centroidx,(int)centroidy,5,5);
-	}
+    // if no specific renderer defined, just plot a point at centroid
+    public void renderTo(Graphics2D graphics, float scaling) {
+	graphics.setColor(color);
+	graphics.drawOval((int)centroidx,(int)centroidy,5,5);
+    }
 
-    public void renderTo(Graphics graphics, Rectangle2D.Double r)
-    {
+    public void renderTo(Graphics graphics, Rectangle2D.Double r) {
 	double xscale = r.width;
 	double yscale = r.height;
 	graphics.setColor(color);
 	graphics.drawOval((int)(centroidx*xscale+r.x),(int)(centroidy*yscale+r.y),(int)(5*xscale),(int)(5*yscale));	
     }
 
-	public float getCentroidX() { return centroidx; }
-	public float getCentroidY() { return centroidy; }
-	public float getCentroidZ() { return centroidz; }
+    public float getCentroidX() { return centroidx; }
+    public float getCentroidY() { return centroidy; }
+    public float getCentroidZ() { return centroidz; }
+
+    // Specific call to get the coordinates of where to display the shape's Id
+    // defaults to the centroid, override for other behavior
+    public float getIdX() { return centroidx; }
+    public float getIdY() { return centroidy; }
+
+    public void setUseDefaultSelection(boolean useSelection) { useDefaultSelection = useSelection; }
+    public boolean getUseDefaultSelection() { return useDefaultSelection; }
+    public void setUseDefaultInversion(boolean useInversion) { useDefaultInversion = useInversion; }
+    public boolean getUseDefaultInversion() { return useDefaultInversion; }
 }
 
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/SketchGUI.java ./tools/mon/org/tekkotsu/sketch/SketchGUI.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/SketchGUI.java	2005-08-05 17:26:57.000000000 -0400
+++ ./tools/mon/org/tekkotsu/sketch/SketchGUI.java	2006-10-02 16:38:24.000000000 -0400
@@ -17,6 +17,7 @@
 import java.util.Arrays;
 import java.util.Enumeration;
 import java.util.Comparator;
+import java.util.Hashtable;
 import java.io.PrintWriter;
 import java.io.FileOutputStream;
 import java.util.prefs.Preferences;
@@ -27,22 +28,26 @@
 import java.awt.geom.*;
 
 
-
 public class SketchGUI extends JFrame implements ActionListener,
 						 TreeSelectionListener,
 						 VisionUpdatedListener,
 						 MouseListener
 {
-    //    boolean isCam; // true if this GUI is displaying a camera space (not world)
-    int space;
+    public enum Space { unknown, cam, local, world }
+    Space space;          // 1 == cam, 2 == local, 3 == world
 
     JFrame sketchFrame;
     SketchPanel sketchPanel;
     JButton rescaleBut;
     JButton refreshListBut;
+    JCheckBox checkAllBut;
+    boolean defaultSelected = true;
+    JCheckBox invertAllBut;
+    boolean defaultInversion = false;
 
     JTree sketchTree = null;
     DefaultMutableTreeNode root;
+    AffineTransform Tmat, TmatInv;
     JLabel status;
     float mspf=0;
     float mspfGamma = 0.9f;
@@ -60,33 +65,58 @@
     VisionListener listener;
 
     PopupMenu popMenu;
-    VisualObjectInfo currentMenuObject;
+    SketchOrShapeInfo currentMenuObject;
 
     Vector sketchStack;
     BufferedImage img;
     boolean imageNeedsUpdate;
+    boolean focusJustChanged = false;
     TreeSelectionEvent lastEvent = null;
 
+    int imageWidth = -1, imageHeight = -1;
+
+    Color backgroundColor = new Color(64,64,64);
+    int defaultWidth = 208, defaultHeight = 160; // Use ERS-7 defaults if it cannot connect. 
+    boolean panelBoundsSet = false;
+
     SketchPanel curSketchPanel;
+    SketchOrShapeInfo curObject;
+    String panelTitle;
+    int panelCount = 1;
+    static SketchGUI gui;
 
     public static void main(String args[]) {
-	if(args.length<4)
+	if(args.length<2)
 	     usage();
 
-	int _listingPort = Integer.parseInt(args[2]);
-	int _sketchPort = Integer.parseInt(args[3]);
-	
-	//	boolean _isCam = args[1].equals("cam");
-	int _space = args[1].equals("cam") ? 1 : (args[1].equals("local") ? 2 : 3);
-	//	SketchGUI gui = new SketchGUI(args[0], _listingPort, _sketchPort, _isCam);
-	SketchGUI gui = new SketchGUI(args[0], _listingPort, _sketchPort, _space);
+	Space _space = Space.unknown;
+	int _listingPort = 0;
+	int _sketchPort = 0;
+	if ( args[1].equals("cam") ) {
+	    _space = Space.cam;
+	    _listingPort = 5800;
+	    _sketchPort = 5801;
+	}
+	else if ( args[1].equals("local") ) {
+	    _space = Space.local;
+	    _listingPort = 5802;
+	    _sketchPort = 5803;
+	}
+	else if ( args[1].equals("world") ) {
+	    _space = Space.world;
+	    _listingPort = 5804;
+	    _sketchPort = 5805;
+	}
+	else usage();
+
+        gui = new SketchGUI(args[0], _listingPort, _sketchPort, _space);
 	gui.addWindowListener(new WindowAdapter() {
 		 public void windowClosing(WindowEvent e) {System.exit(0);}});
 	gui.setVisible(true);
     }
 
     public static void usage() {
-	System.out.println("Usage: java org/tekkotsu/mon/SketchGUI host [cam/world] listport sketchport");
+	System.out.println("Usage: java org/tekkotsu/sketch/SketchGUI hostname [cam/local/world]");
 	System.exit(2);
     }
 
@@ -96,6 +126,10 @@
 		rescaleAction();
 	    else if(e.getActionCommand().compareTo("refreshlist")==0)
 		refreshlistAction();
+	    else if(e.getActionCommand().compareTo("checkall")==0)
+		checkAllAction(e);
+	    else if(e.getActionCommand().compareTo("invertall")==0)
+		invertAllAction(e);
 	}
 	catch(IOException ioe) {
 	    System.err.println("Transfer error");
@@ -104,12 +138,64 @@
 	}
     }
 
+    public void checkAllAction(ActionEvent e) {
+	defaultSelected = ((JCheckBox)(e.getSource())).isSelected();
+
+	DefaultMutableTreeNode n = root;
+	Vector<TreePath> newPaths = new Vector<TreePath>();
+	TreePath[] paths = sketchTree.getSelectionPaths();
+
+	if (paths != null) {
+	    for (int i=0; i<paths.length; i++) 
+		newPaths.add(paths[i]);
+	}
+	while((n = n.getNextNode())!= null) {
+	    if (n.getUserObject() instanceof SketchOrShapeInfo) {
+		SketchOrShapeInfo obj = (SketchOrShapeInfo)n.getUserObject();
+		if (defaultSelected) {
+		    // Reset all shapes to follow the default when turning on select all
+		    if (obj instanceof ShapeInfo) {
+			((ShapeInfo)obj).setUseDefaultSelection(true);
+			newPaths.addElement(new TreePath(n.getPath()));
+		    }
+		}
+		else {
+		    if (obj instanceof ShapeInfo && ((ShapeInfo)obj).getUseDefaultSelection()) {
+			newPaths.removeElement(new TreePath(n.getPath()));
+			obj.setVisible(false);
+		    }
+		}
+	    }
+	}
+	sketchTree.setSelectionPaths((TreePath[])newPaths.toArray(new TreePath[0]));
+    }
+
+    public void invertAllAction(ActionEvent e) {
+
+	defaultInversion = ((JCheckBox)(e.getSource())).isSelected();
+
+	DefaultMutableTreeNode n = root;
+	while((n = n.getNextNode())!= null) {
+	    if (n.getUserObject() instanceof SketchOrShapeInfo) {
+		SketchOrShapeInfo obj = (SketchOrShapeInfo)n.getUserObject();
+		// Reset all shapes to follow the default when turning on invert all
+		if (defaultInversion && obj instanceof ShapeInfo) {
+		    ((ShapeInfo)obj).setUseDefaultInversion(true);
+		}
+		if (obj instanceof ShapeInfo && ((ShapeInfo)obj).getUseDefaultInversion()) {
+		    obj.setInverted(defaultInversion);
+		}
+	    }
+	}
+	valueChanged(lastEvent);
+	sketchTree.treeDidChange();
+    }
+
     public void rescaleAction() {
-	// reset bounds **** THIS CODE ASSUMES ERS-2XX CAMERA DIMENSIONS; SHOULD FIX
-	sketchPanel.leftBound = 0;
-	sketchPanel.rightBound = 176;
-	sketchPanel.topBound = 0;
-	sketchPanel.bottomBound = 144;
+	curSketchPanel.leftBound = 0;
+	curSketchPanel.rightBound = imageWidth;
+	curSketchPanel.topBound = 0;
+	curSketchPanel.bottomBound = imageHeight;
 	TreePath[] paths = sketchTree.getSelectionPaths();
 	if(paths!=null) {
 	    for (int path_i = 0; path_i < paths.length; path_i++) {
@@ -117,13 +203,14 @@
 		    =(DefaultMutableTreeNode)(paths[path_i].getLastPathComponent());
 		
 		if (node == root) continue;
-		if(!(node.getUserObject() instanceof VisualObjectInfo)) {
+		if(!(node.getUserObject() instanceof SketchOrShapeInfo)) {
 		    System.out.println("rescaleAction:: placeholder text can't be selected");
 		    continue;
 		}
 		
-		VisualObjectInfo vinfo = (VisualObjectInfo)(node.getUserObject());
-		sketchPanel.scaleToVisualObject(vinfo);
+		SketchOrShapeInfo vinfo = (SketchOrShapeInfo)(node.getUserObject());
+		if ( vinfo.getVisible() )
+		    curSketchPanel.scaleToSketchOrShape(vinfo);
 		if (vinfo instanceof SketchInfo)
 		    {
 			((SketchInfo)vinfo).unloadImage();
@@ -134,29 +221,85 @@
     }
 
     public void refreshlistAction() throws IOException {
+
+	// Save existing selection settings for any objects that might remain
+	Hashtable oldInverted = new Hashtable();
+	Hashtable oldSelected = new Hashtable();
+
+	DefaultMutableTreeNode n = root;
+	if (n!= null) {
+	    while((n = n.getNextNode())!= null) {
+		if (n.getUserObject() instanceof ShapeInfo) {
+		    ShapeInfo sinfo = (ShapeInfo)n.getUserObject();
+		    if (!sinfo.getUseDefaultSelection())
+			oldSelected.put(new Integer(sinfo.getId()),new Boolean(sinfo.getVisible()));
+		    if (!sinfo.getUseDefaultInversion())
+			oldInverted.put(new Integer(sinfo.getId()),new Boolean(sinfo.inverted));
+		} else if (n.getUserObject() instanceof SketchInfo) {
+		    ((SketchInfo)n.getUserObject()).unloadImage();
+		}
+	    }
+	}
+
 	// send command to refresh the sketch tree list
-	if(netout==null)
-	    reconnect();
-	if(netout==null)
-	    return;
+	if(netout==null) reconnect();
+	if(netout==null) return;
 	root.removeAllChildren();
 	sketchStack = new Vector();
+
+	String inputLine;
 	
-	// reset bounds **** THIS CODE ASSUMES ERS-2XX CAMERA DIMENSIONS; SHOULD FIX
+	if (!panelBoundsSet){
+	    // Get image bounds from the dog
+	    netout.println("size");
+	    System.out.println(inputLine = readLine());
+	    while((inputLine=readLine()).compareTo("size end") != 0) {
+		System.out.println(inputLine);
+		StringTokenizer sizetoken = new StringTokenizer(inputLine);
+		String token = sizetoken.nextToken();
+		if (token.equals("width")){
+		    imageWidth = Integer.parseInt(sizetoken.nextToken());
+		}
+		else if (token.equals("height")){
+		    imageHeight = Integer.parseInt(sizetoken.nextToken());
+		}
+	    }
+	    System.out.println(inputLine);
+	    panelBoundsSet = true;
+	}
+
 	sketchPanel.leftBound = 0;
-	sketchPanel.rightBound = 176;
+	sketchPanel.rightBound = imageWidth;
 	sketchPanel.topBound = 0;
-	sketchPanel.bottomBound = 144;
+	sketchPanel.bottomBound = imageHeight;
+
+	System.out.println("Setting bounds to "+sketchPanel.rightBound + " x "+sketchPanel.bottomBound);
 	
 	// read in new sketch/shape list
 	netout.println("list");
-	String inputLine;
-	System.out.println(inputLine = readLine());
+	System.out.println(inputLine = readLine());  // eat the "list begin"
 	while((inputLine=readLine()).compareTo("list end") != 0) {
 	    // parse type (sketch or shape)	
 	    StringTokenizer st = new StringTokenizer(inputLine,": ");
 	    String type = st.nextToken();
 	    
+	    if (type.equals("tmat")) {
+		float[] tvals = new float[16];
+		inputLine = readLine();
+		st = new StringTokenizer(inputLine,": ");
+		for (int i=0; i<16; i++)
+		    tvals[i] = Float.parseFloat(st.nextToken());
+		float s = 1/tvals[15];
+		System.out.println("tmat:  tx="+tvals[3]+"  ty="+tvals[7]+"  scale="+s);
+		Tmat.setTransform(tvals[0]*s, tvals[1]*s, tvals[4]*s, tvals[5]*s, tvals[3]*s, tvals[7]*s);
+		try { TmatInv.setTransform(Tmat.createInverse()); } 
+		catch (java.awt.geom.NoninvertibleTransformException nte) 
+		    { System.out.println("Error occured while trying to make the inverse of Tmat"); }
+		continue;
+	    }
+
+	    // if we get here, it's a sketch or a shape
+
 	    // parse id
 	    inputLine = readLine();
 	    st = new StringTokenizer(inputLine,": ");
@@ -180,7 +323,6 @@
 	    st = new StringTokenizer(inputLine,": ");
 	    st.nextToken();
 	    int subtype = Integer.parseInt(st.nextToken());
-	    System.out.println(type+"type:" + subtype);
 	    
 	    // parse color
 	    inputLine = readLine();
@@ -189,29 +331,60 @@
 	    Color color = new Color( Integer.parseInt(st.nextToken()),
 				     Integer.parseInt(st.nextToken()),
 				     Integer.parseInt(st.nextToken()));
-	    System.out.println("color: " + color);
 	    
+	    //parse colormap if sketch
+	    int colormap = SketchInfo.COLORMAP_SEG_TYPE;
+	    if(type.equals("sketch")) {
+		inputLine = readLine();
+		st = new StringTokenizer(inputLine,": ");
+		st.nextToken();
+		colormap = Integer.parseInt(st.nextToken());
+	    }
+
 	    // create node
-	    System.out.println(type + " id:"+id+"parentId:"+parentId+"name:"+name);
-	    VisualObjectInfo oinfo;
-	    if(type.equals("sketch")) 
-		oinfo =  new SketchInfo(id, parentId, name, color, subtype);
-	    else if (type.equals("shape"))
-		oinfo = parseShape(id, parentId, name, color, subtype);
+	    System.out.println(type + 
+			       " id:"+id+" parentId:"+parentId+" name:"+name +
+			       " type:" + subtype);
+	    String colormsg = "  color: " + color +
+		(type.equals("sketch") ? (" colormap:" + colormap) : "");
+	    System.out.println(colormsg);
+	    SketchOrShapeInfo oinfo;
+	    if(type.equals("sketch")) {
+		oinfo =  new SketchInfo(id, parentId, name, color, colormap, 
+					subtype, imageWidth, imageHeight);
+	    }
+	    else if (type.equals("shape")) {
+		oinfo = parseShape(id, parentId, name, color, subtype, imageWidth, imageHeight);
+		ShapeInfo sinfo = (ShapeInfo)oinfo;
+		if (oldSelected.containsKey(new Integer(id))) {
+		    sinfo.setUseDefaultSelection(false);
+		    sinfo.setVisible(((Boolean)oldSelected.get(new Integer(id))).booleanValue());
+		}
+		else {
+		    sinfo.setVisible(defaultSelected);
+		}
+		if (oldInverted.containsKey(new Integer(id))) {
+		    sinfo.setUseDefaultInversion(false);
+		    sinfo.setInverted(((Boolean)oldInverted.get(new Integer(id))).booleanValue());
+		}
+		else {
+		    sinfo.setInverted(defaultInversion);
+		}
+	    }
 	    else {
 		System.out.println("Invalid type!");
 		color = new Color(0);
-		oinfo = new VisualObjectInfo(id, parentId, name, color);
+		oinfo = new SketchOrShapeInfo(id, parentId, name, color);
 	    }
 	    
-	    //	    if (!isCam) sketchPanel.scaleToVisualObject(oinfo);
-	    if (space != 1) sketchPanel.scaleToVisualObject(oinfo);
+	    if (space != Space.cam) sketchPanel.scaleToSketchOrShape(oinfo);
 	    
 	    DefaultMutableTreeNode newnode = new DefaultMutableTreeNode(oinfo);
 	    root.add(newnode);
 	    
 	    sketchTree.updateUI();
 	}
+	System.out.println(inputLine);
 
 	// pair children with parents
 	DefaultMutableTreeNode curNode;
@@ -220,42 +393,34 @@
 	while(nodeEn.hasMoreElements()){
 	    allnodes.add(nodeEn.nextElement());
 	}
-	for (int i=0; i<allnodes.size(); i++)
-	    {
-		curNode = (DefaultMutableTreeNode)(allnodes.elementAt(i));
-		DefaultMutableTreeNode potentialParent = root;
-		while((potentialParent = potentialParent.getNextNode()) != null) {
-		    
-		    if (curNode != root)
-			{
-			    if(((VisualObjectInfo)(curNode.getUserObject())).parentId == 
-			       ((VisualObjectInfo)(potentialParent.getUserObject())).id && 
-			       !potentialParent.isNodeAncestor(curNode)) {
-				potentialParent.add(curNode);
-				break;
-			    }
-			}
+	for (int i=0; i<allnodes.size(); i++) {
+	    curNode = (DefaultMutableTreeNode)(allnodes.elementAt(i));
+	    DefaultMutableTreeNode potentialParent = root;
+	    while((potentialParent = potentialParent.getNextNode()) != null) {
+		if (curNode != root) {
+		    if(((SketchOrShapeInfo)(curNode.getUserObject())).parentId == 
+		       ((SketchOrShapeInfo)(potentialParent.getUserObject())).id && 
+		       !potentialParent.isNodeAncestor(curNode)) {
+			potentialParent.add(curNode);
+			break;
+		    }
 		}
-		
 	    }
+	    
+	}
 	sortTree(root);
 	
-	// display the first sketch
-	SketchInfo firstinfo = (SketchInfo)(((DefaultMutableTreeNode)(root.getFirstChild())).getUserObject());
-	netout.println("get "+firstinfo.getId());
-	while((inputLine=readLine()).compareTo("get end") != 0) {
-	    System.out.println(inputLine);
-	}	
-	
-	System.out.println(inputLine);
 	for (int i = 0; i < sketchTree.getRowCount(); i++) {
 	    sketchTree.expandRow(i);
 	}
 	sketchTree.clearSelection();
 	sketchTree.updateUI();
+	valueChanged(lastEvent);
     }
     
-    public VisualObjectInfo parseShape(int id, int parentId, String name, Color color, int shapetype) 
+    public SketchOrShapeInfo parseShape(int id, int parentId, String name, 
+					Color color, int shapetype, 
+					int width, int height) 
 	throws IOException
     {
 	String inputLine;
@@ -267,7 +432,6 @@
 	float cx = Float.parseFloat(st.nextToken());
 	float cy = Float.parseFloat(st.nextToken());
 	float cz = Float.parseFloat(st.nextToken());
-	System.out.println("cxyz:" +cx+" "+cy+" "+cz);
     
 	if(shapetype == 1) { // lineshape
 	    inputLine = readLine();
@@ -275,101 +439,338 @@
 	    st.nextToken();
 	    float e1x = Float.parseFloat(st.nextToken());
 	    float e1y = Float.parseFloat(st.nextToken());
-	    float e1v = Float.parseFloat(st.nextToken());
-	    System.out.println("e1xyv:"+e1x+" "+e1y +" "+e1v);
+	    float e1z = Float.parseFloat(st.nextToken());
 	    
 	    inputLine = readLine();
 	    st = new StringTokenizer(inputLine,": ");
 	    st.nextToken();
 	    float e2x = Float.parseFloat(st.nextToken());
 	    float e2y = Float.parseFloat(st.nextToken());
-	    float e2v = Float.parseFloat(st.nextToken());
-	    System.out.println("e1xyv:"+e1x+" "+e1y +" "+e1v);
+	    float e2z = Float.parseFloat(st.nextToken());
 	    
 	    inputLine = readLine();
 	    st = new StringTokenizer(inputLine,": ");
 	    st.nextToken();
 	    float r = Float.parseFloat(st.nextToken());
-	    System.out.println("r:"+r);
 	    
 	    inputLine = readLine();
 	    st = new StringTokenizer(inputLine,": ");
 	    st.nextToken();
 	    float theta = Float.parseFloat(st.nextToken());
-	    System.out.println("theta:"+theta);
-	    
+
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine,": ");
+	    st.nextToken();
+	    boolean end1_valid = Integer.parseInt(st.nextToken()) == 1;
+	    boolean end1_active = Integer.parseInt(st.nextToken()) == 1;
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine,": ");
+	    st.nextToken();
+	    boolean end2_valid = Integer.parseInt(st.nextToken()) == 1;
+	    boolean end2_active = Integer.parseInt(st.nextToken()) == 1;
+	
+	    System.out.println("  cxyz: " +cx+" "+cy+" "+cz);
+	    System.out.println("  e1xyz/va: "+e1x+" "+e1y +" "+e1z+" / "+end1_valid+" "+end1_active);
+	    System.out.println("  e2xyz/va: "+e2x+" "+e2y +" "+e2z+" / "+end2_valid+" "+end2_active);
+	    System.out.println("  r: " + r + "  theta: "+theta);
 	    return new LineShapeInfo(id, parentId, name, color,
-				     cx,cy,cz, e1x, e1y, e1v, e2x, e2y, e2v, r, theta);
+				     cx,cy,cz, e1x, e1y, e1z, e2x, e2y, e2z, 
+				     r, theta, end1_valid, end1_active, end2_valid, end2_active);
 	
-    } else if(shapetype == 2) { // ellipseshape
+	} else if(shapetype == 2) { // ellipseshape
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine,": ");
+	    st.nextToken();
+	    float semimajor = Float.parseFloat(st.nextToken());
+	    float semiminor = Float.parseFloat(st.nextToken());
+	    System.out.println(" axes:"+semimajor+" "+semiminor);
+	
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine,": ");
+	    st.nextToken();
+	    float orientation = Float.parseFloat(st.nextToken());
+	    System.out.println(" orientation:"+orientation);
+	
+	    return new EllipseShapeInfo(id,parentId,name,color,
+					cx,cy,cz, semimajor, semiminor, orientation);
+	
+	} else if (shapetype == 3) { // pointshape
+	    return new PointShapeInfo(id,parentId, name, color, cx, cy, cz);
+
+	} else if (shapetype == 4) { // agentshape
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine,": ");
+	    st.nextToken();
+	    float orientation = Float.parseFloat(st.nextToken());
+	    System.out.println(" orientation:"+orientation);
+	
+	    return new AgentShapeInfo(id,parentId, name, color,
+				      cx,cy,cz, orientation);
+	} else if (shapetype == 5) { // sphereshape
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine,": ");
+	    st.nextToken();
+	    float radius = Float.parseFloat(st.nextToken());
+	    System.out.println(" radius:"+radius);
+	
+	    return new SphereShapeInfo(id,parentId,name,color,cx,cy,cz,radius);
+
+	} else if (shapetype == 6) { // polygonshape
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine,": ");
+	    st.nextToken();
+	    int num_vertices = Integer.parseInt(st.nextToken());
+	    System.out.println("num_vtx: " + num_vertices);
+	    float[][] vertices = new float[num_vertices][3];
+	
+	    for (int i = 0; i < num_vertices; i++) {
+		inputLine = readLine();
+		st = new StringTokenizer(inputLine,": ");
+		st.nextToken();
+		vertices[i][0] = Float.parseFloat(st.nextToken());
+		vertices[i][1] = Float.parseFloat(st.nextToken());
+		vertices[i][2] = Float.parseFloat(st.nextToken());
+		System.out.println("vertex "+i+": "+vertices[i][0]+" "+vertices[i][1] +" "+vertices[i][2]);
+	    }
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine,": ");
+	    st.nextToken();
+	    //	System.out.println("end1_ln valid: " + st.nextToken());
+	    boolean end1_valid = Integer.parseInt(st.nextToken()) == 1;
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine,": ");
+	    st.nextToken();
+	    boolean end2_valid = Integer.parseInt(st.nextToken()) == 1;
+	    System.out.println("End1_valid: " + end1_valid);
+	    System.out.println("End2_valid: " + end2_valid);
+	    return new PolygonShapeInfo(id, parentId, name, color, cx, cy, cz,
+					num_vertices, vertices, end1_valid, end2_valid);
+	
+	} else if(shapetype == 7) { // blobshape
+	    return parseBlob(id,parentId,name,color,cx,cy,cz);
+	} else if(shapetype == 8) { // brickshape
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float GFLx = Float.parseFloat(st.nextToken());
+	    float GFLy = Float.parseFloat(st.nextToken());
+	    System.out.println("GFL: " + GFLx + " " + GFLy);
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float GFRx = Float.parseFloat(st.nextToken());
+	    float GFRy = Float.parseFloat(st.nextToken());
+	    System.out.println("GFR: " + GFRx + " " + GFRy);
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float GBLx = Float.parseFloat(st.nextToken());
+	    float GBLy = Float.parseFloat(st.nextToken());
+	    System.out.println("GBL: " + GBLx + " " + GBLy);
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float GBRx = Float.parseFloat(st.nextToken());
+	    float GBRy = Float.parseFloat(st.nextToken());
+	    System.out.println("GBR: " + GBRx + " " + GBRy);
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float TFLx = Float.parseFloat(st.nextToken());
+	    float TFLy = Float.parseFloat(st.nextToken());
+	    System.out.println("TFL: " + TFLx + " " + TFLy);
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float TFRx = Float.parseFloat(st.nextToken());
+	    float TFRy = Float.parseFloat(st.nextToken());
+	    System.out.println("TFR: " + TFRx + " " + TFRy);
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float TBLx = Float.parseFloat(st.nextToken());
+	    float TBLy = Float.parseFloat(st.nextToken());
+	    System.out.println("TBL: " + TBLx + " " + TBLy);
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float TBRx = Float.parseFloat(st.nextToken());
+	    float TBRy = Float.parseFloat(st.nextToken());
+	    System.out.println("TBR: " + TBRx + " " + TBRy);
+       
+	    return new BrickShapeInfo(id, parentId, name, color, cx, cy, cz,
+				      GFLx, GFLy, GFRx, GFRy, GBLx, GBLy, GBRx, GBRy,
+				      TFLx, TFLy, TFRx, TFRy, TBLx, TBLy, TBRx, TBRy);
+	
+	} else if(shapetype == 9) { // pyramidshape
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float FLx = Float.parseFloat(st.nextToken());
+	    float FLy = Float.parseFloat(st.nextToken());
+	    System.out.println("FL: " + FLx + " " + FLy);
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float BLx = Float.parseFloat(st.nextToken());
+	    float BLy = Float.parseFloat(st.nextToken());
+	    System.out.println("BL: " + BLx + " " + BLy);
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float FRx = Float.parseFloat(st.nextToken());
+	    float FRy = Float.parseFloat(st.nextToken());
+	    System.out.println("FR: " + FRx + " " + FRy);
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float BRx = Float.parseFloat(st.nextToken());
+	    float BRy = Float.parseFloat(st.nextToken());
+	    System.out.println("BR: " + BRx + " " + BRy);
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float Topx = Float.parseFloat(st.nextToken());
+	    float Topy = Float.parseFloat(st.nextToken());
+	    System.out.println("Top: " + Topx + " " + Topy);
+
+	    return new PyramidShapeInfo(id, parentId, name, color, cx, cy, cz,
+				      FLx, FLy, FRx, FRy, BLx, BLy, BRx, BRy,
+				      Topx, Topy);
+	} else {
+	    System.out.println("Invalid shape!");
+	    return new ShapeInfo(id, parentId, name, color, cx, cy, cz);
+	}
+    }
+
+    public BlobShapeInfo parseBlob(int id, int parentId, String name, Color color,
+				   float cx, float cy, float cz)
+	throws IOException
+    {
+	String inputLine;
+	StringTokenizer st;
+
 	inputLine = readLine();
 	st = new StringTokenizer(inputLine,": ");
 	st.nextToken();
-	float semimajor = Float.parseFloat(st.nextToken());
-	float semiminor = Float.parseFloat(st.nextToken());
-	System.out.println("axes:"+semimajor+" "+semiminor);
-	
+	float area = Float.parseFloat(st.nextToken());
+	System.out.println("area: "+area);
+
 	inputLine = readLine();
 	st = new StringTokenizer(inputLine,": ");
 	st.nextToken();
-	float orientation = Float.parseFloat(st.nextToken());
-	System.out.println("orientation:"+orientation);
-	
-	return new EllipseShapeInfo(id,parentId,name,color,
-				     cx,cy,cz, semimajor, semiminor, orientation);
-	
-    } else if (shapetype == 4) { // agentshape
+	int orient = Integer.parseInt(st.nextToken());
+	System.out.println("orient: "+orient);
+
 	inputLine = readLine();
 	st = new StringTokenizer(inputLine,": ");
 	st.nextToken();
-	float orientation = Float.parseFloat(st.nextToken());
-	System.out.println("orientation:"+orientation);
-	
-	return new AgentShapeInfo(id,parentId, name, color,
-				   cx,cy,cz, orientation);
-    } else if (shapetype == 5) { // sphereshape
+	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 + " " + 
+			   topLeft_y + " " + topLeft_z);
+
 	inputLine = readLine();
 	st = new StringTokenizer(inputLine,": ");
 	st.nextToken();
-	float radius = Float.parseFloat(st.nextToken());
-	System.out.println("radius:"+radius);
-	
-	return new SphereShapeInfo(id,parentId,name,color,cx,cy,cz,radius);
-    } else {
-	System.out.println("Invalid shape!");
-	return new ShapeInfo(id, parentId, name, color, cx, cy, cz);
+	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 + " " + 
+			   topRight_y + " " + topRight_z);
+
+	inputLine = readLine();
+	st = new StringTokenizer(inputLine,": ");
+	st.nextToken();
+	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 + " " + 
+			   bottomLeft_y + " " + bottomLeft_z);
+
+	inputLine = readLine();
+	st = new StringTokenizer(inputLine,": ");
+	st.nextToken();
+	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 + " " + 
+			   bottomRight_y + " " + bottomRight_z);
+
+	return new BlobShapeInfo(id,parentId,name,color,cx,cy,cz,area,orient,
+				 topLeft_x, topLeft_y, topLeft_z,
+				 topRight_x, topRight_y, topRight_z,
+				 bottomLeft_x, bottomLeft_y, bottomLeft_z,
+				 bottomRight_x, bottomRight_y, bottomRight_z);
     }
-}
 
-public SketchGUI(String host, int _listingPort, int _sketchPort, 
-		 //		 boolean _isCam) {
-		 int _space) {
-    super();
-    this.host = host;
-    this.listingPort = _listingPort;
-    this.sketchPort = _sketchPort;
-    //    this.isCam = _isCam;
-    this.space = _space;
+    public SketchGUI(String _host, int _listingPort, int _sketchPort, 
+		     Space _space) {
+	super();
+	host = _host;
+	listingPort = _listingPort;
+	sketchPort = _sketchPort;
+	space = _space;
+
+	Tmat = new AffineTransform();
+	TmatInv = new AffineTransform();
     
-    //    if(isCam)
-    if(space == 1)
-	root = new DefaultMutableTreeNode("camspace");
-    else if (space == 2)
-	root = new DefaultMutableTreeNode("localspace");
-    else
-	root = new DefaultMutableTreeNode("worldspace");
+	if(space == Space.cam)
+	    root = new DefaultMutableTreeNode("camspace");
+	else if (space == Space.local)
+	    root = new DefaultMutableTreeNode("localspace");
+	else if (space == Space.world)
+	    root = new DefaultMutableTreeNode("worldspace");
+
+
+	listener = new TCPVisionListener(host, sketchPort);
 
-    img = new BufferedImage(VisionListener.DEFAULT_WIDTH, VisionListener.DEFAULT_HEIGHT, BufferedImage.TYPE_INT_RGB);
-    Graphics2D g = img.createGraphics();
-    // g.setBackground(Color.GRAY);
-    g.clearRect(0,0,VisionListener.DEFAULT_WIDTH, VisionListener.DEFAULT_HEIGHT);
-    sketchStack = new Vector();
     
-    init();
+	// network setup
+	reconnect();
+
+	// Get the image size immediately after connecting
+	if (netout != null) {
+	    try{
+		String inputLine;
+		netout.println("size");
+		System.out.println(inputLine = readLine());
+		while((inputLine=readLine()).compareTo("size end") != 0) {
+		    System.out.println(inputLine);
+		    StringTokenizer sizetoken = new StringTokenizer(inputLine);
+		    String token = sizetoken.nextToken();
+		    if (token.equals("width")){
+			imageWidth = Integer.parseInt(sizetoken.nextToken());
+
+		    }
+		    else if (token.equals("height")){
+			imageHeight = Integer.parseInt(sizetoken.nextToken());
+		    }
+		}
+		System.out.println(inputLine);
+		
+	    }
+	    catch(IOException ioe) {
+		System.err.println("Transfer error");
+	    }
+	    panelBoundsSet = true;
+	}
+	else {
+	    imageWidth = defaultWidth;
+	    imageHeight = defaultHeight;
+	}
     
-    // network setup
-    reconnect();
-}
+	sketchPanel = new SketchPanel(this, listener, space, prefs, imageWidth, imageHeight);
+
+	img = new BufferedImage(imageWidth, imageHeight, BufferedImage.TYPE_INT_RGB);
+	Graphics2D g = img.createGraphics();
+	g.clearRect(0,0,imageWidth, imageHeight);
+	sketchStack = new Vector();
+
+	init();
+    
+    }
 	
     public void init() {
 
@@ -380,51 +781,83 @@
 	getContentPane().add(Box.createHorizontalStrut(strutsize),BorderLayout.WEST);
 	getContentPane().add(Box.createHorizontalStrut(strutsize),BorderLayout.EAST);
 		
-	//	setTitle("TekkotsuMon: "+(isCam ? "Cam" : "World")+" Space");
-	setTitle("TekkotsuMon: "+((space==1) ? "Cam" : ((space==2) ? "Local" : "World"))+" Space");
-	listener = new TCPVisionListener(host, sketchPort);
-	//	sketchPanel = new SketchPanel(this, listener, isCam, prefs);
-	sketchPanel = new SketchPanel(this, listener, space, prefs);
-	sketchPanel.setMinimumSize(new Dimension(VisionListener.DEFAULT_WIDTH/2, VisionListener.DEFAULT_HEIGHT/2));
-	sketchPanel.setPreferredSize(new Dimension(VisionListener.DEFAULT_WIDTH*2, VisionListener.DEFAULT_HEIGHT*2));
+	//	setTitle(((space==1) ? "Cam" : ((space==2) ? "Local" : "World"))+"Space "+host);
+	setTitle(space.name()+": "+host);
+
+	sketchPanel.setMinimumSize(new Dimension(imageWidth/2, imageHeight/2));
+	sketchPanel.setPreferredSize(new Dimension(imageWidth*2, imageHeight*2));
 	sketchPanel.setLockAspectRatio(true);
 
 	curSketchPanel = sketchPanel;
-	//	sketchPanel.makeSketchFrame(sketchPanel, isCam ? "Cam" : "World");
-	sketchPanel.makeSketchFrame(sketchPanel, (space==1) ? "Cam" : ((space==2) ? "Local" : "World"));
+	//	panelTitle = ((space==1) ? "Cam" : ((space==2) ? "Local" : "World")) + "Img";
+	panelTitle = space.name() + " view: ";
+	sketchPanel.makeSketchFrame(sketchPanel, panelTitle+" "+host);
 	{
 
 	    Box tmp1 = Box.createHorizontalBox();
 	    tmp1.add(Box.createHorizontalStrut(strutsize));
-	    {		Box tmp2 = Box.createVerticalBox();
-
+	    {		
+		Box tmp2 = Box.createVerticalBox();
 		tmp2.add(Box.createVerticalStrut(strutsize));
 
 		{
-		    Box tmp3 = Box.createHorizontalBox();
-		    tmp3.add(status=new JLabel(state));
-		    tmp3.add(Box.createHorizontalGlue());
+		    Box buttonBox = Box.createVerticalBox();
+		    {
+			Box tmp3 = Box.createHorizontalBox();
+			tmp3.add(status=new JLabel(state));
+			//tmp3.add(Box.createHorizontalGlue());
 
-		    tmp3.add(Box.createHorizontalStrut(strutsize));
+			//tmp3.add(Box.createHorizontalStrut(strutsize));
 		
-		    rescaleBut = new JButton("Rescale the Image");
-		    rescaleBut.setAlignmentX(0.5f);
-		    rescaleBut.addActionListener(this);
-		    rescaleBut.setActionCommand("refresh");
-		    rescaleBut.setEnabled(true);
-		    rescaleBut.setToolTipText("Rescales the displayed sketch;");
-		    tmp3.add(rescaleBut);
-		    tmp3.add(Box.createHorizontalStrut(strutsize));
+			rescaleBut = new JButton("Rescale the Image");
+			rescaleBut.setAlignmentX(0.5f);
+			rescaleBut.addActionListener(this);
+			rescaleBut.setActionCommand("rescale");
+			rescaleBut.setEnabled(true);
+			rescaleBut.setToolTipText("Rescales the displayed sketch;");
+			tmp3.add(rescaleBut);
+			tmp3.add(Box.createHorizontalStrut(strutsize));
 
-		    refreshListBut = new JButton("Refresh Listing");
-		    refreshListBut.setAlignmentX(0.5f);
-		    refreshListBut.addActionListener(this);
-		    refreshListBut.setActionCommand("refreshlist");
-		    refreshListBut.setEnabled(true);
-		    refreshListBut.setToolTipText("Refreshes the sketch listing;");
-		    tmp3.add(refreshListBut);
+			refreshListBut = new JButton("Refresh Listing");
+			refreshListBut.setAlignmentX(0.5f);
+			refreshListBut.addActionListener(this);
+			refreshListBut.setActionCommand("refreshlist");
+			refreshListBut.setEnabled(true);
+			refreshListBut.setToolTipText("Refreshes the sketch listing;");
+			tmp3.add(refreshListBut);
+			tmp3.add(Box.createGlue());
+
+			buttonBox.add(tmp3);
+		    }
+
+		    buttonBox.add(Box.createVerticalStrut(strutsize));
+		    {
+			Box tmp4 = Box.createHorizontalBox();
+			//tmp4.add(Box.createHorizontalGlue());
+			//tmp4.add(Box.createHorizontalStrut(strutsize));
+			
+			checkAllBut = new JCheckBox("Select All Shapes", defaultSelected);
+			checkAllBut.setAlignmentX(0.5f);
+			checkAllBut.addActionListener(this);
+			checkAllBut.setActionCommand("checkall");
+			checkAllBut.setEnabled(true);
+			checkAllBut.setToolTipText("Selects all shapes for display.");
+			tmp4.add(checkAllBut);
+			tmp4.add(Box.createHorizontalStrut(strutsize));
+
+			invertAllBut = new JCheckBox("Invert All Shapes", defaultInversion);
+			invertAllBut.setAlignmentX(0.5f);
+			invertAllBut.addActionListener(this);
+			invertAllBut.setActionCommand("invertall");
+			invertAllBut.setEnabled(true);
+		        invertAllBut.setToolTipText("Inverts all shapes.");
+			tmp4.add(invertAllBut);
+			tmp4.add(Box.createGlue());
+
+			buttonBox.add(tmp4);
+		    }
 		    
-		    tmp2.add(tmp3, BorderLayout.CENTER);
+		    tmp2.add(buttonBox, BorderLayout.CENTER);
 		}
 
 		tmp2.add(Box.createVerticalStrut(strutsize));
@@ -433,7 +866,7 @@
 		tmp2.add(new JScrollPane(sketchTree));
 		// set up sketch node selection
 		sketchTree.getSelectionModel().setSelectionMode
-		            (TreeSelectionModel.DISCONTIGUOUS_TREE_SELECTION);
+		    (TreeSelectionModel.DISCONTIGUOUS_TREE_SELECTION);
 		//Listen for when the selection changes.
 		sketchTree.addTreeSelectionListener(this);
 		sketchTree.addMouseListener(this);
@@ -457,7 +890,7 @@
 	setLocation(prefs.getInt(name+".x",50),prefs.getInt(name+".y",50));
 	addWindowListener(new CloseSketchGUIAdapter(this));
 
-	sketchPanel.getListener().addListener(this);
+	//sketchPanel.getListener().addListener(this);
 
 
 	popMenu = new PopupMenu();
@@ -468,9 +901,12 @@
 	newWindow.addActionListener(new PopupNewWindowListener(this));
 	popMenu.add(newWindow);
 	this.add(popMenu);
+
+	refreshListBut.doClick();
     }
 
-    class CloseSketchGUIAdapter extends WindowAdapter {		SketchGUI gui;
+    class CloseSketchGUIAdapter extends WindowAdapter {
+	SketchGUI gui;
 	CloseSketchGUIAdapter(SketchGUI gui) {this.gui=gui;}
 	public void windowClosing(WindowEvent e) {
 	    gui.close();
@@ -481,6 +917,10 @@
  	public void actionPerformed(ActionEvent e)
 	{
 	    currentMenuObject.invert();
+	    if (currentMenuObject instanceof ShapeInfo)
+		{
+		    ((ShapeInfo)currentMenuObject).setUseDefaultInversion(false);
+		}
 	    valueChanged(lastEvent);
 	    sketchTree.treeDidChange();
 	}
@@ -493,42 +933,40 @@
 
 	public void actionPerformed(ActionEvent e)
 	{
-	    //		 SketchPanel sketchPanel=new SketchPanel(gui, listener, true, prefs);
-		 SketchPanel sketchPanel=new SketchPanel(gui, listener, 1, prefs);
-	    sketchPanel.setMinimumSize(new Dimension(VisionListener.DEFAULT_WIDTH/2, 
-							  VisionListener.DEFAULT_HEIGHT/2));
-		 sketchPanel.setPreferredSize(new Dimension(VisionListener.DEFAULT_WIDTH*2, 
-							    VisionListener.DEFAULT_HEIGHT*2));
-		 sketchPanel.setLockAspectRatio(true);
-		 
-		 sketchPanel.makeSketchFrame(sketchPanel, "Cloned");
-		 		 
-		 sketchPanel.imageUpdated(getSketchImage(),sketchTree.getSelectionPaths());   
+	    SketchPanel sketchPanel=new SketchPanel(gui, listener, Space.cam, prefs, imageWidth, imageHeight);
+	    sketchPanel.setMinimumSize(new Dimension(imageWidth/2, imageHeight/2));
+	    sketchPanel.setPreferredSize(new Dimension(imageWidth*2, imageHeight*2));
+	    sketchPanel.setLockAspectRatio(true);
+	    
+	    sketchPanel.makeSketchFrame(sketchPanel, "Dummy");
+	    
+	    sketchPanel.imageUpdated(getSketchImage(),sketchTree.getSelectionPaths());   
 	}
     }
 
-	public void close() {
-		try {
-			if(listingSocket!=null && !listingSocket.isClosed())
-				listingSocket.close();		} catch (IOException ioe) {
-			System.err.println("close failed:");
-			ioe.printStackTrace();
-		}
-		prefs.putInt("SketchGUI.location.x",getLocation().x);
-		prefs.putInt("SketchGUI.location.y",getLocation().y);
-		sketchPanel.getListener().removeListener(this);
-		Component p=sketchPanel;
-		while(p.getParent()!=null)
-			p=p.getParent();
-		if(p instanceof Window) {
-			Window w=(Window)p;
-			prefs.putInt("SketchPanel.location.x",w.getLocation().x);
-			prefs.putInt("SketchPanel.location.y",w.getLocation().y);
-			w.dispose();
-		} else
-			System.out.println("That's weird - root container isn't window");
-		dispose();
+    public void close() {
+	try {
+	    if(listingSocket!=null && !listingSocket.isClosed())
+		listingSocket.close();
+	} catch (IOException ioe) {
+	    System.err.println("close failed:");
+	    ioe.printStackTrace();
 	}
+	prefs.putInt("SketchGUI.location.x",getLocation().x);
+	prefs.putInt("SketchGUI.location.y",getLocation().y);
+	sketchPanel.getListener().kill();
+	Component p=sketchPanel;
+	while(p.getParent()!=null)
+	    p=p.getParent();
+	if(p instanceof Window) {
+	    Window w=(Window)p;
+	    prefs.putInt("SketchPanel.location.x",w.getLocation().x);
+	    prefs.putInt("SketchPanel.location.y",w.getLocation().y);
+	    w.dispose();
+	} else
+	    System.out.println("That's weird - root container isn't window");
+	dispose();
+    }
 
     public TreeNode initSketchTree(String host, int port) {
 
@@ -539,60 +977,83 @@
     }
 
     public void sortTree(DefaultMutableTreeNode curNode) {
-		// set up comparator
-		Comparator comp =
-			new Comparator() {
-				public int compare(Object o1, Object o2) {
-					return compare((DefaultMutableTreeNode) o1, (DefaultMutableTreeNode) o2);  
-				}
-				public int compare(DefaultMutableTreeNode n1, DefaultMutableTreeNode n2) {
-					Integer i1 = new Integer(((VisualObjectInfo)n1.getUserObject()).id);
-					Integer i2 = new Integer(((VisualObjectInfo)n2.getUserObject()).id);
-					return i1.compareTo(i2);
-				}
-			};
-
-		// sort the roots children
-		Object[] objs = new Object[curNode.getChildCount()];
-		Enumeration children = curNode.children();
-		for (int i=0;children.hasMoreElements();i++) {
-			DefaultMutableTreeNode child = (DefaultMutableTreeNode) children.nextElement();
-			objs[i] = child;
+	// set up comparator
+	Comparator comp =
+	    new Comparator() {
+		public int compare(Object o1, Object o2) {
+		    return compare((DefaultMutableTreeNode) o1, (DefaultMutableTreeNode) o2);  
+		}
+		public int compare(DefaultMutableTreeNode n1, DefaultMutableTreeNode n2) {
+		    Integer i1 = new Integer(((SketchOrShapeInfo)n1.getUserObject()).id);
+		    Integer i2 = new Integer(((SketchOrShapeInfo)n2.getUserObject()).id);
+		    return i1.compareTo(i2);
 		}
+	    };
 
-		Arrays.sort(objs, comp);
-		curNode.removeAllChildren();
+	// sort the roots children
+	Object[] objs = new Object[curNode.getChildCount()];
+	Enumeration children = curNode.children();
+	for (int i=0;children.hasMoreElements();i++) {
+	    DefaultMutableTreeNode child = (DefaultMutableTreeNode) children.nextElement();
+	    objs[i] = child;
+	}
 
-		// insert newly ordered children
-		for (int i=0;i<objs.length;i++) {
-			DefaultMutableTreeNode orderedNode = (DefaultMutableTreeNode) objs[i];
-			curNode.add(orderedNode);
-			if (!orderedNode.isLeaf()) {
-				sortTree(orderedNode);
-			}
-		}
+	Arrays.sort(objs, comp);
+	curNode.removeAllChildren();
+
+	// insert newly ordered children
+	for (int i=0;i<objs.length;i++) {
+	    DefaultMutableTreeNode orderedNode = (DefaultMutableTreeNode) objs[i];
+	    curNode.add(orderedNode);
+	    if (!orderedNode.isLeaf()) {
+		sortTree(orderedNode);
+	    }
 	}
+    }
 
-	// gets called when a Sketch selection is clicked
+    // gets called when a Sketch selection is clicked
     public void valueChanged(TreeSelectionEvent e) {
 	imageNeedsUpdate = true;
 	lastEvent = e;
-	TreePath[] paths = sketchTree.getSelectionPaths();
 	
 	// Go through all objects and set visible to false
+	// If a sketch was selected, only de-select shapes, and vice-versa
 	DefaultMutableTreeNode n = root;
-	while((n = n.getNextNode())!= null)
-	    {
-		((VisualObjectInfo)n.getUserObject()).setVisible(false);
+	boolean curIsSketch = curObject instanceof SketchInfo;
+	while((n = n.getNextNode())!= null) {
+	    if (!(n.getUserObject() instanceof SketchOrShapeInfo)) {
+		continue;
 	    }
+	    if ((n.getUserObject() instanceof SketchInfo) == curIsSketch ||
+		focusJustChanged) {
+		((SketchOrShapeInfo)n.getUserObject()).setVisible(false);
+		
+		// Override the default behavior of the tree
+		// If the default is to have shapes selected, then re-add any shapes that follow the default
+		if (defaultSelected && n.getUserObject() instanceof ShapeInfo && 
+		    ((ShapeInfo)n.getUserObject()).getUseDefaultSelection()) {
+		    ShapeInfo sinfo = (ShapeInfo)n.getUserObject();
+		    sinfo.setVisible(true);
+		    sketchTree.addSelectionPath(new TreePath(n.getPath()));
+		}
+	    }
+	    // Keep shapes if a sketch was selected, keep sketches if a shape was selected
+	    else if (((SketchOrShapeInfo)n.getUserObject()).getVisible()) {
+		sketchTree.addSelectionPath(new TreePath(n.getPath()));
+	    }
+	}
 	
+	focusJustChanged = false;
+	TreePath[] paths = sketchTree.getSelectionPaths();
 
 	if (paths == null) {
-	    //renderSelectedInTree(null);
 	    curSketchPanel.imageUpdated(null, null);
 	    return;
 	}
 
+
+	sketchStack.clear();
+
 	for (int path_i = 0; path_i < paths.length; path_i++) {
 	    DefaultMutableTreeNode node 
 		=(DefaultMutableTreeNode)(paths[path_i].getLastPathComponent());
@@ -600,41 +1061,40 @@
 	    if (node == root) continue;	
 	    if (node == null) {System.err.println("node is null???"); return; }
 	    
-	    if(!(node.getUserObject() instanceof VisualObjectInfo)) {
+	    if(!(node.getUserObject() instanceof SketchOrShapeInfo)) {
 		System.out.println("valueChanged:: placeholder text can't be displayed");
 		continue;
 	    }
 	    
 	    
-	    VisualObjectInfo vinfo = (VisualObjectInfo)(node.getUserObject());
+	    SketchOrShapeInfo vinfo = (SketchOrShapeInfo)(node.getUserObject());
 	    if (!node.isRoot()) {
-		System.out.println("id clicked:"+vinfo.id);
-		if (! (vinfo instanceof SketchInfo) || ! ((SketchInfo)vinfo).isImageLoaded())
-		    {
-			((TCPVisionListener)listener).setReadingImage();
-			netout.println("get "+vinfo.id);
-			try {
-			    String inputLine;
-			    while((inputLine=readLine()).compareTo("get end") != 0) {
-				System.out.println(inputLine);
-			    }
-			} catch (IOException ioe) {
-			    System.err.println("Transfer error");
-			    reconnect();
-			    valueChanged(null);
+		if (vinfo instanceof SketchInfo && ! ((SketchInfo)vinfo).isImageLoaded()) {
+		    ((TCPVisionListener)listener).setReadingImage();
+		    netout.println("get "+vinfo.id);
+		    try {
+			String inputLine;
+			while((inputLine=readLine()).compareTo("get end") != 0) {
+			    System.out.println(inputLine);
 			}
-			if (vinfo instanceof SketchInfo)
-			    {
-				while(((TCPVisionListener)listener).isReadingImage())
-				    ;
-				((SketchInfo)vinfo).copyImage(((TCPVisionListener)listener).getImage());
-			    }
-			System.out.println("done with id:"+vinfo.id);
+		    } catch (IOException ioe) {
+			System.err.println("Transfer error");
+			reconnect();
+			valueChanged(null);
 		    }
+		    while(((TCPVisionListener)listener).isReadingImage())
+			// thread.yield() in java?
+			;
+		    ((SketchInfo)vinfo).copyImage(((TCPVisionListener)listener).getImage());
+		    System.out.println("done with id:"+vinfo.id);
+		}
+		else {
+		    curSketchPanel.scaleToSketchOrShape(vinfo);
+		}
 		vinfo.setVisible(true);
-		if (!sketchStack.contains(vinfo)) { sketchStack.add(vinfo); }
-	    } else {
-
+		if (!sketchStack.contains(vinfo)) { 
+		    sketchStack.add(vinfo); 
+		}
 	    }
 	}
 	
@@ -652,81 +1112,99 @@
 	return ans;
     }
 	
-	public void reconnect() {
-		System.out.print(host+":"+listingPort+" reconnecting...");
-		try {
-			if(listingSocket!=null && !listingSocket.isClosed())
-				listingSocket.close();
-			netin=null;
-			netout=null;
-			listingSocket = new Socket(host,listingPort);
-			netout = new PrintWriter(listingSocket.getOutputStream(), true);
-			netin = new BufferedReader(new InputStreamReader(listingSocket.getInputStream()));
-		} catch (UnknownHostException e) {
-			System.err.println("Don't know about host:"+host);
-			System.exit(1);
-		} catch (IOException ioe) {
-			System.err.println("reconnection failed:");
-			//ioe.printStackTrace();
-			return;
-		}
-		System.out.println("done");
-		refreshListBut.doClick(); //auto refresh on reconnect
+    public void reconnect() {
+	System.out.print(host+":"+listingPort+" reconnecting...");
+	netout = null;
+	try {
+	    if(listingSocket!=null && !listingSocket.isClosed())
+		listingSocket.close();
+	    netin=null;
+	    netout=null;
+	    listingSocket = new Socket(host,listingPort);
+	    netout = new PrintWriter(listingSocket.getOutputStream(), true);
+	    netin = new BufferedReader(new InputStreamReader(listingSocket.getInputStream()));
+        } catch (UnknownHostException e) {
+	    System.err.println("Don't know about host:"+host);
+	    System.exit(1);
+	} catch (IOException ioe) {
+	    System.err.println("reconnection failed:");
+	    //ioe.printStackTrace();
+	    return;
 	}
-
-	public void visionUpdated(VisionListener listener) {
-	    //renderSelectedInTree(l.getImage().createGraphics());
-		listener.removeListener(this);
-		listener.fireVisionUpdate();
-		listener.addListener(this);
+	System.out.println("done");
+	if (refreshListBut != null) {
+	    refreshListBut.doClick(); //auto refresh on reconnect
 	}
+    }
+    
+    public void visionUpdated(VisionListener listener) {
+	//renderSelectedInTree(l.getImage().createGraphics());
+	/*listener.removeListener(this);
+	listener.fireVisionUpdate();
+	listener.addListener(this);*/
+    }
+
+    public void sensorsUpdated(VisionListener l) {}
 	
-	// renders all the currently selected elements in the tree
-	public void renderSelectedInTree(Graphics2D g) {
-		if(g==null) {
-			g = img.createGraphics();
-			// g.setBackground(Color.GRAY);
-			g.clearRect(0,0,img.getWidth(),img.getHeight());
-		}
-		TreePath[] paths = sketchTree.getSelectionPaths();
-		if (paths == null) {
-			sketchPanel.repaint();
-			return;
-		}
-		for (int path_i = 0; path_i < paths.length; path_i++) {
-			DefaultMutableTreeNode node 
-				=(DefaultMutableTreeNode)(paths[path_i].getLastPathComponent());
+    // renders all the currently selected elements in the tree
+    public void renderSelectedInTree(Graphics2D g) {
+	if(g==null) {
+	    g = img.createGraphics();
+	    // g.setBackground(Color.GRAY);
+	    g.clearRect(0,0,img.getWidth(),img.getHeight());
+	}
+	TreePath[] paths = sketchTree.getSelectionPaths();
+	if (paths == null) {
+	    sketchPanel.repaint();
+	    return;
+	}
+	for (int path_i = 0; path_i < paths.length; path_i++) {
+	    DefaultMutableTreeNode node 
+		=(DefaultMutableTreeNode)(paths[path_i].getLastPathComponent());
 
-			if (node == root) continue;
-			if (node == null) return;
+	    if (node == root) continue;
+	    if (node == null) return;
 			
-			if(!(node.getUserObject() instanceof VisualObjectInfo)) {
-				System.out.println("renderSelectedInTree:: placeholder text can't be displayed");
-				continue;
-			}
+	    if(!(node.getUserObject() instanceof SketchOrShapeInfo)) {
+		System.out.println("renderSelectedInTree:: placeholder text can't be displayed");
+		continue;
+	    }
 			
-			VisualObjectInfo vinfo = (VisualObjectInfo)(node.getUserObject());
-			g.setColor(vinfo.getColor());
+	    SketchOrShapeInfo vinfo = (SketchOrShapeInfo)(node.getUserObject());
+	    g.setColor(vinfo.getColor());
 
-			//g.setTransform(sketchPanel.resultAtrans);
-			//vinfo.renderTo(g);
-		}
-		sketchPanel.repaint();
-		//repaint(); // repaints this frame
-		//paintAll(); // repaints everything in this frame
+	    //g.setTransform(sketchPanel.resultAtrans);
+	    //vinfo.renderTo(g);
 	}
+	sketchPanel.repaint();
+	//repaint(); // repaints this frame
+	//paintAll(); // repaints everything in this frame
+    }
 
     public void mousePressed(MouseEvent e)
     {
 	TreePath selectedPath = sketchTree.getPathForLocation(e.getX(),e.getY());
 	//System.out.println("Got mouse event for "+selectedPath);
-	if (e.getButton() == MouseEvent.BUTTON3)
+	if (selectedPath != null)
 	    {
-		if (selectedPath != null)
+		Object obj = ((DefaultMutableTreeNode)(selectedPath.getLastPathComponent())).getUserObject();
+		if (! (obj instanceof SketchOrShapeInfo))
 		    {
-			currentMenuObject = ((VisualObjectInfo)(((DefaultMutableTreeNode)(selectedPath.getLastPathComponent())).getUserObject()));
+			return;
+		    }
+		curObject = (SketchOrShapeInfo)obj;
+		if (e.getButton() == MouseEvent.BUTTON3)
+		    {
+			currentMenuObject = curObject;
 			popMenu.show(sketchTree,e.getX(), e.getY());
 		    }
+		else if (e.getButton() == MouseEvent.BUTTON1)
+		    {
+			if (curObject instanceof ShapeInfo)
+			    {
+				((ShapeInfo)curObject).setUseDefaultSelection(false);
+			    }
+		    }
 	    }
     }
 
@@ -746,137 +1224,119 @@
 	// Cull not visible objects from vector
 	// render all the sketches in the vector
 
-	img = new BufferedImage(VisionListener.DEFAULT_WIDTH, VisionListener.DEFAULT_HEIGHT, BufferedImage.TYPE_INT_RGB	);
+	img = new BufferedImage(imageWidth, imageHeight, BufferedImage.TYPE_INT_RGB);
 	Graphics2D g = img.createGraphics();
-	g.setBackground(Color.GRAY);
-	g.clearRect(0,0,VisionListener.DEFAULT_WIDTH, VisionListener.DEFAULT_HEIGHT);
+	g.setBackground(backgroundColor);
+	g.clearRect(0,0,imageWidth, imageHeight);
 
 	int pixcount = img.getWidth()*img.getHeight();
 	int rarr[] = new int[pixcount];
 	int garr[] = new int[pixcount];
 	int barr[] = new int[pixcount];
 	int counts[] = new int[pixcount];
-	for (int i=0; i < pixcount; i++)
-	    {
-		rarr[i] = 0;
-		garr[i] = 0;
-		barr[i] = 0;
-		counts[i] = 0;
-	    }
+	for (int i=0; i < pixcount; i++) {
+	    rarr[i] = 0;
+	    garr[i] = 0;
+	    barr[i] = 0;
+	    counts[i] = 0;
+	}
 
 	// Draw SketchINTS
-	for (int i=0; i<sketchStack.size(); i++)
-	    {
-		VisualObjectInfo vinfo = (VisualObjectInfo)sketchStack.elementAt(i);
-		if (vinfo.getVisible()) {
-		    if (vinfo instanceof SketchInfo && !((SketchInfo)vinfo).isSketchBool()) {
-			((SketchInfo)vinfo).renderToArrays(rarr,garr,barr,counts);
-		    }
-		} else {
-		    sketchStack.removeElementAt(i--);
+	for (int i=0; i<sketchStack.size(); i++) {
+	    SketchOrShapeInfo vinfo = (SketchOrShapeInfo)sketchStack.elementAt(i);
+	    if (vinfo.getVisible()) {
+		if (vinfo instanceof SketchInfo && ((SketchInfo)vinfo).getSketchType() != SketchInfo.SKETCH_BOOL_TYPE) {
+		    ((SketchInfo)vinfo).renderToArrays(rarr,garr,barr,counts);
 		}
+	    } else {
+		sketchStack.removeElementAt(i--);
 	    }
-
-	for (int y=0; y<img.getHeight(); y++)
-	    {
-		for (int x=0; x<img.getWidth(); x++)
-		    {
-			int pos = y*img.getWidth()+x;
-			if (counts[pos] > 0)
-			    {
-				g.setColor(new Color(rarr[pos]/counts[pos],
-						     garr[pos]/counts[pos],
-						     barr[pos]/counts[pos]));
-				g.drawLine(x,y,x,y);
-			    }
-		    }
+	}
+	
+	for (int y=0; y<img.getHeight(); y++) {
+	    for (int x=0; x<img.getWidth(); x++) {
+		int pos = y*img.getWidth()+x;
+		if (counts[pos] > 0) {
+		    g.setColor(new Color(rarr[pos]/counts[pos],
+					 garr[pos]/counts[pos],
+					 barr[pos]/counts[pos]));
+		    g.drawLine(x,y,x,y);
+		}
 	    }
-
-
+	}
+	
 	// Draw SketchBOOLs
-	for (int i=0; i < img.getWidth()*img.getHeight(); i++)
-	    {
-		rarr[i] = 0;
-		garr[i] = 0;
-		barr[i] = 0;
-		counts[i] = 0;
-	    }
+	for (int i=0; i < img.getWidth()*img.getHeight(); i++) {
+	    rarr[i] = 0;
+	    garr[i] = 0;
+	    barr[i] = 0;
+	    counts[i] = 0;
+	}
 
-	for (int i=0; i<sketchStack.size(); i++)
-	    {
-		VisualObjectInfo vinfo = (VisualObjectInfo)sketchStack.elementAt(i);
-		if (vinfo.getVisible())
-		    {
-			if (vinfo instanceof SketchInfo && ((SketchInfo)vinfo).isSketchBool())
-			    {
-				((SketchInfo)vinfo).renderToArrays(rarr,garr,barr,counts);
-			    }
-		    }
-		else
-		    {
-			sketchStack.removeElementAt(i--);
- 		    }
+	for (int i=0; i<sketchStack.size(); i++) {
+	    SketchOrShapeInfo vinfo = (SketchOrShapeInfo)sketchStack.elementAt(i);
+	    if (vinfo.getVisible()) {
+		if (vinfo instanceof SketchInfo && ((SketchInfo)vinfo).getSketchType() == SketchInfo.SKETCH_BOOL_TYPE) {
+		    ((SketchInfo)vinfo).renderToArrays(rarr,garr,barr,counts);
+		}
 	    }
-
-	for (int y=0; y<img.getHeight(); y++)
-	    {
-		for (int x=0; x<img.getWidth(); x++)
-		    {
-			int pos = y*img.getWidth()+x;
-			if (counts[pos] > 0)
-			    {
-				g.setColor(new Color(rarr[pos]/counts[pos],
-						     garr[pos]/counts[pos],
-						     barr[pos]/counts[pos]));
-				g.drawLine(x,y,x,y);
-			    }
-		    }
+	    else {
+		sketchStack.removeElementAt(i--);
 	    }
-
+	}
+	
+	for (int y=0; y<img.getHeight(); y++) {
+	    for (int x=0; x<img.getWidth(); x++) {
+		int pos = y*img.getWidth()+x;
+		if (counts[pos] > 0) {
+		    g.setColor(new Color(rarr[pos]/counts[pos],
+					 garr[pos]/counts[pos],
+					 barr[pos]/counts[pos]));
+		    g.drawLine(x,y,x,y);
+		}
+	    }
+	}
+	
 	imageNeedsUpdate = false;
-
-	//renderSelectedInTree(img.createGraphics());
     }
 
     public void setCurrentSketchPanel(SketchPanel s, TreePath[] paths)
     {
-	if (curSketchPanel != s)
-	    {
-		curSketchPanel.loseFocus();
-	    }
+	if (curSketchPanel != s) {
+	    curSketchPanel.loseFocus();
+	    focusJustChanged = true;
+	}
 	curSketchPanel = s;
-	if (sketchTree != null)
-	    {
-		sketchTree.setSelectionPaths(paths);
-	    }
+	if (sketchTree != null) {
+	    sketchTree.setSelectionPaths(paths);
+	}
+	
     }
 
 
-	private class SketchTreeRenderer extends DefaultTreeCellRenderer {
-		public SketchTreeRenderer(/*Icon icon*/) {
-//			tutorialIcon = icon;
-		}
-
-		public Component getTreeCellRendererComponent(
-				JTree tree,
-				Object value,
-				boolean sel,
-				boolean expanded,
-				boolean leaf,
-				int row,
-				boolean hasFocus) {
-			super.getTreeCellRendererComponent(
-					tree, value, sel,
-					expanded, leaf, row,
-					hasFocus);
-			try {
-			VisualObjectInfo vinfo = (VisualObjectInfo)(((DefaultMutableTreeNode)value).getUserObject());
-			
-			setIcon(vinfo.getIcon());
-			setToolTipText(vinfo.toString());
-			} catch (ClassCastException e) {}
-
-			return this;
-		}
+    private class SketchTreeRenderer extends DefaultTreeCellRenderer {
+	public SketchTreeRenderer(/*Icon icon*/) {
+	    //tutorialIcon = icon;
+	}
+	
+	public Component getTreeCellRendererComponent(JTree tree,
+						      Object value,
+						      boolean sel,
+						      boolean expanded,
+						      boolean leaf,
+						      int row,
+						      boolean hasFocus) {
+	    super.getTreeCellRendererComponent(tree, value, sel,
+					       expanded, leaf, row,
+					       hasFocus);
+	    try {
+		SketchOrShapeInfo vinfo = (SketchOrShapeInfo)(((DefaultMutableTreeNode)value).getUserObject());
+		
+		setIcon(vinfo.getIcon());
+		setToolTipText(vinfo.toString());
+	    } catch (ClassCastException e) {}
+	    
+	    return this;
 	}
+    }
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/SketchInfo.java ./tools/mon/org/tekkotsu/sketch/SketchInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/SketchInfo.java	2005-06-19 08:56:21.000000000 -0400
+++ ./tools/mon/org/tekkotsu/sketch/SketchInfo.java	2006-02-20 18:43:32.000000000 -0500
@@ -11,143 +11,132 @@
 import java.awt.Graphics;
 
 // stores info for a Sketch, to use as UserObject for DefaultMutableTreeNode
-public class SketchInfo extends VisualObjectInfo {
-    static Icon icon = new ImageIcon("org/tekkotsu/mon/icons/sketch.png");
-    static Icon inverted_icon = new ImageIcon("org/tekkotsu/mon/icons/sketchinv.png");;
+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 int_icon = new ImageIcon("org/tekkotsu/mon/icons/sketchint.png");
-    static Icon inverted_int_icon = new ImageIcon("org/tekkotsu/mon/icons/sketchintinv.png");
+    static Icon int_icon = new ImageIcon(icon_path+"sketchint.png");
+    static Icon inverted_int_icon = new ImageIcon(icon_path+"sketchintinv.png");
 
 
-    public static final int SKETCH_INT_TYPE   = 1;
-    public static final int SKETCH_BOOL_TYPE  = 2;
-    public static final int SKETCH_FLOAT_TYPE = 3;
+    public static final int SKETCH_BOOL_TYPE  = 1;
+    public static final int SKETCH_UCHAR_TYPE  = 2;
+    public static final int SKETCH_USINT_TYPE   = 3;
+    public static final int SKETCH_FLOAT_TYPE = 4;
     
 
+    public static final int COLORMAP_SEG_TYPE = 0;
+    public static final int COLORMAP_GRAY_TYPE = 1;
+    public static final int COLORMAP_JET_TYPE = 2;
+    public static final int COLORMAP_JET_SCALED_TYPE = 3;
+
     boolean imageLoaded;
     BufferedImage img;
-    boolean isSketchBool;
-    int grayColor;
+    int sketchType;
+    int grayColor = Color.GRAY.getRGB();
+    int colormap;
+    int width;
+    int height;
 
-    public SketchInfo(int _id, int _parentId, String _name, 
-		      Color _color, int sketchType) {
+
+    int jetred[]; 
+    int jetgreen[];
+    int jetblue[];
+
+    float grayMax, grayMin;
+
+
+    public SketchInfo(int _id, int _parentId, String _name, Color _color, 
+		      int _colormap, int _sketchType, int _width, int _height) {
 	super(_id, _parentId, _name, _color);
+	colormap = _colormap;
+	width = _width;
+	height = _height;
 	imageLoaded = false;
 	img = null;
-	isSketchBool = true;
-	if (sketchType == SKETCH_INT_TYPE)
-	    {
-		isSketchBool = false;
-	    }
-	else if (sketchType == SKETCH_FLOAT_TYPE)
-	    {
-		System.out.println("Warning, got a SketchFloat, treating it like a SketchInt");
-		isSketchBool = false;
-	    }
+	sketchType = _sketchType;
+
+	if (sketchType == SKETCH_FLOAT_TYPE)
+	    System.out.println("Warning, got a SketchFloat, treating it like a SketchUsint");
+	makeJetMap();
     }
     
     public Icon getIcon() { 
-	if (inverted)
-	    {
-		if (isSketchBool)
-		    return inverted_icon;
-		else
-		    return inverted_int_icon;
-	    }
-	else
-	    {
-		if (isSketchBool)
-		    return icon;
-		else
-		    return int_icon;
-	    }
+	if (inverted) {
+	    if (sketchType == SKETCH_BOOL_TYPE) return inverted_icon;
+		else return inverted_int_icon;
 	}
+	else {
+	    if (sketchType == SKETCH_BOOL_TYPE) return icon;
+		else return int_icon;
+	}
+    }
 
     public boolean isImageLoaded() { return imageLoaded; }
 
     public BufferedImage getImage() { return img; }
 
-    public void unloadImage()
-    {
+    public int getSketchType() { return sketchType; }
+
+    public void unloadImage() {
 	imageLoaded = false;
 	img = null;
     }
 
-
-    // Deep image copying
+    // 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)
+	if (_img == null) {
+	    System.err.println("Tried to copy a null image");
 	    return;
-	System.out.println("Type = "+_img.getType()+" RGB="+BufferedImage.TYPE_INT_ARGB);
-	img = new BufferedImage(_img.getWidth(), _img.getHeight(), _img.getType(),((IndexColorModel) _img.getColorModel()));
-	img.getRaster().setRect(_img.getRaster());
+	}
 
-	for (int i=0; i<_img.getWidth()*_img.getHeight(); i++)
+	if (colormap == COLORMAP_SEG_TYPE || sketchType == SKETCH_BOOL_TYPE )
 	    {
-		int x = i % _img.getWidth();
-		int y = i / _img.getWidth();
+		System.out.println("Type = "+_img.getType()+" RGB="+BufferedImage.TYPE_INT_ARGB);
+		img = new BufferedImage(_img.getWidth(), _img.getHeight(), 
+					_img.getType(),((IndexColorModel) _img.getColorModel()));
+		img.getRaster().setRect(_img.getRaster());
 
-		// Count the colors
-		if (!colortable.containsKey(new Integer(_img.getRGB(x,y))))
-		{
-		    System.out.println("Color found: "+new Color(_img.getRGB(x,y)));
-		    colortable.put(new Integer(_img.getRGB(x,y)),new Integer(_img.getRGB(x,y)));
-		    if (++colorCount > 2)
-			{
-			    isSketchBool = false;
-			    break;
-			}
-		}
-		
-		if (lookingForGray && _img.getRGB(x,y) == Color.GRAY.getRGB())
+	    }
+	else
+	    {
+		img = new BufferedImage(_img.getWidth(), _img.getHeight(), BufferedImage.TYPE_USHORT_GRAY);
+		grayMax = -Float.MAX_VALUE;
+		grayMin = Float.MAX_VALUE;
+
+		for (int i=0; i<_img.getWidth()*_img.getHeight(); i++)
 		    {
-			grayColor = img.getRGB(x,y);
-			lookingForGray = false; 
+			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);
+			if (cur > grayMax) 
+			    grayMax = cur;
+			if (cur < grayMin)
+			    grayMin = cur;
 		    }
-	    
-		/*if (!newttable.containsKey(new Integer(img.getRGB(x,y))))
-		{
-		    System.out.println("New Color found: "+new Color(img.getRGB(x,y)));
-		    newttable.put(new Integer(img.getRGB(x,y)),new Integer(img.getRGB(x,y)));
-		    }*/
+		System.out.println("Grayscale image: "+img.getType()+" "+colormap+" ("+
+				   grayMin+","+grayMax+")");
+		if (grayMax == grayMin) {
+		    grayMax++;
+		}
+
+
+		//img.getRaster().setRect(_img.getRaster());
 	    }
 	imageLoaded = true;
     }
 
-    public boolean isSketchBool() { return isSketchBool; }
-
-    public void renderTo(Graphics2D g)
+    // The RenderTo function is an artifact of the old way sketches 
+    // were rendered and is no longer called. 
+    /*public void renderTo(Graphics2D g)
     {
-	if (inverted)
-	    System.out.print("Inverted ");
-	System.out.println("Sketch rendering");
-	if (img != null)
-	    {
-		g.setColor(getColor());
-		for (int x = 0; x<img.getWidth(); x++)
-		    {
-			for (int y=0; y< img.getHeight(); y++)
-			    {
-				int cur = img.getRGB(x,y);
-				if (cur != grayColor)
-				    {
-					if (isSketchBool)
-					    g.drawLine(x,y,x,y);
-					else
-					{
-					    g.setColor(new Color(cur));
-					    g.drawLine(x,y,x,y);
-					}
-				    }
-			    }
-		    }
-	    }
-    }
+    }*/
 
 
     public void renderToArrays(int r[], int g[], int b[], int counts[])
@@ -155,40 +144,102 @@
 	int curR = getColor().getRed();
 	int curG = getColor().getGreen();
 	int curB = getColor().getBlue();
-	if (img!= null)
-	    {
-		for (int y=0; y< img.getHeight(); y++)
-		    {
-			for (int x = 0; x<img.getWidth(); x++)
-			    {
-				int pos = y*img.getWidth()+x;
-				int cur = img.getRGB(x,y);
-				if (cur != grayColor)
-				    {
-					if (!isSketchBool)
-					    {
-						Color c = new Color(cur);
-						curR = c.getRed();
-						curG = c.getGreen();
-						curB = c.getBlue();
-						if (inverted)
-						    {
-							curR = 255 - curR;
-							curG = 255 - curG;
-							curB = 255 - curB;
-						    }
-					    }
-					
-					r[pos] += curR;
-					g[pos] += curG;
-					b[pos] += curB;
-					counts[pos]++;
-				    }
+	if (img!= null) {
+	    for (int y = 0; y < img.getHeight(); y++) {
+		for (int x = 0; x < img.getWidth(); x++) {
+		    int pos = y*img.getWidth()+x;
+		    int cur = img.getRGB(x,y);
+		    if (colormap == COLORMAP_SEG_TYPE || sketchType == SKETCH_BOOL_TYPE) {
+			if (cur != grayColor) {
+			    if (sketchType != SKETCH_BOOL_TYPE) {
+				Color c = new Color(cur);
+				curR = c.getRed();
+				curG = c.getGreen();
+				curB = c.getBlue();
+				if (inverted) {
+				    curR = 255 - curR;
+				    curG = 255 - curG;
+				    curB = 255 - curB;
+				}
 			    }
+			    
+			    r[pos] += curR;
+			    g[pos] += curG;
+			    b[pos] += curB;
+			    counts[pos]++;
+			}
+		    }
+		    else if (colormap == COLORMAP_GRAY_TYPE) {
+			cur = img.getRaster().getSample(x,y,0);
+			if (cur>255) cur = 255;
+			else if (cur<0) cur = 0;
+			if (inverted)
+			    cur = 255 - cur;
+			r[pos]+=cur;
+			g[pos]+=cur;
+			b[pos]+=cur;
+			counts[pos]++;
+		    }
+		    else if (colormap == COLORMAP_JET_TYPE || 
+			     colormap == COLORMAP_JET_SCALED_TYPE) {
+			cur = img.getRaster().getSample(x,y,0);
+			if (colormap == COLORMAP_JET_SCALED_TYPE) {
+			    cur = (int)Math.ceil((cur - grayMin)*255/(grayMax - grayMin));
+			}
+			else {
+			    if (cur > 255) cur = 255;
+			    else if (cur < 0) cur = 0;
+			}
+			if (inverted)
+			    cur = 255 - cur;
+			r[pos]+=jetred[cur];
+			g[pos]+=jetgreen[cur];
+			b[pos]+=jetblue[cur];
+			counts[pos]++;
 		    }
+		}
 	    }
-   }
+	}
+    }
 
+    public void makeJetMap()
+    {
+
+	jetred = new int[256];
+	jetgreen = new int[256];
+	jetblue = new int[256];
+
+	for (int i=0;i<256; i++) {
+	    if (i < 32)
+		jetgreen[i] = 0;
+	    else if (i < 96)
+		jetgreen[i] = (i-32)*4;
+	    else if (i <= 160)
+		jetgreen[i] = 255;
+	    else if (i < 224)
+		jetgreen[i] = (224-i)*4;
+	    else
+		jetgreen[i] = 0;
+	}
+
+	for (int i=0; i<256; i++) {
+	    if (i < 192)
+		jetblue[i] = jetgreen[i+64];
+	    else
+		jetblue[i] = 0;
+		
+	    if (i >= 64)
+		jetred[i] = jetgreen[i-64];
+	    else
+		jetred[i] = 0;
+	}
+
+	// manually set color 0 to background gray
+	jetred[0] = 128;
+	jetgreen[0] = 128;
+	jetblue[0] = 128;
+    }
+    
 }
 
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/SketchOrShapeInfo.java ./tools/mon/org/tekkotsu/sketch/SketchOrShapeInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/SketchOrShapeInfo.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/org/tekkotsu/sketch/SketchOrShapeInfo.java	2006-03-02 13:28:03.000000000 -0500
@@ -0,0 +1,98 @@
+package org.tekkotsu.sketch;
+
+import java.awt.Graphics2D;
+import java.awt.Graphics;
+import java.awt.Color;
+import javax.swing.Icon;
+import javax.swing.ImageIcon;
+import java.awt.PopupMenu;
+
+import java.awt.Rectangle;
+import java.awt.geom.*;
+
+// SketchOrShapeInfo is the parent class for SketchInfo and ShapeInfo
+
+public class SketchOrShapeInfo {
+    final static String icon_path = "org/tekkotsu/sketch/icons/";
+
+    static Icon icon = new ImageIcon(icon_path+"unknown.png");
+    static Icon inverted_icon = null;
+    int id;
+    int parentId;
+    String name;
+    Color color;
+    boolean isVisible;
+    boolean inverted;
+    int width;
+    int height;
+
+    public SketchOrShapeInfo(int _id, int _parentId, String _name, Color _color){
+	id = _id;
+	parentId = _parentId;
+	name = _name;
+	color = _color;
+    }
+
+    public int getId() { return id; }
+    public int getParentId() { return parentId; }
+    public String getName() { return name; }
+
+    public float getLeft() { return 0; }
+    public float getRight() { return 0; }
+    public float getTop() { return 0; }
+    public float getBottom() { return 0; }
+
+    public Color getColor() 
+    { 
+	if (inverted)
+	    return new Color(255-color.getRed(),
+				 255-color.getGreen(),
+				 255-color.getBlue());
+	else
+	    return color; 
+    }
+
+    public Color getColorInverted()
+    {
+	return new Color(255-color.getRed(),
+			 255-color.getGreen(),
+			 255-color.getBlue());
+    }
+
+    public void setVisible(boolean vis) {
+	isVisible = vis;
+    }
+
+    public boolean getVisible() {
+	return isVisible;
+    }
+    
+    public String toString() {
+	//	return (name + "(id " + id + ", parentId " + parentId + ")");
+	return name + " " + id;
+    }
+
+    public Icon getIcon() { 
+	if (!inverted || inverted_icon == null)
+	    return icon;
+	else
+	    return inverted_icon;
+    }
+
+    public void renderTo(Graphics2D graphics, float scaling) {
+	System.out.println("Rendering "+id);
+    }
+    
+    public void renderTo(Graphics graphics, Rectangle2D.Double r) {}
+
+    public void invert() {
+	inverted = !inverted;
+    }
+
+    public void setInverted(boolean _inverted) {
+	inverted = _inverted;
+    }
+    
+}
+
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/SketchPanel.java ./tools/mon/org/tekkotsu/sketch/SketchPanel.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/SketchPanel.java	2005-08-05 17:26:57.000000000 -0400
+++ ./tools/mon/org/tekkotsu/sketch/SketchPanel.java	2006-04-27 20:15:03.000000000 -0400
@@ -27,6 +27,7 @@
 import java.awt.event.WindowEvent;
 import java.awt.event.WindowFocusListener;
 import java.awt.image.IndexColorModel;
+import java.lang.Enum;
 import java.util.prefs.Preferences;
 import java.io.File;
 import java.io.*;
@@ -39,11 +40,15 @@
      SketchGUI gui; // reference back to owning SketchGUI
      AffineTransform atrans;
      AffineTransform resultAtrans;
-     //     boolean isCam;
-     int space;
 
-    //Vector featureList = null;
-    protected TreePath[] paths;
+     //     int space;      // 1 == cam, 2 == local, 3 == world
+     //     Space space; // enum defined inside VisionPanel
+
+     int imageWidth, imageHeight;
+     float scaling = 1;
+     float offset = 1.2f; // leave 10% of window blank for local and world
+     //Vector featureList = null;
+     protected TreePath[] paths;
 
      boolean drawText;
 
@@ -51,22 +56,28 @@
      Component buttonStrut;
 
      static Preferences prefs;
+     
 
      // coordinate bounds for the view of the SketchPanel
      float leftBound=0, rightBound=176, topBound=0, bottomBound=144;
      
-     //     protected SketchPanel(SketchGUI _gui, VisionListener listener, 
-     //			   boolean _isCam, Preferences _prefs) {
-     protected SketchPanel(SketchGUI _gui, VisionListener listener, 
-     			   int _space, Preferences _prefs) {
+     //     protected SketchPanel(SketchGUI _gui, VisionListener listener, int _space, 
+     protected SketchPanel(SketchGUI _gui, VisionListener listener, SketchGUI.Space _space, 
+			   Preferences _prefs, int _imageWidth, int _imageHeight) {
 	 //	 super(listener, _gui, _isCam);
 	 super(listener, _gui, _space);
 	 gui = _gui;
 	 space = _space;
+	 scaling = 1;
+	 offset = 1.2f;
 	 prefs = _prefs;
 	 drawText = true;
 	 mouseX = -1;
 	 mouseY = -1;
+	 imageWidth = _imageWidth;
+	 imageHeight = _imageHeight;
+	 rightBound = imageWidth;
+	 bottomBound = imageHeight;
     }	
 	
      public void visionUpdated(VisionListener listener) {
@@ -76,15 +87,18 @@
      protected void drawImage(Graphics _g, BufferedImage img, int x, int y, int w, int h) {
 	 Graphics2D g2d = (Graphics2D)_g;
 	 AffineTransform origtrans = g2d.getTransform();
-	 float scaling = 1;
+	 scaling = 1;
 	 // right now sketches start at (0,0) but this will change someday for worldspace
+	 // April '06: x and y are probably always 0 and shouldn't be passed in
 	 int imgLeft = 0; int imgTop = 0;
 	 if (img != null) {
 	     //if(isCam) {
-	     if(space == 1) {
+	     if(space == SketchGUI.Space.cam) {
 		 scaling = java.lang.Math.min(w/(rightBound-leftBound),
 					      h/(bottomBound-topBound));
-		 atrans = new AffineTransform(scaling, 0, 0, scaling, x, y);
+		 atrans = new AffineTransform(scaling, 0, 0, scaling, 
+					      x - leftBound * scaling, 
+					      y - topBound * scaling);
 	     } else {
 		 scaling = java.lang.Math.min(w/(bottomBound-topBound),
 					      h/(rightBound-leftBound));
@@ -93,12 +107,25 @@
 	     }
 	     // System.out.println("SketchPanel::img width/height = "+img.getWidth() + " " + img.getHeight());
 	     // System.out.println("Bounds = "+leftBound+" "+rightBound+" "+topBound+" "+bottomBound);
-	     // System.out.println("SketchPanel::scaling = "+scaling);
+	     //	     System.out.println("SketchPanel::scaling = "+scaling);
 
 	     g2d.transform(atrans);
 	     resultAtrans = atrans;
 	     g2d.drawImage(img,imgLeft,imgTop,img.getWidth(),img.getHeight(),null);
-
+	     // add crosshairs if requested
+	     if (space == SketchGUI.Space.cam && crosshairsEnabled) {
+		 g2d.setXORMode(Color.GRAY);
+		 g2d.setColor(Color.WHITE);
+		 g2d.setStroke(new BasicStroke(1.0f));
+		 g2d.drawLine(imgLeft+img.getWidth()/2,imgTop,imgLeft+img.getWidth()/2,imgLeft+img.getHeight());
+		 g2d.drawLine(imgLeft,imgTop+img.getHeight()/2, imgLeft+img.getWidth(), imgTop+img.getHeight()/2);
+		 /*int tmpx = java.lang.Math.round(leftBound*scaling+x+w*scaling/2);
+		   g2d.drawLine(tmpx,y,tmpx,java.lang.Math.round(y+h*scaling));
+		   int tmpy = java.lang.Math.round(y+h*scaling/2);
+		   g2d.drawLine(x,tmpy,java.lang.Math.round(x+w*scaling),tmpy);*/
+		 g2d.setPaintMode();
+	     }
+	     
 	 } else {
 	     g2d.setColor(getBackground());
 	     g2d.fillRect(x,y,w,h);
@@ -111,16 +138,19 @@
 	 }
 	
 	 // draw the Shapes:
+	 //	 drawFeatures(g2d);
+	 g2d.transform(gui.Tmat);
 	 drawFeatures(g2d);
+	 g2d.transform(gui.TmatInv);
 
-	 // undo the transform so we can write worldspace text that isn't flipped
+	 // undo the transform so we can write world/local space text that isn't flipped
 	 g2d.setTransform(origtrans);
+	 //	 g2d.transform(origtrans);
 
 	 // draw image bounds and mouse coordinates
 	 if (img != null && drawText) {
 	     FontMetrics fmet=g2d.getFontMetrics();
-	     //	     if (isCam) {
-	     if (space == 1) {
+	     if(space == SketchGUI.Space.cam) {
 		 // draw bounds and mouse position in cam coordinates
 		 g2d.setColor(getForeground());
 		 String msg="("+String.valueOf((int)leftBound)+","+String.valueOf((int)topBound)+")";
@@ -150,21 +180,9 @@
 		 if (mouseX >= 0 && mouseY >= 0) {
 		     int worldX = java.lang.Math.round(rightBound-mouseY/scaling);
 		     int worldY = java.lang.Math.round(bottomBound-mouseX/scaling);
-		     g2d.setXORMode(Color.BLUE);
+		     g2d.setColor(Color.BLUE);
 		     g2d.drawString("(" + worldX + "," + worldY + ")", x, y+h-fmet.getDescent());
-		     g2d.setPaintMode();
-		 }
-		 // add crosshairs if requested
-		 if (crosshairsEnabled) {
-		     g2d.setXORMode(Color.GRAY);
-		     g2d.setColor(Color.WHITE);
-		     g2d.setStroke(new BasicStroke(1.0f));
-		     int tmpx = java.lang.Math.round(x+(bottomBound-topBound)*scaling/2);
-		     g2d.drawLine(tmpx,y,tmpx,java.lang.Math.round(y+(rightBound-leftBound)*scaling));
-		     int tmpy = java.lang.Math.round(y+(rightBound-leftBound)*scaling/2);
-		     g2d.drawLine(x,tmpy,java.lang.Math.round(x+(bottomBound-topBound)*scaling),tmpy);
-		     g2d.setPaintMode();
-
+		     g2d.setColor(getForeground());
 		 }
 	     }
 	     if (idEnabled) {
@@ -172,28 +190,59 @@
 		     DefaultMutableTreeNode node = (DefaultMutableTreeNode)(paths[path_i].getLastPathComponent());
 		     if (node == null) break;
 		     
-		     if((node.getUserObject() instanceof VisualObjectInfo)) {
-			 VisualObjectInfo vinfo = (VisualObjectInfo)(node.getUserObject());
+		     if((node.getUserObject() instanceof SketchOrShapeInfo)) {
+			 SketchOrShapeInfo vinfo = (SketchOrShapeInfo)(node.getUserObject());
 			 g2d.setColor(vinfo.getColor());
 			 float[] id_coords = new float[2];
-			 if (vinfo instanceof EllipseShapeInfo) { // id added at the centroid
-			     id_coords[0] = ((EllipseShapeInfo)vinfo).getCentroidX();
-			     id_coords[1] =  ((EllipseShapeInfo)vinfo).getCentroidY();
+			 if (vinfo instanceof ShapeInfo) {
+			     id_coords[0] = ((ShapeInfo)vinfo).getIdX();
+			     id_coords[1] = ((ShapeInfo)vinfo).getIdY();
 			 }
-			 else if (vinfo instanceof SphereShapeInfo) { // id added at the centroid
+			 /*if (vinfo instanceof EllipseShapeInfo) { // draw id at the centroid
+			   id_coords[0] = ((EllipseShapeInfo)vinfo).getCentroidX();
+			   id_coords[1] =  ((EllipseShapeInfo)vinfo).getCentroidY();
+			   }
+			   if (vinfo instanceof PointShapeInfo) { // draw id at the centroid
+			     id_coords[0] = ((PointShapeInfo)vinfo).getCentroidX();
+			     id_coords[1] =  ((PointShapeInfo)vinfo).getCentroidY();
+			 }
+			 else if (vinfo instanceof SphereShapeInfo) { // draw id at the centroid
 			     id_coords[0] = ((SphereShapeInfo)vinfo).getCentroidX();
 			     id_coords[1] =  ((SphereShapeInfo)vinfo).getCentroidY();
 			 }
-			 else if(vinfo instanceof LineShapeInfo) { // id added at the first end point
+			 else if (vinfo instanceof BlobShapeInfo) { // draw id at the centroid
+			     id_coords[0] = ((BlobShapeInfo)vinfo).getCentroidX();
+			     id_coords[1] =  ((BlobShapeInfo)vinfo).getCentroidY();
+			 }
+			 else if(vinfo instanceof LineShapeInfo) { // draw id at the first end point
 			     id_coords[0] = ((LineShapeInfo)vinfo).getE1X();
 			     id_coords[1] = ((LineShapeInfo)vinfo).getE1Y();
 			 }
-			 //if (isCam)
-			 if (space == 1)
-			     atrans.transform(id_coords, 0, id_coords, 0, 1);//chage this, or no id for cam
+			 else if(vinfo instanceof PolygonShapeInfo) { // draw id next to the first vertex
+			     id_coords[0] = ((PolygonShapeInfo)vinfo).getFirstVertex()[0];
+			     id_coords[1] = ((PolygonShapeInfo)vinfo).getFirstVertex()[1];
+			 }
+			 else if(vinfo instanceof BrickShapeInfo) { // draw id at the centroid
+			 id_coords[0] = ((BrickShapeInfo)vinfo).getCentroidX();
+			 id_coords[1] = ((BrickShapeInfo)vinfo).getCentroidY();
+			 }*/
+			     //if (isCam)
+			 //			 g2d.transform(AffineTransform.getScaleInstance(.25,.25));
+			 //			 System.out.print(id_coords[0] + ", " + id_coords[1] + " => ");
+			 gui.Tmat.transform(id_coords, 0, id_coords, 0, 1);
+			 if(space == SketchGUI.Space.cam)
+			     //			 if (space == 1)
+			     atrans.transform(id_coords, 0, id_coords, 0, 1);//change this, or no id for cam
 			 else
 			     atrans.transform(id_coords, 0, id_coords, 0, 1);
+			 //			 System.out.println((int)id_coords[0] + ", " + (int)id_coords[1]);
 			 g2d.drawString(Integer.toString(vinfo.getId()),(int)id_coords[0], (int)id_coords[1]);
+			 /*
+			 try { g2d.transform(gui.Tmat.createInverse());
+			 } catch (java.awt.geom.NoninvertibleTransformException nte) {
+			     System.out.println("Error occured trying to inverse Tmat");
+			 }
+			 */
 		     }
 		     g2d.setPaintMode();
 		 }
@@ -203,7 +252,7 @@
      
      public void makeSketchFrame(SketchPanel sketchPanel, String title)
      {
-	 JFrame sketchFrame = new JFrame(title+" space");
+	 JFrame sketchFrame = new JFrame(title);
 	 Box sketchBox = Box.createVerticalBox();
 	 buttonBox = Box.createHorizontalBox();
 	 buttonBox.setBackground(Color.red);
@@ -225,14 +274,15 @@
 
 	 buttonBox.add(Box.createHorizontalStrut(10));
 	
-	 //Icon xhairIcon = new ImageIcon("org/tekkotsu/sketch/crosshairs.png");
-	 //JCheckBox xhairsBox = new JCheckBox(xhairIcon, true);
-	 JCheckBox xhairsBox = new JCheckBox("Crosshairs", false);
-	 xhairsBox.addActionListener(sketchPanel);
-	 xhairsBox.setActionCommand("xhairs");
-	 xhairsBox.setEnabled(true);
-	 buttonBox.setVisible(windowHasFocus);
-	 buttonBox.add(xhairsBox);
+	 if(space == SketchGUI.Space.cam) {
+		 //	 if (space == 1) { // only show crosshairs for the local model
+	     JCheckBox xhairsBox = new JCheckBox("Crosshairs", false);
+	     xhairsBox.addActionListener(sketchPanel);
+	     xhairsBox.setActionCommand("xhairs");
+	     xhairsBox.setEnabled(true);
+	     buttonBox.setVisible(windowHasFocus);
+	     buttonBox.add(xhairsBox);
+	 }
 
 	 JCheckBox idBox = new JCheckBox("ID", false);
 	 idBox.addActionListener(sketchPanel);
@@ -252,94 +302,92 @@
 	 sketchBox.add(sketchPanel);
 	 sketchFrame.getContentPane().add(sketchBox);
 	 sketchFrame.setCursor(new Cursor(Cursor.CROSSHAIR_CURSOR));
-	 //sketchFrame.getContentPane().add(sketchPanel);
 	 sketchFrame.pack();
-	 //sketchFrame.setLocation(prefs.getInt("SketchPanel.location.x",50),prefs.getInt("SketchPanel.location.y",50));
-	 
 	 sketchFrame.addWindowFocusListener(sketchPanel);
-
 	 sketchFrame.setVisible(true);
      }
 
      public void actionPerformed(ActionEvent e) 
      {
-	 if (e.getActionCommand().compareTo("clone")==0)
-	     {
-		 SketchPanel sketchPanel=new SketchPanel(gui, _listener, space, prefs);
-		 sketchPanel.setMinimumSize(new Dimension(VisionListener.DEFAULT_WIDTH/2, 
-							  VisionListener.DEFAULT_HEIGHT/2));
-		 sketchPanel.setPreferredSize(new Dimension(VisionListener.DEFAULT_WIDTH*2, 
-							    VisionListener.DEFAULT_HEIGHT*2));
-		 sketchPanel.setLockAspectRatio(true);
-		 
-		 //getContentPane().add(sketch,BorderLayout.NORTH);
-		 
-		 sketchPanel.makeSketchFrame(sketchPanel, "Cloned");
-		 
-		 
-		 //BufferedImage newImage = new BufferedImage(_image.getWidth(), _image.getHeight(), _image.getType());
-		 //newImage.createGraphics().drawImage(_image,0,0,null);
-		 
-		 //sketchPanel.imageUpdated(newImage, null);
-		 sketchPanel.imageUpdated(_image,paths);		
-	     } 
-	 else if(e.getActionCommand().compareTo("saveimg")==0) 
-	     {
-		 File cursavepath = new File(prefs.get("cursavepath",""));
-		 JFileChooser dia=new JFileChooser(cursavepath);
-		 dia.setDialogTitle("Save Image...");
-		 Component cur=this;
-		 while(cur.getParent()!=null)
-		     cur=cur.getParent();
-		 if(dia.showSaveDialog(cur)==JFileChooser.APPROVE_OPTION) {
-		     prefs.put("cursavepath",dia.getCurrentDirectory().getPath());
-		     String base=dia.getSelectedFile().getName();
-		     String format;
-		     if(base.lastIndexOf('.')==-1) {
-			 format="png";
-		     } else {
-			 int i=base.lastIndexOf(".");
-			 format=base.substring(i+1);
-			 base=base.substring(0,i);
-		     }
-		     try {
-			 FileOutputStream fileout=new FileOutputStream(dia.getSelectedFile().getParent()+File.separator+base+"."+format);
-			 //ImageIO.write(sketchPanel.getListener().getImage(),format,fileout);
-			 ImageIO.write(getSaveImage(),format,fileout);
-		     } catch(IOException ex) {}
+	 if (e.getActionCommand().compareTo("clone")==0) {
+	     SketchPanel sketchPanel=new SketchPanel(gui, _listener, space, prefs, 
+						     imageWidth, imageHeight);
+	     sketchPanel.setMinimumSize(new Dimension(imageWidth/2, imageHeight/2));
+	     sketchPanel.setPreferredSize(new Dimension(imageWidth*2, imageHeight*2));
+	     sketchPanel.setLockAspectRatio(true);
+	     ++gui.panelCount;
+	     sketchPanel.makeSketchFrame(sketchPanel, 
+					 gui.panelTitle+gui.panelCount+" "+gui.host);
+	     sketchPanel.setBounds(leftBound, rightBound, topBound, bottomBound);
+	     sketchPanel.imageUpdated(_image,paths);		
+	 } 
+	 else if(e.getActionCommand().compareTo("saveimg")==0) {
+	     File cursavepath = new File(prefs.get("cursavepath",""));
+	     JFileChooser dia=new JFileChooser(cursavepath);
+	     dia.setDialogTitle("Save Image...");
+	     Component cur=this;
+	     while(cur.getParent()!=null)
+		 cur=cur.getParent();
+	     if(dia.showSaveDialog(cur)==JFileChooser.APPROVE_OPTION) {
+		 prefs.put("cursavepath",dia.getCurrentDirectory().getPath());
+		 String base=dia.getSelectedFile().getName();
+		 String format;
+		 if(base.lastIndexOf('.')==-1) {
+		     format="png";
+		 } else {
+		     int i=base.lastIndexOf(".");
+		     format=base.substring(i+1);
+		     base=base.substring(0,i);
 		 }
+		 try {
+		     FileOutputStream fileout=new FileOutputStream(dia.getSelectedFile().getParent()+File.separator+base+"."+format);
+		     //ImageIO.write(sketchPanel.getListener().getImage(),format,fileout);
+		     ImageIO.write(getSaveImage(),format,fileout);
+		 } catch(IOException ex) {}
 	     }
-	 else if (e.getActionCommand().compareTo("xhairs") == 0)
-	     {
-		 crosshairsEnabled = ((JCheckBox)(e.getSource())).isSelected();
-		 repaint();
-	     }
-	 else if (e.getActionCommand().compareTo("id") == 0)
-	     {
-		 idEnabled = ((JCheckBox)(e.getSource())).isSelected();
-		 repaint();
-	     }	 
+	 }
+	 else if (e.getActionCommand().compareTo("xhairs") == 0) {
+	     crosshairsEnabled = ((JCheckBox)(e.getSource())).isSelected();
+	     repaint();
+	 }
+	 else if (e.getActionCommand().compareTo("id") == 0) {
+	     idEnabled = ((JCheckBox)(e.getSource())).isSelected();
+	     repaint();
+	 }	 
      }
      
 
 
-	// stretches the view of the SketchPanel to accomodate the specified object 
-	public void scaleToVisualObject(VisualObjectInfo oinfo) {
-	    if(oinfo.getLeft() < leftBound)
-		leftBound = oinfo.getLeft();
-	    if(oinfo.getRight() > rightBound)
-		rightBound = oinfo.getRight();
-	    if(oinfo.getTop() < topBound)
-		topBound = oinfo.getTop();
-	    if(oinfo.getBottom() > bottomBound)
-		bottomBound = oinfo.getBottom();
-	}
+     // stretches the view of the SketchPanel to accomodate the specified object 
+     public void scaleToSketchOrShape(SketchOrShapeInfo oinfo) {
+	 if(space == SketchGUI.Space.cam) {
+	     //	    if (space == 1) {
+	     if(oinfo.getLeft() < leftBound)
+		 leftBound = oinfo.getLeft();
+	     if(oinfo.getRight() > rightBound)
+		 rightBound = oinfo.getRight();
+	     if(oinfo.getTop() < topBound)
+		 topBound = oinfo.getTop();
+	     if(oinfo.getBottom() > bottomBound)
+		 bottomBound = oinfo.getBottom();
+	 }
+	 else {
+	     if(offset*oinfo.getLeft() < leftBound)
+		 leftBound = offset*oinfo.getLeft();
+	     if(offset*oinfo.getRight() > rightBound)
+		 rightBound = offset*oinfo.getRight();
+	     if(offset*oinfo.getTop() < topBound)
+		 topBound = offset*oinfo.getTop();
+	     if(offset*oinfo.getBottom() > bottomBound)
+		 bottomBound = offset*oinfo.getBottom();
+	 }
+     }
 
-    public void imageUpdated(BufferedImage sketchImage, TreePath[] _paths)
+    public void imageUpdated(BufferedImage sketchImage, TreePath[] newPaths)
     {
-		_image = sketchImage;
-		paths = _paths;
-		repaint();
+	_image = sketchImage;
+	paths = newPaths;
+	repaint();
     }
     
      public void loseFocus()
@@ -360,12 +408,17 @@
 	 repaint();
      }
 
+     // Don't use the standard lose focus, because it only actually should lose 
+     // concept of focus when a different sketchpanel gains focus
      public void windowLostFocus(WindowEvent e) {}
 
      public BufferedImage getSaveImage() {
 	 int width=0, height=0;
 	 //if (isCam) {
-	 if (space==1) {
+	 System.out.println("space= " + space);
+	 //	 if(space == SketchGUI.Space.cam) {
+	 if(space == SketchGUI.Space.cam) {
+	     //	 if (space==1) {
 	     width = (int)(rightBound-leftBound);
 	     height = (int)(bottomBound-topBound);
 	 } else {
@@ -381,30 +434,38 @@
 	 g.setColor(Color.WHITE);
 	 g.fillRect(0,0,width,height);
 	 drawImage(g,_image,0,0,width,height);
-	 drawFeatures((Graphics2D)g);
+	 //	 drawFeatures((Graphics2D)g);
 	 crosshairsEnabled = oldxhairs;
 	 drawText = olddrawtext;
 	 return saveimg;
      }
 
      public void drawFeatures(Graphics2D g)
-    {
-	if (paths == null) return;
+     {
+	 if (paths == null) return;
+	 
+	 for (int path_i = 0; path_i < paths.length; path_i++) {
+	     DefaultMutableTreeNode node = (DefaultMutableTreeNode)(paths[path_i].getLastPathComponent());
+	     if (node == null) return;
+	    
+	     // check for dummy node; it's used for "camspace" or "worldspace" folder
+	     if((node.getUserObject() instanceof SketchOrShapeInfo)) {
+		 SketchOrShapeInfo vinfo = (SketchOrShapeInfo)(node.getUserObject());
+		 if (vinfo instanceof ShapeInfo) {
+		     g.setColor(vinfo.getColor());
+		     vinfo.renderTo(g, scaling);
+		 }
+	     }
+	 }
+     }
 
-	for (int path_i = 0; path_i < paths.length; path_i++) 
-	    {
-		DefaultMutableTreeNode node = (DefaultMutableTreeNode)(paths[path_i].getLastPathComponent());
-		if (node == null) return;
 
-		// check for dummy node; it's used for "camspace" or "worldspace" folder
-		if((node.getUserObject() instanceof VisualObjectInfo)) {
-		    VisualObjectInfo vinfo = (VisualObjectInfo)(node.getUserObject());
-		    if (vinfo instanceof ShapeInfo)
-			{
-			    g.setColor(vinfo.getColor());
-			    vinfo.renderTo(g);
-			}
-		}
-	    }
-    }
+
+     public void setBounds(float newLeft, float newRight, float newTop, float newBottom)
+     {
+	 leftBound = newLeft;
+	 rightBound = newRight;
+	 topBound = newTop;
+	 bottomBound = newBottom;
+     }
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/SphereShapeInfo.java ./tools/mon/org/tekkotsu/sketch/SphereShapeInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/SphereShapeInfo.java	2005-08-05 21:04:58.000000000 -0400
+++ ./tools/mon/org/tekkotsu/sketch/SphereShapeInfo.java	2006-03-02 13:28:03.000000000 -0500
@@ -13,17 +13,15 @@
 // stores info for a EllipseShape
 // note that ellipse center is same as centroid
 public class SphereShapeInfo extends ShapeInfo {
-    static Icon icon = new ImageIcon("org/tekkotsu/mon/icons/ellipse.png");
-    static Icon inv_icon = new ImageIcon("org/tekkotsu/mon/icons/ellipseinv.png");
+    static Icon icon = new ImageIcon("org/tekkotsu/sketch/icons/ellipse.png");
+    static Icon inv_icon = new ImageIcon("org/tekkotsu/sketch/icons/ellipseinv.png");
     float radius; // length of semimajor axes
-    int id;
 
-	public SphereShapeInfo(int _id, int _parentId, String _name, Color _color,
+    public SphereShapeInfo(int _id, int _parentId, String _name, Color _color,
 			float _centroidx, float _centroidy, float _centroidz,
 			float _radius) {
 		super(_id, _parentId, _name, _color, _centroidx, _centroidy, _centroidz);
 		radius = _radius;
-		id = _id;
 	}
 
 	// returns left-most coordinate of object
@@ -47,7 +45,7 @@
 	    return icon; 
 	}
 
-    public void renderTo(Graphics2D graphics) {
+    public void renderTo(Graphics2D graphics, float scaling) {
 	graphics.setStroke(new BasicStroke(1.0f));
 	graphics.drawOval((int)(getCentroidX()-radius+1), 
 			  (int)(getCentroidY()-radius+1),
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/VisualObjectInfo.java ./tools/mon/org/tekkotsu/sketch/VisualObjectInfo.java
--- ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/VisualObjectInfo.java	2005-05-23 02:27:18.000000000 -0400
+++ ./tools/mon/org/tekkotsu/sketch/VisualObjectInfo.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,94 +0,0 @@
-package org.tekkotsu.sketch;
-
-import java.awt.Graphics2D;
-import java.awt.Graphics;
-import java.awt.Color;
-import javax.swing.Icon;
-import javax.swing.ImageIcon;
-import java.awt.PopupMenu;
-
-import java.awt.Rectangle;
-import java.awt.geom.*;
-
-// stores info for a VisualObject
-
-public class VisualObjectInfo {
-    static Icon icon = new ImageIcon("org/tekkotsu/mon/icons/unknown.png");
-    static Icon inverted_icon = null;
-    int id;
-    int parentId;
-    String name;
-    Color color;
-    boolean isVisible;
-    boolean inverted;
-
-	public VisualObjectInfo(int _id, int _parentId, String _name, 
-				Color _color){
-		id = _id;
-		parentId = _parentId;
-		name = _name;
-		color = _color;
-	}
-
-	public int getId() { return id; }
-	public int getParentId() { return parentId; }
-	public String getName() { return name; }
-
-	public float getLeft() { return 0; }
-	public float getRight() { return 176; }
-	public float getTop() { return 0; }
-	public float getBottom() { return 144; }
-
-    public Color getColor() 
-    { 
-	if (inverted)
-	    return new Color(255-color.getRed(),
-				 255-color.getGreen(),
-				 255-color.getBlue());
-	else
-	    return color; 
-    }
-
-    public Color getColorInverted()
-    {
-	return new Color(255-color.getRed(),
-			 255-color.getGreen(),
-			 255-color.getBlue());
-    }
-
-    public void setVisible(boolean vis) {
-	isVisible = vis;
-    }
-
-    public boolean getVisible() {
-	return isVisible;
-    }
-    
-    public String toString() {
-	return (name + "(id " + id + ", parentId " + parentId + ")");
-    }
-
-    public Icon getIcon() { 
-	if (!inverted || inverted_icon == null)
-	    return icon;
-	else
-	    return inverted_icon;
-    }
-
-    public void renderTo(Graphics2D graphics) {
-	System.out.println("Rendering "+id);
-    }
-    
-    public void renderTo(Graphics graphics, Rectangle2D.Double r) {}
-
-    public void invert() {
-	inverted = !inverted;
-    }
-
-    public void setInverted(boolean _inverted) {
-	inverted = _inverted;
-    }
-    
-}
-
-
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/agent.png and ./tools/mon/org/tekkotsu/sketch/icons/agent.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/blob.png and ./tools/mon/org/tekkotsu/sketch/icons/blob.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/blobinv.png and ./tools/mon/org/tekkotsu/sketch/icons/blobinv.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/brick.png and ./tools/mon/org/tekkotsu/sketch/icons/brick.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/brickinv.png and ./tools/mon/org/tekkotsu/sketch/icons/brickinv.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/ellipse.png and ./tools/mon/org/tekkotsu/sketch/icons/ellipse.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/ellipseinv.png and ./tools/mon/org/tekkotsu/sketch/icons/ellipseinv.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/line.png and ./tools/mon/org/tekkotsu/sketch/icons/line.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/lineinv.png and ./tools/mon/org/tekkotsu/sketch/icons/lineinv.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/point.png and ./tools/mon/org/tekkotsu/sketch/icons/point.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/pointinv.png and ./tools/mon/org/tekkotsu/sketch/icons/pointinv.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/poly.png and ./tools/mon/org/tekkotsu/sketch/icons/poly.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/polyinv.png and ./tools/mon/org/tekkotsu/sketch/icons/polyinv.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/pyramid.png and ./tools/mon/org/tekkotsu/sketch/icons/pyramid.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/pyramidinv.png and ./tools/mon/org/tekkotsu/sketch/icons/pyramidinv.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/sketch.png and ./tools/mon/org/tekkotsu/sketch/icons/sketch.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/sketchint.png and ./tools/mon/org/tekkotsu/sketch/icons/sketchint.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/sketchintinv.png and ./tools/mon/org/tekkotsu/sketch/icons/sketchintinv.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/sketchinv.png and ./tools/mon/org/tekkotsu/sketch/icons/sketchinv.png differ
Binary files ../Tekkotsu_2.4.1/tools/mon/org/tekkotsu/sketch/icons/unknown.png and ./tools/mon/org/tekkotsu/sketch/icons/unknown.png differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/osx_find_memstick ./tools/osx_find_memstick
--- ../Tekkotsu_2.4.1/tools/osx_find_memstick	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/osx_find_memstick	2006-03-30 19:39:13.000000000 -0500
@@ -0,0 +1,50 @@
+#!/bin/sh
+
+device=`diskutil list | grep DOS_FAT_12 | tail -n 1 | sed -n 's/.* //p'`
+ans=`diskutil info "$device" | sed -n 's/.*Mount Point: *//p'`
+#ans=/Volumes/`diskutil list | grep DOS_FAT_12 | tail -n 1 | sed -n 's/^.*DOS_FAT_12 \(.*\) *[0-9]*.[0-9] MB.*/\1/p' | sed 's/ *[0-9]*$//g'`
+
+if [ -d "$ans" ] ; then
+	echo "$ans";
+	exit 0;
+fi;
+
+echo "warning: Could not determine memory stick mount point:" 1>&2;
+echo "  * if memory stick is not inserted, please insert it now" 1>&2;
+echo "  * if memory stick is inserted, but does not appear in Finder, try re-inserting" 1>&2;
+echo "  * if memory stick is inserted and shown in Finder, but the script is not" 1>&2;
+echo "    continuing, you can manually define MEMSTICK_ROOT in Environment.conf" 1>&2;
+
+#check that we are running in a termincal (not Xcode)
+if stty > /dev/null 2>&1 ; then
+	until [ -d "$ans" ] ; do
+		printf "\\a" > /dev/stderr;
+		sleep 1;
+		device=`diskutil list | grep DOS_FAT_12 | tail -n 1 | sed -n 's/.* //p'`
+		ans=`diskutil info "$device" | sed -n 's/.*Mount Point: *//p'`
+	done;
+else
+	TMPFEEDBACK=/tmp/$USER-osx_find_memstick
+	until [ -d "$ans" ] ; do
+		osascript -l AppleScript > $TMPFEEDBACK 2>&1 << EOF
+tell application "Xcode"
+	activate (beep)
+	show window "Make - Build Results"
+	display dialog "Please insert memory stick" buttons {"Cancel"} with icon 0 default button 1 giving up after 2
+end tell
+EOF
+		if grep -q "canceled" $TMPFEEDBACK ; then
+			echo "error: The user cancelled build" 1>&2;
+			killall make;
+			rm $TMPFEEDBACK;
+			exit 1;
+		fi;
+		rm $TMPFEEDBACK;
+		#osascript -l AppleScript -e beep;
+		#sleep 1;
+		device=`diskutil list | grep DOS_FAT_12 | tail -n 1 | sed -n 's/.* //p'`
+		ans=`diskutil info "$device" | sed -n 's/.*Mount Point: *//p'`
+	done;
+fi
+printf "$ans";
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/safemot/Makefile ./tools/safemot/Makefile
--- ../Tekkotsu_2.4.1/tools/safemot/Makefile	2005-08-09 21:58:36.000000000 -0400
+++ ./tools/safemot/Makefile	2006-03-28 12:08:23.000000000 -0500
@@ -25,7 +25,7 @@
 $(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))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
-include $(TEKKOTSU_ENVIRONMENT_CONFIGURATION)
+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))
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/safemot/safemot.cc ./tools/safemot/safemot.cc
--- ../Tekkotsu_2.4.1/tools/safemot/safemot.cc	2004-11-08 16:48:19.000000000 -0500
+++ ./tools/safemot/safemot.cc	2006-09-09 00:33:07.000000000 -0400
@@ -91,11 +91,11 @@
 				ms.setSaveRadians();
 			else
 				ms.setSaveDegrees();
-			ms.LoadFile(argv[i]);
+			ms.loadFile(argv[i]);
 			ms.makeSafe(MaxOutputSpeed,margin);
 			if(compress)
 				ms.compress();
-			ms.SaveFile(path.c_str());
+			ms.saveFile(path.c_str());
 		}
 		used=argc;
 	} else if(argc-used==2) {
@@ -104,11 +104,11 @@
 			ms.setSaveRadians();
 		else
 			ms.setSaveDegrees();
-		ms.LoadFile(argv[used]);
+		ms.loadFile(argv[used]);
 		ms.makeSafe(MaxOutputSpeed,margin);
 		if(compress)
 			ms.compress();
-		ms.SaveFile(argv[used+1]);
+		ms.saveFile(argv[used+1]);
 		used=argc;
 	} else
 		return usage(argc,argv);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/ClassPathModifier.java ./tools/seg/ClassPathModifier.java
--- ../Tekkotsu_2.4.1/tools/seg/ClassPathModifier.java	2003-07-26 21:55:58.000000000 -0400
+++ ./tools/seg/ClassPathModifier.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,32 +0,0 @@
-import java.lang.*;
-import java.net.*;
-import java.io.*;
-import java.lang.reflect.*;
-
-public class ClassPathModifier {
-  private static final Class[] parameters = new Class[]{URL.class};
-
-  public static void addFile(String s) throws IOException {
-    File f = new File(s);
-    addFile(f);
-  }
-
-  public static void addFile(File f) throws IOException {
-    addURL(f.toURL());
-  }
-
-  public static void addURL(URL u) throws IOException {
-    URLClassLoader sysloader =
-      (URLClassLoader)ClassLoader.getSystemClassLoader();
-
-		Class sysclass = URLClassLoader.class;
-
-    try {
-      Method method = sysclass.getDeclaredMethod("addURL",parameters);
-      method.setAccessible(true);
-      method.invoke(sysloader, new Object[]{ u });
-    } catch (Throwable t) {
-      throw new IOException("could not add "+u+" to classpath");
-		}
-  }
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/ColorControlPanel.java ./tools/seg/ColorControlPanel.java
--- ../Tekkotsu_2.4.1/tools/seg/ColorControlPanel.java	2005-08-09 21:53:10.000000000 -0400
+++ ./tools/seg/ColorControlPanel.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,128 +0,0 @@
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.util.*;
-import java.awt.geom.*;
-import java.io.*;
-
-class ColorControlPanel extends JFrame implements ActionListener,
-    ListSelectionListener {
-  Container root;
-  JTextField colorname;
-  JList colorlist;
-  DefaultListModel list;
-  JScrollPane colorlistscroll;
-  JButton remove, clear, save, imageview, invert;
-  int curcolor;
-
-  TrainCanvas trainCanvas;
-  ImageShow imageShow;
-
-  public ColorControlPanel (TrainCanvas trainCanvas, ImageShow imageShow) {
-    this.trainCanvas=trainCanvas;
-    this.imageShow=imageShow;
-    imageShow.addMouseMotionListener(trainCanvas);
-    imageShow.addMouseListener(trainCanvas);
-
-    setSize(new Dimension (120,350));
-    setLocation(800,50);
-
-    setResizable(false);
-    root=this.getContentPane();
-    root.setLayout(new FlowLayout());
-
-    colorname=new JTextField(10);
-    colorname.addActionListener(this);
-    root.add(colorname);
-
-    list=new DefaultListModel();
-    colorlist=new JList(list);
-    colorlist.setFixedCellWidth(90);
-    colorlist.setSelectionMode(ListSelectionModel.SINGLE_SELECTION);
-    colorlist.addListSelectionListener(this);
-
-    colorlistscroll=new JScrollPane(colorlist,
-                       JScrollPane.VERTICAL_SCROLLBAR_ALWAYS,
-                       JScrollPane.HORIZONTAL_SCROLLBAR_NEVER);
-    root.add(colorlistscroll);
-
-    remove=new JButton("remove");
-    remove.addActionListener(this);
-    root.add(remove);
-
-    clear=new JButton("clear");
-    clear.addActionListener(this);
-    root.add(clear);
-
-    invert=new JButton("invert");
-    invert.addActionListener(this);
-    root.add(invert);
-
-    imageview=new JButton("image view");
-    imageview.addActionListener(this);
-    root.add(imageview);
-
-    save=new JButton("save");
-    save.addActionListener(this);
-    root.add(save);
-
-    setCurColor(-1);
-    show();
-  }
-
-  public void actionPerformed(ActionEvent e) {
-    if (e.getSource()==save) {
-      JFileChooser chooser=new JFileChooser();
-      chooser.setSelectedFile(new File("default.tm"));
-      int returnval=chooser.showSaveDialog(save);
-      if (returnval==JFileChooser.APPROVE_OPTION) {
-        trainCanvas.save(chooser.getSelectedFile().getAbsolutePath());
-      }
-    } else if (e.getSource()==clear) {
-      trainCanvas.clear();
-    } else if (e.getSource()==invert) {
-      trainCanvas.invert();
-    } else if (e.getSource()==remove) {
-      trainCanvas.remove((String)list.get(curcolor));
-      list.remove(curcolor);
-      setCurColor(-1);
-    } else if (e.getSource()==imageview) {
-      imageShow.show();
-    } else if (e.getSource()==colorname) {
-      String s=e.getActionCommand();
-      if (!s.equals("")) {
-        int i=0;
-        while (i<list.getSize() && !list.get(i).equals(s)) {
-          i++;
-        }
-        if (i==list.getSize()) {
-          list.addElement(s);
-          colorname.setText("");
-          colorlist.setSelectedIndex(i);
-        }
-      }
-    }
-  }
-
-  public void valueChanged(ListSelectionEvent e) {
-    if (!e.getValueIsAdjusting()) {
-      setCurColor(colorlist.getSelectedIndex());
-    }
-  }
-
-  void setCurColor(int index) {
-    curcolor=index;
-
-    if (index<0) {
-      remove.setEnabled(false);
-      clear.setEnabled(false);
-      trainCanvas.setCurColor(null);
-    } else {
-      remove.setEnabled(true);
-      clear.setEnabled(true);
-      trainCanvas.setCurColor((String)list.get(curcolor));
-    }
-  }
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/ColorConverter.java ./tools/seg/ColorConverter.java
--- ../Tekkotsu_2.4.1/tools/seg/ColorConverter.java	2003-07-26 21:55:59.000000000 -0400
+++ ./tools/seg/ColorConverter.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,10 +0,0 @@
-public abstract class ColorConverter {
-  ColorConverter() { }
-  public final float[] getColor(int rgb) {
-    int r=(rgb>>16)&0xff;
-    int g=(rgb>>8)&0xff;
-    int b=rgb&0xff;
-    return getColor(r, g, b);
-  }
-  public abstract float[] getColor(int r, int g, int b);
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/DogConfig.java ./tools/seg/DogConfig.java
--- ../Tekkotsu_2.4.1/tools/seg/DogConfig.java	2003-07-26 21:55:59.000000000 -0400
+++ ./tools/seg/DogConfig.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,185 +0,0 @@
-import java.util.*;
-import java.io.*;
-import java.lang.*;
-
-public class DogConfig {
-  List IPs;
-  String IP;
-  Hashtable config;
-
-  public static void main(String args[]) {
-    try {
-      DogConfig config=new DogConfig(args);
-    } catch (IllegalArgumentException ex) { }
-  }
-
-  void usage() {
-    System.out.println("java DogConfig Internet_Address");
-  }
-
-  public DogConfig(String args[]) {
-    try { ClassPathModifier.addFile("ftp.jar"); }
-    catch (Exception ex) { System.out.println(ex); System.exit(1); }
-
-    for (int i=0; i<args.length; i++) {
-      if (args[i].charAt(0)=='-') {
-        System.out.println(args[i] + "is not a valid internet address");
-        throw new IllegalArgumentException();
-      }
-    }
-
-    readConfig();
-    for (int i=0; i<args.length; i++) {
-      if (tryIP(args[i])) {
-        IP=args[i];
-        break;
-      }
-    }
-
-    if (IP==null) {
-      for (ListIterator iter = IPs.listIterator(); iter.hasNext(); ) {
-        String cline=(String)iter.next();
-        int clength=cline.length();
-        if (clength!=0 && cline.charAt(0)!='#') {
-          if (tryIP(cline)) {
-            IP=cline;
-            break;
-          }
-        }
-      }
-    } else {
-      int insertpos=0;
-      boolean ipbegun=false;
-
-      for (ListIterator iter = IPs.listIterator(); iter.hasNext(); ) {
-        String cline=(String)iter.next();
-        int clength=cline.length();
-
-        if (clength!=0 && cline.charAt(0)!='#') ipbegun=true;
-        else if (!ipbegun) insertpos++;
-
-        if (cline.compareToIgnoreCase(IP)==0) {
-          insertpos=-1;
-          break;
-        }
-      }
-      
-      if (insertpos>=0) {
-        IPs.add(insertpos,IP); 
-        writeConfig();
-      }
-    }
-  
-    if (IP==null) {
-      System.out.println("Dog not found; please switch on dog or specify" +
-                         " correct IP address");
-      throw new IllegalArgumentException();
-      // pop up dialog box asking for IP address?
-    }
-  }
-
-  boolean tryIP(String ip) {
-    DogConfigFTP dog_ftp=new DogConfigFTP(ip, 21, "config", "config");
-    System.out.print("Trying "+ip+" ... ");
-    System.out.flush();
-    if (dog_ftp.test()) {
-      System.out.println("found");
-      try {
-        readAiboConfig(dog_ftp.getFile("tekkotsu.cfg"));
-        return true;
-      } catch (Exception ex) {
-        System.out.println("ftp error: "+ ex);
-      }
-    } else {
-      System.out.println("not found");
-    }
-    return false;
-  }
-
-  public DogConfig() {
-    this(new String[]{});
-  }
-
-  public DogConfig(String s) {
-    this(new String[]{s});
-  }
-
-  public String getIP() {
-    return IP;
-  }
-
-  void readAiboConfig(String conf) {
-    String[] lines=conf.split("[\r\n]");
-    config=new Hashtable();
-    Hashtable current=config;
-
-    for (int i=0; i<lines.length; i++) {
-      String cline=lines[i];
-      int clength=cline.length();
-      if (clength!=0 && cline.charAt(0)!='#') {
-        if (cline.charAt(0)=='[' && cline.charAt(clength-1)==']') {
-          String category=cline.substring(1,clength-1);
-          current=new Hashtable();
-          config.put(category, current);
-        } else {
-          int ind=cline.indexOf('=');
-          if (ind<0) {
-            System.out.println("warning: line "+(i+1)+" ignored");
-            System.out.println("       > "+cline);
-          } else {
-            String key=cline.substring(0,ind);
-            String value=cline.substring(ind+1,clength);
-            current.put(key, value);
-          }
-        }
-      }
-    }
-  }
-
-  public String getValue(String section, String key) {
-    Hashtable sectionhash=(Hashtable)config.get(section);
-    if (sectionhash!=null)
-      return (String)sectionhash.get(key);
-    return null;
-  }
-
-  File configFile() {
-    String homedir="";
-    try { homedir=System.getProperty("user.home"); } catch (Exception ex) {}
-    return new File(homedir, ".aibo_ip");
-  }
-
-  void readConfig() {
-    IPs=new ArrayList(10);
-    try {
-      BufferedReader in = new BufferedReader
-        ( new FileReader (configFile()) );
-      String curLine=in.readLine();
-      while (curLine!=null) {
-        IPs.add(curLine);
-        curLine=in.readLine();
-      }
-      in.close();
-    } catch (FileNotFoundException ex) {
-      // we just start off with 0 IPs
-      // also creating a new file, so add an intro comment
-      IPs.add("# Ordered list of IPs to be used by Tekkotsu tools\n");
-    } catch (IOException ex) {
-      // we read what we could
-    }
-    // no real need for parsing and verifying correctness of IPs
-  }
-
-  void writeConfig() {
-    try {
-      PrintWriter out = new PrintWriter ( new BufferedWriter (
-            new FileWriter (configFile())));
-      for (ListIterator iter = IPs.listIterator(); iter.hasNext(); ) {
-        out.println(iter.next());
-      }
-      out.close();
-    } catch (IOException ex) {
-      // can't do much about it
-    }
-  }
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/DogConfigFTP.java ./tools/seg/DogConfigFTP.java
--- ../Tekkotsu_2.4.1/tools/seg/DogConfigFTP.java	2003-10-09 02:29:39.000000000 -0400
+++ ./tools/seg/DogConfigFTP.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,78 +0,0 @@
-import com.enterprisedt.net.ftp.*;
-import java.util.*;
-import java.net.*;
-import java.io.*;
-
-public class DogConfigFTP {
-  String _ip;
-  int _port;
-  String _user;
-  String _pass;
-
-  public DogConfigFTP(String ip) {
-    this(ip, 21);
-  }
-
-  public DogConfigFTP(String ip, int port) {
-    _ip=ip;
-    _port=port;
-    _user="anonymous";
-    _pass="blah@tekkotsu.org";
-  }
-
-  public DogConfigFTP(String ip, int port, String user, String pass) {
-    this(ip, port);
-    _user=user;
-    _pass=pass;
-  }
-  
-  public boolean test() {
-    return test(500);
-  }
-
-  public boolean test(int millis) {
-    Socket _ftpSocket=new Socket();
-    try {
-      _ftpSocket.connect(new InetSocketAddress(_ip, _port), millis);
-    } catch (Exception ex) { }
-    if (_ftpSocket.isConnected()) {
-      try { _ftpSocket.close(); } catch (Exception ex) { }
-      return true;
-    } else {
-      return false;
-    }
-  }
-
-  public String getFile(String remotename) throws FTPException, IOException {
-    FTPClient ftp=new FTPClient(_ip, _port);
-    ftp.login(_user, _pass);
-    ftp.setConnectMode(FTPConnectMode.ACTIVE);
-    ftp.setType(FTPTransferType.ASCII);
-    String ret=new String(ftp.get(remotename));
-    ftp.quit();
-    return ret;
-  }
-
-	public void putFile(String localname) throws FTPException, IOException {
-		putFile(localname,localname);
-	}
-
-  public void putFile(String localname, String remoteName) throws FTPException, IOException {
-    FTPClient ftp=new FTPClient(_ip, _port);
-    ftp.login(_user, _pass);
-    ftp.setConnectMode(FTPConnectMode.ACTIVE);
-    ftp.setType(FTPTransferType.BINARY);
-    ftp.put(localname, remoteName);
-    ftp.quit();
-  }
-
-  public void login(String user, String pass) {
-    _user=user;
-    _pass=pass;
-  }
-
-  public static void main(String args[]) {
-    System.out.println("This is an internal class - run DogConfig instead");
-    System.exit(0);
-  }
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/ImageData.java ./tools/seg/ImageData.java
--- ../Tekkotsu_2.4.1/tools/seg/ImageData.java	2004-01-20 22:32:26.000000000 -0500
+++ ./tools/seg/ImageData.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,229 +0,0 @@
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.util.*;
-import java.awt.geom.*;
-import java.io.*;
-import java.awt.image.Raster;
-import javax.imageio.ImageIO;
-import javax.imageio.ImageReader;
-import javax.imageio.stream.ImageInputStream;
-import javax.imageio.stream.MemoryCacheImageInputStream;
-
-
-public class ImageData extends Frame {
-  Toolkit toolkit;
-  public int[] retdata;
-  public int[] data;
-
-  public float[] RG;
-  public float[] HS;
-  public float[] HB;
-  public float[] SB;
-
-  public int image_width;
-  public int image_height;
-
-  public int[] getPixels() {
-    return retdata;
-  }
-
-	// assumes retdata holds RGB
-  public float[] getRG() {
-    if (RG==null) {
-      RG=new float[retdata.length*2];
-      for (int i=0; i<retdata.length; i++) {
-        float r=(float)((retdata[i]>>16)&0xFF);
-        float g=(float)((retdata[i]>>8)&0xFF);
-        float b=(float)(retdata[i]&0xFF);
-        RG[i*2]=r/(r+g+b);
-        RG[i*2+1]=g/(r+g+b);
-      }
-    }
-    return RG;
-  }
-
-	// assumes retdata holds RGB
-  public float[] getHS() {
-    if (HS==null) {
-      HS=new float[retdata.length*2];
-      float[] hsb=new float[3];
-      for (int i=0; i<retdata.length; i++) {
-        int r=(retdata[i]>>16)&0xFF;
-        int g=(retdata[i]>>8)&0xFF;
-        int b=retdata[i]&0xFF;
-        Color.RGBtoHSB(r, g, b, hsb);
-        HS[i*2]=hsb[0];
-        HS[i*2+1]=hsb[1];
-      }
-    }
-    return HS;
-  }
-
-	// assumes retdata holds RGB
-  public float[] getHB() {
-    if (HB==null) {
-      HB=new float[retdata.length*2];
-      float[] hsb=new float[3];
-      for (int i=0; i<retdata.length; i++) {
-        int r=(retdata[i]>>16)&0xFF;
-        int g=(retdata[i]>>8)&0xFF;
-        int b=retdata[i]&0xFF;
-        Color.RGBtoHSB(r, g, b, hsb);
-        HB[i*2]=hsb[0];
-        HB[i*2+1]=hsb[2];
-      }
-    }
-    return HB;
-  }
-
-	// assumes retdata holds RGB
-  public float[] getSB() {
-    if (SB==null) {
-      SB=new float[retdata.length*2];
-      float[] hsb=new float[3];
-      for (int i=0; i<retdata.length; i++) {
-        int r=(retdata[i]>>16)&0xFF;
-        int g=(retdata[i]>>8)&0xFF;
-        int b=retdata[i]&0xFF;
-        Color.RGBtoHSB(r, g, b, hsb);
-        SB[i*2]=hsb[1];
-        SB[i*2+1]=hsb[2];
-      }
-    }
-    return SB;
-  }
-  
-  public ImageData() {
-    toolkit=Toolkit.getDefaultToolkit();
-  }
-
-  void loadFile(String filename) {
-    Image image=toolkit.createImage(filename);
-    MediaTracker mediaTracker=new MediaTracker(this);
-    mediaTracker.addImage(image, 0);
-    try {
-      mediaTracker.waitForID(0);
-    } catch (InterruptedException e) {
-      System.out.println(e);
-      System.exit(1);
-    }
-    image_width=image.getWidth(this);
-    image_height=image.getHeight(this);
-
-    BufferedImage bi = new BufferedImage(image_width, image_height,
-                                         BufferedImage.TYPE_INT_RGB);
-    Graphics big = bi.createGraphics();
-    big.drawImage(image,0,0,null);
-    data=bi.getRGB(0,0,image_width,image_height,null,0,image_width);
-  }
-
-	public void loadYUVJPEG(String filename) {
-		try {
-			ImageInputStream jpegStream=new MemoryCacheImageInputStream(new FileInputStream(filename));
-			ImageReader jpegReader=(ImageReader)ImageIO.getImageReadersByFormatName("jpeg").next();
-			jpegReader.setInput(jpegStream); 
-			Raster decoded=jpegReader.readRaster(0,null);
-			image_width=decoded.getWidth();
-			image_height=decoded.getHeight();
-			data = new int[image_width*image_height];
-			int off=0;
-			for(int y=0; y<image_height; y++)
-				for(int x=0; x<image_width; x++) {
-					int yc=decoded.getSample(x,y,0);
-					int uc=decoded.getSample(x,y,2);
-					int vc=decoded.getSample(x,y,1);
-					data[off++]=(yc<<16) | (uc<<8) | vc;
-				}
-		} catch(Exception ex) { ex.printStackTrace(); }
-	}
-
-  public void loadYUVFileAsRGB(String filename) {
-    loadFile(filename);
-    YUV2RGB();
-    retdata=data;
-  }
-
-	public void loadRGBFileAsYUV(String filename) {
-		if(filename.endsWith(".jpg") || filename.endsWith(".jpeg") || filename.endsWith(".JPG") || filename.endsWith(".JPEG"))
-			loadYUVJPEG(filename);
-		else {
-			loadFile(filename);
-			RGB2YUV();
-		}
-    retdata=data;
-	}
-
-	public void loadRGBFileAsRGB(String filename) {
-    loadFile(filename);
-    retdata=data;
-	}
-
-	public void loadYUVFileAsYUV(String filename) {
-    loadFile(filename);
-    retdata=data;
-	}
-
-	// this isn't the "real" conversion, but a quick approx.
-	// it's the same that's used in tekkotsumon's VisionListener
-  public void YUV2RGB() {
-    for (int i=0; i<data.length; i++) {
-      int y=(int)((data[i]>>16)&0xFF);
-      int u=(int)((data[i]>>8)&0xFF);
-      int v=(int)(data[i]&0xFF);
-      u=u*2-255;
-      v=v*2-255;
-      int r=y+u;
-      int b=y+v;
-      u=u>>1;
-      v=(v>>2)-(v>>4);
-      int g=y-u-v;
-      if (r<0) r=0; if (g<0) g=0; if (b<0) b=0;
-      if (r>255) r=255; if (g>255) g=255; if (b>255) b=255;
-
-      data[i]= (r<<16) | (g<<8) | b;
-    }
-  }
-
-	// this isn't the "real" conversion, nor a quick approx, but
-	// it will get as close as possible to an exact undo of the YUV2RGB conversion
-	// we use in VisionListener (and here)
-  public void RGB2YUV() {
-    for (int i=0; i<data.length; i++) {
-      int r=(int)((data[i]>>16)&0xFF);
-      int g=(int)((data[i]>>8)&0xFF);
-      int b=(int)(data[i]&0xFF);
-			int y=(int)( 8*r/27 +  g/ 9  + 16*b/27 - 203/27);
-			int u=(int)(19*r/54 -  g/18  -  8*b/27 +3544/27);
-			int v=(int)(-4*r/27 +4*g/ 9  -  8*b/27 +3544/27); 
-      if (y<0) y=0; if (u<0) u=0; if (v<0) v=0;
-      if (y>255) y=255; if (u>255) u=255; if (v>255) v=255;
-      data[i]= (y<<16) | (u<<8) | v;
-    }
-  }
-
-  public void loadFullRGBFilesAsRGB(String files[]) {
-    for (int i=0; i<files.length; i++) {
-			loadFile(files[i]);
-      if (i==0) retdata=new int[files.length*data.length];
-			//for (int j=0; j<data.length; j++)
-			//retdata[j+(i*data.length)]=data[j];
-      int l=0;
-			for (int j=i; j<retdata.length; j+=files.length)
-				retdata[j]=data[l++];
-    }
-  }
-
-  public void loadFullYUVFilesAsRGB(String files[]) {
-    for (int i=0; i<files.length; i++) {
-      loadFile(files[i]);
-      if (i==0) retdata=new int[files.length*data.length];
-      YUV2RGB();
-      int l=0;
-      for (int j=i; j<retdata.length; j+=files.length)
-        retdata[j]=data[l++];
-    }
-  }
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/ImageShow.java ./tools/seg/ImageShow.java
--- ../Tekkotsu_2.4.1/tools/seg/ImageShow.java	2005-05-09 15:19:51.000000000 -0400
+++ ./tools/seg/ImageShow.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,124 +0,0 @@
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.io.*;
-import java.util.*;
-
-public class ImageShow extends JFrame implements KeyListener {
-  BufferedImage _image;
-  String[] imglist;
-  byte[] tmap;
-  ImageData imageData;
-  int curimg;
-	boolean isRGB;
-
-  public static void main(String args[]) {
-    if (args.length<1)
-			usageAndExit();
-		boolean isRGB=true;
-		if(args[0].equals("-isRGB"))
-			isRGB=true;
-		else if(args[0].equals("-isYUV"))
-			isRGB=false;
-		else {
-			System.out.println(args[0]+" is not valid color mode");
-			usageAndExit();
-		}
-		
-		String files[]=new String[args.length-1];
-		for(int i=0; i<files.length; i++)
-			files[i]=args[i+1];
-
-    ImageShow imageShow=new ImageShow(isRGB,files);
-    imageShow.show();
-    imageShow.addWindowListener(new WindowAdapter() {
-        public void windowClosing(WindowEvent e) { System.exit(0); } });
-  }
-
-
-	public static void usageAndExit() {
-		System.out.println("usage: java ImageShow (-isRGB|-isYUV) raw_image [raw images]");
-		System.exit(1);
-	}
-
-  public ImageShow (boolean isRGB, String args[]) {
-    imageData=new ImageData();
-		this.isRGB=isRGB;
-		if(isRGB)
-			imageData.loadRGBFileAsRGB(args[0]);
-		else
-			imageData.loadYUVFileAsRGB(args[0]);
-
-    int[] data=imageData.getPixels();
-
-    setBackground(Color.black);
-    setSize(imageData.image_width*2, imageData.image_height*2);
-    setTitle(args[0]);
-    _image=new BufferedImage(imageData.image_width, imageData.image_height,
-        BufferedImage.TYPE_INT_RGB);
-   
-    showImage(data, tmap, imageData.image_width, imageData.image_height);
-
-    imglist=new String[args.length];
-    curimg=0;
-    for (int i=0; i<args.length; i++) {
-      imglist[i]=args[i];
-    }
-
-    addKeyListener(this);
-  }
-
-  void showImage(int[] data, byte[] tmap, int width, int height) {
-    _image.getRaster().setDataElements(0,0,width,height,data);
-    repaint();
-  }
-
-  public void paint(Graphics graphics) {
-    Dimension sz=getSize();
-    if (_image!=null)
-      graphics.drawImage(_image, 0, 0, sz.width, sz.height, null);
-  }
-
-  public int getPixel(int x, int y) {
-    Dimension sz=getSize();
-    x=(x*_image.getWidth())/sz.width;
-    y=(y*_image.getHeight())/sz.height;
-    return _image.getRGB(x, y);
-  }
-
-  public void keyPressed(KeyEvent e) {
-    if (e.getKeyCode()==KeyEvent.VK_LEFT ||
-        e.getKeyCode()==KeyEvent.VK_UP ||
-        e.getKeyCode()==KeyEvent.VK_PAGE_UP ||
-        e.getKeyCode()==KeyEvent.VK_KP_UP ||
-        e.getKeyCode()==KeyEvent.VK_KP_LEFT) {
-      curimg--;
-      if (curimg<0) curimg+=imglist.length;
-			if(isRGB)
-				imageData.loadRGBFileAsRGB(imglist[curimg]);
-			else
-				imageData.loadYUVFileAsRGB(imglist[curimg]);
-      int[] data=imageData.getPixels();
-      showImage(data, tmap, imageData.image_width, imageData.image_height);
-    } else if (e.getKeyCode()==KeyEvent.VK_RIGHT ||
-        e.getKeyCode()==KeyEvent.VK_DOWN ||
-        e.getKeyCode()==KeyEvent.VK_PAGE_DOWN ||
-        e.getKeyCode()==KeyEvent.VK_KP_DOWN ||
-        e.getKeyCode()==KeyEvent.VK_KP_RIGHT) {
-      curimg++;
-      if (curimg>=imglist.length) curimg-=imglist.length;
-			if(isRGB)
-				imageData.loadRGBFileAsRGB(imglist[curimg]);
-			else
-				imageData.loadYUVFileAsRGB(imglist[curimg]);
-
-      setTitle(imglist[curimg]);
-      int[] data=imageData.getPixels();
-      showImage(data, tmap, imageData.image_width, imageData.image_height);
-    }
-  }
-  public void keyReleased(KeyEvent e) { }
-  public void keyTyped(KeyEvent e) { }
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/ImageShowArea.java ./tools/seg/ImageShowArea.java
--- ../Tekkotsu_2.4.1/tools/seg/ImageShowArea.java	2005-05-23 22:32:40.000000000 -0400
+++ ./tools/seg/ImageShowArea.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,151 +0,0 @@
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.io.*;
-import java.util.*;
-import java.awt.geom.*;
-
-public class ImageShowArea extends JFrame implements KeyListener {
-  BufferedImage _image;
-  String[] imglist;
-  byte[] tmap;
-  ImageData imageData;
-  int curimg;
-	boolean isRGB;
-
-    Polygon curPoly;
-    Area curArea;
-
-
-  public static void main(String args[]) {
-    if (args.length<1)
-			usageAndExit();
-		boolean isRGB=true;
-		if(args[0].equals("-isRGB"))
-			isRGB=true;
-		else if(args[0].equals("-isYUV"))
-			isRGB=false;
-		else {
-			System.out.println(args[0]+" is not valid color mode");
-			usageAndExit();
-		}
-		
-		String files[]=new String[args.length-1];
-		for(int i=0; i<files.length; i++)
-			files[i]=args[i+1];
-
-    ImageShowArea imageShow=new ImageShowArea(isRGB,files);
-    imageShow.show();
-    imageShow.addWindowListener(new WindowAdapter() {
-        public void windowClosing(WindowEvent e) { System.exit(0); } });
-  }
-
-
-	public static void usageAndExit() {
-		System.out.println("usage: java ImageShow (-isRGB|-isYUV) raw_image [raw images]");
-		System.exit(1);
-	}
-
-  public ImageShowArea (boolean isRGB, String args[]) {
-      curPoly = null;
-      curArea = null;
-
-    imageData=new ImageData();
-		this.isRGB=isRGB;
-		if(isRGB)
-			imageData.loadRGBFileAsRGB(args[0]);
-		else
-			imageData.loadYUVFileAsRGB(args[0]);
-
-    int[] data=imageData.getPixels();
-
-    setBackground(Color.black);
-    setSize(imageData.image_width*2, imageData.image_height*2);
-    setTitle(args[0]);
-    _image=new BufferedImage(imageData.image_width, imageData.image_height,
-        BufferedImage.TYPE_INT_RGB);
-   
-    showImage(data, tmap, imageData.image_width, imageData.image_height);
-
-    imglist=new String[args.length];
-    curimg=0;
-    for (int i=0; i<args.length; i++) {
-      imglist[i]=args[i];
-    }
-
-    addKeyListener(this);
-  }
-
-  void showImage(int[] data, byte[] tmap, int width, int height) {
-    _image.getRaster().setDataElements(0,0,width,height,data);
-    repaint();
-  }
-
-    public void setCurArea(Area _curArea)
-    {
-	curArea = _curArea;
-	repaint();
-    }
-
-    public void setCurPoly(Polygon _curPoly)
-    {
-	curPoly = _curPoly;
-	repaint();
-    }
-
-  public void paint(Graphics graphics) {
-    Dimension sz=getSize();
-    if (_image!=null)
-      graphics.drawImage(_image, 0, 0, sz.width, sz.height, null);
-
-    graphics.setColor(Color.white);
-    if (curArea!=null)
-      ((Graphics2D)graphics).draw(curArea);
-
-    if (curPoly!=null)
-      ((Graphics2D)graphics).draw(curPoly);
-  }
-
-  public int getPixel(int x, int y) {
-    Dimension sz=getSize();
-    x=(x*_image.getWidth())/sz.width;
-    y=(y*_image.getHeight())/sz.height;
-    return _image.getRGB(x, y);
-  }
-
-  public void keyPressed(KeyEvent e) {
-    if (e.getKeyCode()==KeyEvent.VK_LEFT ||
-        e.getKeyCode()==KeyEvent.VK_UP ||
-        e.getKeyCode()==KeyEvent.VK_PAGE_UP ||
-        e.getKeyCode()==KeyEvent.VK_KP_UP ||
-        e.getKeyCode()==KeyEvent.VK_KP_LEFT) {
-      curimg--;
-      if (curimg<0) curimg+=imglist.length;
-			if(isRGB)
-				imageData.loadRGBFileAsRGB(imglist[curimg]);
-			else
-				imageData.loadYUVFileAsRGB(imglist[curimg]);
-      int[] data=imageData.getPixels();
-      showImage(data, tmap, imageData.image_width, imageData.image_height);
-    } else if (e.getKeyCode()==KeyEvent.VK_RIGHT ||
-        e.getKeyCode()==KeyEvent.VK_DOWN ||
-        e.getKeyCode()==KeyEvent.VK_PAGE_DOWN ||
-        e.getKeyCode()==KeyEvent.VK_KP_DOWN ||
-        e.getKeyCode()==KeyEvent.VK_KP_RIGHT) {
-      curimg++;
-      if (curimg>=imglist.length) curimg-=imglist.length;
-			if(isRGB)
-				imageData.loadRGBFileAsRGB(imglist[curimg]);
-			else
-				imageData.loadYUVFileAsRGB(imglist[curimg]);
-
-      setTitle(imglist[curimg]);
-      int[] data=imageData.getPixels();
-      showImage(data, tmap, imageData.image_width, imageData.image_height);
-    }
-  }
-  public void keyReleased(KeyEvent e) { }
-  public void keyTyped(KeyEvent e) { }
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/Listener.java ./tools/seg/Listener.java
--- ../Tekkotsu_2.4.1/tools/seg/Listener.java	2003-07-26 21:55:59.000000000 -0400
+++ ./tools/seg/Listener.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,178 +0,0 @@
-import java.net.ServerSocket;
-import java.net.Socket;
-import java.io.InputStream;
-import java.io.OutputStream;
-import java.io.IOException;
-
-public abstract class Listener implements Runnable {
-	public Listener() { _port=-1; _isConnected=false; }
-	public Listener(int port) { this(); setPort(port); }
-	public Listener(String host, int port) { this(); setHostPort(host, port); }
-
-	public void setPort(int port) {
-		_isServer=true;
-		_port=port;
-		startThread();
-	}
-
-	public void setHostPort(String host, int port) {
-		_isServer=false;
-		_host=host;
-		_port=port;
-		startThread();
-	}
-
-	public void startThread() {
-		destroy=false;
-		_listenerThread=new Thread(this);
-		_listenerThread.start();
-	}
-
-	public void run() {
-		if (_port >= 0) {
-			if (_isServer)
-				runServer();
-			else
-				runConnect();
-		} else {
-			System.out.println("can't start Listener without [host],port");
-		}
-	}
-
-	public void kill() {
-		destroy=true;
-		_isConnected=false;
-		if(_listenerThread!=null)
-			_listenerThread.interrupt();
-		close();
-	}
-
-	void frameTimer() {
-		_frametimer_numframes++;
-		if (System.currentTimeMillis()-_frametimer_timer>1000) {
-			System.out.println("updated at "+_frametimer_numframes+"hz");
-			_frametimer_numframes=0;
-			_frametimer_timer=System.currentTimeMillis();
-		}
-	}
-
-	double readDouble(InputStream in) throws IOException {
-		return Double.longBitsToDouble(readLong(in));
-	}
-
-	void writeDouble(OutputStream out, double x) throws IOException {
-		writeLong(out,Double.doubleToLongBits(x));
-	}
-
-	long readLong(InputStream in) throws IOException {
-		int read=0;
-		int last=0;
-		byte[] buf=new byte[8];
-		while (read<8 && last>=0) { last=in.read(buf,read,8-read); read+=last; }
-		if(last<0)
-			_isConnected=false;
-		return (b2l(buf[7])<<56) | (b2l(buf[6])<<48) |
-					 (b2l(buf[5])<<40) | (b2l(buf[4])<<32) |
-					 (b2l(buf[3])<<24) | (b2l(buf[2])<<16) |
-					 (b2l(buf[1])<< 8) | b2l(buf[0]);
-	}
-
-	void writeLong(OutputStream out, long x) throws IOException {
-		int bytelen=8;
-		byte[] buf=new byte[bytelen];
-		for(int i=0; i<bytelen; i++)
-			buf[i]=(new Long((x>>(8*i)) & 0xff)).byteValue();
-		out.write(buf,0,bytelen);
-	}
-
-	float readFloat(InputStream in) throws IOException {
-		return Float.intBitsToFloat(readInt(in));
-	}
-	
-	void writeFloat(OutputStream out, float x) throws IOException {
-		writeInt(out,Float.floatToIntBits(x));
-	}
-
-	int readInt(InputStream in) throws IOException {
-		int read=0;
-		int last=0;
-		byte[] buf=new byte[4];
-		while (read<4 && last>=0) { last=in.read(buf,read,4-read); read+=last; }
-		if(last<0)
-			_isConnected=false;
-		return (b2i(buf[3])<<24) | (b2i(buf[2])<<16) |
-					 (b2i(buf[1])<< 8) | b2i(buf[0]);
-	}
-	
-	void writeInt(OutputStream out, int x) throws IOException {
-		int bytelen=4;
-		byte[] buf=new byte[bytelen];
-		for(int i=0; i<bytelen; i++)
-			buf[i]=(new Integer((x>>(8*i)) & 0xff)).byteValue();
-		out.write(buf,0,bytelen);
-	}
-
-  byte[] readBytes(InputStream in, int bytes) throws IOException {
-    byte[] ret=new byte[bytes];
-    readBytes(ret, in, bytes);
-    return ret;
-  }
-
-	void readBytes(byte[] buf, InputStream in, int bytes) throws IOException {
-		int read=0;
-		int last=0;
-		while (read<bytes && last>=0) {
-			last=in.read(buf, read, bytes-read);
-			read+=last;
-		}
-		if(last<0)
-			_isConnected=false;
-	}
-
-	String readLine(InputStream in) throws java.io.IOException{
-		StringBuffer sbuf=new StringBuffer();
-		int x=in.read();
-		if(x==-1) {
-			_isConnected=false;
-			return sbuf.toString();
-		}
-		char c=(char)x;
-		while(c!='\n') {
-			sbuf.append(c);
-			x=in.read();
-			if(x==-1) {
-				_isConnected=false;
-				return sbuf.toString();
-			}
-			c=(char)x;
-		}
-		return sbuf.toString();
-	}
-	
-	int b2i(byte b) { return (b>=0)?(int)b:((int)b)+256; }
-	long b2l(byte b) { return (b>=0)?(long)b:((long)b)+256; }
-
-	abstract void runServer();
-	abstract void runConnect();
-	abstract public void close();
-
-	boolean _isServer;
-	int _port;
-	String _host;
-	boolean _isConnected;
-	volatile Thread _listenerThread;
-	volatile boolean destroy=false;
-
-	int _frametimer_numframes=0;
-	long _frametimer_timer=System.currentTimeMillis();
-
-  public static final int PACKET_TEXT=0;
-  public static final int PACKET_VISIONRAW_HALF=1;
-  public static final int PACKET_VISIONRAW_FULL=2;
-  public static final int PACKET_VISIONRAW_YFULL_UVHALF=3;
-  public static final int PACKET_VISIONRLE_FULL=4;
-  public static final int PACKET_WORLDSTATEJOINTS=5;
-  public static final int PACKET_WORLDSTATEPIDS=6;
-  public static final int PACKET_WORLDSTATEBUTTONS=7;
-  public static final int PACKET_WMCLASS=8;
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/MoveIndex.java ./tools/seg/MoveIndex.java
--- ../Tekkotsu_2.4.1/tools/seg/MoveIndex.java	2003-10-09 02:30:08.000000000 -0400
+++ ./tools/seg/MoveIndex.java	2006-09-13 18:29:46.000000000 -0400
@@ -20,7 +20,7 @@
     try {
 			//Move index found in tm file
 			{
-				byte[] header=new byte[19];
+				byte[] header=new byte[20];
 				byte[] tmdata=new byte[65536];
 				
 				FileInputStream in=new FileInputStream(inf+".tm");
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/TCPListener.java ./tools/seg/TCPListener.java
--- ../Tekkotsu_2.4.1/tools/seg/TCPListener.java	2003-07-26 21:55:59.000000000 -0400
+++ ./tools/seg/TCPListener.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,67 +0,0 @@
-import java.net.ServerSocket;
-import java.net.Socket;
-
-public abstract class TCPListener extends Listener {
-	abstract void connected(Socket socket);
-
-	void runServer() {
-		Thread me = Thread.currentThread();
-		try { _serverSocket=new ServerSocket(_port); }
-		catch (Exception ex) {
-			System.out.println("port "+_port+": "+ex);
-			return;
-		}
-
-		while (me == _listenerThread && !destroy) {
-			try {
-				_socket=_serverSocket.accept();
-				connected(_socket);
-			} catch (Exception ex) { }
-		}
-	}
-
-	void runConnect() {
-		int attempts=0;
-		Thread me = Thread.currentThread();
-		while (me==_listenerThread && !destroy) {
-			if(attempts==0) {
-				System.out.println("["+_port+"] connecting ...");
-			}
-			try {
-				_socket=new Socket(_host,_port);
-				System.out.println("["+_port+"] connected");
-				attempts=0;
-				_isConnected=true;
-			} catch (Exception ex) {}
-			if(_isConnected) {
-				connected(_socket);
-				if(!destroy)
-					System.out.println("["+_port+"] disconnected");
-          System.out.println("["+_port+"] attempting to reestablish ..");
-			}
-			attempts++;
-			if(destroy) {
-				System.out.println("["+_port+"] connection closed");
-				break;
-			}
-			try {
-				Thread.sleep(500);
-			} catch (Exception ex) {}
-		}
-	}
-
-	public void close() {
-		_listenerThread=null;
-		_isConnected=false;
-		try { _socket.close(); } catch (Exception ex) { }
-		if (_isServer)
-			try { _serverSocket.close(); } catch (Exception ex) { }
-	}
-
-	public TCPListener() { super(); }
-	public TCPListener(int port) { super(port); }
-	public TCPListener(String host, int port) { super(host,port); }
-
-	Socket _socket;
-	ServerSocket _serverSocket;
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/TextListener.java ./tools/seg/TextListener.java
--- ../Tekkotsu_2.4.1/tools/seg/TextListener.java	2003-07-26 21:55:59.000000000 -0400
+++ ./tools/seg/TextListener.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,54 +0,0 @@
-import java.io.InputStreamReader;
-import java.io.BufferedReader;
-import java.io.PrintStream;
-import java.net.Socket;
-
-public class TextListener extends TCPListener {
-  String _data="";
-  PrintStream _out;
-
-  void connected(Socket socket) {
-    _isConnected=true;
-    try {
-      BufferedReader in=new BufferedReader(new InputStreamReader(
-                          socket.getInputStream()));
-      _out=new PrintStream(socket.getOutputStream());
-      while (true) {
-        String read=in.readLine();
-        if (read==null) break;
-        synchronized (_data) { _data=_data+read+"\n"; }
-      }
-    } catch (Exception ex) { }
-
-    try { socket.close(); } catch (Exception ex) { }
-    _isConnected=false;
-  }
- 
-  public boolean hasData() {
-    return _data.length()!=0;
-  }
-
-  public String getData() {
-    String ret;
-    synchronized (_data) { 
-      ret=_data;
-      _data="";
-    }
-    return ret;
-  }
-
-  public void write(String s) {
-    if (_isConnected) {
-      _out.print(s);
-      _out.flush();
-    }
-  }
-
-  public boolean isConnected() {
-    return _isConnected;
-  }
-
-  public TextListener() { super(); }
-  public TextListener(int port) { super(port); }
-  public TextListener(String host, int port) { super(host,port); }
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/ThresholdAdd.java ./tools/seg/ThresholdAdd.java
--- ../Tekkotsu_2.4.1/tools/seg/ThresholdAdd.java	2003-10-09 02:29:39.000000000 -0400
+++ ./tools/seg/ThresholdAdd.java	2006-09-13 18:29:46.000000000 -0400
@@ -33,8 +33,8 @@
       for (int i=0; i<files.length-1; i++) {
         System.out.println("Adding "+files[i]+ "...");
         FileInputStream in=new FileInputStream(files[i]);
-        in.read(tmdata, 0, 19);
-        if (i==0) out.write(tmdata, 0, 19);
+        in.read(tmdata, 0, 20);
+        if (i==0) out.write(tmdata, 0, 20);
         in.read(tmdata);
 				
 				for (int j=0; j<mergeddata.length; j++)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/ThresholdMerge.java ./tools/seg/ThresholdMerge.java
--- ../Tekkotsu_2.4.1/tools/seg/ThresholdMerge.java	2003-10-09 02:29:39.000000000 -0400
+++ ./tools/seg/ThresholdMerge.java	2006-09-13 18:29:46.000000000 -0400
@@ -31,8 +31,8 @@
       for (int i=0; i<files.length-1; i++) {
         System.out.println("Adding "+files[i]+ "...");
         FileInputStream in=new FileInputStream(files[i]);
-        in.read(tmdata, 0, 19);
-        if (i==0) out.write(tmdata, 0, 19);
+        in.read(tmdata, 0, 20);
+        if (i==0) out.write(tmdata, 0, 20);
         in.read(tmdata);
 
         for (int j=0; j<mergeddata.length; j++)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/TileTrain.java ./tools/seg/TileTrain.java
--- ../Tekkotsu_2.4.1/tools/seg/TileTrain.java	2004-09-28 16:51:43.000000000 -0400
+++ ./tools/seg/TileTrain.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,577 +0,0 @@
-/* 
-   TileTrain.java
-   Vision training tool to be used with the Tekkotsu framework.
-   Originally modified from ImageShow and VisionTrain
-   Requires ImageData
-   By Rob Salkin (salkin@cs.albany.edu) and Shawn Turner (st2750@albany.edu)
-   University at Albany - May 2004
-*/
-
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.io.*;
-import java.util.*;
-import java.awt.geom.*;
-
-public class TileTrain extends Canvas implements KeyListener, MouseListener, MouseMotionListener{
-    BufferedImage _image;
-    String[] names;         //tracking color names
-    byte[] tmap;            //threshold map
-    int[] RGBdata;
-    int[] YUVdata;
-    ImageData imageDataYUV; //for YUV data
-    ImageData imageDataRGB; //for RGB data
-    int count;             //color counter
-
-    int[] red;
-    int[] green;
-    int[] blue;
-
-    //tiling layout
-    //"prime" numbered layouts will run in a single row -- not very fun
-    
-    //dimensions                            W    H
-    private static int [][]  sizetable = { {0  , 0},   //0 images  
-					   {1  , 1},   //1
-					   {2  , 1},   //2
-					   {3  , 1},   //3
-					   {2  , 2},   //4, etc.
-					   {5  , 1},
-					   {3  , 2},
-					   {7  , 1},
-					   {4  , 2},
-					   {3  , 3},
-					   {5  , 2},
-					   {11 , 1},
-					   {4  , 3},   //12
-					   {13 , 1},
-					   {7  , 2},
-					   {5  , 3},
-					   {4  , 4},   //16
-					   {17 , 1},
-					   {6  , 3},
-					   {19 , 1},
-					   {5  , 4},
-					   {7  , 3},
-					   {11 , 2},
-					   {23 , 1},
-					   {6  , 4},
-					   {5  , 5}  };
-
-    private static final int MAX_DIM = 25;             // maximum tiling area. Should match table
-
-    //for storing YUV data
-    public static final int size_y=16, size_u=64, size_v=64;
-    public static final int size_total=size_y*size_u*size_v;
-
-
-    //for marquee tool
-    Area curArea;
-    Polygon curPoly;
-    int lastx, lasty;
-    
-    //for control
-    public static final int MODIFIER_NONE=0;
-    public static final int MODIFIER_SHIFT=1;
-    public static final int MODIFIER_CTRL=2;
-    public int curSelectModifier;
-    public int curSelectModified;
-
-
-    public static int WIDTH; // number of images wide
-    public static int HEIGHT; // number of images high
-    public static int TOTAL_IMGS; //total images
-
-    // per tile. Set in main, based on argc
-    public static int PIXEL_WIDTH;
-    public static int PIXEL_HEIGHT;
-    public static int TOTAL_PIXELS;
-
-    // maximum number of allowable color names
-    public static final int MAX_COLORS=8;
-
-    //all of these should be set on the command line
-    public static final int SMOOTH_FACTOR=2; //1 pixel used for (1 + (2*SMOOTH_FACTOR))^3 colors when same SMOOTH_FACTOR is used for Y,U,V
-    public static final int Y_SMOOTH_FACTOR=3;//SMOOTH_FACTOR; //Y should have greatest smoothing for lighting variation
-    public static final int U_SMOOTH_FACTOR=1;//SMOOTH_FACTOR; 
-    public static final int V_SMOOTH_FACTOR=1;//SMOOTH_FACTOR; 
-    
-    
-    public static void main(String args[]) {
-
-	System.out.println
-	    ("TileTrain is a vision training tool to be used with the Tekkotsu framework.\n"
-	     +"Originally modified from ImageShow and VisionTrain\n"
-	     +"Requires ImageData\n"
-	     +"By Rob Salkin (salkin@cs.albany.edu) and Shawn Turner (st2750@albany.edu)\n"
-	     +"University at Albany - May 2004\n");
-
-
-	if(args.length-1 <= 0 || args.length-1 > MAX_DIM){
-	    System.out.println("Number of images must be > 0 and <= "+MAX_DIM);
-	    usageAndExit(args.length-1);
-	}
-
-	//determine proper image size for tiling by model
-	if(args[0].equals("-is7")){
-	    System.out.println("Processing images for ERS7");
-	    PIXEL_WIDTH = 104;
-	    PIXEL_HEIGHT = 80;
-	}
-	else if(args[0].equals("-is2xx")){
-	    System.out.println("Processing images for ERS2xx");
-	    PIXEL_WIDTH = 88;
-	    PIXEL_HEIGHT = 72;
-	}
-	else{
-	    usageAndExit(args.length);
-	}
-
-	
-
-	TOTAL_PIXELS = PIXEL_WIDTH*PIXEL_HEIGHT;           //pixels per tile
-	
-	//set tile dimensions
-	WIDTH = sizetable[args.length-1][0];
-	HEIGHT = sizetable[args.length-1][1];
-	TOTAL_IMGS = WIDTH*HEIGHT;
-    
-	String files[]=new String[args.length-1];
-	for(int i=0; i<args.length-1; i++){
-	    files[i]=args[i+1];
-	}
-	
-	TileTrain tileTrain=new TileTrain(files);
-
-	JFrame fraDisplay = new JFrame();
-	fraDisplay.getContentPane().add(tileTrain);
-
-	//ALWAYS PACK! OTHERWISE ARRAY OFFSET PROBLEMS HAPPEN!!!
-	//	fraDisplay.setSize(WIDTH*PIXEL_WIDTH,HEIGHT*PIXEL_HEIGHT);
-	fraDisplay.setResizable(false);
-	fraDisplay.pack();
-	fraDisplay.show();
-		
-	fraDisplay.addWindowListener(new WindowAdapter() {
-		public void windowClosing(WindowEvent e) { System.exit(0); } });
-
-    }
-    
-    
-    public static void usageAndExit(int imgs) {
-	System.out.println("usage: java TileTrain -is[7|2xx] raw_image (up to "+MAX_DIM+" raw images -- you gave me "+imgs+")");
-	System.exit(1);
-    }
-    
-    public int[] getRGBdata(){
-	return RGBdata;
-    }
-
-    public int[] getYUVdata(){
-	return YUVdata;
-    }
-
-    public TileTrain (String args[]) {
-	ImageData imageDataRGB=new ImageData();
-	ImageData imageDataYUV=new ImageData();
-
-	tmap=new byte[size_total];
-
-	red=new int[MAX_COLORS];
-	green=new int[MAX_COLORS];
-	blue=new int[MAX_COLORS];
-
-	ImageData tempRGB;
-	ImageData tempYUV;
-
-	int iaRGB[];
-	int iaYUV[];
-	RGBdata=new int[TOTAL_IMGS*TOTAL_PIXELS];
-	YUVdata=new int[TOTAL_IMGS*TOTAL_PIXELS];
-	count=0;
-	try{
-	    for(int k=0;k<TOTAL_IMGS;k++){
-		
-		tempRGB=new ImageData();
-		tempYUV=new ImageData();
-		System.out.println("Loading " + args[k] );
-		tempRGB.loadYUVFileAsRGB(args[k]);
-		tempYUV.loadYUVFileAsYUV(args[k]);
-		iaYUV=tempYUV.getPixels();
-		iaRGB=tempRGB.getPixels();
-		
-		for(int h=0;h<PIXEL_HEIGHT;h++){
-		    for(int w=0;w<PIXEL_WIDTH;w++){
-			RGBdata[(k/WIDTH)*(WIDTH*TOTAL_PIXELS) //tile row offset
-				+(k%WIDTH)*(PIXEL_WIDTH)       //tile col offset 
-				+h*WIDTH*PIXEL_WIDTH           //pixel row offset
-				+w]                            //pixel col offset
-			    =iaRGB[h*PIXEL_WIDTH+w]; //RGB data for display
-			
-			YUVdata[(k/WIDTH)*(WIDTH*TOTAL_PIXELS) //tile row offset
-				+(k%WIDTH)*(PIXEL_WIDTH)       //tile col offset 
-				+h*WIDTH*PIXEL_WIDTH           //pixel row offset
-				+w]                            //pixel col offset
-			    =iaYUV[h*PIXEL_WIDTH+w]; //YUV data for seg use
-		    }
-		}
-	    }	    
-	}
-	catch(Exception e){
-	    System.out.println(e.getClass() + " thrown. \nPlease verify that the arguments to TileTrain" + 
-			       " are consistent with the robot model and image filenames before trying again.\n\n");
-	    
-	    e.printStackTrace();
-	    System.exit(1);
-	}
-   
-	setBackground(Color.black);
-	setSize(PIXEL_WIDTH*WIDTH, PIXEL_HEIGHT*HEIGHT);
-	_image=new BufferedImage(PIXEL_WIDTH*WIDTH, PIXEL_HEIGHT*HEIGHT,
-				 BufferedImage.TYPE_INT_RGB);
-	
-	showImage(RGBdata, tmap, PIXEL_WIDTH*WIDTH, PIXEL_HEIGHT*HEIGHT);
-	
-	names=new String[MAX_COLORS];
-	curArea = new Area();
-	addKeyListener(this);
-	addMouseListener(this);
-	addMouseMotionListener(this);     
-	
-	showHelp();
-
-    }
-
-    void showImage(int[] data, byte[] tmap, int width, int height) {
-	_image.getRaster().setDataElements(0,0,width,height,data);
-	repaint();
-    }
-
-    public void paint(Graphics graphics) {
-	update(graphics);
-    }
-
-    public void keyPressed(KeyEvent e) {
-	
-	//modified to carry the shift/control selection features from them image to the canvas.
-	if (e.getKeyCode()==KeyEvent.VK_SHIFT) {
-	    curSelectModifier=MODIFIER_SHIFT;
-	} else if (e.getKeyCode()==KeyEvent.VK_CONTROL) {
-	    curSelectModifier=MODIFIER_CTRL;
-	}
-    }
-    
-    public static void showHelp(){
-	JOptionPane.showMessageDialog
-	    (null,"Start by selecting as much of a target color as possible to be segmented.\n"+
-	     "Press N (=Name) to store the current selection and enter a name for the selection.\n"+
-	     "Press S (=Save) to save the stored selections to .tm and .col files.\n"+
-	     "Press C (=Clear) to clear ALL current mapped colors\n"+
-	     "Press Q (=Quit) to quit this program\n" +
-	     "Tips:\n"+
-	     "\t-Press N after each selection -- don't forget to do so before pressing S.\n"+
-	     "\t-Hold SHIFT to select multiple regions or append to regions.\n"+
-	     "\t-Hold CTRL to deselect from regions.\n"+
-	     "\t-On the color chooser, select a representative color that will stand out compared to other colors.\n"+
-	     "\t-Click anywhere in the window to deselect all regions -- useful after pressing N.\n"+
-	     "\t-All .tm and .col files should have names <=8 characters.\n"+
-	     "Press H (=Help) for this message.\n", "TileTrain Help", JOptionPane.OK_OPTION);
-    }
-    
-    public void keyReleased(KeyEvent e) { 
-	if (e.getKeyCode()==KeyEvent.VK_SHIFT
-	    ||e.getKeyCode()==KeyEvent.VK_CONTROL) {
-	    curSelectModifier=MODIFIER_NONE;
-	}
-	else if (e.getKeyCode()==KeyEvent.VK_H){
-	    showHelp();
-	}
-	else if (e.getKeyCode()==KeyEvent.VK_N){
-	    //verify we have colors left to create
-	    if(checkcolors() == false)
-		return;
-
-	    String tname = null;//temporary string for color name
-	    do{
-		tname=JOptionPane.showInputDialog("Enter name for color "+(count+1));
-	    }while(tname!=null&&tname.trim().equals(""));
-	    if(tname!=null){
-		names[count] = tname;
-		
-		Color segcol = null;//segmentation will be seen as this color
-		do{
-		    segcol = JColorChooser.showDialog(null, "Segmented Color", Color.WHITE);
-		}while(segcol == null);
-		
-		red[count]=segcol.getRed();
-		green[count]=segcol.getGreen();
-		blue[count]=segcol.getBlue();
-		
-		count++;
-		doCalc(tmap, size_total);
-		
-		System.out.println(tname + " stored");
-		
-		//clear the area
-		curArea.reset();
-		repaint();
-		
-		checkcolors();
-	    }
-	    else{
-		JOptionPane.showMessageDialog(null, "The current selection was not stored!");
-	    }
-	}	
-	else if (e.getKeyCode()==KeyEvent.VK_S){
-
-	    JFileChooser chooser=new JFileChooser();
-	    
-	    chooser.setCurrentDirectory(new File(System.getProperty("user.dir")));
-	    chooser.setSelectedFile(new File("default.tm"));
-	    int returnval=chooser.showSaveDialog(this);
-	    if (returnval==JFileChooser.APPROVE_OPTION) {
-		//bug fix for save path
-		save(chooser.getCurrentDirectory() + "/" + chooser.getSelectedFile().getName());   
-	    }   
-	}
-	else if (e.getKeyCode()==KeyEvent.VK_Q){
-	    if( (JOptionPane.showConfirmDialog(null, "Are you Sure?\nAll unsaved work will be lost!", "Quit?", 
-					       JOptionPane.OK_CANCEL_OPTION)) == JOptionPane.OK_OPTION)
-		System.exit(0);
-	}
-	else if (e.getKeyCode()==KeyEvent.VK_C){
-	    if( (JOptionPane.showConfirmDialog(null, "Are you Sure?\nAll Colors Will be lost!", "Clear Colors?", JOptionPane.OK_CANCEL_OPTION)) 
-		== JOptionPane.OK_OPTION)
-		count = 0;
-	}
-    
-    }
-
-    public void keyTyped(KeyEvent e) {
-
-    }
-
-    public boolean checkcolors(){
-	//do we have any usuable colors left?
-
-	if(count >= MAX_COLORS){
-	    JOptionPane.showMessageDialog(null, "The maximum number of creatable colors ("+MAX_COLORS+
-					  ") has been filled\nPlease save your work, or hit \"C\" to clear ALL colors");
-	    return false;
-	}
-	return true;
-    }
-					  
-
-    public void doCalc(byte[] tmap, int size){
-
-	int size_total=size;
-
-	int i,x,y,yuv,y_val,u_val,v_val,index;
-
-	int rgb,r_val,g_val,b_val;
-
-
-	if(count<=1){
-	    for(i=0; i<size_total; i++){
-		tmap[i]=(byte)0;
-	    }
-	}
-
-	//scan the whole tiled image
-	for(y=0;y<HEIGHT*PIXEL_HEIGHT;y++){
-	    for(x=0;x<WIDTH*PIXEL_WIDTH;x++){
-		//if the pixel is in the area selected
-		if(curArea.contains(x,y)){	//could it be done without .contains?
-		    //get the corresponding YUV pixel
-		    yuv=YUVdata[y*WIDTH*PIXEL_WIDTH+x];
-
-		    y_val=(yuv>>16)&0xff;
-		    u_val=(yuv>>8)&0xff;
-		    v_val=yuv&0xff;
-		    y_val=y_val>>4;
-		    u_val=u_val>>2;
-		    v_val=v_val>>2;
-
-		    //save the selected pixel color, or set it to conflict if previously set
-		    int y1,u1,v1;
-		    for(y1=y_val-Y_SMOOTH_FACTOR;y1<=y_val+Y_SMOOTH_FACTOR;y1++){
-			for(u1=u_val-U_SMOOTH_FACTOR;u1<=u_val+U_SMOOTH_FACTOR;u1++){
-			    for(v1=v_val-V_SMOOTH_FACTOR;v1<=v_val+V_SMOOTH_FACTOR;v1++){
-				index=(y1*size_u+u1)*size_v+v1;
-				
-				if(index>=0&&index<=size_total-1){
-				    if(tmap[index]==(byte)0){
-					tmap[index]=(byte)count;
-				    }
-				    else if(tmap[index]!=(byte)count){
-					tmap[index]=(byte)9;
-				    }
-				}
-			    }
-			}
-		    }
-		}
-	    }
-	}
-
-    }
-
-    public void save(String filename){
-	int dotpos=filename.lastIndexOf('.');
-	if (dotpos>0) filename=filename.substring(0,dotpos);
-    
-	try {
-	    FileOutputStream file_tm_fos=new FileOutputStream(filename + ".tm");
-	    OutputStreamWriter file_tm_osw=new OutputStreamWriter(file_tm_fos);
-	    file_tm_osw.write("TMAP\nYUV8\n" +
-			      size_y + " " + size_u + " " + size_v + "\n");
-	    file_tm_osw.flush();
-	    file_tm_fos.write(tmap);
-	    file_tm_osw.close();
-	    System.out.println(filename + ".tm saved");
-	} catch (Exception ex) {
-	    System.out.println("Error saving to "+filename +".tm: " + ex);
-	}
-
-	try {
-	    FileWriter file_col_fw=new FileWriter(filename + ".col");
-
-	    //grey
-	    file_col_fw.write("0 (128 128 128) \"unclassified\" 8 1.00\n");
-
-	    //selected colors
-	    for(int colors=0;colors<count;colors++){
-		//are 8 and 0.75 the best values?
-		file_col_fw.write((1+colors)+" ("+red[colors]+" "+green[colors]+" "+blue[colors]+") \""+names[colors]+"\" 8 0.75\n");
-	    }
-
-	    //black
-	    file_col_fw.write("9 (0 0 0) \"conflict\" 8 0.75\n");
-
-	    file_col_fw.close();
-
-	    System.out.println(filename + ".col saved");
-	    
-	} catch (Exception ex) {
-	    System.out.println("Error saving to "+filename + ".col: " + ex);
-	}
-
-
-
-    }
-
-    //ported mouse functions from TrainCanvas 
-    public void mousePressed(MouseEvent e) {
-
-	if (curArea==null) return;
-      
-	if (e.getButton()!=MouseEvent.BUTTON1) return;
-      
-	curSelectModified=curSelectModifier;
-      
-	if (curSelectModified!=MODIFIER_SHIFT
-	    && curSelectModified!=MODIFIER_CTRL)
-	    curArea.reset();
-      
-	curPoly=new Polygon();
-      
-	//standard
-	lastx=e.getX();
-	lasty=e.getY();
-	curPoly.addPoint(e.getX(), e.getY());
-      
-    
-	repaint();
-
-
-    }
-
-    public void mouseDragged(MouseEvent e) {
-	if (curArea==null) return;
-	try{
-	    int x=e.getX();
-	    int y=e.getY();
-	    if ((Math.abs(x-lastx)+Math.abs(y-lasty))>2) {
-		curPoly.addPoint(e.getX(), e.getY());
-		lastx=x;
-		lasty=y;
-		repaint();
-	    }
-	
-	}
-	catch(Exception ex){
-	    System.out.println("TileTrain::mouseDragged handled exception");
-	    System.out.println("Probably due to the mouse accidently dragging off the preview window");
-	}
-	repaint();
-      
-    }
-
-    public void mouseReleased(MouseEvent e) {
-	if (curArea==null) return;
-	if (e.getButton()!=MouseEvent.BUTTON1) return;
-	try{
-	    curPoly.addPoint(e.getX(), e.getY());
-
-  
-	    if (curPoly.npoints>=3) {
-		if (curSelectModified==MODIFIER_CTRL) curArea.subtract(new Area(curPoly));
-		else curArea.add(new Area(curPoly));
-	    }
-	}
-	catch(Exception ex){
-	    System.out.println("TileTrain::mouseReleased handled exception");
-	    System.out.println("Probably due to the mouse accidently dragging off the preview window");
-	}
-
-	curPoly=null;
-	repaint();
-    }
-
-    //pointing happening here
-    public void mouseMoved(MouseEvent e){
-      
-	//      repaint();
-      
-    }
-
-    public void mouseClicked(MouseEvent e){
-	
-    }
-
-    public void mouseExited(MouseEvent e){
-
-    }
-
-    public void mouseEntered(MouseEvent e){}
-    
-    public void update(Graphics g) {
-	Graphics2D g2d=(Graphics2D) g;
-
-	Dimension sz=getSize();
-      
-	//draw image
-	if (_image!=null)
-	    g2d.drawImage(_image, 0, 0, sz.width, sz.height, null);
-    
-	//line color
-	g2d.setColor(Color.white);
-
-	//add shapes
-	if (curArea!=null)
-	    g2d.draw(curArea);
-
-	if (curPoly!=null)
-	    g2d.draw(curPoly);
-  
-	//I hate that thing...so it's off.
-	//draw "hint" square
-	//g2d.drawRect(lastx-2, lasty-2, 5, 5);
-
-    }
-
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/TrainCanvas.java ./tools/seg/TrainCanvas.java
--- ../Tekkotsu_2.4.1/tools/seg/TrainCanvas.java	2005-08-09 21:53:10.000000000 -0400
+++ ./tools/seg/TrainCanvas.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,349 +0,0 @@
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.util.*;
-import java.awt.geom.*;
-import java.io.*;
-
-class TrainCanvas extends Canvas implements MouseListener,
-    MouseMotionListener, KeyListener {
-  BufferedImage image;
-  BufferedImage cachedplot;
-  BufferedImage inv_cachedplot;
-
-  Graphics2D graphics;
-  Polygon curPoly;
-  int lastx, lasty;
-  float f_width, f_height, f_offset;
-
-  Area curArea;
-  String curColor;
-  int curSelectModifier;
-  int curSelectModified;
-
-  Point imageHint;
-
-  Hashtable areasHash;
-
-  boolean inverted;
-
-  public static final int MODIFIER_NONE=0;
-  public static final int MODIFIER_SHIFT=1;
-  public static final int MODIFIER_CTRL=2;
-
-  float[] xy;
-  int[] rgb;
-
-  public TrainCanvas() {
-    setBackground(Color.black);
-    addMouseListener(this);
-    addMouseMotionListener(this);
-    curSelectModifier=MODIFIER_NONE;
-    curSelectModified=MODIFIER_NONE;
-    addKeyListener(this);
-    areasHash=new Hashtable();
-    inverted=false;
-    imageHint=null;
-  }
-
-  public void plotImage(float[] xy, int[] rgb) {
-    this.xy=xy;
-    this.rgb=rgb;
-    Dimension d=getSize();
-    f_width=(float)d.width-41;
-    f_height=(float)d.height-41;
-    f_offset=20;
-    cachedplot=new BufferedImage(d.width, d.height, BufferedImage.TYPE_INT_RGB);
-    inv_cachedplot=
-               new BufferedImage(d.width, d.height, BufferedImage.TYPE_INT_RGB);
-
-    graphics=(Graphics2D)cachedplot.getGraphics();
-    Graphics2D inv_graphics=(Graphics2D)inv_cachedplot.getGraphics();
-
-    inv_graphics.setColor(Color.white);
-    inv_graphics.fillRect(0,0,d.width, d.height);
-
-    for (int i=0; i<rgb.length; i++) {
-      //      draws thin
-      //      cachedplot.setRGB((int)(xy[i*2]*f_width),
-      //                        (int)(xy[i*2+1]*f_height), rgb[i]);
-
-      // draws thick
-      graphics.setColor(new Color(rgb[i]));
-      graphics.drawRect((int)(xy[i*2]*f_width+f_offset),
-                        (int)(xy[i*2+1]*f_height+f_offset), 1,1);
-
-      inv_graphics.setColor(new Color(rgb[i]));
-      inv_graphics.drawRect((int)(xy[i*2]*f_width+f_offset),
-                        (int)(xy[i*2+1]*f_height+f_offset), 1,1);
-    }
-
-    image=new BufferedImage(d.width, d.height, BufferedImage.TYPE_INT_RGB);
-    graphics=(Graphics2D)image.getGraphics();
-//    graphics.drawImage(cachedplot,0,0,this);
-    redrawScene();
-    repaint();
-  }
-
-  public void mousePressed(MouseEvent e) {
-    if (curArea==null) return;
-    if (e.getButton()!=MouseEvent.BUTTON1) return;
-
-    curSelectModified=curSelectModifier;
-
-    if (curSelectModified!=MODIFIER_SHIFT
-        && curSelectModified!=MODIFIER_CTRL)
-      curArea.reset();
-
-    curPoly=new Polygon();
-    lastx=e.getX();
-    lasty=e.getY();
-    curPoly.addPoint(e.getX(), e.getY());
-    repaint();
-  }
-
-  public void mouseDragged(MouseEvent e) {
-    if (curArea==null) return;
-
-    int x=e.getX();
-    int y=e.getY();
-    if ((Math.abs(x-lastx)+Math.abs(y-lasty))>2) {
-      curPoly.addPoint(e.getX(), e.getY());
-      lastx=x;
-      lasty=y;
-      repaint();
-    }
-  }
-
-  public void mouseReleased(MouseEvent e) {
-    if (curArea==null) return;
-    if (e.getButton()!=MouseEvent.BUTTON1) return;
-
-    curPoly.addPoint(e.getX(), e.getY());
-    if (curPoly.npoints>=3) {
-      if (curSelectModified==MODIFIER_CTRL) curArea.subtract(new Area(curPoly));
-      else curArea.add(new Area(curPoly));
-    }
-    curPoly=null;
-    repaint();
-  }
-
-  public void mouseMoved(MouseEvent e){
-    Object source=e.getSource();
-    if (source instanceof ImageShow) {
-      ImageShow imageShow=(ImageShow)source;
-      int rgb=imageShow.getPixel(e.getX(), e.getY());
-      float[] xy=VisionTrain.colorConverter.getColor(rgb);
-      int x=(int)(xy[0]*f_width+f_offset);
-      int y=(int)(xy[1]*f_height+f_offset);
-      imageHint=new Point(x, y);
-      repaint();
-    }
-  }
-
-  public void mouseClicked(MouseEvent e){}
-  public void mouseExited(MouseEvent e){
-    if (e.getSource() instanceof ImageShow) {
-      imageHint=null;
-      repaint();
-    }
-  }
-  public void mouseEntered(MouseEvent e){}
-  public void updateLocation(MouseEvent e){}
-
-  public void paint(Graphics g) {
-    update(g);
-  }
-
-  public void update(Graphics g) {
-    Graphics2D g2d=(Graphics2D) g;
-    if (image!=null) g.drawImage(image, 0, 0, this);
-    if (inverted)
-      g2d.setColor(Color.black);
-    else
-      g2d.setColor(Color.white);
-
-    if (curArea!=null)
-      g2d.draw(curArea);
-
-    if (curPoly!=null)
-      g2d.draw(curPoly);
-
-    if (imageHint!=null) {
-      g2d.drawRect(imageHint.x-2, imageHint.y-2, 5, 5);
-    }
-  }
-
-  public void setCurColor(String color) {
-    curColor=color;
-    if (color==null) {
-      curArea=null;
-      return;
-    }
-
-    curArea=(Area)areasHash.get(color);
-    if (curArea==null) {
-      curArea=new Area();
-      areasHash.put(color, curArea);
-    }
-    redrawScene();
-  }
-
-  public void clear () {
-    if (curArea==null) return;
-    curArea.reset();
-    redrawScene();
-  }
-
-  public void invert () {
-    inverted=!inverted;
-    redrawScene();
-  }
-
-  public void remove(String color) {
-    curColor=null;
-    curArea=null;
-    areasHash.remove(color);
-    redrawScene();
-  }
-
-  public void redrawScene() {
-    if (inverted)
-      graphics.drawImage(inv_cachedplot,0,0,this);
-    else 
-      graphics.drawImage(cachedplot,0,0,this);
-    graphics.setColor(Color.gray);
-    Collection values=areasHash.values();
-    for (Iterator i=values.iterator(); i.hasNext(); ) {
-      Area area=(Area)i.next();
-      if (area!=curArea)
-        graphics.draw(area);
-    }
-    repaint();  
-  }
-
-  public void keyPressed(KeyEvent e) {
-    if (e.getKeyCode()==KeyEvent.VK_SHIFT) {
-      curSelectModifier=MODIFIER_SHIFT;
-    } else if (e.getKeyCode()==KeyEvent.VK_CONTROL) {
-      curSelectModifier=MODIFIER_CTRL;
-    }
-  }
-
-  public void keyReleased(KeyEvent e) {
-    if (e.getKeyCode()==KeyEvent.VK_SHIFT
-        ||e.getKeyCode()==KeyEvent.VK_CONTROL) {
-      curSelectModifier=MODIFIER_NONE;
-    }
-  }
-
-  public void keyTyped(KeyEvent e) { }
-
-  public void save (String filename) {
-    int dotpos=filename.lastIndexOf('.');
-    if (dotpos>0) filename=filename.substring(0,dotpos);
-    
-    Enumeration colors=areasHash.keys();
-    ArrayList colornames=new ArrayList(20);
-    while (colors.hasMoreElements()) colornames.add(colors.nextElement());
-    Collections.sort(colornames);
-    ArrayList areas=new ArrayList(20);
-
-    for (Iterator i=colornames.iterator(); i.hasNext();
-         areas.add(areasHash.get(i.next())));
-    
-    int size_y=16, size_u=64, size_v=64;
-    byte[] tmap=new byte[size_y*size_u*size_v];
-
-    float[] hsb=new float[3];
-    int y, u, v, r, g, b, h, s;
-    int iy, iu, iv, i;
-
-    for (iy=0; iy<16; iy++) {
-      for (iu=0; iu<64; iu++) {
-        for (iv=0; iv<64; iv++) {
-          y=iy<<4; u=iu<<2; v=iv<<2;
-          u=u*2-255;
-          v=v*2-255;
-          r=y+u;
-          b=y+v;
-          u=u>>1;
-          v=(v>>2)-(v>>4);
-          g=y-u-v;
-          if (r<0) r=0; if (g<0) g=0; if (b<0) b=0;
-          if (r>255) r=255; if (g>255) g=255; if (b>255) b=255;
-          float[] xy=VisionTrain.colorConverter.getColor(r, g, b);
-          h=(int)(xy[0]*f_width+f_offset);
-          s=(int)(xy[1]*f_height+f_offset);
-          Point point=new Point(h, s);
-          for (i=0; i<areas.size(); i++) {
-            Area area = (Area) areas.get(i);
-            if (area.contains(point)) {
-              tmap[(iy*size_u+iu)*size_v+iv]=(byte)(i+1);
-              break;
-            }
-          }
-        }
-      }
-    }
-
-    try {
-      FileOutputStream file_tm_fos=new FileOutputStream(filename + ".tm");
-      OutputStreamWriter file_tm_osw=new OutputStreamWriter(file_tm_fos);
-      file_tm_osw.write("TMAP\nYUV8\n" +
-          size_y + " " + size_u + " " + size_v + "\n");
-      file_tm_osw.flush();
-      file_tm_fos.write(tmap);
-      file_tm_osw.close();
-    } catch (Exception ex) {
-      System.out.println("Error saving to "+filename +".tm: " + ex);
-    }
-
-    int[][] avgcolors=new int[areas.size()][4]; 
-
-    int skip=(rgb.length/10000)+1;
-    for (i=0; i<rgb.length; i+=skip) {
-      for (int a=0; a<areas.size(); a++) {
-        Area area=(Area)areas.get(a);
-        Point p=new Point((int)(xy[i*2]*f_width+f_offset),
-                          (int)(xy[i*2+1]*f_height+f_offset));
-        if (area.contains(p)) {
-          avgcolors[a][0]+=(rgb[i]>>16)&0xff;
-          avgcolors[a][1]+=(rgb[i]>>8)&0xff;
-          avgcolors[a][2]+=rgb[i]&0xff;
-          avgcolors[a][3]++;
-        }
-      }
-    }
-
-    for (i=0; i<avgcolors.length; i++) {
-      if (avgcolors[i][3]>0) {
-        avgcolors[i][0]=avgcolors[i][0]/avgcolors[i][3];
-        avgcolors[i][1]=avgcolors[i][1]/avgcolors[i][3];
-        avgcolors[i][2]=avgcolors[i][2]/avgcolors[i][3];
-      } else {
-        avgcolors[i][0]=0;
-        avgcolors[i][1]=0;
-        avgcolors[i][2]=0;
-      }
-    }
- 
-    try {
-      FileWriter file_col_fw=new FileWriter(filename + ".col");
-      file_col_fw.write("0 (128 128 128) \"unclassified\" 8 1.00\n");
-      for (i=0; i<areas.size(); i++) {
-        file_col_fw.write((i+1)+ " (" +
-                          avgcolors[i][0] + " " +
-                          avgcolors[i][1] + " " +
-                          avgcolors[i][2] + ") " +
-                          "\"" + colornames.get(i)+ "\" 8 0.75\n");
-      }
-
-      file_col_fw.close();
-    } catch (Exception ex) {
-      System.out.println("Error saving to "+filename + ".col: " + ex);
-    }
-  }
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/UseThresh.java ./tools/seg/UseThresh.java
--- ../Tekkotsu_2.4.1/tools/seg/UseThresh.java	2003-10-09 15:54:36.000000000 -0400
+++ ./tools/seg/UseThresh.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,56 +0,0 @@
-
-public class UseThresh {
-  public static void main(String s[]) {
-    if (s.length<2) {
-      System.out.println("usage: java UseThresh threshfile colfile [host]");
-      System.out.println("       will upload as default.tm and default.col");
-      System.out.println("       the host will have to be rebooted to reload vision files");
-      System.exit(1);
-    }
-
-		String tm=s[0];
-		String col=s[1];
-		String[] addrs;
-		if(s.length>2) {
-			addrs=new String[s.length-2];
-			for(int i=0; i<s.length-2; i++)
-				addrs[i]=s[i+2];
-		} else
-			addrs=new String[0];
-
-    try {
-      DogConfig dogConfig=new DogConfig (addrs);
-      DogConfigFTP dog_ftp=new DogConfigFTP(dogConfig.getIP(), 21,
-                                            "config", "config");
-			String dogtm=dogConfig.getValue("Vision","thresh");
-			dogtm=col.substring(col.lastIndexOf('/')+1);
-      dog_ftp.putFile(tm,dogtm);
-      sleep(1000);
-      dog_ftp=new DogConfigFTP(dogConfig.getIP(), 21,
-                                            "config", "config");
-			String dogcol=dogConfig.getValue("Vision","colors");
-			dogcol=col.substring(col.lastIndexOf('/')+1);
-      dog_ftp.putFile(col,dogcol);
-      sleep(1000);
-			//Someday.... dynamic reloading...
-      /*
-				TextListener listener=new TextListener(dogConfig.getIP(),
-          Integer.parseInt(dogConfig.getValue("Controller", "gui_port")));
-      while (!listener.isConnected()) {
-        sleep(10);
-      }
-			listener.write("!set vision.thresh=/ms/config/"+tm+"\n");
-			listener.write("!set vision.colors=/ms/config/"+col+"\n");
-      sleep(100);
-      listener.kill();
-			*/
-    } catch (IllegalArgumentException ex) {
-    } catch (Exception ex) {
-      ex.printStackTrace();
-    }
-  }
-
-  public static final void sleep(int tm) {
-    try { Thread.sleep(tm); } catch (Exception ex) {} 
-  }
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/VisionFilter.java ./tools/seg/VisionFilter.java
--- ../Tekkotsu_2.4.1/tools/seg/VisionFilter.java	2003-07-28 02:31:46.000000000 -0400
+++ ./tools/seg/VisionFilter.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,58 +0,0 @@
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.io.*;
-import java.util.*;
-
-public class VisionFilter {
-  static final int size_y=16;
-  static final int size_u=64;
-  static final int size_v=64;
-  
-  public static void main(String args[]) {
-    if (args.length!=2) {
-      System.out.println("usage: java VisionFilter infile outfile");
-      System.exit(0);
-    }
-    VisionFilter filter=new VisionFilter(args[0], args[1]);
-  }
-
-  public VisionFilter (String infile, String outfile) {
-    try {
-      FileInputStream in=new FileInputStream(infile);
-      FileOutputStream out=new FileOutputStream(outfile);
-
-      byte[] tmdata=new byte[65536];
-      in.read(tmdata,0,19);
-      out.write(tmdata,0,19);
-      in.read(tmdata);
-
-      filter(tmdata);
-
-      out.write(tmdata);
-      in.close();
-      out.close();
-    } catch (Exception ex) {
-      System.out.println(ex);
-    }
-  }
-
-  void filter(byte[] data) {
-    int y, u, v;
-    int cnt=0; 
-    for (y=0; y<16; y++)
-      for (u=0; u<64; u++)
-        for (v=0; v<64; v++)
-          if (data[offset(y, u, v)]==1) {
-            data[offset(y, u, v)]=9;
-            cnt++;
-          }
-    System.out.println(cnt);
-  }
-
-  static final int offset(int y, int u, int v) {
-    return (y*size_u+u)*size_v+v;
-  }
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/VisionSegment.java ./tools/seg/VisionSegment.java
--- ../Tekkotsu_2.4.1/tools/seg/VisionSegment.java	2004-01-20 22:32:26.000000000 -0500
+++ ./tools/seg/VisionSegment.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,191 +0,0 @@
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.io.*;
-import java.util.*;
-
-public class VisionSegment extends JFrame implements KeyListener {
-  BufferedImage _image;
-  String[] imglist;
-  byte[] tmap;
-  ImageData imageData;
-  int curimg;
-	boolean isRGB;
-
-  public static void main(String args[]) {
-    if (args.length<3)
-			usageAndExit();
-		boolean isRGB=true;
-		if(args[0].equals("-isRGB"))
-			isRGB=true;
-		else if(args[0].equals("-isYUV"))
-			isRGB=false;
-		else {
-			System.out.println(args[0]+" is not valid color mode");
-			usageAndExit();
-		}
-		
-		String newargs[]=new String[args.length-1];
-		for(int i=0; i<newargs.length; i++)
-			newargs[i]=args[i+1];
-
-    VisionSegment visionSegment=new VisionSegment(isRGB,newargs);
-    visionSegment.addWindowListener(new WindowAdapter() {
-        public void windowClosing(WindowEvent e) { System.exit(0); } });
-  }
-
-	public static void usageAndExit() {
-		System.out.println("usage: java VisionSegment (-isRGB|-isYUV) threshold_file colors_file raw_image [raw images]");
-		System.exit(1);
-	}
-  public VisionSegment (boolean isRGB, String args[]) {
-    imageData=new ImageData();
-		if(isRGB)
-			imageData.loadRGBFileAsYUV(args[2]);
-		else
-			imageData.loadYUVFileAsYUV(args[2]);
-		this.isRGB=isRGB;
-
-    int[] data=imageData.getPixels();
-    tmap=readThresholdMap(args[0]);
-    IndexColorModel cmodel=readColorModel(args[1]);
-
-    if (tmap==null || cmodel==null) return;
-
-    setBackground(Color.black);
-    setSize(imageData.image_width*2, imageData.image_height*2);
-    _image=new BufferedImage(imageData.image_width, imageData.image_height,
-        BufferedImage.TYPE_BYTE_INDEXED,cmodel);
-   
-    segmentImage(data, tmap, imageData.image_width, imageData.image_height);
-
-    imglist=new String[args.length-2];
-    curimg=0;
-    for (int i=2; i<args.length; i++) {
-      imglist[i-2]=args[i];
-    }
-
-    show();
-    addKeyListener(this);
-  }
-
-  void segmentImage(int[] data, byte[] tmap, int width, int height) {
-    int size_y=16, size_u=64, size_v=64;
-    byte[] imgdata=new byte[data.length];
-
-    for (int i=0; i<data.length; i++) {
-      int y=(data[i]>>16)&0xff;
-      int u=(data[i]>>8)&0xff;
-      int v=data[i]&0xff;
-      y=y>>4;
-      u=u>>2;
-      v=v>>2;
-      imgdata[i]=tmap[(y*size_u+u)*size_v+v];
-    }
-    _image.getRaster().setDataElements(0,0,width,height,imgdata);
-    repaint();
-  }
-
-  IndexColorModel readColorModel(String colorsfile) {
-    int[] cmap=readColorMap(colorsfile);
-    if (cmap==null || cmap.length==0) return null;
-    byte[] byte_cmap=new byte[cmap.length*3];
-
-    for (int i=0; i<cmap.length; i++) {
-      byte_cmap[i*3]=(byte) ((cmap[i]>>16) & 0xff);
-      byte_cmap[i*3+1]=(byte) ((cmap[i]>>8) & 0xff);
-      byte_cmap[i*3+2]=(byte) (cmap[i] & 0xff);
-    }
-    IndexColorModel cmodel=new IndexColorModel(7, cmap.length, byte_cmap,
-                                               0, false); 
-    return cmodel;
-  }
-
-  byte[] readThresholdMap(String thresholdfile) {
-    try {
-      byte[] tmdata=new byte[65536];
-      FileInputStream file_tm_fis=new FileInputStream(thresholdfile);
-      file_tm_fis.read(tmdata,0,19);
-      file_tm_fis.read(tmdata);
-      file_tm_fis.close();
-      return tmdata;
-    } catch (Exception ex) {
-      System.out.println("Error reading file "+thresholdfile+": "+ex);
-      return null;
-    }
-  }
-
-  int[] readColorMap(String colorsfile) {
-    try {
-      BufferedReader reader=new BufferedReader(new FileReader(colorsfile));
-      int[] v=new int[32];
-      int vnum=0;
-      String s=reader.readLine();
-      while(s!=null) {
-        if (s.length()==0 || s.charAt(0)=='#') { s=reader.readLine(); continue; }
-        
-        int pos=Integer.parseInt(s.substring(0,s.indexOf(" ")));
-
-        String colorstr=s.substring(s.indexOf("(")+1, s.indexOf(")")).trim();
-        String[] colorarr=colorstr.split("\\s+");
-
-        int color=0;
-        color|=Integer.parseInt(colorarr[0])<<16;
-        color|=Integer.parseInt(colorarr[1])<<8;
-        color|=Integer.parseInt(colorarr[2]);
-
-        v[pos]=color;
-        if (pos>vnum) vnum=pos;
-        s=reader.readLine();
-      }
-      int[] colors=new int[vnum+1];
-      for (int i=0; i<=vnum; i++) {
-        colors[i]=v[i];
-      }
-      return colors;
-    } catch (Exception ex) {
-      System.out.println("Error reading file "+colorsfile+": "+ex);
-      return null;
-    }
-  }
-
-  public void paint(Graphics graphics) {
-    Dimension sz=getSize();
-    if (_image!=null)
-      graphics.drawImage(_image, 0, 0, sz.width, sz.height, null);
-  }
-
-  public void keyPressed(KeyEvent e) {
-    if (e.getKeyCode()==KeyEvent.VK_LEFT ||
-        e.getKeyCode()==KeyEvent.VK_UP ||
-        e.getKeyCode()==KeyEvent.VK_PAGE_UP ||
-        e.getKeyCode()==KeyEvent.VK_KP_UP ||
-        e.getKeyCode()==KeyEvent.VK_KP_LEFT) {
-      curimg--;
-      if (curimg<0) curimg+=imglist.length;
-			if(isRGB)
-				imageData.loadRGBFileAsYUV(imglist[curimg]);
-			else
-				imageData.loadYUVFileAsYUV(imglist[curimg]);
-      int[] data=imageData.getPixels();
-      segmentImage(data, tmap, imageData.image_width, imageData.image_height);
-    } else if (e.getKeyCode()==KeyEvent.VK_RIGHT ||
-        e.getKeyCode()==KeyEvent.VK_DOWN ||
-        e.getKeyCode()==KeyEvent.VK_PAGE_DOWN ||
-        e.getKeyCode()==KeyEvent.VK_KP_DOWN ||
-        e.getKeyCode()==KeyEvent.VK_KP_RIGHT) {
-      curimg++;
-      if (curimg>=imglist.length) curimg-=imglist.length;
-			if(isRGB)
-				imageData.loadRGBFileAsYUV(imglist[curimg]);
-			else
-				imageData.loadYUVFileAsYUV(imglist[curimg]);
-      int[] data=imageData.getPixels();
-      segmentImage(data, tmap, imageData.image_width, imageData.image_height);
-    }
-  }
-  public void keyReleased(KeyEvent e) { }
-  public void keyTyped(KeyEvent e) { }
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/VisionTrain.java ./tools/seg/VisionTrain.java
--- ../Tekkotsu_2.4.1/tools/seg/VisionTrain.java	2005-08-09 21:53:10.000000000 -0400
+++ ./tools/seg/VisionTrain.java	1969-12-31 19:00:00.000000000 -0500
@@ -1,83 +0,0 @@
-import java.awt.image.*;
-import java.awt.*;
-import javax.swing.*;
-import javax.swing.event.*;
-import java.awt.event.*;
-import java.util.*;
-import java.awt.geom.*;
-import java.io.*;
-
-public class VisionTrain extends JFrame {
-  int height=700, width=700;
-  public ColorControlPanel controlPanel;
-  public static ColorConverter colorConverter;
-
-  public static void main(String args[]) {
-    if (args.length<1) {
-			usageAndExit();
-    }
-    colorConverter=new ColorConverter() {
-      public final float[] getColor(int r, int g, int b) {
-        float[] hsb=new float[3];
-        Color.RGBtoHSB(r, g, b, hsb);
-        float[] res=new float[2];
-        res[0]=hsb[0];
-        res[1]=hsb[1];
-        return res;
-      }
-    };
-    
-		boolean isRGB=true;
-		if(args[0].equals("-isRGB"))
-			isRGB=true;
-		else if(args[0].equals("-isYUV"))
-			isRGB=false;
-		else {
-			System.out.println(args[0]+" is not valid color mode");
-			usageAndExit();
-		}
-		
-		String files[]=new String[args.length-1];
-		for(int i=0; i<files.length; i++)
-			files[i]=args[i+1];
-
-    VisionTrain visionTrain=new VisionTrain(isRGB,files);
-    visionTrain.addWindowListener(new WindowAdapter() {
-        public void windowClosing(WindowEvent e) { System.exit(0); } });
-    visionTrain.controlPanel.addWindowListener(new WindowAdapter() {
-        public void windowClosing(WindowEvent e) { System.exit(0); } });
-  }
-
-	public static void usageAndExit() {
-		System.out.println("usage: java VisionTrain (-isRGB|-isYUV) filename [filename ..]");
-		System.out.println("       Using YUV images is recommended.");
-		System.out.println("       A mode must be specified.");
-		System.exit(1);
-	}
- 
-  public VisionTrain(boolean isRGB, String files[]) {
-		System.out.println("Interpreting images as "+(isRGB?"RGB":"YUV")+" colorspace");
-    ImageShow imageShow=new ImageShow(isRGB,files);
-    
-    setBackground(Color.black);
-    setSize(new Dimension(width, height));
-    Container root=this.getContentPane();
-    root.setLayout(new BorderLayout());
-    TrainCanvas trainCanvas=new TrainCanvas();
-    root.add(trainCanvas);
-    addKeyListener(trainCanvas);
-    show();
-
-    controlPanel=new ColorControlPanel(trainCanvas, imageShow);
-
-    ImageData imageData=new ImageData();
-
-		//Thanks to martin.mueller at mni.fh-giessen.de for the bug fix:
-		if(isRGB)
-			imageData.loadFullRGBFilesAsRGB(files);
-		else 
-			imageData.loadFullYUVFilesAsRGB(files);
-    trainCanvas.plotImage(imageData.getHS(), imageData.getPixels());
-  }
-}
-
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/seg/Vote.java ./tools/seg/Vote.java
--- ../Tekkotsu_2.4.1/tools/seg/Vote.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/seg/Vote.java	2006-09-13 18:30:49.000000000 -0400
@@ -0,0 +1,63 @@
+import java.awt.image.*;
+import java.awt.*;
+import javax.swing.*;
+import javax.swing.event.*;
+import java.awt.event.*;
+import java.io.*;
+import java.util.*;
+
+public class Vote {
+	public static void main(String args[]) {
+		if (args.length<3) {
+			System.out.println("usage: java Vote infile1 [infile2 ...] outfile");
+			System.out.println("       Each threshold file casts a vote for each classified color.");
+			System.out.println("       The output is the 'winning' classification for each.");
+			System.out.println("       Hint: pass a threshold multiple times to weight it more heavily.");
+			System.out.println("       For this to make any sense, each threshold file must agree on the color indicies");
+			System.exit(2);
+		}
+		Vote filter=new Vote(args);
+	}
+
+	final static byte MAX_INDEX=10;
+
+	public Vote (String files[]) {
+		try {
+			byte[] header=new byte[20];
+			byte[][] votes=new byte[65536][MAX_INDEX];
+			byte[] tmdata=new byte[65536];
+
+
+			for (int i=0; i<votes.length; i++)
+				for(byte j=0; j<MAX_INDEX; ++j)
+					votes[i][j]=0;
+
+			for (int i=0; i<files.length-1; i++) {
+				System.out.println("Processing "+files[i]+ "...");
+				FileInputStream in=new FileInputStream(files[i]);
+				in.read(header);
+				in.read(tmdata);
+				in.close();
+				for (int j=0; j<tmdata.length; j++) {
+					//System.out.println(j+": "+tmdata[j]);
+					if(tmdata[j]!=0) {
+						votes[j][tmdata[j]]++;
+					}
+				}
+			}
+			
+			for (int i=0; i<tmdata.length; i++) {
+				tmdata[i]=0;
+				for(byte j=1; j<MAX_INDEX; ++j)
+					if(votes[i][j]>votes[i][tmdata[i]])
+						tmdata[i]=j;
+			}
+			FileOutputStream out=new FileOutputStream(files[files.length-1]);
+			out.write(header);
+			out.write(tmdata);
+			out.close();
+		} catch (Exception ex) {
+			ex.printStackTrace();
+		}
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/test/base64/Makefile ./tools/test/base64/Makefile
--- ../Tekkotsu_2.4.1/tools/test/base64/Makefile	2005-08-16 16:13:22.000000000 -0400
+++ ./tools/test/base64/Makefile	2006-03-28 12:08:24.000000000 -0500
@@ -26,7 +26,7 @@
 $(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))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
-include $(TEKKOTSU_ENVIRONMENT_CONFIGURATION)
+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))
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/test/base64/base64.cc ./tools/test/base64/base64.cc
--- ../Tekkotsu_2.4.1/tools/test/base64/base64.cc	2005-08-16 15:37:11.000000000 -0400
+++ ./tools/test/base64/base64.cc	2005-09-13 19:04:06.000000000 -0400
@@ -57,8 +57,10 @@
     }
     unsigned int len=base64::decodeSize(enc);
     write(STDOUT_FILENO,dat,len);
+		delete [] dat;
   }
-  
+  delete [] buf;
+
   destruct();
   return 0;
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/test/kinematics/Makefile ./tools/test/kinematics/Makefile
--- ../Tekkotsu_2.4.1/tools/test/kinematics/Makefile	2005-08-16 16:13:26.000000000 -0400
+++ ./tools/test/kinematics/Makefile	2006-03-28 12:08:24.000000000 -0500
@@ -26,7 +26,7 @@
 $(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))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
-include $(TEKKOTSU_ENVIRONMENT_CONFIGURATION)
+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))
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/test/network/Makefile ./tools/test/network/Makefile
--- ../Tekkotsu_2.4.1/tools/test/network/Makefile	2005-08-16 16:13:28.000000000 -0400
+++ ./tools/test/network/Makefile	2006-03-28 12:08:24.000000000 -0500
@@ -26,7 +26,7 @@
 $(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))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
-include $(TEKKOTSU_ENVIRONMENT_CONFIGURATION)
+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))
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/test/network/network.cc ./tools/test/network/network.cc
--- ../Tekkotsu_2.4.1/tools/test/network/network.cc	2005-08-01 19:18:00.000000000 -0400
+++ ./tools/test/network/network.cc	2006-09-27 17:21:01.000000000 -0400
@@ -14,19 +14,21 @@
 int main(int argc, char** argv) {
 	initialize(); //minisim function for global setup
 	
+	{//restricting scope so behavior is destructed before minisim::destruct is called
 
-	EchoBehavior eb;
-	eb.SetAutoDelete(false); //needed when using stack allocation
-	eb.DoStart();
-
-	for(string in; cin; getline(cin,in)) {
-		if(in.size()>0) {
-			erouter->postEvent(new TextMsgEvent(in));
+		EchoBehavior eb;
+		eb.SetAutoDelete(false); //needed when using stack allocation
+		eb.DoStart();
+		
+		for(string in; cin; getline(cin,in)) {
+			if(in.size()>0) {
+				erouter->postEvent(TextMsgEvent(in));
+			}
 		}
-	}
+		
+		eb.DoStop();
 
-	eb.DoStop();
-	
+	}//restricting scope so behavior is destructed before minisim::destruct is called
 	
 	destruct(); //minisim function for global teardown
 	return 0;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/test/plist/Makefile ./tools/test/plist/Makefile
--- ../Tekkotsu_2.4.1/tools/test/plist/Makefile	2005-08-16 16:16:15.000000000 -0400
+++ ./tools/test/plist/Makefile	2006-03-28 12:08:24.000000000 -0500
@@ -26,7 +26,7 @@
 $(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))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
-include $(TEKKOTSU_ENVIRONMENT_CONFIGURATION)
+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))
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/test/plist/ideal-savetest.plist ./tools/test/plist/ideal-savetest.plist
--- ../Tekkotsu_2.4.1/tools/test/plist/ideal-savetest.plist	2005-07-27 01:58:55.000000000 -0400
+++ ./tools/test/plist/ideal-savetest.plist	2006-09-27 17:20:26.000000000 -0400
@@ -13,10 +13,55 @@
 <!--fooI: This is an integer value, the other is a float-->
     <key>fooI</key>
       <integer>16</integer>
-    </dict>
+    
+    <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>
-  </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/>
+</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>
+</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>
+</array>
+</dict>
 </plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/test/plist/ideal-virgin.plist ./tools/test/plist/ideal-virgin.plist
--- ../Tekkotsu_2.4.1/tools/test/plist/ideal-virgin.plist	2005-08-16 16:16:15.000000000 -0400
+++ ./tools/test/plist/ideal-virgin.plist	2006-09-27 17:20:27.000000000 -0400
@@ -1,12 +1,47 @@
 <?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>
+<!--======== 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/>
+</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>
+</dict>
+
 <!--======== numeric ========-->
 <!--numeric contains some numeric values
 	One is a float
-	The other is an int-->
+	The other is an int
+	...and a char as text for good measure-->
 <key>numeric</key> <dict>
-    <key>fooF</key> <real>3.1415927410125732</real>
+    <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>
@@ -14,4 +49,15 @@
 
 <!--test str: Seen this one before?-->
 <key>test str</key> <string>Hello world!</string>
+
+<!--======== 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>
+</array>
 </dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/test/plist/plist.cc ./tools/test/plist/plist.cc
--- ../Tekkotsu_2.4.1/tools/test/plist/plist.cc	2005-07-27 01:58:55.000000000 -0400
+++ ./tools/test/plist/plist.cc	2006-09-27 18:15:41.000000000 -0400
@@ -1,3 +1,4 @@
+#include <vector>
 #include "Shared/plist.h"
 #include "Events/VisionObjectEvent.h"
 #include <cmath>
@@ -6,32 +7,77 @@
 using namespace std;
 
 int main(int argc, const char** argv) {
-  Primitive<int> fooI=42;
-  Primitive<float> fooF=M_PI;
-  Primitive<std::string> str("Hello world!");
+	Dictionary outer;
 	
-  Dictionary outer;
-  Dictionary inner;
-  inner.addEntry("fooI",fooI,"This is an integer value, the other is a float");
-  inner.addEntry("fooF",fooF);
-  outer.addEntry("numeric",inner,"numeric contains some numeric values\n\tOne is a float\n\tThe other is an int");
-  outer.addEntry("test str",str,"Seen this one before?");
+	// Dictionary within a dictionary
+	Dictionary inner;
+	// This inner dictionary will be labeled "numeric" in the outer dictionary
+	outer.addEntry("numeric",inner,"numeric contains some numeric values\n\tOne is a float\n\tThe other is an int\n\t...and a char as text for good measure");
 	
-  if(!outer.SaveFile("virgin.plist")) {
-    cerr << "Save virgin had error" << endl;
-    return 1;
-  }
-  if(!outer.LoadFile("loadtest.plist")) {
-    cerr << "Load test had error" << endl;
-    return 1;
-  }
-  str="Hello World, again!";
-  if(!outer.SaveFile("savetest.plist")) {
-    cerr << "Save test had error" << endl;
-    return 1;
-  }
-
-  VisionObjectEvent e(0,EventBase::activateETID);
-  e.SaveFile("vision.event");
-  return 0;
+	// These numeric tests will be stored in the inner dictionary
+	Primitive<int> fooI=42;
+	inner.addEntry("fooI",fooI,"This is an integer value, the other is a float");
+	
+	Primitive<float> fooF=M_PI;
+	inner.addEntry("fooF",fooF);
+	
+	// chars can be treated as either a character (i.e. one letter
+	// string) or a byte (i.e. 8 bit value)
+	Primitive<char> fooC1='a'; // by default is a letter
+	fooC1.setNumeric(false);  // can confirm this through setNumeric
+	inner.addEntry("char-text",fooC1);
+	
+	Primitive<char> fooC2('a',true); //...can also setNumeric through constructor
+	inner.addEntry("char-num",fooC2);
+	
+	// OK, back to add some more to the outer dictionary
+	Primitive<std::string> str("Hello world!");
+	outer.addEntry("test str",str,"Seen this one before?");
+	
+	Array mixed;
+	outer.addEntry("Mixed",mixed,"A collection of mixed types of specified length");
+	Primitive<int> itema=0; mixed.addEntry(itema);
+	Primitive<int> itemb=1; mixed.addEntry(itemb);
+	Primitive<int> itemc=2; mixed.addEntry(itemc);
+	Primitive<std::string> item1="This is item 1"; mixed.addEntry(item1);
+	Primitive<std::string> item2="item 2: arrays can contain mixed types"; mixed.addEntry(item2);
+	Primitive<float> item3 = 123; mixed.addEntry(item3,"like this int");
+	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
+	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
+	outer.addEntry("map",m,"The squares, from 0 to 5, but with keys");
+	for(int i=0; i<5; i++) {
+		stringstream ss;
+		ss << i << "^2";
+		m.addValue(ss.str(),i*i); //now we use value types, the vector maintains the Primitive<>'s internally
+	}
+	m.addValue("tada","mixed types -- no surprise");
+	
+	cout << outer;
+	
+	if(!outer.saveFile("virgin.plist")) {
+		cerr << "Save virgin had error" << endl;
+		return 1;
+	}
+	if(!outer.loadFile("loadtest.plist")) {
+		cerr << "Load test had error" << endl;
+		return 1;
+	}
+	str="Hello World, again!";
+	if(!outer.saveFile("savetest.plist")) {
+		cerr << "Save test had error" << endl;
+		return 1;
+	}
+	
+	VisionObjectEvent e(0,EventBase::activateETID);
+	e.setTimeStamp(0); // ensures precisely repeatable results
+	e.saveFile("vision.event");
+	return 0;
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/test/worldstatepool/Makefile ./tools/test/worldstatepool/Makefile
--- ../Tekkotsu_2.4.1/tools/test/worldstatepool/Makefile	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/worldstatepool/Makefile	2006-09-27 18:01:32.000000000 -0400
@@ -0,0 +1,91 @@
+
+# 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
+
+# Source files, defaults to all files ending matching *$(SRCSUFFIX)
+SRCSUFFIX:=.cc
+PROJ_SRC:=$(shell find . -name "*$(SRCSUFFIX)")
+
+# 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))
+
+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))
+
+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../../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) *~
+
+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_2.4.1/tools/test/worldstatepool/worldstatepool.cc ./tools/test/worldstatepool/worldstatepool.cc
--- ../Tekkotsu_2.4.1/tools/test/worldstatepool/worldstatepool.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/worldstatepool/worldstatepool.cc	2006-09-28 16:42:53.000000000 -0400
@@ -0,0 +1,108 @@
+#define TK_ENABLE_THREADING
+#include "local/minisim.h"
+
+#include "Shared/WorldStatePool.h"
+#include "Shared/MarkScope.h"
+#include "IPC/PollThread.h"
+#include "local/EntryPoint.h"
+#include <string>
+#include <iostream>
+#include <iomanip>
+
+using namespace std;
+using namespace minisim;
+
+void usage(char* p) {
+	cerr << "Usage: " << p << " [-h|--help] [[read] freq1 freq2 ...] [write freq1 freq2 ...]" << endl;
+}
+
+WorldStatePool& getPool() {
+	static WorldStatePool p;
+	return p;
+}
+/*EntryPoint& getEntryPoint() {
+	static EntryPoint e(getPool());
+	return e;
+}*/
+unsigned int frame=0;
+
+class ReadThread : public PollThread {
+public:
+	ReadThread(int myid, long freq) : PollThread(freq,freq,true,false), id(myid) {}
+protected:
+	virtual bool poll() {
+		//cout << dec << setw(12) << get_time() << ' ' << id << " Read wait " << flush;
+		//MarkScope l(getEntryPoint());
+		EntryPoint::WorldStateRead wsr;
+		MarkScope l(getPool(),wsr);
+		cout << dec << setw(12) << get_time() << ' ' << id << " Read active " << state << ' ' << flush;
+		TimeET t;
+		//while(t.Age()<20L) {}
+		usleep(20*1000);
+		cout << "- " << id <<" done (" << get_time() << ")" << endl;
+		return true;
+	}
+	int id;
+};
+
+class WriteThread : public PollThread {
+public:
+	WriteThread(int myid, long freq) : PollThread(freq,freq,true,false), id(myid) {}
+protected:
+	virtual bool poll() {
+		cout << dec << setw(12) << get_time() << ' ' << id << " Write wait " << flush;
+		EntryPoint::WorldStateWrite wsw(get_time()/10);
+		//MarkScope l(getEntryPoint(),wsw);
+		MarkScope l(getPool(),wsw);
+		cout << dec << setw(12) << get_time() << ' ' << id << " Write active " << state << "/" << wsw.src << ' ' << flush;
+		TimeET t;
+		//while(t.Age()<20L) {}
+		usleep(20*1000);
+		cout << "- " << id <<" done (" << get_time() << ")" << endl;
+		return true;
+	}
+	int id;
+};
+
+int main(unsigned argc, char** argv) {
+	initialize();
+
+	bool read=true;
+	vector<PollThread*> threads;
+	
+	for(unsigned i=1; i<argc; i++) {
+		if(strcmp(argv[i],"-h")==0 || strcmp(argv[i],"--help")==0) {
+			usage(argv[0]);
+			for(vector<PollThread*>::iterator it=threads.begin(); it!=threads.end(); ++it)
+				delete *it;
+			destruct();
+			return 2;
+		} else if(strcmp(argv[i],"read")==0) {
+			read=true;
+		} else if(strcmp(argv[i],"write")==0) {
+			read=false;
+		} else {
+			unsigned t=atoi(argv[i]);
+			threads.push_back(read ? static_cast<PollThread*>(new ReadThread(threads.size(),t)) : static_cast<PollThread*>(new WriteThread(threads.size(),t)));
+		}
+	}
+	
+	cout << setw(12) << get_time() << " starting " << threads.size() << " threads" << endl;
+	for(vector<PollThread*>::iterator it=threads.begin(); it!=threads.end(); ++it)
+		(*it)->start();
+	
+	/*string s;
+	getline(cin,s);
+	while(s=="i") {
+		for(vector<PollThread*>::iterator it=threads.begin(); it!=threads.end(); ++it)
+			(*it)->interrupt();
+		getline(cin,s);
+	}*/
+	sleep(600);
+	
+	for(vector<PollThread*>::iterator it=threads.begin(); it!=threads.end(); ++it)
+		delete *it;
+	destruct();
+	return 0;
+}
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/tool_makefile ./tools/tool_makefile
--- ../Tekkotsu_2.4.1/tools/tool_makefile	2005-08-09 21:58:36.000000000 -0400
+++ ./tools/tool_makefile	2006-09-27 18:01:31.000000000 -0400
@@ -28,7 +28,7 @@
 $(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))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
-include $(TEKKOTSU_ENVIRONMENT_CONFIGURATION)
+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))
@@ -79,7 +79,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_2.4.1/tools/trace_lookup ./tools/trace_lookup
--- ../Tekkotsu_2.4.1/tools/trace_lookup	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/trace_lookup	2006-05-08 14:44:22.000000000 -0400
@@ -0,0 +1,30 @@
+#!/bin/sh
+
+if [ -z "$OPENRSDK_ROOT" ] ; then
+	OPENRSDK_ROOT=/usr/local/OPEN_R_SDK;
+fi;
+
+BUILD=build;
+
+obj=MMCombo.nosnap.elf;
+if [ $# -gt 0 ] ; then
+	obj=$1.nosnap.elf
+fi;
+
+objfile=$BUILD/PLATFORM_APERIOS/TGT_ERS7/aperios/$obj
+
+gp=0x`$OPENRSDK_ROOT/bin/mipsel-linux-readelf -s $objfile | grep ' _gp$' | sed 's/.*: \([0-9a-fA-F]*\).*/\1/'`
+
+echo "Parsing $objfile: gp is $gp"
+while read -a words ; do
+	i=0;
+	while [ $i -lt ${#words[*]} ] ; do
+		addr=`echo ${words[i]} | grep '^[0-9A-Fa-fx]*$'`
+		if [ -n "$addr" ] ; then
+			laddr=`printf "%#x" $((gp-addr))`
+			$OPENRSDK_ROOT/bin/mipsel-linux-addr2line -C -f -e $objfile $laddr | ( read fn; read fl; echo "$fn" "$fl"; )
+		fi;
+		i=$((i+1))
+	done
+done
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/umntmem ./tools/umntmem
--- ../Tekkotsu_2.4.1/tools/umntmem	2003-08-21 18:34:43.000000000 -0400
+++ ./tools/umntmem	2006-04-06 16:55:23.000000000 -0400
@@ -1,9 +1,16 @@
 #!/bin/sh
-	
-pt="/mnt/memstick";
+
 if [ $# -gt 0 ] ; then
 	pt="$1";
-fi;
+elif [ "$MEMSTICK_ROOT" ] ; then
+	pt="$MEMSTICK_ROOT";
+else
+	case "`uname`" in
+		CYGWIN*) pt="/cygdrive/e";;
+		Darwin) d="`dirname $0`"; pt="`$d/osx_find_memstick`";;
+		*) pt="/mnt/memstick";;
+	esac	
+fi
 
 case "`uname`" in
 	CYGWIN*)
@@ -12,14 +19,13 @@
 		;;
 	Darwin)
 		echo "Waiting for unmount... this may take a few seconds for buffered writes to complete";
-		drive=`disktool -l | grep "$pt" | cut -f 2 -d \'`;
-		disktool -e $drive > /dev/null;
-		echo "$pt unmounted, you may remove the memstick";
+		if diskutil eject "$pt" > /dev/null; then
+			echo "$pt unmounted, you may remove the memstick";
+		fi;
 		;;
 	*)
 		printf "Waiting for unmount...";
-		umount $pt;
-		if [ $? -eq 0 ] ; then
+		if umount $pt ; then
 			printf "successful.\n";
 		else
 			printf "an error occured.\n";
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_2.4.1/tools/versionFilter ./tools/versionFilter
--- ../Tekkotsu_2.4.1/tools/versionFilter	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/versionFilter	2006-03-03 10:35:51.000000000 -0500
@@ -0,0 +1,2 @@
+#!/bin/sh
+sed -n "s@^/$1/\([^/]*\)/.*@\1@p" CVS/Entries
