Neato XV Laser scanner (LIDAR)

So today my Neat XV LIDAR module arrived, and I had to test it directly with the Raspberry Pi. For everyone that does not know this wonderful piece of hardware yet: It is a low-cost 360-degree spinning laserscanner that is usually scavenged from the Neato XV vacuum-robots. In Germany it is quite hard to get your hands on one, so I ordered one via ebay from the US.

Test-Setup:

According to https://xv11hacking.wikispaces.com/LIDAR+Sensor, the wires of the LIDAR-unit have the following pinout:

Red: 5V
Brown: LDS_RX
Orange: LDS_TX
Black: GND

Although the logic-unit is supplied with 5V, the interface (rx/tx) is 3.3v. Perfect for talking to a raspberry pi!

As stated in the wiki, the sensor (without the motor!) draws ~45mA in idle and ~135mA when in use (rotating).

For these first tests, I wired it up by connection the power-lines of the logic to an external 5v power supply (that can definitely provide the needed mA), the TX of the scanner directly to the RX of the raspberry pi, connected the GNDs. Without connecting the motor yet and just powering the logic-unit on while connected to the serial (115200 baud, 8N1), it would greet me with the following welcome-message:

Piccolo Laser Distance Scanner
Copyright (c) 2009-2011 Neato Robotics, Inc.
All Rights Reserved

Loader	V2.5.15295
CPU	F2802x/c001
Serial	KSH14415AA-0358429
LastCal	[5371726C]
Runtime	V2.6.15295
#Spin...3 ESCs or BREAK to abort

After that I hooked up the motor to an external power-supply with approx. 3V.

Meanwhile, the final connection as it is installed in the robot is the one shown below. I use a the ULN2803A Darlington Transistor Array to drive the motor, as it draws 60mA and above (the single pins of the RPi are specified with a maximum of 50mA, so we use this chip to handle the current). The red wire of the motor is connected directly to the 5V-rail of the Raspberry Pi, the black wire is connected to Out-7 of the ULN2803A with a Resistor of 15 Ohm to bring down the voltage from 5V to approximately 3V. In-7 is currently just connected to +5V, but could be wired to the raspberry pi in order to turn the motor on or off, or control it using PWM. The logic-VCC and -GND are directly connected to the Raspberry Pi’s 5V rail, the TX-line of the Laser Distance Sensor is connected to RX on the Raspberry Pi.

After spinning it up to 300rpm and got my first measurement-packets, which sadly did not look very promising:

fa:a6:f0:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:4e:20:
fa:a7:e9:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:52:19:
fa:a8:e9:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:56:19:
fa:a9:e9:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:5a:19:
fa:aa:e9:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:5e:19:
fa:ab:e9:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:62:19:
fa:ac:e9:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:66:19:
fa:ad:e2:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:6a:12:
fa:ae:e2:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:6e:12:
fa:af:e2:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:72:12:
fa:b0:e2:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:76:12:
fa:b1:e2:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:7a:12:
fa:b2:e2:4a:55:80:00:00:55:80:00:00:55:80:00:00:55:80:00:00:7e:12:

