Open main menu

Difference between revisions of "Neato XV-11"

(Added a period.)
 
(53 intermediate revisions by the same user not shown)
Line 1: Line 1:
==Hacking the Neato XV-11==
+
[[File:Neato XV-11.jpg|alt=|thumb|Neato XV-11 Robotic Vacuum]]
<br />[[File:Neato-xv-11.jpg|thumb]]'''''This content has been migrated from the old xv11hacking.com website'''''
+
The Neato XV-11([[wikipedia:Neato_Robotics|Wikipedia]]) is a robot which vacuum’s your house. It is unlike any other however because it includes a low cost 360 degree laser distance scanner (LIDAR See [[wikipedia:Lidar|Wikipedia]]). This can be removed from the XV-11 and used in your own robotics projects or used within the XV-11 with the help of the Robot Operating System (ROS). The pages within this wiki document interfacing methods into the XV-11 and is open to anyone who wants to help. For $399 you can’t find a better robotics platform in my opinion, definitely worth the cost even if you do nothing more than strip it down for parts. You will find it is very well constructed by some people who definitely know about robotics.
  
What is the Neato XV-11 you ask?? The Neato XV-11(Wikipedia) is a robot which vacuum’s your house. It is unlike any other however because it includes a low cost 360 degree laser distance scanner (LIDAR See Wikipedia). This can be removed from the XV-11 and used in your own robotics projects or used within the XV-11 with the help of the Robot Operating System (ROS). The pages within this wiki document interfacing methods into the XV-11 and is open to anyone who wants to help. For $399 you can’t find a better robotics platform in my opinion, definitely worth the cost even if you do nothing more than strip it down for parts. You will find it is very well constructed by some people who definitely know about robotics.
+
'''''This content has been migrated from [https://web.archive.org/web/20180721051927/http://xv11hacking.wikispaces.com/ xv11hacking.com] which is no longer available.'''''
 
==Connecting to ROS==
 
==Connecting to ROS==
'''<br />The following procedure will help you install the Robot Operating System on Ubuntu 10.10 for use with the XV-11.'''
 
  
I have tested this running Ubuntu 10.10 as a VMware virtual machine as well as installed on a system as the booted OS. Ubuntu is a very easy to use Linux release you can download from here Now lets get started! Open a terminal by clicking on '''Applications -> Accessories -> Terminal''' Enter the following commands by copying and pasting them into the terminal window. Use '''CTRL-C''' to copy and then '''CTRL-SHIFT-V''' to paste them in the terminal window.
+
==='''ROS Driver'''===
 +
