LightWare SF10 and SF11 Lidar¶
The Lightware SF10 and SF11 series of laser rangefinders are particularly lightweight, and provide fast and accurate distance measurements. Although slightly more expensive than other rangefinders, members of the dev team have had good success with them. The series includes a number of models: SF10/A (25m), SF10/B (50m), SF10/C (100m) and SF11/C (120m)
Connecting to the Pixhawk¶
The diagram below shows the sensor output pins and a conveniently colour-coded cable (normally included or see spec here) which is used to connect to the flight controller. Serial, I2C and Analog connections are possible but we recommended using Serial if possible especially if using cables that are 30cm or longer.
Tip
The serial connection is recommended when using longer cables
Serial connection¶
For a serial connection you can use any spare UART. Connect the RX line of the UART to the TX line of the Lidar, and the TX line of the UART to the RX line of the Lidar. Also connect the GND and 5V lines. You do not need flow control pins.
The diagram below shows how to connect to SERIAL4.
You then need to setup the serial port and rangefinder parameters. If you have used the SERIAL4/5 port on the Pixhawk then you would set the following parameters (this is done in the Mission Planner Config/Tuning | Full Parameter List page):
- SERIAL4_PROTOCOL = 9 (Lidar)
- SERIAL4_BAUD = 115 (115200 baud)
- RNGFND_TYPE = 8 (LightWareSerial)
- RNGFND_SCALING = 1
- RNGFND_MIN_CM = 5
- RNGFND_MAX_CM = 2500 (for SF10A), 5000 (for SF10B), 10000 (for SF10C) or 12000 (for SF11C). This is the distance in centimeters that the rangefinder can reliably read. The value depends on the model of the lidar.
- RNGFND_GNDCLEAR = 10 or more accurately the distance in centimetres from the range finder to the ground when the vehicle is landed. This value depends on how you have mounted the rangefinder.
If you instead were using the Telem2 port on the Pixhawk then you would set SERIAL2_PROTOCOL = 9, and SERIAL2_BAUD = 115
Lightware lidars manufactured before May 2018 shipped with a default baud rate of 19200. If your device was produced before this date, you will need to set the baud rate to 19200 (Parameter value 19). Alternatively, you may reconfigure your lightware device to use a baudrate of 115200 using the Lightware Terminal application and use the settings above.
I2C connection¶
Warning
I2C support is present in Plane 3.4 (and higher) and Rover 2.50 (and higher) and Copter 3.4 (and higher).
Connect the SDA line of the Lidar to the SDA line of the I2C port on the Pixhawk, and the SCL line of the Lidar to the SCL line of the I2C port. Also connect the GND and 5V lines.
You then need to configure the rangefinder parameters as shown below (this is done in the Mission Planner Config/Tuning | Full Parameter List page):
- RNGFND_TYPE = 7 (LightWareI2C)
- RNGFND_ADDR = 102 (I2C Address of lidar in decimal). Please note that this setting is in decimal and not hexadecimal as shown in the lidar settings screen. The default address is 0x66 which is 102 in decimal.
- RNGFND_SCALING = 1
- RNGFND_MIN_CM = 5
- RNGFND_MAX_CM = 2500 (for SF10A), 5000 (for SF10B), 10000 (for SF10C) or 12000 (for SF11C). This is the distance in centimeters that the rangefinder can reliably read. The value depends on the model of the lidar.
- RNGFND_GNDCLEAR = 10 or more accurately the distance in centimetres from the range finder to the ground when the vehicle is landed. This value depends on how you have mounted the rangefinder.
Warning
The default I2C address was 0x55 on older LightWare rangefinders. This was changed to prevent conflict with another device on ArduPilot. Please check your rangefinder system settings to determine what your I2C address is.
Analog connection¶
The SF10’s Analog Out pin (5) should be connected to the Pixhawk’s 3.3V ADC (analog to digital converter). The Pixhawk will provide the regulated 5V power supply needed by the sensor using the 5V and GND pins of the ADC connector.
You then need to setup the ADC and rangefinder parameters as shown below (this is done in the Mission Planner Config/Tuning | Full Parameter List page):
- RNGFND_TYPE = 1 (Analog)
- RNGFND_PIN = 14 (2nd pin of 3.3V ADC connector)
- RNGFND_SCALING = 9.76 (for SF10A), 19.531 (for SF10B), 39.06 (for SF10C), 46.87 (for SF11C)
- RNGFND_MIN_CM = 5
- RNGFND_MAX_CM = 2000 (for SF10A), 4500 (for SF10B), 9500 (for SF10C) or 11500 (for SF11C). This is the distance in centimeters that the rangefinder can reliably read. The value depends on the model of the lidar. Note the range is 5m less than using Serial or I2C protocols so that out-of-range can be reliably detected
- RNGFND_GNDCLEAR = 10 or more accurately the distance in centimetres from the range finder to the ground when the vehicle is landed. This value depends on how you have mounted the rangefinder.
The RNGFND_SCALING value depends on the voltage on the rangefinders output pin at the maximum range. By default the SF10/B will output 2.56V at 50m, so the scaling factor is 50m / 2.56v ≈ 19.53 (the analog distance range for each of the rangefinder variants can be found in the SF10 Manual). The manual explains how you can confirm and change the maximum output range/voltage.
Tip
We highly recommend that you tune the RNGFND_SCALING
value by
comparing the output against a known distance.
Testing the sensor¶
Distances read by the sensor can be seen in the Mission Planner’s Flight Data screen’s Status tab. Look closely for “sonarrange”.