The packet-format (https://xv11hacking.wikispaces.com/LIDAR+Sensor) is the following:
22 Bytes: <start> <index> <speed_L> <speed_H> [Data 0] [Data 1] [Data 2] [Data 3] <checksum_L> <checksum_H>

where:

  • start 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> <distance 13:8>`
`byte 2 : <signal strength 7:0>`
`byte 3 : <signal strength 15:8>`

I wrote up a little python script to decode the packets in real-time for me:

#!/usr/bin/python
import serial
import time
import math

# Some settings and variables
outfile = open("outfile.txt", "w+")
print("Start")

f = serial.Serial(port='/dev/ttyAMA0', 
                            baudrate=115200, 
                            parity=serial.PARITY_NONE, 
                            stopbits=serial.STOPBITS_ONE, 
                            bytesize=serial.EIGHTBITS, 
                            timeout=0)

def decode_string(string):
    print string
    data = []

    for byte in string.strip("\n").split(":")[:21]:
        data.append(int(byte,16))

    start = data[0]
    idx = data[1] - 0xa0
    speed = float(data[2] | (data[3] << 8)) / 64.0
    in_checksum = data[-2] + (data[-1] << 8)

    # first data package (4 bytes after header)
    angle = idx*4 + 0
    angle_rad = angle * math.pi / 180.
    dist_mm = data[4] | ((data[5] & 0x1f) << 8)
    quality = data[6] | (data[7] << 8)

    if data[5] & 0x80:
         print "X - ",
    else:
        print "O - ",
    if data[5] & 0x40:
         print "NOT GOOD"
    print "Speed: ", speed, ", angle: ", angle, ", dist: ",dist_mm, ", quality: ", quality
    #print "Checksum: ", checksum(data), ", from packet: ", in_checksum
    outfile.write(string+"\n")
    print "-----------"

byte = f.read(1)
started = False
string = "Start"
while True:
    if byte != '':
        enc = (byte.encode('hex') + ":")
        if enc == "fa:":
            if started:
                try:
                    decode_string(string)
                except Exception, e:
                    print e

            started = True
            string = "fa:"
        elif started:
            string += enc
        else:
            print "Waiting for start"

    byte = f.read(1)
outfile.close()
print("End")

Until now I did not have any luck. One thing I noticed was that during the spin-up of the motor to full speed, it would give me valid readings for approximately half a second (without the bad-flag). However, even if I adjusted the rpm to exactly these values, it would still output only bad packets. Additionaly, the rotational speed at which those few good packets came through always changed, so my current guess is that either the laser- oder imager-unit is faulty, or that their connection through the slip-ring is somehow bad.

I contacted the seller and he agreed to send another unit, so lets wait. Yay, the new unit arrived, and it is working!

Below is my test-setup with the robot in a cardboard-box, and the visualization of the values I read from the Picollo (leave a comment if you want the script) using Numpy and Matplotlib:

TobiasWeis | 19. Mai 2017
  • Jean-Marc 31. August 2017 at 7:42
    Hi Tobias, Thanks for this post: really,really helpful as there are very few posts about connecting the XV11 directly to RPi (no controller). I have a question regarding the setup of the RPi. for enabling serial port reading. So far, I have only plugged the interface cable to the RPi following your diagram). The motor is not used so no need for the Transistor (for the moment). I have a RPI3. First, I disabled the use of the serial port for the “console” login (sudo raspi-config...etc). Reboot the RPi. Then I use part of your code above: f = serial.Serial(port='/dev/ttyAMA0',.....) and print( f.read(1)). I don't get any output. There no error, just an empty string. Would you have some suggestions on how I could get things working? Thanks a lot.
  • TobiasWeis 31. August 2017 at 8:45
    Hi Jean-Marc! With the RPI3, the highspeed-RX/TX-pins (/dev/ttyAMA0) are used for bluetooth in the new versions as far as I remember. You can use /dev/ttyS0 and Pins 14/15 for serial (after you have enabled uart, because for some reason it is disabled by default in the new releases). If you want to use the highspeed-uart-interface for serial, you can activate some hardware-overlay (This site gives a good overview I think: https://spellfoundry.com/2016/05/29/configuring-gpio-serial-port-raspbian-jessie-including-pi-3/#Raspberry_Pi_3)
    • Jean-Marc 31. August 2017 at 12:10
      Cool Thanks a lot. It's now working. (+100 ) For some reason, I can use /dev/ttyAMA0 (/dev/ttyS0 returns an error: this port does not exists or something like that) I am now getting packets similar to what you had: fa:bc:36:08:52:80:00:00:52:80:00:00:52:80:00:00:52:80:00:00:22:64: Now, I am using your code above to convert the string to real number. Shouldn't line 24 thru 44 be outside the for-loop. Otherwise, it gives an error: "list index out of range". Would you share the script for extracting the point cloud data and the code for the visualization. Thanks a lot for your help.
      • TobiasWeis 31. August 2017 at 12:32
        Awesome, good to hear! Yes, you are absolutely right about the code, corrected it (sorry, have missed this error when I transferred the code to my blog). I have a prototypical script with plotting here: https://github.com/TobiasWeis/pypibot/blob/master/code/prototypes/lidar_live_view.py, but I cannot test if it still works at the moment (I am in holiday and do not have access to my hardware atm). The linked script was a quick-and-dirty visualization, it will just calculate x/y-coordinates from angle/distance, scale it to the image size (I assume that 6000mm is the farthest distance that gets measured), color pixels in an image grid and display it. You could plot it in a little more sophisticated manner using matplotlib and just keepint the x/y-calculations in place.
  • Jean-Marc 4. September 2017 at 7:31
    HI Tobias, Thank you for your time, and valuable help. The LIDAR is working great! Just need to come up with a design to attach the lidar on the RC car. BTW, have you tried to send data to the lidar. I'd like to find a way to shut down the motor remotely : send a command to the lidar thru the RX (brown) line.
    • TobiasWeis 6. September 2017 at 10:04
      You cannot control the motor using serial commands, as you are the one supplying the motor with power. The DC-motor itself is not connected in any way to the logic of the lidar-unit.
  • Laia 16. Januar 2018 at 0:18
    Can you send the final script with the last part of the project?
    • TobiasWeis 16. Januar 2018 at 12:57
      Dear Laia, it's really only a small step from there. In the above script, we already calculate the distance in mm (dist_mm) for a given angle (angle_rad) of the laserscanner. We can now calculate the x/y-coordinates with respect to the laserscanner/robot-coordinate system:<br /> x = dist_mm*np.cos(angle_rad); y = dist_mm*np.sin(angle_rad) For each point, you can calculate these coordinates and put them in a list (e.g. points.append([x,y])), and later convert them to a numpy-array ( points = np.array(poins) ). For the above plot I used matplotlib: import matplotlib; fig = plt.figure(); plt.scatter(points[:,0], points[:,1]); plt.show(); You can customize the above plot by adding ticks, gridlines, etc.
  • Wladi 21. Februar 2018 at 20:43
    Hi Tobi! Incredible that others share the same madness ;-) I salvaged a XV Lidar out of my broken vacuum, hooked it up to my Raps, and low and behold it speaks to me. I am able to decode the messages and the measurements from the sensor (by the way, you do not correct the geometry of the rotating puck, thats why your card box looks so slanted ;-) ) - I wrote a litte C++ library to manage the communication and decoding and also a PID controller for the rotation speed. And here is my issue - I observe a very weird "spike" in the rotational speed of the sensor at the beginning of every revolution - I did not have this in my initial experiments. I also see a error code in the distance filed of the data packet, but I don't have a list or description of the codes. So did you ever experience something similar? Do you have a list of error codes? Happy Hacking! Wladi
    • Wladi 21. Februar 2018 at 21:57
      Raps = Raspi
  • Wladi 22. Februar 2018 at 21:00
    OK - once you got going.... I found the issue - I had rewired the stuff on a breadboard and while doing so i changed the rotation direction - this seems to bring up this strange spike in the speed readings as well as some bogus readings in between. Now I know :-)
  • Anny 24. April 2018 at 23:17
    HI Tobias, a newbie question. How do you obtain this message from the Rpi during first, Tobias? Did you have to run any Python script to get that message? I used Arduino Uno board and have to connect both RX and TX using SoftwareSerial library to read the message and display on Arduino IDE. I'm puzzling how everyone on the internet can obtain this message using RX port alone. Really appreciate any light shining here! Piccolo Laser Distance Scanner Copyright (c) 2009-2011 Neato Robotics, Inc. All Rights Reserved Loader V2.5.15295 CPU F2802x/c001 Serial KSH14415AA-0358429 LastCal [5371726C] Runtime V2.6.15295 #Spin...3 ESCs or BREAK to abort
    • TobiasWeis 25. April 2018 at 11:14
      Hi Anny, as stated above in the article: "For these first tests, I wired it up by connection the power-lines of the logic to an external 5v power supply (that can definitely provide the needed mA), the TX of the scanner directly to the RX of the raspberry pi, connected the GNDs. ". The Rx-lines are for receiving, the Tx-lines for sending, so just for receiving the message of the scanner it's enough to connect Tx of the Scanner to the Rx auf the Raspberry. As far as I recall I just ran minicom the first time, and used a python-script afterwards.

Leave a Reply to TobiasWeis Cancel replay