SRV-1 robot and protocol

“Designed for research, education, and exploration, Surveyor’s SRV-1 internet controlled robot employs the SRV-1 Blackfin Camera Board with 1000MIPS 500MHz Analog Devices Blackfin BF537 processor, a digital video camera with resolution from 160×128 to 1280×1024 pixels, laser pointer or optional ultrasonic ranging, and WLAN 802.11b/g networking on a quad-motor tracked mobile robotic base.”

[From the now defunct website for the SRV-1]

Definition of the SRV-1 Control Protocol

All commands from the host to the SRV-1 robot are comprised of ASCII characters or ASCII followed by 8-binary or ASCII decimal characters. All commands receive an acknowledgment from the robot to the host, which is either a ‘#’ character followed by the command, or ‘##’ for variable length responses. Variable length commands which don’t specify a return size append a CR + newline (‘\r\n’) to their response.
Command Response Description
Core Robot Commands
except for ‘q’ command, all parameters are sent as 8-bit binary characters (0x00 – 0xFF)
‘7’ ‘#7’ note that keypad commands (‘1’ – ‘9’) don’t become active until an ‘Mxxx’ motor control command has been received

robot drift left

‘8’ ‘#8’ robot drive forward
‘9’ ‘#9’ robot drift right
‘4’ ‘#4’ robot drive left
‘5’ ‘#5’ robot stop
‘6’ ‘#6’ robot drive right
‘1’ ‘#1’ robot back left
‘2’ ‘#2’ robot drive back
‘3’ ‘#3’ robot back right
‘0’ ‘#0’ robot rotate left 20-deg
‘.’ ‘#.’ robot rotate right 20-deg
‘+’ ‘#+’ increase motor/servo level
‘-‘ ‘#-‘ decrease motor/servo level
‘<‘ ‘#<‘ trim motor balance toward left
‘>’ ‘#>’ trim motor balance toward right
‘a’ ‘#a’ set capture resolution to 160×120
‘b’ ‘#b’ set capture resolution to 320×240
‘c’ ‘#c’ set capture resolution to 640×480
‘d’ or ‘A’ ‘#A’ set capture resolution to 1280×1024
‘D’ ‘##D’ checks MN13812 battery level detect circuit on SVS
returns:
##D – battery voltage okay
##D – low battery voltage detected
‘E’ launches flash buffer line editor –
(T)op (B)ottom (P)reviouse (N)ext line (L)ist (I)nsert until ESC (D)elete (H)elp (X)exit
‘Fab’ ‘#F’ Enables Failsafe mode for motor control
‘ab’ parameters sent as 8-bit binarya = left motor/servo failsafe level, b = right motor/servo failsafe level.sets motor/servo levels for ‘M’ and ‘S’ commands in case no command is received via the radio link within 2 seconds.
‘f’ ‘#f’ disables Failsafe mode
‘G’ HTML stream HTTP GET command – parses HTTP request, e.g.
GET /index.html HTTP/1.1- recognizes files /00.html .. /09.html, stored respectively in flash sectors 10/11, 12/13 .. 28/29- /index.html == /00.html- will replace “$$camera$$” with base64 live captured JPEG- use ‘zBxx’ to store in sector pair – zb10 stores 128kB from flash buffer to sectors 10/11
‘I’ ‘##IMJxs0s1s2s3….’ grab JPEG compressed video frame

x = frame size in pixels:
1 = 80×64, 3 = 160×120, 5 = 320×240, 7 = 640×480, 9 = 1280×1024

s0s1s2s3=frame size in bytes (s0 * 256^0 + s1 * 256^1 + s2 * 256^2 + s3 * 256^3)
…. = full JPEG frame

Note that sometimes the ‘I’ command returns nothing if the robot camera is busy, so the ‘I’ command should be called as many times as needed until a frame is returned