There is a ROS driver that connects to the XV-11 through the USB port, documentation can be found on the [https://wiki.ros.org/neato_robot ROS wiki]. This driver includes both an ROS-independent python implementation and an ROS node wrapper for the python implementation. It currently controls the mobile base, provides odometry feedback, and publishes laser scans. Future versions will include battery and sensor access features (the currently exist in the ROS-independent code, but have not yet been given a proper ROS API).
  
#sudo sh -c ‘echo “deb http://code.ros.org/packages/ros/ubuntu maverick main” > /etc/apt/sources.list.d/ros-latest.list’
+
==='''Install ROS on Ubuntu'''===
#wget http://code.ros.org/packages/ros.key -O - | sudo apt-key add -
+
''The following procedure will help you install the Robot Operating System on Ubuntu 10.10 for use with the XV-11.''
#sudo apt-get update
+
 
#sudo apt-get install ros-cturtle-base
+
I have tested this running Ubuntu 10.10 as a VMware virtual machine as well as installed on a system as the booted OS. Ubuntu is a very easy to use Linux release you can download from [http://www.ubuntu.com/ here] Now lets get started! Open a terminal by clicking on '''Applications -> Accessories -> Terminal''' Enter the following commands by copying and pasting them into the terminal window. Use '''CTRL-C''' to copy and then '''CTRL-SHIFT-V''' to paste them in the terminal window.
 +
<br />
 +
sudo sh -c ‘echo “deb <nowiki>http://code.ros.org/packages/ros/ubuntu</nowiki> maverick main” > /etc/apt/sources.list.d/ros-latest.list’
 +
wget <nowiki>http://code.ros.org/packages/ros.key</nowiki> -O - | sudo apt-key add -
 +
sudo apt-get update
 +
sudo apt-get install ros-cturtle-base
  
 
The last command will install approximately 5GB worth of software so grab some coffee, a Rockstar, or your stimulant of choice! Once it is done installing run the commands below to install some more ROS software in your home folder.
 
The last command will install approximately 5GB worth of software so grab some coffee, a Rockstar, or your stimulant of choice! Once it is done installing run the commands below to install some more ROS software in your home folder.
 
+
<br />
#cd; mkdir ros; cd ros
+
cd; mkdir ros; cd ros
#svn co https://brown-ros-pkg.googlecode.com/svn/tags/brown-ros-pkg/teleop_twist_keyboard
+
svn co <nowiki>https://brown-ros-pkg.googlecode.com/svn/tags/brown-ros-pkg/teleop_twist_keyboard</nowiki>
#svn co http://albany-ros-pkg.googlecode.com/svn/trunk/slam_coreslam/coreslam
+
svn co <nowiki>http://albany-ros-pkg.googlecode.com/svn/trunk/slam_coreslam/coreslam</nowiki>
#svn co http://albany-ros-pkg.googlecode.com/svn/trunk/neato_robot
+
svn co <nowiki>http://albany-ros-pkg.googlecode.com/svn/trunk/neato_robot</nowiki>
#echo ‘. /opt/ros/cturtle/setup.sh’ >> ~/.bashrc
+
echo ‘. /opt/ros/cturtle/setup.sh’ >> ~/.bashrc
#echo ‘export ROS_PACKAGE_PATH=~/ros:${ROS_PACKAGE_PATH}’ >> ~/.bashrc
+
echo ‘export ROS_PACKAGE_PATH=~/ros:${ROS_PACKAGE_PATH}’ >> ~/.bashrc
#source ~/.bashrc
+
source ~/.bashrc
#sudo su
+
sudo su
#echo ‘. /opt/ros/cturtle/setup.sh’ >> ~/.bashrc
+
echo ‘. /opt/ros/cturtle/setup.sh’ >> ~/.bashrc
#echo ‘export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}’ >> ~/.bashrc
+
echo ‘export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}’ >> ~/.bashrc
#exit
+
exit
#cd ~/ros/teleop_twist_keyboard; rosmake
+
cd ~/ros/teleop_twist_keyboard; rosmake
#cd ~/ros/coreslam; rosmake
+
cd ~/ros/coreslam; rosmake
#cd ~/ros/neato_robot; rosmake
+
cd ~/ros/neato_robot; rosmake
  
 
Now we will edit the /etc/modules file so the usbserial driver will be automatically loaded with the parameters needed. We also add the cdc_acm driver to the blacklist so it will not be used with the XV-11. On a Macbook Pro the system used this driver instead of usbserial.
 
Now we will edit the /etc/modules file so the usbserial driver will be automatically loaded with the parameters needed. We also add the cdc_acm driver to the blacklist so it will not be used with the XV-11. On a Macbook Pro the system used this driver instead of usbserial.
 
+
<br />
#sudo su
+
sudo su
#echo “usbserial vendor=0x2108 product=0x780B” >> /etc/modules
+
echo “usbserial vendor=0x2108 product=0x780B” >> /etc/modules
#echo “blacklist cdc_acm” >> /etc/modprobe.d/blacklist.conf
+
echo “blacklist cdc_acm” >> /etc/modprobe.d/blacklist.conf
#modprobe usbserial vendor=0x2108 product=0x780B
+
modprobe usbserial vendor=0x2108 product=0x780B
#rmmod cdc_acm
+
rmmod cdc_acm
#exit
+
exit
  
 
Almost time to plug your XV-11 into the system!! For the sake of simplicity do not plug in any other USB to serial devices at this point. This will ensure your XV-11 appears as '''/dev/ttyUSB0''' and will simplify setup at this point.
 
Almost time to plug your XV-11 into the system!! For the sake of simplicity do not plug in any other USB to serial devices at this point. This will ensure your XV-11 appears as '''/dev/ttyUSB0''' and will simplify setup at this point.
  
#ls /dev/ttyU*
+
ls /dev/ttyU*
  
 
Once you plug in the XV-11 you should see '''/dev/ttyUSB0''' appear. Now lets load the XV-11 drivers.
 
Once you plug in the XV-11 you should see '''/dev/ttyUSB0''' appear. Now lets load the XV-11 drivers.
  
#roslaunch neato_node bringup.launch
+
roslaunch neato_node bringup.launch
  
 
Entering the above command should initiate a connection to '''/dev/ttyUSB0''' and after a couple seconds you will hear the LIDAR start to spin on the XV-11. Don’t worry if you don’t hear it, press '''CTRL-C''' to exit the driver then enter the command again. I have found it does not seem to start properly upon first load. Now press '''CTRL-SHIFT-T''' while your terminal window is selected to open a new tab within that terminal window, just like a new web browser tab. We will open a few of these tabs to load the different ROS drivers/programs.
 
Entering the above command should initiate a connection to '''/dev/ttyUSB0''' and after a couple seconds you will hear the LIDAR start to spin on the XV-11. Don’t worry if you don’t hear it, press '''CTRL-C''' to exit the driver then enter the command again. I have found it does not seem to start properly upon first load. Now press '''CTRL-SHIFT-T''' while your terminal window is selected to open a new tab within that terminal window, just like a new web browser tab. We will open a few of these tabs to load the different ROS drivers/programs.
  
#roslaunch 2dnav_neato move_base.launch
+
roslaunch 2dnav_neato move_base.launch
#(open a new tab before running the next command)
+
(open a new tab before running the next command)
#rosrun rviz rviz
+
rosrun rviz rviz
  
 
Just to verify, you should have three tabs open now with these three commands simultaneously running. SWEET HUH!! Now you have the GUI application running, just a couple more steps and its play time! On the top menu bar click '''Plugins -> Manage''' then click the box next to '''Loaded''' and click '''OK'''. There is a video [http://www.ros.org/wiki/navigation/Tutorials/Using%20rviz%20with%20the%20Navigation%20Stack here] with details on setting up RViz. You can use this file with RViz and it has all those parameters already setup. Right click on the file and save it. Within RViz just go to '''File -> Open Config''' and select the XV11.vcg file. Now open a new terminal which we will use for keyboard control to manually navigate the XV-11.
 
Just to verify, you should have three tabs open now with these three commands simultaneously running. SWEET HUH!! Now you have the GUI application running, just a couple more steps and its play time! On the top menu bar click '''Plugins -> Manage''' then click the box next to '''Loaded''' and click '''OK'''. There is a video [http://www.ros.org/wiki/navigation/Tutorials/Using%20rviz%20with%20the%20Navigation%20Stack here] with details on setting up RViz. You can use this file with RViz and it has all those parameters already setup. Right click on the file and save it. Within RViz just go to '''File -> Open Config''' and select the XV11.vcg file. Now open a new terminal which we will use for keyboard control to manually navigate the XV-11.
  
#rosrun teleop_twist_keyboard teleop_twist_keyboard.py
+
rosrun teleop_twist_keyboard teleop_twist_keyboard.py
  
 
You will see which keys are used to navigate on the screen once the program is running. The default speed settings are too fast for the XV-11 so you need to reduce the speed before it will respond to any input. Repeatedly press the '''“x”''' key to reduce speed when traveling in a straight line to about 0.10 and then do the same with the “c” key to reduce rotational speed to about 0.15. Now you can use the keyboard keys to navigate.
 
You will see which keys are used to navigate on the screen once the program is running. The default speed settings are too fast for the XV-11 so you need to reduce the speed before it will respond to any input. Repeatedly press the '''“x”''' key to reduce speed when traveling in a straight line to about 0.10 and then do the same with the “c” key to reduce rotational speed to about 0.15. Now you can use the keyboard keys to navigate.
Line 74: Line 79:
  
 
Anyone who has updated their Neato firmware will notice a new message is returned when you enter ” Help” when connected to the robots USB port. Entering Help with a space before it used to return an extended hidden help menu with a lot more commands! When Neato released the 2.6 firmware update (or maybe earlier?) they removed the ” Help” and instead you got this response...
 
Anyone who has updated their Neato firmware will notice a new message is returned when you enter ” Help” when connected to the robots USB port. Entering Help with a space before it used to return an extended hidden help menu with a lot more commands! When Neato released the 2.6 firmware update (or maybe earlier?) they removed the ” Help” and instead you got this response...
 +
<br />
 +
Nice try, but I’m not falling for that one again! :P
 +
 +
Some commands such as “SetStreamFormat” let you actually SEE what the robot is doing while driving around and mapping the environment internally. Some of the guys on Trossen Robotics forum (Chunk) have made really good progress using the output from this command! Sadly this is one of the commands removed from the 2.6 firmware version. But not for long!!
 +
 +
 +
If you just press and hold the orange Start button and Back button at the same time for 4 seconds the robot will reboot into a different firmware that includes all those previous commands! Below is a capture from the on-board 4 pin serial port that shows debug data while the XV-11 is booting.
 +
 +
 +
This capture is of the normal reboot (just holding the orange Start button for 4 seconds)
 +
<br />
 +
Neato Robotics XV-11/XEB V11:16:01
 +
Copyright (c) 2006-2010 Neato Robotics, Inc
 +
 +
Loading installed application
 +
Starting app
 +
NEROSConfigErr: BlowerType=-1 (Expected 0
 +
ConfigErr: BrushMotorType=-1 (Expected 0
 +
ConfigErr: SideBrushType=-1 (Expected 0
 +
FCB Invalid! Configurations may need to be initialized.
 +
 +
  Build 15840 Nov 14 2011 16:09:19
 +
 +
Init A2D
 +
Configure power to STANDBY.
 +
uart0EnablePeripheral
 +
Power On reset: 8 :Software
 +
DEBUG compile
 +
 +
Edison Design Group compiler
 +
 +
Init Pushbuttons.Finished halInit();
 +
Sending GetVersion...
 +
RCVD: Finished LDS getversion cmd in 5 ms
 +
LDS reports build , we need build 15295 (size=16512)
 +
Stop LDS driver to prevent contention
 +
[]
 +
Finished LDSBurn.
 +
Sending GetVersion...
 +
RCVD: Finished LDS getversion cmd in 4 ms
 +
mmcReset Error
 +
 +
PH-drvrInit:Ignoring detected battery type because XV11.
 +
PH-drvrStart:vacuumType(): Invalid SCB blower value. How did we get here?!
  
 +
This capture is after holding the Start and Back buttons for 4 seconds.
  
''Nice try, but I’m not falling for that one again! :P''
+
Neato Robotics XV-11/XEB V11:16:01
 +
Copyright (c) 2006-2010 Neato Robotics, Inc
 +
 +
Loading factory application
 +
Starting app
 +
NEROS Build 12882:12959 Jul 26 2010 22:38:28
 +
 +
Init A2D
 +
Configure power to STANDBY.
 +
uart0EnablePeripheral
 +
Power On reset: 8 oftware
 +
DEBUG compile
 +
 +
Edison Design Group compiler
 +
Enabling USB-CDC ...
 +
 +
Crashblock file: @ 0
 +
Crashblock fn:
 +
Crashblock TOS:0x00000000
 +
Crashblock watchvalues:
 +
 +
Init Pushbuttons.Finished halInit();
 +
mmcReset Error
 +
 +
PH-drvrInit:
 +
PH-drvrStart:
  
  
Some commands such as “SetStreamFormat” let you actually SEE what the robot is doing while driving around and mapping the environment internally. Some of the guys on Trossen Robotics forum (Chunk) have made really good progress using the output from this command! Sadly this is one of the commands removed from the 2.6 firmware version. But not for long!!
+
'''It appears this may be a secondary firmware loaded as a failsafe in case a USB firmware upgrade fails. This would make tech support easier as you have a firmware to revert too in case something goes wrong. You can see from the dates in each print out that they are completely different builds. Thanks to Theo Deyle for e-mailing me and inspiring me to work on this some more! Hopefully his own hacks will be posted soon as well!'''
 +
 
 +
===Neato Firmware v3.0===
 +
The Neatos that are delivered with Firmware 3.0 are a different hardware revision compared to previous models.
 +
 
 +
Previous versions (incl. the Vorwerk VR100) are codename ‘Cruz’.
 +
 
 +
The new hardware revision has codename ‘Binky’.
 +
 
 +
There’s a bootloader you can get into on my XV25/Binky. I don’t know if this is unique for Binky:
 +
<br />
 +
testmode on
 +
setsystemmode PowerCycleCDC
 +
The Neato then disappears from the USB, and reappears with a limited CLI that doesn’t local echo and doesn’t support most commands I’ve tried.
 +
help
 +
Cmd not recognized.
 +
getversion
 +
NeatoBootVer,2.0,0
 +
upload code
 +
File size invalid
 +
There’s more, but be careful.
 +
 
 +
Also, don’t try to stuff the Vorwerk update into here.
 +
 
 +
That’s for Cruz, and will probably brink your Binky.
 +
 
 +
Here’s the version data before upgrade:
 +
<br />
 +
getversion
 +
Component,Major,Minor,Build
 +
ModelID,-1,XV25,
 +
ConfigID,2,,
 +
Serial Number,XXX00000XX,0015662,P
 +
Software,3,0,17235
 +
BatteryType,1,NIMH_12CELL,
 +
BlowerType,1,BLOWER_ORIG,
 +
BrushSpeed,1200,,
 +
BrushMotorType,1,BRUSH_MOTOR_ORIG,
 +
SideBrushType,1,SIDE_BRUSH_NONE,
 +
WheelPodType,1,WHEEL_POD_ORIG,
 +
DropSensorType,1,DROP_SENSOR_ORIG,
 +
MagSensorType,1,MAG_SENSOR_ORIG,
 +
WallSensorType,1,WALL_SENSOR_ORIG,
 +
Locale,1,LOCALE_USA,
 +
LDS Software,V2.6.15295,0000000000,
 +
LDS Serial,XXX00000XX-0000000,,
 +
LDS CPU,F2802x/c001,,
 +
BootLoader Software,17225,P,p
 +
MainBoard Vendor ID,543,,
 +
MainBoard Serial Number,000000000000000000000000,,
 +
MainBoard Software,17242,1,
 +
MainBoard Boot,16219,
 +
MainBoard Version,4,0,
 +
ChassisRev,2,,
 +
UIPanelRev,1,,
 +
testmode on
 +
testlds cmd getversion
 +
Sending getversion...
 +
getversion
 +
 
 +
GetVersion...3 ESCs or BRAK to abort...:)
 +
Piccolo Laser Distance Scanner
 +
Copyright (c) 2009-2011 Neato Robotics, Inc.
 +
All Rights Reserved
 +
 
 +
Loader    V2.5.14010
 +
CPU    F2802x/c001
 +
Serial    XXX00000XX-0000000,,
 +
LastCal    5371726C
 +
Runtime    V2.6.15295
 +
OK
 +
 +
#testmode off
 +
This is after the upgrade
 +
<br />
 +
getversion
 +
Component,Major,Minor,Build
 +
ModelID,-1,XV25,
 +
ConfigID,2,,
 +
Serial Number,XXX00000XX,0015662,P
 +
Software,3,1,17844
 +
BatteryType,1,NIMH_12CELL,
 +
BlowerType,1,BLOWER_ORIG,
 +
BrushSpeed,1200,,
 +
BrushMotorType,1,BRUSH_MOTOR_ORIG,
 +
SideBrushType,1,SIDE_BRUSH_NONE,
 +
WheelPodType,1,WHEEL_POD_ORIG,
 +
DropSensorType,1,DROP_SENSOR_ORIG,
 +
MagSensorType,1,MAG_SENSOR_ORIG,
 +
WallSensorType,1,WALL_SENSOR_ORIG,
 +
Locale,1,LOCALE_USA,
 +
LDS Software,V2.6.15295,0000000000,
 +
LDS Serial,XXX00000XX-0000000,,
 +
LDS CPU,F2802x/c001,,
 +
MainBoard Vendor ID,543,,
 +
MainBoard Serial Number,555,,
 +
BootLoader Software,17225,P,p
 +
MainBoard Software,17624,1,
 +
MainBoard Boot,16219,
 +
MainBoard Version,4,0,
 +
ChassisRev,2,,
 +
UIPanelRev,1,,
 +
testmode on
 +
testlds cmd getversion
 +
Sending getversion...
 +
getversion
 +
GetVersion...3 ESCs or BREAK to abort...:)
 +
Piccolo Laser Distance Scanner
 +
Copyright (c) 2009-2011 Neato Robotics, Inc.
 +
All Rights Reserved
 +
 
 +
Loader V2.5.14010
 +
CPU F2802x/c001
 +
Serial XXX00000XX-0000000,,
 +
LastCal 5371726C
 +
Runtime V2.6.15295
 +
OK
 +
 +
#testmode off
 +
 
 +
==Interfacing with LIDAR Sensor==
 +
I created a board to interface the LIDAR sensor to a PC without the rest of the XV-11. The PCB consists of a PIC18F2221, and FTDI-232R, a 3.3V regulator, and a Fet for controlling the motor. The pic watches the data from the LIDAR and uses the speed information to control the PWM pin attached to the FET. In this way the correct speed can be maintained. The Firmware for the pic currently only supports the old LIDAR firmware ( that is what I have). Hopefully someone else can modify it to work with the other firmware as well. There are jumpers for configuring who talks to what between the PC, PIC, and LIDAR. There are also options for supplying your own 5V instead of getting it from USB and an option for using an XBEE for wireless communication. Schematics are posted below as well as the Eagle brd files. Source code for the PIC will be posted soon. I have spare boards for sale if anyone is interested. Ringo (dot) Davis (at) gmail (dot) com.
 +
[[File:LIDAR mounted on PCB.jpg|none|thumb|LIDAR mounter on interface board|alt=]]
 +
[[File:LIDAR plugged in to Interface board.jpg|none|thumb|LIDAR plugged in to Interface board|alt=]]
 +
<br />
 +
 
 +
==LIDAR API Commands==
 +
Commands available from the LIDAR via direct serial connection or through the Main PCB API To access the API directly via the serial connection of the sensor, send an ESCAPE character (0x1B). The lidar then responds with an invite : “#” You can then enter commands (below is the result of Help command, some additional hidden commands are probably available)
 +
<br />
 +
#
 +
# Help
 +
GetVersion
 +
Help
 +
Log
 +
SaveCal
 +
SetSerial
 +
Upload
 +
Wanderer
 +
Calibrate b16 b8 SunBlind loop2AA loop155
 +
GetCal A B C LPT LFL LFT LFH IMX IB LPI LCH LPD ANG
 +
SetCal A B C LPT LFL LFT LFH IMX IB LPI LCH LPD ANG
 +
Spin Fake DotX DotI Text Hash Timing Foto RPS Pac
 +
TestEncoder
 +
 
 +
Commands are case-insensitive, and can be entered incompletely : getversion, getvers, getv, GeTvErSiOn will all work alike. Be aware that one at least of these commands can brick your LDS... Here are the details of what is currently known about these commands: (To be completed!)
 +
 
 +
GetVersion
 +
 
 +
Prints informations about the version of the LDS.
 +
Example:
 +
 
 +
GetVersion...press ESC 3 times to abort...OK
 +
Piccolo Laser Distance Scanner
 +
Copyright (c) 2009-2010 Neato Robotics, Inc.
 +
All Rights Reserved
 +
 +
Loader V2.4.13386
 +
CPU F2802x/c600
 +
Serial AAA42110AA-0003616
 +
LastCal [2010110136]
 +
Runtime V2.4.13386
 +
SUCCEEDED
 +
 
 +
Help
 +
 
 +
Prints a list of available commands.
 +
Example:
 +
 
 +
Help...press ESC 3 times to abort...
 +
  GetVersion
 +
  Help
 +
  Log
 +
  SaveCal
 +
  SetBaud
 +
  SetSerial
 +
  Upload
 +
  Wanderer
 +
  Calibrate b16 b8 SunBlind loop2AA loop155
 +
  GetCal A B C LPT LFL LFT LFH IMX IB LPI LCH LPD ANG
 +
  SetCal A B C LPT LFL LFT LFH IMX IB LPI LCH LPD ANG
 +
  Spin Fake DotX DotI Text Hash Timing Foto RPS Pac
 +
  TestEncoder
 +
SUCCEEDED
 +
 
 +
Wanderer
 +
 
 +
Draws a squirrel in a heart, in ASCII art...
 +
Example:
 +
[[File:Wanderer Screen Shot.png|none|thumb|alt=]]
 +
<br />
 +
 
 +
==LIDAR Mechanical Info==
 +
Place any info here relating to mechanical aspects of the LIDAR.
 +
 
 +
*Weight: ~195.3g
 +
*Use [https://www.digikey.com/product-detail/en/te-connectivity-amp-connectors/440054-4/A100036-ND/2077941 TE 440054-4] and [https://www.digikey.com/product-detail/en/te-connectivity-amp-connectors/440054-2/A100034-ND/2077939 TE 440054-2] for the 4-pin signal and 2-pin power connectors (thanks '''''chenglung''''')
 +
**You can get free samples of these parts from [https://tycoelectronics.com/ TE’s website]
 +
 
 +
2D CAD files of the XV-11’s LIDAR unit, in mm. Thanks goes to '''''chenglung''''' from the [https://www.trossenrobotics.com/ Trossen Robotics] Forums.
 +
 
 +
3D CAD model of the LIDAR unit. Note that I used the 2d cad files mentioned above along with my own measurements, so be warned that the following is not completely accurate. Also, I’m no CAD professional, so you won’t find much detail in the model - just enough to account for any significant design properties which may be useful to know when building the module into your own applicatio
 +
 
 +
[[:File:XV-11 LIDAR Mechanical Files.zip|XV-11 LIDAR Mechanical Files]] contains the following
 +
 
 +
*2D CAD Files
 +
**XV-11_LDS CAD.zip
 +
**XV-11 LDS.pdf
 +
*3D CAD Files
 +
**xv-11_lidar.SLDPRT
 +
**xv-11_lidar.STL
 +
**xv-11_lidar.IGS
 +
**xv-11_lidar.PDF
 +
 
 +
If anyone needs the file in some other format, just send me a request and I’ll try to help you out: rus.tech.studio ‘@’ gmail.com
 +
 
 +
<br />
 +
 
 +
==LIDAR Sensor==
 +
 
 +
 
 +
The LIDAR sensor is what started this entire project. Find all the information you need below.
 +
 
 +
The angle of the data is not aligned with the natural axis of the device. It seems that the first sample of the first packet is in fact looking at a -10° angle, not 0°. Needs confirmation.
 +
 
 +
===Data format for firmware V2.4===
 +
(recent production units)
 +
 
 +
A full revolution will yield 90 packets, containing 4 consecutive readings each.
 +
 
 +
The length of a packet is 22 bytes.
 +
This amounts to a total of 360 readings (1 per degree) on 1980 bytes.
 +
Each packet is organized as follows:
 +
<br />
 +
start  byte  index  speed  Data 0  Data 1  Data 2  Data 3  checksum
 +
 
 +
where:
 +
 
 +
*start byte is always 0xFA
 +
*index is the index byte in the 90 packets, going from 0xA0 (packet 0, readings 0 to 3) to 0xF9 (packet 89, readings 356 to 359).
 +
*speed is a two-byte information, little-endian. It represents the speed, in 64th of RPM (aka value in RPM represented in fixed point, with 6 bits used for the decimal part).
 +
*Data 0 to Data 3 are the 4 readings. Each one is 4 bytes long, and organized as follows :
 +
 
 +
byte 0 : Distance 7:0
 +
byte 1 : “invalid data” flag : “strength warning” flag
 +
byte 2 : Signal Strength 7:0
 +
byte 3 : Signal Strength 15:8
 +
 
 +
As [https://sites.google.com/site/chenglung/home/xv-11-open-lidar-project-matlab-script chenglung] points out, the distance information is in mm, and coded on 14 bits. This puts the tests made by Sparkfun in a room of around 3.3m x 3.9m (11ft x 13 ft ?), which seems reasonable.
 +
 
 +
The minimum distance is around 15cm, and the maximum distance is around 6m.
 +
 
 +
When bit 7 of byte 1 is set, it indicates that the distance could not be calculated. When this bit is set, it seems that byte 0 contains an error code. Examples of error code are 0x02, 0x03, 0x21, 0x25, 0x35 or 0x50...
 +
 
 +
When it’s `21`, then the whole block is `21 80 XX XX`, but for all the other values it’s the data block is `YY 80 00 00`...
 +
 
 +
The bit 6 of byte 1 is a warning when the reported strength is greatly inferior to what is expected at this distance. This may happen when the material has a low reflectance (black material...), or when the dot does not have the expected size or shape (porous material, transparent fabric, grid, edge of an object...), or maybe when there are parasitic reflections (glass... ).
 +
 
 +
Byte 2 and 3 are the LSB and MSB of the strength indication. This value can get very high when facing a retroreflector.
 +
 
 +
*checksum is a two-byte checksum of the packet.
 +
 
 +
The algorithm is as follows, provided that `data` is the list of the 20 first bytes, in the same order they arrived in.
 +
<br />
 +
def checksum(data):
 +
  “”“Compute and return the checksum as an int.”“”
 +
  # group the data by word, little-endian
 +
  data_list = []
 +
  for t in range(10):
 +
    data_list.append( data2*t + (data2*t+1<<8) )
 +
 +
  # compute the checksum on 32 bits
 +
  chk32 = 0
 +
  for d in data_list:
 +
    chk32 = (chk32 << 1) + d
 +
 +
  # return a value wrapped around on 15bits, and truncated to still fit into 15 bits
 +
  checksum = (chk32 & 0x7FFF) + ( chk32 >> 15 ) # wrap around to fit into 15 bits
 +
  checksum = checksum & 0x7FFF # truncate to 15 bits
 +
  return int( checksum )
 +
 
 +
===Data format for firmware 2.1===
 +
(Sparkfun scans, pre-production units)
 +
 
 +
The periodicity of the data is 1446 bytes.
 +
 
 +
It is organized as follow :
 +
 
 +
5A  A5  00  C0  XX  XX  data
 +
 
 +
where `XX XX` is an information about the current rotation speed of the module, in clock ticks (little endian). <nowiki>http://forums.trossenrobotics.com/showthread.php?t=4470&page=5</nowiki> posted interesting data about this.
 +
 
 +
`` is composed of 360 group of 4 bytes, organized like this :
 +
 
 +
byte 0 : Distance 7:0
 +
byte 1 :  “invalid data” flag : ”quality warning” flag : distance 13:8
 +
byte 2 : Quality 7:0
 +
byte 3 : Quality 15:8
 +
 
 +
As [https://sites.google.com/site/chenglung/home/xv-11-open-lidar-project-matlab-script chenglung] points out, the distance information is in mm, and coded on 13 or 14 bits. This would put the tests made by Sparkfun in a room of around 3.3m x 3.9m (11ft x 13 ft ?), which seems reasonable to me. 13 bits should be enough if the sensor is destined to work up to 6m. This needs some tests...
 +
 
 +
The bit 7 of byte 1 seems to indicate that the distance could not be calculated.
 +
 
 +
It’s interesting to see that when this bit is set, the second byte is always `80`, and the values of the first byte seem to be only `02`, `03`, `21`, `25`, `35` or `50`...
 +
 
 +
When it’s `21`, then the whole block is `21 80 XX XX`, but for all the other values it’s the data block is `YY 80 00 00`
 +
 
 +
maybe it’s a code to say what type of error ? (`35` is preponderant, `21` seems to be when the beam is interrupted by the supports of the cover) .
 +
 
 +
Another thing to have a look to is the temporal repartition of the data... the first sample after the sync seems to always be `21 80 XX XX`, and when this pattern appears again, it’s immediately after an other value, without the 0.2ms interval we can see most of the time between two blocks of 4...
 +
 
 +
The bit 6 of byte 1 is a warning when the reported strength is greatly inferior to what is expected at this distance. This may happen when the material has a low reflectance (black material...), or when the dot does not have the expected size or shape (porous material, transparent fabric, grid, edge of an object...), or maybe when there are parasitic reflections (glass... ).
 +
 
 +
Byte 2 and 3 are the LSB and MSB of the strength indication. This value can get very high when facing a retroreflector.
 +
 
 +
<br />
 +
 
 +
==Motors==
 +
Data on the drive motors, brush motor, and vacuum fan.
 +
 
 +
===SetMotor Command===
 +
Motor speeds can be set using the SetMotor commands. This command is handled asynchronously, so you can query other commands while the robot is moving. The simplest way to set both the left and right motor speed is to use:
 +
SetMotor left_dist right_dist speed
 +
Where left_dist and right_dist are a distance to travel in millimeters, and speed is the speed to use for movement in millimeters per second. Speed must be positive, and at least one of left_dist or right_dist must be non-zero. Drive motor speeds are -300 mm/s to 300 mm/s. These max speeds also induce a rotational max speed of approximately +/- 2.25 radians/sec given the separation of the wheels.
 +
 
 +
It appears that when different distances are put in, the speed will be applied to the wheel moving the farther distance, and the other wheel will be scaled such that both wheels take the same amount of time to travel their complete distance. (Can someone confirm this on their bot? - Fergy).
 +
 
 +
Some examples:
 +
 
 +
*SetMotor 100 100 100 - will move the robot forward 100mm, in approximately one second
 +
*SetMotor 100 -100 100 - will turn the robot to the right in place, for 1 second.
 +
*SetMotor 100 200 100 - the robot will move forward and to the left, for 2 seconds.
 +
 
 +
The base width separation of the wheel is approximately 248 millimeters. Therefore, the circumference when turning in place is approximately 780 millimeters. Thus, we can turn the robot using:
 +
 
 +
*SetMotor 195 -195 100 - the robot will turn in place, 90 degrees to the right.
 +
 
 +
<br />
 +
 
 +
==Neato XV series WiFi remote control==
 +
Neato is great in cleaning by it self, it also has good “spot clean” algorithm! But, what if you want to clean just a certain spot? In other words - use it like a regular vacuum?
 +
 
 +
That was the basic idea which led to realization of the full wireless remote control.
 +
 
 +
As you may know, you can manually control Neato right out of the box by connecting it to any computer via usb and, through any terminal program, send commands to robot (for some reason article describing command list on official Neato site is unreachable at this moment, but you can get it by typing ‘help’). The way you can control Neato movements is described here: [[#XV-11 API Commands|XV-11 API Commands]]
 +
 
 +
This is really great, but how can one use it for robot’s intended purpose if he or she is limited by the length of the wire? Of course you can take a laptop!  But for me it was not the answer. Luckily, my friend recently has brought a compact (very compact) WiFi router (Commonly available from eBay as “2g/3g/4g wifi router”, also known as HAME MPR-A5 and MIFI-F5. MPR-A1 and clones are likely to work as well if you manage to fit them in. Some additional material is available on http://my-embedded.blogspot.com/2013/12/mini-4g-router-rt5350f.html) and suggested that we should try to embed it into my Neato.
 +
 
 +
So, it was obvious that all we needed was to find +5V power supply and connect usb from router to neato’s usb. All that sounds simple, so we did it. (i should say that my Neato has rev.64 main board)
 +
[[File:Neato WiFi Controller attached.jpg|none|thumb|''VCC - Red wire, D- - White wire, D+ - Green wire. (regular USB pinout)'']]
 +
Very soon we realized that, first of all - there is no powerful enough +5V source on the main board, and the second one - Neato’s software blocks it from normal functioning if it senses power supply on its usb
  
 +
The answer to the first problem was as simple as buying 5V 500mA DC-DC converter ([http://www.digikey.com/product-search/en?FV=fff40042%2Cfff800df%2C1140050%2C114016f%2C11401ab%2C11401c9%2C15c0002%2C8f40010%2C8f40011%2C8f40012%2C8f40013%2C8f40014%2C8f40016%2C8f40017%2C8f40018%2C8f40019%2C8f4001a%2C8f4001b%2C8f4001c%2C8f4001d%2C8f40021%2C8f40022%2C8f40023%2C8f40024%2C8f40026%2C8f40027%2C8f40028%2C8f40029%2C8f4002a%2C8f4002b%2C8f4002e%2C8f40030%2C8f40031%2C8f40032%2C8f40034%2C8f40035%2C8f40037%2C8f40039%2C8f4003b%2C8f4003c%2C8f4003d%2C8f4003e%2C8f4003f%2C8f40041%2C8f40042%2C8f40043%2C8f40044%2C8f40047%2C8f40048%2C8f40049%2C8f4004b%2C8f4004c%2C8f4004d%2C8f4004e%2C8f4004f%2C8f40050%2C8f40051%2C8f40052%2C8f40053%2C8f40054%2C8f40056%2C8f40058%2C8f40059%2C8f4005a%2C8f4005b%2C8f4005e%2C8f40060%2C8f40061%2C8f40062%2C8f40063%2C8f40064%2C8f40067%2C8f40069%2C8f4006a%2C8f4006b%2C8f4006c%2C8f4006d%2C8f4006e%2C8f40083%2C8f40085%2C8f40086%2C8f40087%2C8f40088%2C8f40089%2C8f4008f%2C8f40090%2C8f40091%2C8f40093%2C8f40095%2C8f40096%2C8f40097%2C8f40098%2C8f4009b%2C8f4009e%2C8f400a1%2C8f400a2%2C8f400a3%2C8f400a4%2C8f400a5%2C8f400a7%2C8f400a8%2C1180005c%2C17d4003e&mnonly=0&newproducts=0&ColumnSort=1000011&page=1&stock=0&pbfree=0&rohs=0&quantity=&ptm=0&fid=0&pageSize=25 DC-DC on digikey.com]) A local shop had Peak PSR-7805LF available for a reasonable price so I settled on that one.
 +
[[File:Neato WiFi PCB Power.jpg|none|thumb|Neato WiFi PCB Power]]
 +
Answer to the second problem was a bit tricky! On the router board there is a source of power which can be turned on/off by changing state of its GPIO8 (echo 1 >/sys/class/gpio/gpio8/value), so my friend suggested that we will be able to control usb power supply by one P-N-P transistor witch base must be connected to that gpio. All that going to be great if only router could gave us +5V, but its voltage is only +3.3V. In the end the answer was found: we’d connected +5V from DC-DC to the Neato’s usb through one p-n-p and one n-p-n transistor (with a pair of resistors) controlled by the router’s +3.3V as shown below.
 +
[[File:Neato WiFi adaptor schematic.jpg|none|thumb|Neato WiFi adaptor schematic]]
 +
[[File:Neato Wifi Adaptor solder points.jpg|none|thumb|To get rid of micro USB plug we soldered power supply wires from DC-DC right on router’s board]]
 +
[[File:Mini 4g router pcb bottom.jpg|none|thumb|To get rid of micro USB plug we soldered power supply wires from DC-DC right on router’s board]]
 +
[[File:Neato Wifi Dremel Modification.jpg|none|thumb|To fit router with all the stuff inside neato’s body i’ve made a small ‘modification’ using my dremel]]
 +
[[File:Neato Wifi Adaptor install.jpg|none|thumb]]
 +
So now i have a fully functional Neato with a full control from any place in the world ;) I can remotely start cleaning in full cycle, or change its schedule, or use it full manual, or, even, just play like with RC car!
  
If you just press and hold the orange Start button and Back button at the same time for 4 seconds the robot will reboot into a different firmware that includes all those previous commands! Below is a capture from the on-board 4 pin serial port that shows debug data while the XV-11 is booting.
+
<br />
  
 +
==Open source Linux for Neato==
 +
Newer models (XV-14/XV-15/XV-21/XV-25 ???) with board revision 64 are running on Linux Kernel 2.6.33.7
  
This capture is of the normal reboot (just holding the orange Start button for 4 seconds)
+
The open source parts of the code are provided on the CD labeled as “Neato Vacuum User Guide” that comes with the robot. The source is located under the directory “LinuxSrc”
 +
[[File:Neato XV-11 Photo of CD.jpg|thumb|Neato XV-11 Photo of CD]]
 +
[[File:Neato XV-11 Folders of CD.jpg|thumb|Neato XV-11 Folders of CD]]
  
<code>Neato Robotics XV-11/XEB V11:16:01</code>
 
  
<code>Copyright (c) 2006-2010 Neato Robotics, Inc</code>
+
The source contains few Neato specific bits related to the operation of the robot, however some interesting details are disclosed:
  
 +
*The unpopulated footprint (J2) on the PCB Rev 64 is indeed a SD Card footprint, and the source reveals that the kernel has SD Card support.
 +
*The presence USB Gadget drivers of suggests that the Neato has USB OTG support and “Ethernet over USB” capabilities (unconfirmed)
 +
*Mystery .raw file \LinuxSrc\rootfs\etc\test_map.raw (400KB). Could this be sample LIDAR data?
 +
*Contents of the file \LinuxSrc\rootfs\etc\Issue: “Welcome hackers!”. :
 +
*[[:File:Neato XV-11 Readme.txt|Readme.txt]] of the LinuxSrc folder
  
<code>Loading installed application</code>
+
<br />
  
<code>Starting app</code>
+
===Bootloader Access===
  
<code>NEROSConfigErr: BlowerType=-1 (Expected 0</code>
 
  
<code>ConfigErr: BrushMotorType=-1 (Expected 0</code>
+
Bootloader access can be achived by isseuing the following command to the robot over USB Serial connection.
 +
testmode on
 +
setsystemmode PowerCycleCDC
 +
(*CDC = Communications Device Class ????)
  
<code>ConfigErr: SideBrushType=-1 (Expected 0</code>
+
The Neato then reappears on the serial bus (on Windows you might have to unplug and reconnect the USB cable for this device to appear) as an another device “XV-11 BOOTLOADER”
  
<code>FCB Invalid! Configurations may need to be initialized.</code>
+
Accessing this device offers a limited console over USB serial with no local echo.
  
 +
Contents of the folder LinuxSrc\boot indicate that [http://www.denx.de/wiki/U-Boot U-boot] is, or was used as, bootloader on the Neato at some point “''Hopefully u-boot doesn’t make it to production, but if it does..'', LinuxSrc\boot\arch\arm\cpu\lpc313, line 453.
  
<code>Build 15840 Nov 14 2011 16:09:19</code>
+
The Neato bootloader console does not support any of the standard U-boot commands.
 +
help
 +
Cmd not recognized.
 +
getversion
 +
NeatoBootVer,2.0,0
  
 +
===Supported commands at bootloader console===
 +
{| class="wikitable"
 +
|Command
 +
|Usage
 +
|Description
 +
|-
 +
|GetVersion
 +
|getversion
 +
|Prints version information
 +
|-
 +
|Boot
 +
|boot
 +
|boot the robot OS
 +
|-
 +
|Upload
 +
|?
 +
|upload firmware to the robot?
 +
|-
 +
|
 +
|
 +
|download firmware from the robot?
 +
|}
 +
'''Looking for commands at the bootloader console'''
  
<code>Init A2D</code>
+
The bootloader console matches input stream “byte by byte” to find the first match. For example input “bootxyz123hskdfhskdjfhksjd”, triggers the “boot” command, ignoring any trailing charachters. This implies that there are no variations on commands like “bootusb” (unconfirmed).
  
<code>Configure power to STANDBY.</code>
+
===Flashing the Neato===
 +
'''''Warning messing around with the bootloader could potentially brick your robot with no known method of recovery'''''
  
<code>uart0EnablePeripheral</code>
+
Using the bootloader console it might be possible to flash the Neato using a custom firmware (unconfirmed).
 +
upload code
 +
File size invalid
  
<code>Power On reset: 8 :Software</code>
+
===Neato open source code===
 +
The files are clearly identified as open source! (106MB)
  
<code>DEBUG compile</code>
+
http://www.axifile.com/en/F2D0DB4C4E
  
 +
(note: if this link doesn’t work anymore, then there was no use for it in the past 30 days... let me (KPPlayer)
  
<code>Edison Design Group compiler</code>
+
know and I’ll upload again.)
  
 +
===Other resources===
 +
http://www.nxp.com/products/microcontrollers/arm9/LPC3143FET180.html Vendor info and datasheet for the NXP LPC3134
  
<code>Init Pushbuttons.Finished halInit();</code>
+
http://dfu-util.gnumonks.org/ USB DFU (Device Firmware Upgrade) Utilities. DFU possible?
  
<code>Sending GetVersion...</code>
+
http://www.lpclinux.com/LPC313x/LPC313xMain How to get Linux running on a NXP LPC313/4/5
  
<code>RCVD: ''Finished LDS getversion cmd in 5 ms''</code>
+
<br />
  
''<code>LDS reports build , we need build 15295 (size=16512)</code>''
+
==PCB Versions==
  
''<code>Stop LDS driver to prevent contention</code>''
+
===Early PCB Version===
 +
[[File:Neato XV-11 Early PCB Version.jpg|thumb|'''Neato XV-11 Early PCB Version''']]
 +
{| class="wikitable"
 +
! colspan="4" |Neato XV-11 BOM and Parts identification
 +
|-
 +
|Ref. Desg.
 +
|Manufacturer
 +
|Part Number
 +
|Description
 +
|-
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U1
 +
|Allegro
 +
|A3950SEUTR-T
 +
|DMOS Full-Bridge Motor Driver
 +
|-
 +
|U5
 +
|Allegro
 +
|A3950SEUTR-T
 +
|DMOS Full-Bridge Motor Driver
 +
|-
 +
|U16
 +
|ST
 +
|LIS302DL
 +
|3-axis - ± 2g/± 8g smart digital output “piccolo” accelerometer
 +
|-
 +
|U17
 +
|Fairchild
 +
|MM74HC4051MTC
 +
|8-Channel Analog Multiplexer
 +
|-
 +
|U18
 +
|Fairchild
 +
|MM74HC4051MTC
 +
|8-Channel Analog Multiplexer
 +
|-
 +
|U26
 +
|Allegro
 +
|A4490EESTR-T
 +
|Triple Output Step-Down Switching Regulator
 +
|-
 +
|U29
 +
|ATMEL
 +
|AT91SAM9XE128-QU
 +
|AT91 ARM Thumb Microcontrollers PQFP208
 +
|-
 +
|U32
 +
|Winbond
 +
|W988D6FB
 +
|SDRAM (typeno varies) - 256Mb (32MByte) Mobile LPSDR
 +
|-
 +
|U34
 +
|ZETEX
 +
|ZXMHC3A01T8
 +
|COMPLEMENTARY 30V ENHANCEMENT MODE MOSFET H-BRIDGE
 +
|-
 +
|U36
 +
|National Semi
 +
|NC7SZ14
 +
|Tiny UHS Inverter with Schmitt Trigger Input
 +
|-
 +
|U39
 +
|
 +
|
 +
|
 +
|-
 +
|U44
 +
|National Semi
 +
|NC7SZ14
 +
|Tiny UHS Inverter with Schmitt Trigger Input
 +
|-
 +
|U45
 +
|National Semi
 +
|NC7SZ14
 +
|Tiny UHS Inverter with Schmitt Trigger Input
 +
|-
 +
|U35
 +
|ST
 +
|NAND128W3A2BN6
 +
|16MByte small-page NAND flash
 +
(on bottom side of PCB)
 +
|}
 +
<br />
 +
{| class="wikitable"
 +
!Ref. Desg.
 +
!Description
 +
|-
 +
|J1
 +
|Charging Jack
 +
|-
 +
|J2
 +
|UI Board (LCD/Buttons)
 +
|-
 +
|J3
 +
|Direct connection to the ERASE line of the AT91 processor!! Shorting this jumper and rebooting the
 +
XV-11 will result in a complete loss of programming. No known recovery method at this time.
 +
|-
 +
|SW1
 +
|Switch input used to hard reboot the processor. Probably used in conjunction with J3 for development
 +
purposes.
 +
|-
 +
|P1
 +
|Battery pack thermistor input (Thermistor measures ~10k at 70 degrees Fahrenheit on battery)
 +
For battery locations, viewing XV-11 from above with the laser at the bottom and bumpers up top:
 +
Wire Color\Pins
 +
Orange,Blue\1,2 = Left Battery
 +
Yellow,Green\3,4 = Right Battery
 +
|-
 +
|P2
 +
|Main power input
 +
|-
 +
|P3
 +
|Header for Bluetooth module (BlueSMiRF)
 +
|-
 +
|P4
 +
|Unknown. Leads to SPI of the AT91 processor: Probably MMC/SD connection.
 +
|-
 +
|P5
 +
|Bumper switch inputs x4
 +
For button locations, viewing XV-11 from above with the laser at the bottom and bumpers up top:
 +
Wire Color\Pins
 +
Blue\1,2 = Left Side
 +
Yellow\3,4 Top Left
 +
Purple\5,6 Top Right
 +
Orange\7,8 Right Side
 +
|-
 +
|P6
 +
|Header used to communicate with the AT91 via serial connection.
 +
P6:1 Unused (square pad), P6:2 AT91_RXD, P6:3 AT91_TXD, P6:4 Ground
 +
|-
 +
|P8
 +
|LIDAR Motor connector
 +
|-
 +
|P9
 +
|Brush motor Input/Output
 +
Pins
 +
1,2 = Brush motor power
 +
3,4,5 = Input from encoder
 +
|-
 +
|P10
 +
|JTAG. Bottom row: VDDIO (square pin), TRST, TDI, TMS, TCK. Top row: GND, GND, SRST, TDO, RTCK. The JTAG-port unfortunately is software-disabled for debugging the ARM processor core.
 +
|-
 +
|P11
 +
|Viewing XV-11 from above with the laser at the bottom and bumpers up top:
 +
1,2,3 = Top Right Side Wall Distance Sensor (Sharp 0A51SK F 0X)
 +
|-
 +
|P12
 +
|LIDAR power/serial connection
 +
|-
 +
|P13
 +
|Magnetic strip sensors and floor distance sensors (detecting edge before falling down stairs)
 +
For sensor locations, viewing XV-11 from above with the laser at the bottom and bumpers up top:
 +
Pins
 +
1,2,3 = Top Left Distance Sensor (Sharp 0A51SK F 0X)
 +
4,5,6 = Top Left Hall Effect Sensor (Allegro 21E)
 +
7,8,9 = Top Right Distance Sensor (Sharp 0A51SK F 0X)
 +
10,11,12 = Top Right Hall Effect Sensor (Allegro 21E)
 +
|-
 +
|P14
 +
|Speaker
 +
|-
 +
|P16
 +
|Dustbin installed/removed input (Soft rubber button under dustbin)
 +
|-
 +
|P18
 +
|Charging input for wall docking charger
 +
|-
 +
|P19
 +
|Vacuum motor
 +
|-
 +
|P20
 +
|USB Connection to ATMEL processor
 +
|-
 +
|P22
 +
|Right Wheel
 +
Pins
 +
1,2 = motor power
 +
3,4,5 = Input from encoder
 +
|-
 +
|P23
 +
|Left Wheel
 +
Pins
 +
1,2 = motor power
 +
3,4,5 = Input from encoder
 +
|-
 +
|P24
 +
|Temperature input from brush motor, taped to motor (Measures ~10k at 70 degrees Fahrenheit)
 +
|}
  
''<code>[]</code>''
+
===PCB Rev. 64===
 +
[[File:Neato XV-11 PCB Rev64 Top.jpg|thumb|'''Neato XV-11 PCB Rev64 Top''']]
 +
[[File:Neato XV-11 PCB Rev64 Bottom.jpg|thumb|'''Neato XV-11 PCB Rev64 Bottom''']]
 +
{| class="wikitable"
 +
|+
 +
!Ref Desg.
 +
!Manufacturer
 +
!Part Number
 +
!Description
 +
!Info
 +
|-
 +
|U1
 +
|TI
 +
|
 +
|5V Regulator
 +
|Triggered when Room Scanner is on
 +
|-
 +
|U2
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U3
 +
|STM
 +
|LIS3DH
 +
|Three axis accelerometer
 +
|
 +
|-
 +
|U4
 +
|TI
 +
|
 +
|3.3V Regulator
 +
|U4 and U23 both Infineon
 +
[https://www.infineon.com/dgdl/Infineon-IFX25001-DS-v01_02-en.pdf Spec Sheet]
 +
|-
 +
|U5
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U6
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U7
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U8
 +
|STM
 +
|STM32F100R4T6B
 +
ARM
 +
|I/O-controller (motors, switches, etc) with RTC and low frequency quartz (responsible for time keeping during sleep/shut off)
 +
|
 +
|-
 +
|U9
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U10
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U11
 +
|MICRON
 +
|MT48LC16M16A2-7E
 +
|256Mb (32MB) SDRAM
 +
|
 +
|-
 +
|U12
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U13
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U14
 +
|NXP
 +
|LPC3143FET180
 +
ARM9
 +
|(main-)controller with external memory
 +
|http://www.nxp.com/products/microcontrollers/arm9/LPC3143FET180.html
 +
|-
 +
|U15
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U16
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U17
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U18
 +
|STM
 +
|NAND128W3A2BN6F
 +
|128Mb (16MB) NAND
 +
|
 +
|-
 +
|U19
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U20
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U21
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U22
 +
|
 +
|
 +
|
 +
|
 +
|-
 +
|U23
 +
|TI
 +
|
 +
|5V Regulator
 +
|http://www.ti.com/product/LM78M
 +
|}
 +
{| class="wikitable"
 +
!Ref. Desg.
 +
!Description
 +
|-
 +
|J1
 +
|UI Board (LCD/Buttons) connector
 +
|-
 +
|J2
 +
|SD card header (unpopulated)
 +
|-
 +
|P2
 +
|UART header??? (unconfirmed)
 +
|-
 +
|P3
 +
|UART header??? (unconfirmed)
 +
|-
 +
|P9
 +
|Motor from Side brush (VR100)?
 +
|-
 +
|P13
 +
|Main power input
 +
|-
 +
|
 +
|
 +
|-
 +
|P15
 +
|Right Wheel
 +
|-
 +
|P16
 +
|Left Wheel
 +
|}
 +
<br />
  
''<code>Finished LDSBurn.</code>''
+
==Viewing Maps from the XV-11’s Point of View==
 +
[[File:Neato XV-11 Map bathroom1.gif|thumb]]
 +
[[File:Neato XV-11 Map bathroom2.gif|thumb]]
 +
[[File:Neato XV-11 capture.gif|thumb]]
 +
Warning: This feature seems to be missing in the current (v2.6) firmware.)
  
''<code>Sending GetVersion...</code>''
+
Even though we’ve got the ability to make our own maps using the XV-11’s sensor and ROS, it’s nice sometimes to be able to see them from the XV-11’s point of view.
  
''<code>RCVD:</code>'' <code>Finished LDS getversion cmd in 4 ms</code>
+
Due to the efforts of some of the guys at TrossenRobotics ([http://forums.trossenrobotics.com/showthread.php?5123-Some-XV-11-notes/ thread link]), the SetStreamFormat packet datastream has been partially decoded--at least to the point of being able to grab maps from a running XV-11
  
<code>mmcReset Error</code>
+
The source code is available on githhub here: [https://github.com/rbtying/xv11-stream-parser XV-11 Stream Parser]
  
 +
After compilation, the code can be used to translate dumps of the XV-11 packet stream into nice 256x256 animated gifs, so you can see into the mind of the XV-11.
  
<code>PH-drvrInit:Ignoring detected battery type because XV11.</code>
+
You can use the following command to test it out:
 +
bin/parser -f example/Packet\ Mode\ Bathroom1\ 09-03-2011.txt
 +
View the help (run with -h or no flags) for details on the available options.
  
<code>PH-drvrStart:vacuumType(): Invalid SCB blower value. How did we get here?!</code>
+
It can also show you the laser scans of the robot (though the position estimation of the robot is based on some hackish intersection code)
 +
[[File:Neato XV-11 Map bathroom1-laser.gif|none|thumb]]
 +
[[File:Neato XV-11 Map capture-laser.gif|none|thumb]]
  
 +
==XV-11 API Commands==
  
'''This capture is after holding the Start and Back buttons for 4 seconds.'''
+
===Commands available through the USB port on the XV-11===
 +
Neato Robotics currently has an list of commands accessible to people who want to tinker with their robots.
  
 +
See their official site for information: http://www.neatorobotics.com/programmers-manual
  
<code>Neato Robotics XV-11/XEB V11:16:01</code>
+
===Getting a list of Commands===
 +
Your first point of call is the Neato Robotics Programmers Manual listed above. Also if you have an established link to your Neato you can type:-
 +
help
 +
which will list all available commands.
  
<code>Copyright (c) 2006-2010 Neato Robotics, Inc</code>
+
You can also get additional information about commands by typing the command function name after the word help, eg:-
 +
help getmotors
  
 +
===Enabling TestMode===
 +
A lot of the functions available to programmers can only be used if “TestMode” has been enabled on the Neato. Most functions displayed in the Help are listed as “TestMode Only” which will give you an idea as to what can be only be used when TestMode is enabled.
  
<code>Loading factory application</code>
+
If you attempt to use a command before you have enabled TestMode, Neato will politely state that “''TestMode must be on to use this command.''”
  
<code>Starting app</code>
+
To Enable TestMode
 +
testmode on
 +
To Disable TestMode (do remember to disable TestMode to return your Neato back to normal after you have finished tinkering)
 +
testmode off
 +
With TestMode enabled, you Neato will behave a little differently than normal.
  
<code>NEROS Build 12882:12959 Jul 26 2010 22:38:28</code>
+
*All buttons on the robot will NOT respond to input as it normally does
 +
*You may not be able to re-establish connection to your robot if you unplugged and reconnected in a short period of time. If you cant re-establish connection, wait a few mins before attempting again.
  
 +
The following commands and examples listed below will assume you have TestMode enabled, (unless specified differently)
  
<code>Init A2D</code>
+
===Issuing Commands to the Motors===
 +
When you are first experimenting with command, I recommend you turn Neato up-side-down so the wheels can free spin. Otherwise you may get instances where your robot drives away faster than you expected, crashing into things and generally making a mess of your room as it lacks logic to stop.
  
<code>Configure power to STANDBY.</code>
+
The basic command to move is
 +
setmotor LeftWheelDistance RightWheelDistance Speed
 +
As I tested in firmware 2.6, Neato’s maximum speed is 300. If you exceed this value, Neato will report back something like “''Invalid Speed Specified(500). Must be between 0 and 300''”
  
<code>uart0EnablePeripheral</code>
+
Some basic movement examples
  
<code>Power On reset: 8 oftware</code>
+
To drive forward 10cm:-
 +
setmotor 100 100 100
 +
To spin on the spot (rotate clockwise):-
 +
setmotor 900 -900 100
 +
To do a left-handed U-Turn (rotate anti-clockwise):-
 +
setmotor 0 1000 100
 +
As I have been experimenting, my Neato seems to steer to the left a little as it drives along in a ‘straight’ line. I’ve also had differences in distance travelled depending on my speed setting. I have yet to sit down and measure the accuracy of these movement commands.
  
<code>DEBUG compile</code>
+
===Problems You May Encounter===
 +
A little issue I found in my tinkering exploits, Neato would suddenly power off when issuing commands. This seems to be because I was issuing a large amount of commands within a short period of time. To give you an idea, I was issuing a set of three SetLED commands once every 20ms. Within about 2seconds, Neato would power off. To fix the issue, unplug your USB, power up Neato and reconnect the USB.
  
 +
==LCD PCB Information==
 +
[[File:Neato XV-11 LCD panel front labels.png|thumb|Neato XV-11 LCD panel front ]]
 +
[[File:Neato XV-11 LCD panel back labels.png|thumb|Neato XV-11 LCD panel back ]]
 +
'''IMPORTANT LCD INFORMATION!!!''' As you can see in the first image, the LCD is labeled “GVLCM128128G 13572A” on its backside. Googling this brings up the following LCD producer: [http://www.golden-vision.cn/ Golden Vision]. However, this exact LCD is not listed on their site, but [http://www.golden-vision.cn/productxs.asp?id=24 this similar one] is. All the measurable specs are similar (dimensions are approximately the same - the XV-11’s LCD measures approximately 61.6 mm x 55.1 mm x 4.36 mm, which is a bit thicker, probably due to the backlight; 128 x 128 resolution). The only differences I could find are the small white line above the ribbon cable at the bottom of the “similar” LCD isn’t present on the XV-11 LCD, and the ribbon cable of the “similar” LCD is 24 pins, not 25 (so the “similar” '''LCD CANNOT BE USED AS A REPLACEMENT - IT WOULDN’T BE PIN COMPATIBLE!'''). Anyway, the company only lists a few 128x128 LCD’s in production (none of which match the XV-11’s), so this narrows down the list of possible LCD controllers used in the XV-11’s LCD to just the [http://www.tstonramp.com/~pddwebacc/ics_app%20notes/sitronix/ST7541_12.pdf ST7541] (others are possible but you could say these are more likely since we know this is the only chip the company uses in their 128x128 greyscale LCD’s). We can’t be sure until we test out driving this LCD standalone (on my TODO list for the next 2 weeks - I’m waiting on a FFC Ribbon Cable Breakout to come in from New Haven Display ([http://www.newhavendisplay.com/index.php?main_page=product_info&cPath=91_123&products_id=1100 look here if interested]), but from what the datasheet says and the fact that only 2 of the LCD’s ribbon cable pins are appear to have data running thru them, it seems like the LCD is controlled by i2c from the main board (see below for pinouts).
  
<code>Edison Design Group compiler</code>
 
  
<code>Enabling USB-CDC ...</code>
+
The white FFC ribbon cable leading connecting the LCD board to the mainboard has a 1mm pitch.
  
  
<code>Crashblock file: @ 0</code>
+
The buttons on the LCD board have a pair of legs connected to ground, so it’s safe to deduce that the main board has these buttons’ signals pulled up (these pullups are not found on the LCD board) and expects to read a LOW signal when these buttons are pressed down. See table below for which button is which.
  
<code>Crashblock fn:</code>
 
  
<code>Crashblock TOS:0x00000000</code>
+
K1, K2, and K3 labeled in the second image are 3 of the 4 pins attaching the LCD backlight to the PCB. These pins go thru resistors to Q1, which appears to be a transistor driven by pin 10 of the white FFC ribbon cable (going to the mainboard). When a voltage is applied to Q1, it connects K(1-3) to GND, turning the backlight ON. K4, the last of the backlight’s pins, connects to pin 14 of the white FFC ribbon cable (see table below for appropriate voltages).
  
<code>Crashblock watchvalues:</code>
 
  
 +
All 4 LED’s (2 per Double-LED) run fine at about 20mA @ 2V, with ~ 68 Ohm resistors each, so a 3.3V signal line that can source about 40mA should suffice for each color (each LED color pair has its own pin - see table below)
  
<code>Init Pushbuttons.Finished halInit();</code>
 
  
<code>mmcReset Error</code>
+
EagleCAD LCD PCB Files:
  
 +
I’ve reverse engineered the LCD peripheral board into EagleCAD, just in case it comes in handy.
  
<code>PH-drvrInit:</code>
+
'''IMPORTANT DISCLAIMER''': I did my best to determine all the dimensions, but there are likely some minor inaccuracies. Looking at the XV-11’s case, the LCD PCB fits snugly in the outline and all the buttons and LED’s have to line up nicely with the plastic to work properly. If for whatever reason you want to use these files to produce a custom LCD peripheral board, just be warned it may not work (but this is probably your best chance at a template for one).
  
<code>PH-drvrStart:</code>
+
*[[:File:Neato_XV-11_LCD_Board.zip|Neato_XV-11_LCD_Board.zip]]
 +
*Contains:  
 +
**LCD_board_opensource.brd
 +
**LCD_board_opensource.sch
  
  
'''It appears this may be a secondary firmware loaded as a failsafe in case a USB firmware upgrade fails. This would make tech support easier as you have a firmware to revert too in case something goes wrong. You can see from the dates in each print out that they are completely different builds. Thanks to Theo Deyle for e-mailing me and inspiring me to work on this some more! Hopefully his own hacks will be posted soon as well!'''
+
16 Pin Main PCB FFC Ribbon Cable (white) Pinout (still working on it...):
 +
{| class="wikitable"
 +
|Pin #
 +
|Signal Type
 +
|Signal
 +
|Notes
 +
|-
 +
|1 (*)
 +
|OUTPUT
 +
|SW1 - “SOFT”
 +
|Pulled up on mainboard (internally in ARM?); LOW means button is pressed
 +
|-
 +
|2
 +
|OUTPUT
 +
|SW3 - “BACK”
 +
|Pulled up on mainboard (internally in ARM?); LOW means button is pressed
 +
|-
 +
|3
 +
|POWER/INPUT
 +
|Green LED’s
 +
|Run HIGH ~(3.3V) to turn on, make sure the pin can source ~40mA
 +
|-
 +
|4
 +
|OUTPUT
 +
|SW4 - “UP”
 +
|Pulled up on mainboard (internally in ARM?); LOW means button is pressed
 +
|-
 +
|5
 +
|POWER/INPUT
 +
|Amber LED’s
 +
|Run HIGH ~(3.3V) to turn on, make sure the pin can source ~40mA
 +
|-
 +
|6
 +
|OUTPUT
 +
|SW2 - “DOWN”
 +
|Pulled up on mainboard (internally in ARM?); LOW means button is pressed
 +
|-
 +
|7
 +
|OUTPUT
 +
|SW5 - “START”
 +
|Pulled up on mainboard (internally in ARM?); LOW means button is pressed
 +
|-
 +
|8
 +
|
 +
|LCD Pin 21
 +
|
 +
|-
 +
|9
 +
|
 +
|LCD Pin 20
 +
|
 +
|-
 +
|10
 +
|INPUT
 +
|Backlight Switch
 +
|Run HIGH (~3.3v) to turn LCD backlight on; signal goes to transistor Q1
 +
|-
 +
|11
 +
|
 +
|LCD Pin 22
 +
|
 +
|-
 +
|12
 +
|POWER
 +
|GND
 +
|
 +
|-
 +
|13
 +
|
 +
|LCD Pin 10
 +
|
 +
|-
 +
|14
 +
|POWER
 +
|5V
 +
|Backlight Power; goes to K4; Measured at ~4.8V... K4 measured at ~3V
 +
|-
 +
|15
 +
|
 +
|LCD Pin 11
 +
|
 +
|-
 +
|16
 +
|POWER
 +
|3.3V
 +
|LCD Power
 +
|}

Latest revision as of 01:19, 3 September 2022

Neato XV-11 Robotic Vacuum

The Neato XV-11(Wikipedia) is a robot which vacuum’s your house. It is unlike any other however because it includes a low cost 360 degree laser distance scanner (LIDAR See Wikipedia). This can be removed from the XV-11 and used in your own robotics projects or used within the XV-11 with the help of the Robot Operating System (ROS). The pages within this wiki document interfacing methods into the XV-11 and is open to anyone who wants to help. For $399 you can’t find a better robotics platform in my opinion, definitely worth the cost even if you do nothing more than strip it down for parts. You will find it is very well constructed by some people who definitely know about robotics.

This content has been migrated from xv11hacking.com which is no longer available.

Connecting to ROS

ROS Driver

There is a ROS driver that connects to the XV-11 through the USB port, documentation can be found on the ROS wiki. This driver includes both an ROS-independent python implementation and an ROS node wrapper for the python implementation. It currently controls the mobile base, provides odometry feedback, and publishes laser scans. Future versions will include battery and sensor access features (the currently exist in the ROS-independent code, but have not yet been given a proper ROS API).

Install ROS on Ubuntu

The following procedure will help you install the Robot Operating System on Ubuntu 10.10 for use with the XV-11.

I have tested this running Ubuntu 10.10 as a VMware virtual machine as well as installed on a system as the booted OS. Ubuntu is a very easy to use Linux release you can download from here Now lets get started! Open a terminal by clicking on Applications -> Accessories -> Terminal Enter the following commands by copying and pasting them into the terminal window. Use CTRL-C to copy and then CTRL-SHIFT-V to paste them in the terminal window.

sudo sh -c ‘echo “deb http://code.ros.org/packages/ros/ubuntu maverick main” > /etc/apt/sources.list.d/ros-latest.list’
wget http://code.ros.org/packages/ros.key -O - | sudo apt-key add -
sudo apt-get update
sudo apt-get install ros-cturtle-base

The last command will install approximately 5GB worth of software so grab some coffee, a Rockstar, or your stimulant of choice! Once it is done installing run the commands below to install some more ROS software in your home folder.

cd; mkdir ros; cd ros
svn co https://brown-ros-pkg.googlecode.com/svn/tags/brown-ros-pkg/teleop_twist_keyboard
svn co http://albany-ros-pkg.googlecode.com/svn/trunk/slam_coreslam/coreslam
svn co http://albany-ros-pkg.googlecode.com/svn/trunk/neato_robot
echo ‘. /opt/ros/cturtle/setup.sh’ >> ~/.bashrc
echo ‘export ROS_PACKAGE_PATH=~/ros:${ROS_PACKAGE_PATH}’ >> ~/.bashrc
source ~/.bashrc
sudo su
echo ‘. /opt/ros/cturtle/setup.sh’ >> ~/.bashrc
echo ‘export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}’ >> ~/.bashrc
exit
cd ~/ros/teleop_twist_keyboard; rosmake
cd ~/ros/coreslam; rosmake
cd ~/ros/neato_robot; rosmake

Now we will edit the /etc/modules file so the usbserial driver will be automatically loaded with the parameters needed. We also add the cdc_acm driver to the blacklist so it will not be used with the XV-11. On a Macbook Pro the system used this driver instead of usbserial.

sudo su
echo “usbserial vendor=0x2108 product=0x780B” >> /etc/modules
echo “blacklist cdc_acm” >> /etc/modprobe.d/blacklist.conf
modprobe usbserial vendor=0x2108 product=0x780B
rmmod cdc_acm
exit

Almost time to plug your XV-11 into the system!! For the sake of simplicity do not plug in any other USB to serial devices at this point. This will ensure your XV-11 appears as /dev/ttyUSB0 and will simplify setup at this point.

ls /dev/ttyU*

Once you plug in the XV-11 you should see /dev/ttyUSB0 appear. Now lets load the XV-11 drivers.

roslaunch neato_node bringup.launch

Entering the above command should initiate a connection to /dev/ttyUSB0 and after a couple seconds you will hear the LIDAR start to spin on the XV-11. Don’t worry if you don’t hear it, press CTRL-C to exit the driver then enter the command again. I have found it does not seem to start properly upon first load. Now press CTRL-SHIFT-T while your terminal window is selected to open a new tab within that terminal window, just like a new web browser tab. We will open a few of these tabs to load the different ROS drivers/programs.

roslaunch 2dnav_neato move_base.launch
(open a new tab before running the next command)
rosrun rviz rviz

Just to verify, you should have three tabs open now with these three commands simultaneously running. SWEET HUH!! Now you have the GUI application running, just a couple more steps and its play time! On the top menu bar click Plugins -> Manage then click the box next to Loaded and click OK. There is a video here with details on setting up RViz. You can use this file with RViz and it has all those parameters already setup. Right click on the file and save it. Within RViz just go to File -> Open Config and select the XV11.vcg file. Now open a new terminal which we will use for keyboard control to manually navigate the XV-11.

rosrun teleop_twist_keyboard teleop_twist_keyboard.py

You will see which keys are used to navigate on the screen once the program is running. The default speed settings are too fast for the XV-11 so you need to reduce the speed before it will respond to any input. Repeatedly press the “x” key to reduce speed when traveling in a straight line to about 0.10 and then do the same with the “c” key to reduce rotational speed to about 0.15. Now you can use the keyboard keys to navigate.

From this point you need to create your own map using gmapping and save the map so a map of your area is loaded when launching 2dnav_neato. gmapping needs to be modified from the base install on your system at this point to correct the reversed laser scan data. This wiki will be updated shortly with that procedure. gmapping is what will allow you to create a map of your surroundings which you will use to navigate.

Disassembly and Reassembly

Pictorial instructions for disassembling and reassembling an XV-11 can be found at the Homebrew Robotics Club wiki linked off of the page: Dave’s XV-11 Notes. There are a few other XV-11 notes there as well, such as how to tap into the battery supply, and I’ll be adding more as I go along. I’m too lazy to update two wiki’s so I’ve decided to make the HBRC wiki my ‘home’ and cross-link from here to there and there to here. Anyway, the disassembly/reassembly instructions were done because I kept forgetting where all the screws go.

Hope it helps.

Hacking with Neato Firmware

Neato Firmware v2.6

A version 2.6 Neato XV-11 can be reverted to a previous firmware by pressing and holding the Back button (curved arrow) and the orange Start button at the same time for 4 seconds. When the robot reboots it will be running an older firmware with all the previous commands available.

Hidden Neato menu in newer 2.6 firmware!

Anyone who has updated their Neato firmware will notice a new message is returned when you enter ” Help” when connected to the robots USB port. Entering Help with a space before it used to return an extended hidden help menu with a lot more commands! When Neato released the 2.6 firmware update (or maybe earlier?) they removed the ” Help” and instead you got this response...

Nice try, but I’m not falling for that one again! :P

Some commands such as “SetStreamFormat” let you actually SEE what the robot is doing while driving around and mapping the environment internally. Some of the guys on Trossen Robotics forum (Chunk) have made really good progress using the output from this command! Sadly this is one of the commands removed from the 2.6 firmware version. But not for long!!


If you just press and hold the orange Start button and Back button at the same time for 4 seconds the robot will reboot into a different firmware that includes all those previous commands! Below is a capture from the on-board 4 pin serial port that shows debug data while the XV-11 is booting.


This capture is of the normal reboot (just holding the orange Start button for 4 seconds)

Neato Robotics XV-11/XEB V11:16:01
Copyright (c) 2006-2010 Neato Robotics, Inc

Loading installed application
Starting app
NEROSConfigErr: BlowerType=-1 (Expected 0
ConfigErr: BrushMotorType=-1 (Expected 0
ConfigErr: SideBrushType=-1 (Expected 0
FCB Invalid! Configurations may need to be initialized.

 Build 15840 Nov 14 2011 16:09:19

Init A2D
Configure power to STANDBY.
uart0EnablePeripheral
Power On reset: 8 :Software
DEBUG compile

Edison Design Group compiler

Init Pushbuttons.Finished halInit();
Sending GetVersion...
RCVD: Finished LDS getversion cmd in 5 ms
LDS reports build , we need build 15295 (size=16512)
Stop LDS driver to prevent contention
[]
Finished LDSBurn.
Sending GetVersion...
RCVD: Finished LDS getversion cmd in 4 ms
mmcReset Error

PH-drvrInit:Ignoring detected battery type because XV11.
PH-drvrStart:vacuumType(): Invalid SCB blower value. How did we get here?!

This capture is after holding the Start and Back buttons for 4 seconds.

Neato Robotics XV-11/XEB V11:16:01
Copyright (c) 2006-2010 Neato Robotics, Inc

Loading factory application
Starting app
NEROS Build 12882:12959 Jul 26 2010 22:38:28

Init A2D
Configure power to STANDBY.
uart0EnablePeripheral
Power On reset: 8 oftware
DEBUG compile

Edison Design Group compiler
Enabling USB-CDC ...

Crashblock file: @ 0
Crashblock fn:
Crashblock TOS:0x00000000
Crashblock watchvalues:

Init Pushbuttons.Finished halInit();
mmcReset Error

PH-drvrInit:
PH-drvrStart:


It appears this may be a secondary firmware loaded as a failsafe in case a USB firmware upgrade fails. This would make tech support easier as you have a firmware to revert too in case something goes wrong. You can see from the dates in each print out that they are completely different builds. Thanks to Theo Deyle for e-mailing me and inspiring me to work on this some more! Hopefully his own hacks will be posted soon as well!

Neato Firmware v3.0

The Neatos that are delivered with Firmware 3.0 are a different hardware revision compared to previous models.

Previous versions (incl. the Vorwerk VR100) are codename ‘Cruz’.

The new hardware revision has codename ‘Binky’.

There’s a bootloader you can get into on my XV25/Binky. I don’t know if this is unique for Binky:

testmode on
setsystemmode PowerCycleCDC

The Neato then disappears from the USB, and reappears with a limited CLI that doesn’t local echo and doesn’t support most commands I’ve tried.

help
Cmd not recognized.
getversion
NeatoBootVer,2.0,0
upload code
File size invalid

There’s more, but be careful.

Also, don’t try to stuff the Vorwerk update into here.

That’s for Cruz, and will probably brink your Binky.

Here’s the version data before upgrade:

getversion
Component,Major,Minor,Build
ModelID,-1,XV25,
ConfigID,2,,
Serial Number,XXX00000XX,0015662,P
Software,3,0,17235
BatteryType,1,NIMH_12CELL,
BlowerType,1,BLOWER_ORIG,
BrushSpeed,1200,,
BrushMotorType,1,BRUSH_MOTOR_ORIG,
SideBrushType,1,SIDE_BRUSH_NONE,
WheelPodType,1,WHEEL_POD_ORIG,
DropSensorType,1,DROP_SENSOR_ORIG,
MagSensorType,1,MAG_SENSOR_ORIG,
WallSensorType,1,WALL_SENSOR_ORIG,
Locale,1,LOCALE_USA,
LDS Software,V2.6.15295,0000000000,
LDS Serial,XXX00000XX-0000000,,
LDS CPU,F2802x/c001,,
BootLoader Software,17225,P,p
MainBoard Vendor ID,543,,
MainBoard Serial Number,000000000000000000000000,,
MainBoard Software,17242,1,
MainBoard Boot,16219,
MainBoard Version,4,0,
ChassisRev,2,,
UIPanelRev,1,,
testmode on
testlds cmd getversion
Sending getversion...
getversion
 
GetVersion...3 ESCs or BRAK to abort...:)
Piccolo Laser Distance Scanner
Copyright (c) 2009-2011 Neato Robotics, Inc.
All Rights Reserved
 
Loader    V2.5.14010
CPU    F2802x/c001
Serial    XXX00000XX-0000000,,
LastCal    5371726C
Runtime    V2.6.15295
OK

#testmode off

This is after the upgrade

getversion
Component,Major,Minor,Build
ModelID,-1,XV25,
ConfigID,2,,
Serial Number,XXX00000XX,0015662,P
Software,3,1,17844
BatteryType,1,NIMH_12CELL,
BlowerType,1,BLOWER_ORIG,
BrushSpeed,1200,,
BrushMotorType,1,BRUSH_MOTOR_ORIG,
SideBrushType,1,SIDE_BRUSH_NONE,
WheelPodType,1,WHEEL_POD_ORIG,
DropSensorType,1,DROP_SENSOR_ORIG,
MagSensorType,1,MAG_SENSOR_ORIG,
WallSensorType,1,WALL_SENSOR_ORIG,
Locale,1,LOCALE_USA,
LDS Software,V2.6.15295,0000000000,
LDS Serial,XXX00000XX-0000000,,
LDS CPU,F2802x/c001,,
MainBoard Vendor ID,543,,
MainBoard Serial Number,555,,
BootLoader Software,17225,P,p
MainBoard Software,17624,1,
MainBoard Boot,16219,
MainBoard Version,4,0,
ChassisRev,2,,
UIPanelRev,1,,
testmode on
testlds cmd getversion
Sending getversion...
getversion
GetVersion...3 ESCs or BREAK to abort...:)
Piccolo Laser Distance Scanner
Copyright (c) 2009-2011 Neato Robotics, Inc.
All Rights Reserved
 
Loader V2.5.14010
CPU F2802x/c001
Serial XXX00000XX-0000000,,
LastCal 5371726C
Runtime V2.6.15295
OK

#testmode off

Interfacing with LIDAR Sensor

I created a board to interface the LIDAR sensor to a PC without the rest of the XV-11. The PCB consists of a PIC18F2221, and FTDI-232R, a 3.3V regulator, and a Fet for controlling the motor. The pic watches the data from the LIDAR and uses the speed information to control the PWM pin attached to the FET. In this way the correct speed can be maintained. The Firmware for the pic currently only supports the old LIDAR firmware ( that is what I have). Hopefully someone else can modify it to work with the other firmware as well. There are jumpers for configuring who talks to what between the PC, PIC, and LIDAR. There are also options for supplying your own 5V instead of getting it from USB and an option for using an XBEE for wireless communication. Schematics are posted below as well as the Eagle brd files. Source code for the PIC will be posted soon. I have spare boards for sale if anyone is interested. Ringo (dot) Davis (at) gmail (dot) com.

 
LIDAR mounter on interface board
 
LIDAR plugged in to Interface board


LIDAR API Commands

Commands available from the LIDAR via direct serial connection or through the Main PCB API To access the API directly via the serial connection of the sensor, send an ESCAPE character (0x1B). The lidar then responds with an invite : “#” You can then enter commands (below is the result of Help command, some additional hidden commands are probably available)

#
# Help
GetVersion
Help
Log
SaveCal
SetSerial
Upload
Wanderer
Calibrate b16 b8 SunBlind loop2AA loop155
GetCal A B C LPT LFL LFT LFH IMX IB LPI LCH LPD ANG
SetCal A B C LPT LFL LFT LFH IMX IB LPI LCH LPD ANG
Spin Fake DotX DotI Text Hash Timing Foto RPS Pac
TestEncoder

Commands are case-insensitive, and can be entered incompletely : getversion, getvers, getv, GeTvErSiOn will all work alike. Be aware that one at least of these commands can brick your LDS... Here are the details of what is currently known about these commands: (To be completed!)

GetVersion

Prints informations about the version of the LDS. Example:

GetVersion...press ESC 3 times to abort...OK
Piccolo Laser Distance Scanner
Copyright (c) 2009-2010 Neato Robotics, Inc.
All Rights Reserved

Loader V2.4.13386
CPU F2802x/c600
Serial AAA42110AA-0003616
LastCal [2010110136]
Runtime V2.4.13386
SUCCEEDED
Help

Prints a list of available commands. Example:

Help...press ESC 3 times to abort...
  GetVersion
  Help
  Log
  SaveCal
  SetBaud
  SetSerial
  Upload
  Wanderer
  Calibrate b16 b8 SunBlind loop2AA loop155
  GetCal A B C LPT LFL LFT LFH IMX IB LPI LCH LPD ANG
  SetCal A B C LPT LFL LFT LFH IMX IB LPI LCH LPD ANG
  Spin Fake DotX DotI Text Hash Timing Foto RPS Pac
  TestEncoder
SUCCEEDED
Wanderer

Draws a squirrel in a heart, in ASCII art... Example:


LIDAR Mechanical Info

Place any info here relating to mechanical aspects of the LIDAR.

2D CAD files of the XV-11’s LIDAR unit, in mm. Thanks goes to chenglung from the Trossen Robotics Forums.

3D CAD model of the LIDAR unit. Note that I used the 2d cad files mentioned above along with my own measurements, so be warned that the following is not completely accurate. Also, I’m no CAD professional, so you won’t find much detail in the model - just enough to account for any significant design properties which may be useful to know when building the module into your own applicatio

XV-11 LIDAR Mechanical Files contains the following

  • 2D CAD Files
    • XV-11_LDS CAD.zip
    • XV-11 LDS.pdf
  • 3D CAD Files
    • xv-11_lidar.SLDPRT
    • xv-11_lidar.STL
    • xv-11_lidar.IGS
    • xv-11_lidar.PDF

If anyone needs the file in some other format, just send me a request and I’ll try to help you out: rus.tech.studio ‘@’ gmail.com


LIDAR Sensor

The LIDAR sensor is what started this entire project. Find all the information you need below.

The angle of the data is not aligned with the natural axis of the device. It seems that the first sample of the first packet is in fact looking at a -10° angle, not 0°. Needs confirmation.

Data format for firmware V2.4

(recent production units)

A full revolution will yield 90 packets, containing 4 consecutive readings each.

The length of a packet is 22 bytes. This amounts to a total of 360 readings (1 per degree) on 1980 bytes. Each packet is organized as follows:

start  byte  index  speed  Data 0  Data 1  Data 2  Data 3  checksum

where:

  • start byte is always 0xFA
  • index is the index byte in the 90 packets, going from 0xA0 (packet 0, readings 0 to 3) to 0xF9 (packet 89, readings 356 to 359).
  • speed is a two-byte information, little-endian. It represents the speed, in 64th of RPM (aka value in RPM represented in fixed point, with 6 bits used for the decimal part).
  • Data 0 to Data 3 are the 4 readings. Each one is 4 bytes long, and organized as follows :
byte 0 : Distance 7:0
byte 1 : “invalid data” flag : “strength warning” flag
byte 2 : Signal Strength 7:0
byte 3 : Signal Strength 15:8

As chenglung points out, the distance information is in mm, and coded on 14 bits. This puts the tests made by Sparkfun in a room of around 3.3m x 3.9m (11ft x 13 ft ?), which seems reasonable.

The minimum distance is around 15cm, and the maximum distance is around 6m.

When bit 7 of byte 1 is set, it indicates that the distance could not be calculated. When this bit is set, it seems that byte 0 contains an error code. Examples of error code are 0x02, 0x03, 0x21, 0x25, 0x35 or 0x50...

When it’s `21`, then the whole block is `21 80 XX XX`, but for all the other values it’s the data block is `YY 80 00 00`...

The bit 6 of byte 1 is a warning when the reported strength is greatly inferior to what is expected at this distance. This may happen when the material has a low reflectance (black material...), or when the dot does not have the expected size or shape (porous material, transparent fabric, grid, edge of an object...), or maybe when there are parasitic reflections (glass... ).

Byte 2 and 3 are the LSB and MSB of the strength indication. This value can get very high when facing a retroreflector.

  • checksum is a two-byte checksum of the packet.

The algorithm is as follows, provided that `data` is the list of the 20 first bytes, in the same order they arrived in.

def checksum(data):
 “”“Compute and return the checksum as an int.”“”
 # group the data by word, little-endian
 data_list = []
 for t in range(10):
   data_list.append( data2*t + (data2*t+1<<8) )

 # compute the checksum on 32 bits
 chk32 = 0
 for d in data_list:
   chk32 = (chk32 << 1) + d

 # return a value wrapped around on 15bits, and truncated to still fit into 15 bits
 checksum = (chk32 & 0x7FFF) + ( chk32 >> 15 ) # wrap around to fit into 15 bits
 checksum = checksum & 0x7FFF # truncate to 15 bits
 return int( checksum )

Data format for firmware 2.1

(Sparkfun scans, pre-production units)

The periodicity of the data is 1446 bytes.

It is organized as follow :

5A  A5  00  C0  XX  XX  data

where `XX XX` is an information about the current rotation speed of the module, in clock ticks (little endian). http://forums.trossenrobotics.com/showthread.php?t=4470&page=5 posted interesting data about this.

`` is composed of 360 group of 4 bytes, organized like this :

byte 0 : Distance 7:0
byte 1 :  “invalid data” flag : ”quality warning” flag : distance 13:8
byte 2 : Quality 7:0
byte 3 : Quality 15:8

As chenglung points out, the distance information is in mm, and coded on 13 or 14 bits. This would put the tests made by Sparkfun in a room of around 3.3m x 3.9m (11ft x 13 ft ?), which seems reasonable to me. 13 bits should be enough if the sensor is destined to work up to 6m. This needs some tests...

The bit 7 of byte 1 seems to indicate that the distance could not be calculated.

It’s interesting to see that when this bit is set, the second byte is always `80`, and the values of the first byte seem to be only `02`, `03`, `21`, `25`, `35` or `50`...

When it’s `21`, then the whole block is `21 80 XX XX`, but for all the other values it’s the data block is `YY 80 00 00`

maybe it’s a code to say what type of error ? (`35` is preponderant, `21` seems to be when the beam is interrupted by the supports of the cover) .

Another thing to have a look to is the temporal repartition of the data... the first sample after the sync seems to always be `21 80 XX XX`, and when this pattern appears again, it’s immediately after an other value, without the 0.2ms interval we can see most of the time between two blocks of 4...

The bit 6 of byte 1 is a warning when the reported strength is greatly inferior to what is expected at this distance. This may happen when the material has a low reflectance (black material...), or when the dot does not have the expected size or shape (porous material, transparent fabric, grid, edge of an object...), or maybe when there are parasitic reflections (glass... ).

Byte 2 and 3 are the LSB and MSB of the strength indication. This value can get very high when facing a retroreflector.


Motors

Data on the drive motors, brush motor, and vacuum fan.

SetMotor Command

Motor speeds can be set using the SetMotor commands. This command is handled asynchronously, so you can query other commands while the robot is moving. The simplest way to set both the left and right motor speed is to use:

SetMotor left_dist right_dist speed

Where left_dist and right_dist are a distance to travel in millimeters, and speed is the speed to use for movement in millimeters per second. Speed must be positive, and at least one of left_dist or right_dist must be non-zero. Drive motor speeds are -300 mm/s to 300 mm/s. These max speeds also induce a rotational max speed of approximately +/- 2.25 radians/sec given the separation of the wheels.

It appears that when different distances are put in, the speed will be applied to the wheel moving the farther distance, and the other wheel will be scaled such that both wheels take the same amount of time to travel their complete distance. (Can someone confirm this on their bot? - Fergy).

Some examples:

  • SetMotor 100 100 100 - will move the robot forward 100mm, in approximately one second
  • SetMotor 100 -100 100 - will turn the robot to the right in place, for 1 second.
  • SetMotor 100 200 100 - the robot will move forward and to the left, for 2 seconds.

The base width separation of the wheel is approximately 248 millimeters. Therefore, the circumference when turning in place is approximately 780 millimeters. Thus, we can turn the robot using:

  • SetMotor 195 -195 100 - the robot will turn in place, 90 degrees to the right.


Neato XV series WiFi remote control

Neato is great in cleaning by it self, it also has good “spot clean” algorithm! But, what if you want to clean just a certain spot? In other words - use it like a regular vacuum?

That was the basic idea which led to realization of the full wireless remote control.

As you may know, you can manually control Neato right out of the box by connecting it to any computer via usb and, through any terminal program, send commands to robot (for some reason article describing command list on official Neato site is unreachable at this moment, but you can get it by typing ‘help’). The way you can control Neato movements is described here: XV-11 API Commands

This is really great, but how can one use it for robot’s intended purpose if he or she is limited by the length of the wire? Of course you can take a laptop!  But for me it was not the answer. Luckily, my friend recently has brought a compact (very compact) WiFi router (Commonly available from eBay as “2g/3g/4g wifi router”, also known as HAME MPR-A5 and MIFI-F5. MPR-A1 and clones are likely to work as well if you manage to fit them in. Some additional material is available on http://my-embedded.blogspot.com/2013/12/mini-4g-router-rt5350f.html) and suggested that we should try to embed it into my Neato.

So, it was obvious that all we needed was to find +5V power supply and connect usb from router to neato’s usb. All that sounds simple, so we did it. (i should say that my Neato has rev.64 main board)

 
VCC - Red wire, D- - White wire, D+ - Green wire. (regular USB pinout)

Very soon we realized that, first of all - there is no powerful enough +5V source on the main board, and the second one - Neato’s software blocks it from normal functioning if it senses power supply on its usb

The answer to the first problem was as simple as buying 5V 500mA DC-DC converter (DC-DC on digikey.com) A local shop had Peak PSR-7805LF available for a reasonable price so I settled on that one.

 
Neato WiFi PCB Power

Answer to the second problem was a bit tricky! On the router board there is a source of power which can be turned on/off by changing state of its GPIO8 (echo 1 >/sys/class/gpio/gpio8/value), so my friend suggested that we will be able to control usb power supply by one P-N-P transistor witch base must be connected to that gpio. All that going to be great if only router could gave us +5V, but its voltage is only +3.3V. In the end the answer was found: we’d connected +5V from DC-DC to the Neato’s usb through one p-n-p and one n-p-n transistor (with a pair of resistors) controlled by the router’s +3.3V as shown below.

 
Neato WiFi adaptor schematic
 
To get rid of micro USB plug we soldered power supply wires from DC-DC right on router’s board
 
To get rid of micro USB plug we soldered power supply wires from DC-DC right on router’s board
 
To fit router with all the stuff inside neato’s body i’ve made a small ‘modification’ using my dremel

So now i have a fully functional Neato with a full control from any place in the world ;) I can remotely start cleaning in full cycle, or change its schedule, or use it full manual, or, even, just play like with RC car!


Open source Linux for Neato

Newer models (XV-14/XV-15/XV-21/XV-25 ???) with board revision 64 are running on Linux Kernel 2.6.33.7

The open source parts of the code are provided on the CD labeled as “Neato Vacuum User Guide” that comes with the robot. The source is located under the directory “LinuxSrc”

 
Neato XV-11 Photo of CD
 
Neato XV-11 Folders of CD


The source contains few Neato specific bits related to the operation of the robot, however some interesting details are disclosed:

  • The unpopulated footprint (J2) on the PCB Rev 64 is indeed a SD Card footprint, and the source reveals that the kernel has SD Card support.
  • The presence USB Gadget drivers of suggests that the Neato has USB OTG support and “Ethernet over USB” capabilities (unconfirmed)
  • Mystery .raw file \LinuxSrc\rootfs\etc\test_map.raw (400KB). Could this be sample LIDAR data?
  • Contents of the file \LinuxSrc\rootfs\etc\Issue: “Welcome hackers!”. :
  • Readme.txt of the LinuxSrc folder


Bootloader Access

Bootloader access can be achived by isseuing the following command to the robot over USB Serial connection.

testmode on
setsystemmode PowerCycleCDC

(*CDC = Communications Device Class ????)

The Neato then reappears on the serial bus (on Windows you might have to unplug and reconnect the USB cable for this device to appear) as an another device “XV-11 BOOTLOADER”

Accessing this device offers a limited console over USB serial with no local echo.

Contents of the folder LinuxSrc\boot indicate that U-boot is, or was used as, bootloader on the Neato at some point “Hopefully u-boot doesn’t make it to production, but if it does.., LinuxSrc\boot\arch\arm\cpu\lpc313, line 453.

The Neato bootloader console does not support any of the standard U-boot commands.

help
Cmd not recognized.
getversion
NeatoBootVer,2.0,0

Supported commands at bootloader console

Command Usage Description
GetVersion getversion Prints version information
Boot boot boot the robot OS
Upload ? upload firmware to the robot?
download firmware from the robot?

Looking for commands at the bootloader console

The bootloader console matches input stream “byte by byte” to find the first match. For example input “bootxyz123hskdfhskdjfhksjd”, triggers the “boot” command, ignoring any trailing charachters. This implies that there are no variations on commands like “bootusb” (unconfirmed).

Flashing the Neato

Warning messing around with the bootloader could potentially brick your robot with no known method of recovery

Using the bootloader console it might be possible to flash the Neato using a custom firmware (unconfirmed).

upload code
File size invalid

Neato open source code

The files are clearly identified as open source! (106MB)

http://www.axifile.com/en/F2D0DB4C4E

(note: if this link doesn’t work anymore, then there was no use for it in the past 30 days... let me (KPPlayer)

know and I’ll upload again.)

Other resources

http://www.nxp.com/products/microcontrollers/arm9/LPC3143FET180.html Vendor info and datasheet for the NXP LPC3134

http://dfu-util.gnumonks.org/ USB DFU (Device Firmware Upgrade) Utilities. DFU possible?

http://www.lpclinux.com/LPC313x/LPC313xMain How to get Linux running on a NXP LPC313/4/5


PCB Versions

Early PCB Version

 
Neato XV-11 Early PCB Version
Neato XV-11 BOM and Parts identification
Ref. Desg. Manufacturer Part Number Description
U1 Allegro A3950SEUTR-T DMOS Full-Bridge Motor Driver
U5 Allegro A3950SEUTR-T DMOS Full-Bridge Motor Driver
U16 ST LIS302DL 3-axis - ± 2g/± 8g smart digital output “piccolo” accelerometer
U17 Fairchild MM74HC4051MTC 8-Channel Analog Multiplexer
U18 Fairchild MM74HC4051MTC 8-Channel Analog Multiplexer
U26 Allegro A4490EESTR-T Triple Output Step-Down Switching Regulator
U29 ATMEL AT91SAM9XE128-QU AT91 ARM Thumb Microcontrollers PQFP208
U32 Winbond W988D6FB SDRAM (typeno varies) - 256Mb (32MByte) Mobile LPSDR
U34 ZETEX ZXMHC3A01T8 COMPLEMENTARY 30V ENHANCEMENT MODE MOSFET H-BRIDGE
U36 National Semi NC7SZ14 Tiny UHS Inverter with Schmitt Trigger Input
U39
U44 National Semi NC7SZ14 Tiny UHS Inverter with Schmitt Trigger Input
U45 National Semi NC7SZ14 Tiny UHS Inverter with Schmitt Trigger Input
U35 ST NAND128W3A2BN6 16MByte small-page NAND flash

(on bottom side of PCB)


Ref. Desg. Description
J1 Charging Jack
J2 UI Board (LCD/Buttons)
J3 Direct connection to the ERASE line of the AT91 processor!! Shorting this jumper and rebooting the

XV-11 will result in a complete loss of programming. No known recovery method at this time.

SW1 Switch input used to hard reboot the processor. Probably used in conjunction with J3 for development

purposes.

P1 Battery pack thermistor input (Thermistor measures ~10k at 70 degrees Fahrenheit on battery)

For battery locations, viewing XV-11 from above with the laser at the bottom and bumpers up top: Wire Color\Pins Orange,Blue\1,2 = Left Battery Yellow,Green\3,4 = Right Battery

P2 Main power input
P3 Header for Bluetooth module (BlueSMiRF)
P4 Unknown. Leads to SPI of the AT91 processor: Probably MMC/SD connection.
P5 Bumper switch inputs x4

For button locations, viewing XV-11 from above with the laser at the bottom and bumpers up top: Wire Color\Pins Blue\1,2 = Left Side Yellow\3,4 Top Left Purple\5,6 Top Right Orange\7,8 Right Side

P6 Header used to communicate with the AT91 via serial connection.

P6:1 Unused (square pad), P6:2 AT91_RXD, P6:3 AT91_TXD, P6:4 Ground

P8 LIDAR Motor connector
P9 Brush motor Input/Output

Pins 1,2 = Brush motor power 3,4,5 = Input from encoder

P10 JTAG. Bottom row: VDDIO (square pin), TRST, TDI, TMS, TCK. Top row: GND, GND, SRST, TDO, RTCK. The JTAG-port unfortunately is software-disabled for debugging the ARM processor core.
P11 Viewing XV-11 from above with the laser at the bottom and bumpers up top:

1,2,3 = Top Right Side Wall Distance Sensor (Sharp 0A51SK F 0X)

P12 LIDAR power/serial connection
P13 Magnetic strip sensors and floor distance sensors (detecting edge before falling down stairs)

For sensor locations, viewing XV-11 from above with the laser at the bottom and bumpers up top: Pins 1,2,3 = Top Left Distance Sensor (Sharp 0A51SK F 0X) 4,5,6 = Top Left Hall Effect Sensor (Allegro 21E) 7,8,9 = Top Right Distance Sensor (Sharp 0A51SK F 0X) 10,11,12 = Top Right Hall Effect Sensor (Allegro 21E)

P14 Speaker
P16 Dustbin installed/removed input (Soft rubber button under dustbin)
P18 Charging input for wall docking charger
P19 Vacuum motor
P20 USB Connection to ATMEL processor
P22 Right Wheel

Pins 1,2 = motor power 3,4,5 = Input from encoder

P23 Left Wheel

Pins 1,2 = motor power 3,4,5 = Input from encoder

P24 Temperature input from brush motor, taped to motor (Measures ~10k at 70 degrees Fahrenheit)

PCB Rev. 64

 
Neato XV-11 PCB Rev64 Top
 
Neato XV-11 PCB Rev64 Bottom
Ref Desg. Manufacturer Part Number Description Info
U1 TI 5V Regulator Triggered when Room Scanner is on
U2
U3 STM LIS3DH Three axis accelerometer
U4 TI 3.3V Regulator U4 and U23 both Infineon

Spec Sheet

U5
U6
U7
U8 STM STM32F100R4T6B

ARM

I/O-controller (motors, switches, etc) with RTC and low frequency quartz (responsible for time keeping during sleep/shut off)
U9
U10
U11 MICRON MT48LC16M16A2-7E 256Mb (32MB) SDRAM
U12
U13
U14 NXP LPC3143FET180

ARM9

(main-)controller with external memory http://www.nxp.com/products/microcontrollers/arm9/LPC3143FET180.html
U15
U16
U17
U18 STM NAND128W3A2BN6F 128Mb (16MB) NAND
U19
U20
U21
U22
U23 TI 5V Regulator http://www.ti.com/product/LM78M
Ref. Desg. Description
J1 UI Board (LCD/Buttons) connector
J2 SD card header (unpopulated)
P2 UART header??? (unconfirmed)
P3 UART header??? (unconfirmed)
P9 Motor from Side brush (VR100)?
P13 Main power input
P15 Right Wheel
P16 Left Wheel


Viewing Maps from the XV-11’s Point of View

Warning: This feature seems to be missing in the current (v2.6) firmware.)

Even though we’ve got the ability to make our own maps using the XV-11’s sensor and ROS, it’s nice sometimes to be able to see them from the XV-11’s point of view.

Due to the efforts of some of the guys at TrossenRobotics (thread link), the SetStreamFormat packet datastream has been partially decoded--at least to the point of being able to grab maps from a running XV-11

The source code is available on githhub here: XV-11 Stream Parser

After compilation, the code can be used to translate dumps of the XV-11 packet stream into nice 256x256 animated gifs, so you can see into the mind of the XV-11.

You can use the following command to test it out:

bin/parser -f example/Packet\ Mode\ Bathroom1\ 09-03-2011.txt

View the help (run with -h or no flags) for details on the available options.

It can also show you the laser scans of the robot (though the position estimation of the robot is based on some hackish intersection code)

XV-11 API Commands

Commands available through the USB port on the XV-11

Neato Robotics currently has an list of commands accessible to people who want to tinker with their robots.

See their official site for information: http://www.neatorobotics.com/programmers-manual

Getting a list of Commands

Your first point of call is the Neato Robotics Programmers Manual listed above. Also if you have an established link to your Neato you can type:-

help

which will list all available commands.

You can also get additional information about commands by typing the command function name after the word help, eg:-

help getmotors

Enabling TestMode

A lot of the functions available to programmers can only be used if “TestMode” has been enabled on the Neato. Most functions displayed in the Help are listed as “TestMode Only” which will give you an idea as to what can be only be used when TestMode is enabled.

If you attempt to use a command before you have enabled TestMode, Neato will politely state that “TestMode must be on to use this command.

To Enable TestMode

testmode on

To Disable TestMode (do remember to disable TestMode to return your Neato back to normal after you have finished tinkering)

testmode off

With TestMode enabled, you Neato will behave a little differently than normal.

  • All buttons on the robot will NOT respond to input as it normally does
  • You may not be able to re-establish connection to your robot if you unplugged and reconnected in a short period of time. If you cant re-establish connection, wait a few mins before attempting again.

The following commands and examples listed below will assume you have TestMode enabled, (unless specified differently)

Issuing Commands to the Motors

When you are first experimenting with command, I recommend you turn Neato up-side-down so the wheels can free spin. Otherwise you may get instances where your robot drives away faster than you expected, crashing into things and generally making a mess of your room as it lacks logic to stop.

The basic command to move is

setmotor LeftWheelDistance RightWheelDistance Speed

As I tested in firmware 2.6, Neato’s maximum speed is 300. If you exceed this value, Neato will report back something like “Invalid Speed Specified(500). Must be between 0 and 300

Some basic movement examples

To drive forward 10cm:-

setmotor 100 100 100

To spin on the spot (rotate clockwise):-

setmotor 900 -900 100

To do a left-handed U-Turn (rotate anti-clockwise):-

setmotor 0 1000 100

As I have been experimenting, my Neato seems to steer to the left a little as it drives along in a ‘straight’ line. I’ve also had differences in distance travelled depending on my speed setting. I have yet to sit down and measure the accuracy of these movement commands.

Problems You May Encounter

A little issue I found in my tinkering exploits, Neato would suddenly power off when issuing commands. This seems to be because I was issuing a large amount of commands within a short period of time. To give you an idea, I was issuing a set of three SetLED commands once every 20ms. Within about 2seconds, Neato would power off. To fix the issue, unplug your USB, power up Neato and reconnect the USB.

LCD PCB Information

 
Neato XV-11 LCD panel front
 
Neato XV-11 LCD panel back

IMPORTANT LCD INFORMATION!!! As you can see in the first image, the LCD is labeled “GVLCM128128G 13572A” on its backside. Googling this brings up the following LCD producer: Golden Vision. However, this exact LCD is not listed on their site, but this similar one is. All the measurable specs are similar (dimensions are approximately the same - the XV-11’s LCD measures approximately 61.6 mm x 55.1 mm x 4.36 mm, which is a bit thicker, probably due to the backlight; 128 x 128 resolution). The only differences I could find are the small white line above the ribbon cable at the bottom of the “similar” LCD isn’t present on the XV-11 LCD, and the ribbon cable of the “similar” LCD is 24 pins, not 25 (so the “similar” LCD CANNOT BE USED AS A REPLACEMENT - IT WOULDN’T BE PIN COMPATIBLE!). Anyway, the company only lists a few 128x128 LCD’s in production (none of which match the XV-11’s), so this narrows down the list of possible LCD controllers used in the XV-11’s LCD to just the ST7541 (others are possible but you could say these are more likely since we know this is the only chip the company uses in their 128x128 greyscale LCD’s). We can’t be sure until we test out driving this LCD standalone (on my TODO list for the next 2 weeks - I’m waiting on a FFC Ribbon Cable Breakout to come in from New Haven Display (look here if interested), but from what the datasheet says and the fact that only 2 of the LCD’s ribbon cable pins are appear to have data running thru them, it seems like the LCD is controlled by i2c from the main board (see below for pinouts).


The white FFC ribbon cable leading connecting the LCD board to the mainboard has a 1mm pitch.


The buttons on the LCD board have a pair of legs connected to ground, so it’s safe to deduce that the main board has these buttons’ signals pulled up (these pullups are not found on the LCD board) and expects to read a LOW signal when these buttons are pressed down. See table below for which button is which.


K1, K2, and K3 labeled in the second image are 3 of the 4 pins attaching the LCD backlight to the PCB. These pins go thru resistors to Q1, which appears to be a transistor driven by pin 10 of the white FFC ribbon cable (going to the mainboard). When a voltage is applied to Q1, it connects K(1-3) to GND, turning the backlight ON. K4, the last of the backlight’s pins, connects to pin 14 of the white FFC ribbon cable (see table below for appropriate voltages).


All 4 LED’s (2 per Double-LED) run fine at about 20mA @ 2V, with ~ 68 Ohm resistors each, so a 3.3V signal line that can source about 40mA should suffice for each color (each LED color pair has its own pin - see table below)


EagleCAD LCD PCB Files:

I’ve reverse engineered the LCD peripheral board into EagleCAD, just in case it comes in handy.

IMPORTANT DISCLAIMER: I did my best to determine all the dimensions, but there are likely some minor inaccuracies. Looking at the XV-11’s case, the LCD PCB fits snugly in the outline and all the buttons and LED’s have to line up nicely with the plastic to work properly. If for whatever reason you want to use these files to produce a custom LCD peripheral board, just be warned it may not work (but this is probably your best chance at a template for one).


16 Pin Main PCB FFC Ribbon Cable (white) Pinout (still working on it...):

Pin # Signal Type Signal Notes
1 (*) OUTPUT SW1 - “SOFT” Pulled up on mainboard (internally in ARM?); LOW means button is pressed
2 OUTPUT SW3 - “BACK” Pulled up on mainboard (internally in ARM?); LOW means button is pressed
3 POWER/INPUT Green LED’s Run HIGH ~(3.3V) to turn on, make sure the pin can source ~40mA
4 OUTPUT SW4 - “UP” Pulled up on mainboard (internally in ARM?); LOW means button is pressed
5 POWER/INPUT Amber LED’s Run HIGH ~(3.3V) to turn on, make sure the pin can source ~40mA
6 OUTPUT SW2 - “DOWN” Pulled up on mainboard (internally in ARM?); LOW means button is pressed
7 OUTPUT SW5 - “START” Pulled up on mainboard (internally in ARM?); LOW means button is pressed
8 LCD Pin 21
9 LCD Pin 20
10 INPUT Backlight Switch Run HIGH (~3.3v) to turn LCD backlight on; signal goes to transistor Q1
11 LCD Pin 22
12 POWER GND
13 LCD Pin 10
14 POWER 5V Backlight Power; goes to K4; Measured at ~4.8V... K4 measured at ~3V
15 LCD Pin 11
16 POWER 3.3V LCD Power