‘irab’ ‘##iraa cc’ I2C register read (‘ab’ parameters sent as 8-bit binary)
a is device id, b is register, cc is 8-bit return value from register displayed as decimal value
‘iRab’ ‘##iRaa cc’ I2C register read (‘ab’ parameters sent as 8-bit binary)
a is device id, b is register, cc is 16-bit return value from register displayed as decimal value
‘iMabc’ ‘##iMaa xx xx … xx’ I2C multiple register read (‘abc’ parameters sent as 8-bit binary)
a is device id, b is register, c is count, xx is 8-bit return values from register displayed as decimal value
‘iwabc’ ‘##iwaa’ I2C register write (‘abc’ parameters sent as 8-bit binary)
a is device id, b is register, c is value written to register
‘iWabcd’ ‘##iWaa’ multi-byte I2C register write (‘abcd’ parameters sent as 8-bit binary)
a is device id, b is first byte, c is second byte, d is third byte
‘idabcef’ ‘##idaa’ I2C dual register write (‘abcde’ parameters sent as 8-bit binary)
a is device id, b is register 1, c is value written to register 1, d is register 2, e is value written to register 2
‘l’ ‘#l’ turn on lasers
‘L’ ‘#L’ turn off lasers
‘Mabc’ ‘#M’ direct motor control
‘abc’ parameters sent as 8-bit binarya=left speed, b=right speed, c=duration*10millisecondsspeeds are 2’s complement 8-bit binary values – 0x00 through 0x7F is forward, 0xFF through 0x81 is reverse, e.g. the decimal equivalent of the 4-byte sequence 0x4D 0x32 0xCE 0x14 = ‘M’ 50 -50 20 (rotate right for 200ms)duration of 00 is infinite, e.g. the 4-byte sequence 0x4D 0x32 0x32 0x00 = M 50 50 00 (drive forward at 50% indefinitely)
‘mabc’ ‘#m’ to employ direct PWM motor control of 2nd bank of timers (TMR6 and TMR7) – same format as ‘M’ command
‘o’ ‘#o’ enable caption overlay
‘O’ ‘#O’ disable caption overlay
‘p’ ‘##ping xxxx xxxx xxxx xxxx\r\n’ ping ultrasonic ranging modules attached to pins 27, 28, 29, 30 with trigger on pin 18 – tested with Maxbotics EZ0 and EZ1 modules. xxxx return value is range in inches * 100 (2500 = 25 inches)
‘qx’ ‘##quality x\r\n’ sets JPEG quality between 1-8 (‘x’ is an ASCII decimal character). 1 is highest, 8 is lowest
‘R’ ‘##Range(cm) = xxx’ measure range to nearest obstacle using laser pointers
‘r’ ‘##Range(cm)’ same as ‘R’, but with lots of diagnostic output
‘Sab’ ‘#S’ direct servo control (TMR2 and TMR3)
‘ab’ parameters sent as 8-bit binarya=left servo setting (0x00-0x64), b=right servo setting (0x00-0x64)servo settings are 8-bit binary values, representing timing pulse widths ranging from 1ms to 2ms. 0x00 corresponds to a 1ms pulse, 0x64 corresponds to a 2ms pulse, and 0x32 is midrange with a 1.5ms pulse
‘sab’ ‘#s’ direct servo control of 2nd bank of servos (TMR6 and TMR7)
‘ab’ parameters sent as 8-bit binarya=left servo setting (0x00-0x64), b=right servo setting (0x00-0x64)servo settings are 8-bit binary values, representing timing pulse widths ranging from 1ms to 2ms. 0x00 corresponds to a 1ms pulse, 0x64 corresponds to a 2ms pulse, and 0x32 is midrange with a 1.5ms pulse
‘t’ ‘##time – millisecs: xxxx\r\n’ outputs time in milliseconds since reset
‘Tx’ ‘#T’ changes threshold in ‘g2’ edge detection – T4 is default, range is T1 to T9
‘V’ ‘##Version …\r\n’ read firmware version info
response is terminated by newline character
‘X’ ‘#Xmodem transfer count: bytes’ Xmodem-1K file transfer – receive file via xmodem protocol – store in flash buffer
‘y’ ‘#y’ flip video capture (for use with upside-down camera)
‘Y’ ‘#Y’ restore video capture to normal orientation
‘zAxx’ ‘##zA – read 131072 bytes\r\n’ flash memory large read – read 128kb from specified flash sector pair xx 02/03 … 62/63 to flash buffer (e.g. read C program from flash sector before running C interpreter). Sectors 00 and 01 are off-limits.
‘zBxx’ ‘##zB – wrote 131072 bytes\r\n’ flash memory large write – write 128kb from flash buffer to specified flash sector buffer pair 02/03 … 62/63 (sectors 00 and 01 are off-limits)
‘zc’ ‘##zclear\r\n’ clear contents of flash buffer
‘zC’ ‘##zCRC xxxx\r\n’ compute crc16_ccitt for flash buffer
‘zd’ ‘##zd…\r\n’ flash buffer dump – dump contents of flash memory buffer to console
‘zr’ ‘##zr\r\n’ flash memory read – read 65kb from user flash sector to flash buffer (e.g. read C program from flash sector before running C interpreter)
‘zRxx’ ‘##zRead\r\n’ flash memory read – read 65kb from specified flash sector xx (02 – 63) to flash buffer (e.g. read C program from flash sector before running C interpreter). Sectors 00 and 01 are off-limits.
‘zw’ ‘##zw\r\n’ flash memory write – write 65kb from flash buffer to user flash sector
‘zWxx’ ‘##zWxx\r\n’ flash memory write – write 65kb from flash buffer to specified flash sector 02-63 (sectors 00 and 01 are off-limits)
‘zZ’ ‘##zZ\r\n’ flash memory boot sector update – writes contents of flash buffer to boot sectors of flash memory – used to replace u-boot.ldr or srv1.ldr – checks first that a valid LDR format image is in the flash buffer
Special Commands
‘$!’ reset Blackfin
‘$E’ read optional wheel encoders on GPIO-H14 and H15
‘$ex’ x = motor # (1-4); read cummulative pulse count from wheel encoder on SRV-4WD
‘$g’ parse GPS input
‘$R’ SVS command – configures slave Blackfin to receive SPI transfer to flash buffer
‘$X’ SVS command – configures master Blackfin to transfer contents of flash buffer via SPI
‘$Axx’ ‘##$Axx yyyy\r\n’ read AD7998 A/D channel xx (01-08, 11-18 or 21-28)
‘$C’ ‘##$C xxx\r\n’ read HMC6352 compass
‘$c’ ‘##c heading=344 x=-505 y=-110 z=447 xmin=-1032 xmax=-228 ymin=-970 ymax=-89\r\n’ read HMC5843 compass
‘$Ta’ ‘##$Tx yyyy\r\n’ read LIS3LV02DQ tilt sensor channel a (1 = x axis, 2 = y axis, 3 = z axis)
Vision Commands
all parameters are sent as ASCII decimal characters (‘0’ – ‘9’)
‘g0’ ‘##g0’ grab reference frame and enable frame differencing
‘g1’ ‘##g1’ enable color segmentation
‘g2’ ‘##g2’ enable edge detection (threshold changed with ‘T’ command)
‘g3’ ‘##g3’ enable horizon detection (threshold changed with ‘T’ command)
‘g4’ ‘##g4’ enable obstacle detection (threshold changed with ‘T’ command)
‘g5’ ‘##g5’ enable stereo processing (only works with SVS that has GPIO-H8 connection between processors)
‘g6x’ ‘##g6 bin# x’ graphically overlay blob search results for color bin# x (e.g. ‘g63’ displays blobs matching color bin 3)
‘g_’ ‘#g_’ disable frame differencing / color segmentation / edge detection. the ‘_’ in ‘g_’ could be any character other than 0, 1, 2, 3, 4
‘vax’ ‘##vax\r\n’ the ‘va’ command enables/disables automatic gain, white balance and exposure camera functions (default x=7)
x=4 -> AGC enable
x=2 -> AWB enable
x=1 -> AEC enable
x=7 -> AGC+AWB+AEC on
x=0 -> AGC+AWB+AEC off
‘vbc’ ‘##vbc dd\r\n ssss x1 x2 y1 y2\r\n ….’ the ‘vb’ command searches for blobs matching the colors in color bin #c, indicates the number of blobs found as dd, and returns a count of matching pixels in the blob, along with coordinates of an x1, x2, y1, y2 rectangular region containing the matching pixels. up to 16 blobs can be returned, and the blobs are sent in order of pixel count, though blobs smaller than MIN_BLOB_SIZE (currently set to 5 pixels) aren’t shown.
‘vccy1y2u1u2v1v2’ ‘##vcc\r\n’ the ‘vc’ command directly sets the contents of color bin #c.
this command will return string with ‘vc’ followed by the color bin number.
for example, we could save a set of colors to color bin #3 corresponding to measurements taken at another time, such as the above mentioned orange golf ball color measurement, using ‘vc3127176086111154200’. we could then confirm that the colors were properly stored by issuing the command ‘vr3’ to retrieve the contents of color bin #3.
‘vfxxx1xxx2yyy1yyy2’ ‘##vf xxxx\r\n’ the ‘vf’ counts the number of pixels matching color bin #c in the range of x1, x2, y1, y2
e.g. ‘vf10100020001500220’ searches for color bin #1 pixels in the x range from 100-200 and y range from 150-220
‘vh’ ‘##vhist y u v\r\n’ computes and lists the distribution of Y, U and V pixels over the entire range of possible values, divided into bins of 0-3, 4-7, 8-11, … 248-251, 252-255
‘vm’ ‘##vmean yy uu vv\r\n’ computes mean values for Y, U and V over the entire image.
‘vpxxxxyyyy’ ‘##vp yyy uuu vvv\r\n’ the ‘vp’ command samples a single pixel defined by coordinates xxxx (column 0000-0159, 0000-0319, 0000-0639, 0000-1279 depending on resolution) and yy (row 0000-0127, 0000-0255, 0000-0511, 0000-1023, where 0000 is top of image). ‘vp01600128’ will sample a pixel in the middle of the image at 320×256 resolution, ‘vp01600000’ will sample a pixel in the middle of the top row, etc…
‘vrc’ ‘##vrc y1 y2 u1 u2 v1 v2\r\n’ the ‘vr’ command retrieves the stored color info from color bin #c.
this command will return string with ‘vr’ followed by the color bin number, followed by y1=Ymin, y2=Ymax, u1=Umin, u2=Umax, v1=Vmin, v2=Vmax.
in the above example where colors for an orange golf ball were captured using the ‘vg’ command for color bin #0, issuing a ‘vr0’ command will return the colors stored in color bin #0 – e.g. ‘##vr0 127 176 86 111 154 200\r\n’.
‘vsx’ ‘##vscan = pix xxxx xxxx xxxx xxxx … xxxx\r\n’ vs scans for edge pixels in x (1-9) columns using edge_thresh set by ‘T’ or ‘vt’ command. displays total number of edge pixels found and distance from bottom to first edge pixel in each column
‘vtxxx’ ‘##vthresh xxxx\r\n’ vt sets the edge_thresh global variable from 0000-9999 for edge detection (default is 3200). equivalent to ‘T’ console function but with more precision
‘vzx’ ‘##vzero\r\n’ vz0 zeros out all of the color bins, vz1 / vz2 / vz3 / vz4 segments colors into various color spaces which can be used by enabling ‘g1’ color segmentation function (‘G’ turns it off)
Neural Network Commands
all parameters are sent as ASCII hex characters (‘0’ – ‘f’)
‘np’ store a new pattern
‘nd’ display a stored pattern
‘ni’ initialize the network with random weights
‘nt’ train the network from stored patterns
‘nx’ test the network with sample pattern
‘ng’ grab a pattern using blob located by “vb”
‘nb’ match pattern against specific blob from “vb”