360 Avoidance using multiple CygBot Lidars

Indoor Drone operation requires methods for detecting obstacles and avoiding them effectively. Ardupilot offer a great selection of peripherals to accomplish this task
https://ardupilot.org/copter/docs/common-rangefinder-landingpage.html
and I enjoyed experimenting with different type of configuration like the POC, using STM ToF sensors or BENEWAKE TFMini Lidars

Lidar’s technology has evolved at a fast pace in recent years and the unidirectional sensors using Time Of Flight technology can accurately read longer distances with less interference of the ambient light. The limitation of this technology is the small coverage of obstacles detection as they read the average distance of a very narrow FoV (Field of View), hence the requirement for building arrays , like the POC but the detection remains spotty.

Until now , to effectively read distance on a full 360 coverage, we had to rely on mechanical rotating lidars that are quite accurate and relatively fast but not well adapted to flying vehicles as they are heavy and fragile. I worked with different models on my builds and in order to get good coverage, you generally need to install the device on top of vehicle, making it exposed to direct hit in case of crash (and that happens a lot when performing indoor experiment)

Recently, CYGBOT released a Solid State 2D Lidar that offers interesting features

https://www.cygbot.com/2d-3d-dual-solid-state-tof-lidar

Specification

Detection Range 2D : < 200mm ~ 8,000mm 3D : 50mm ~ 2,000mm (DRM)
Distance Accuracy ±1%
Field of View 2D/3D Horizontal : 120º 3D Vertical : 65º
Resolution 2D : 0.75º (Angle) 3D : 160 x 60 (Pixel)
Measur. Speed 2D : 15Hz 3D : 15Hz
Wavelength LED : NIR 808nm Laser Diode : NIR 808nm
Operating Temp. -20º ~ 60º
Interface UART TTL(3.3V) 57600 - 3,000,000 bps
Size (W
HD) 37.437.4*24.5 (mm)
Weight 28g

With the help of Rishabh Singh, a CygBot Lidar Proximity Driver was quickly developed Complete Parameter List — Copter documentation
and the accuracy and fast sensor distance direction on a large FoV of 120 degrees was tested successfully.

Multiple Backed Proximity Sensor
In order to benefit from this new type of Proximity sensor, a new feature for the driver was required and once again Rishabh was pivotal in the development of a Multiple Backend for the Proximity Driver. This development consists of running concurrently multiple instances of a driver in order to “stitch” together the reading of the 3 x 120 degree sensors and then getting a full 360 deg. of coverage.

These are the picture of the integration of the sensors on my HolyBro X500 V2 development Quadcopter with the CygBot installed at +45 , -45 and -180 degrees relative to Fwd of vehicle giving some overlap (15 degs) on the front detection and 2 blind spots on the side (105 to 120 deg on each sides).

Bottom and Front view of Installation

Radar View of Proximity Sensors

Parameters for this configuration:
UART 1 , 3 and 4 are respectively connected to sensors C,B, A as the backend populate in reverse UART order

SERIAL1_BAUD,115
SERIAL1_OPTIONS,0
SERIAL1_PROTOCOL,11

SERIAL3_BAUD,115
SERIAL3_OPTIONS,0
SERIAL3_PROTOCOL,11

SERIAL4_BAUD,115
SERIAL4_OPTIONS,0
SERIAL4_PROTOCOL,11

AVOID_ACCEL_MAX,
AVOID_ALT_MIN,0.5
AVOID_ANGLE_MAX,1000
AVOID_BACKUP_DZ,0.1
AVOID_BACKUP_SPD,0.75
AVOID_BEHAVE,1
AVOID_DIST_MAX,1
AVOID_ENABLE,2
AVOID_MARGIN,1

PRX_ALT_MIN,1 **
PRX_FILT,0.25
PRX1_MAX,0
PRX1_MIN,0
PRX1_ORIENT,0
PRX1_TYPE,13
PRX1_YAW_CORR,180

PRX2_TYPE,13
PRX2_YAW_CORR,45

PRX3_TYPE,13
PRX3_YAW_CORR,-45

** Cygbots sensors are tilted down to avoid propellers interference, so in order to reduce ground detection, we set Proximity minimum altitude to 1 Meter

Setting the CYGBOT Baud Rate
In order to get the Cygbot working with the Flight Controller, we have to change speed to 115200 bps. We can make this change using the Cygbot Lidar Viewer and and connect to the device using the supplied USB to Serial adapter. You connect using the default speed (3,000,000) and then select Baud Rate 115200 and APPLY change and after power cycle the Cygbot you should be able to connect at 115200.

Demo Flight

A word of caution here: Doing automated flight indoor in confined space is not safe. This drone has been modified with soft blades and i wear safety glasses and the foam I am using for Avoidance is my protection as well. Be carefull , and please wear glasses

Converting the Serial Proximity to CAN
Having to work with multiple serial devices requires a lot of Uarts and we do not have too many on the Flight Controllers. One way to address this problem is to convert a serial proximity sensor into a DroneCAN device. In order to proceed, we need to develop a DroneCAN driver for the Proximity devices that can be loaded into a small and affordable DroneCAN Adaptor Node, like the Matek L431 Board.

https://ardupilot.org/copter/docs/common-uavcan-adapter-node.html#l431-based

Guess who made the development for this driver ? Yes , the talented Rishabh :slightly_smiling_face:, actually, the development is still in progress and it is passing the different phases of Push Request and Peer Review in the development process on github. We will update when the code will be available in Main Branch, ready to test.

Left Picture of MatekSysCAN NODE L431 and Right is is how I proceed for integration with Cygbot using the supplied connector and soldering it directly to TX3/RX3 pads of the L431

Below is how we configure using Mission Planner connected to an Orange Cube SLCAN port. We assigned NODE to 100 , Proximity ADD to 10 and Orientation to 45 and Type to 13
Take note that we assigned PRXPORT to 2 as the port numbering starts from zero “0”

On the Flight Controller we assign the proximity type 14 = DroneCAN Proximity Sensor
PRX1_TYPE,14
PRX2_TYPE,14
PRX3_TYPE,14

That’s it for the moment, just hope that this Blog can help anyone interested on experimenting with these new devices and the associated techniques of implementation.

12 Likes

Really nice development and detailed write-up thanks! These solid state lidar are a great advance.

2 Likes

Great system. I have one question about PRX_MIN.

Can i use decimal value like 0.4 in the latest firmwares ?

As i remember 1 m was the lowest, which just was too far for my purpose.

Thanks

1 Like

These value are 0.0f type, so you should be able to add a 1.2 meter for example

I see, so below 1 m is not possible although most of the sensors can read closer. I guess changing that in the code would be too complicated.(for me at least :grinning:)

Thanks for the answer.

Is there an estimate as to when the serial to CAN adapter driver will be released? Or is there a github link? Thanks!

Hello

It was merged 3 monts ago, see here

1 Like

Thank you for your answer!
Is this the right driver for the adapter as shown in your tutorial?
https://firmware.ardupilot.org/AP_Periph/latest/MatekL431-Proximity/

Yes it is, it should work ok

1 Like

Thank you!

I just added a single Cygbot D1 using the L431, and noticed a few things different, that might just be the evolution of things.

After configuring the Cygbot to be 115k and saving…

This is my first time using DroneCAN.

I set PRX1_TYPE to 14 and rebooted.
I ran the SLSCAN.
I look at the parameters.
I was able to change the port, but have NO PRX* settings in the CAN parameters - I do have GPS and others.

I checked for firmware updates for the L431 and various other options.
I upgraded from Rover 4.2.3 to the new 4.4 beta, with no changes.

However, I checked the Proximity view in MIssion Planner and… things seem to be working, despite not seeing the options.

So far OK. More testing is needed.

Otherwise, I need to look more at ardupilot/Tools/AP_Periph at master · ArduPilot/ardupilot · GitHub and perhaps replace the firmware on the L431 with something else…

I am curious - and I looked at the source code some without spending enough time to fully answer it myself - but is it necessary to use UART3, or could I have used UART2 on the L431?

I did confirm the Cygbot connector is a Molex 5267-05.

It does not seem you flashed the L431 with the Proximity firmware ?

https://firmware.ardupilot.org/AP_Periph/latest/MatekL431-Proximity/

Once flashed, you should see the parameters exactly as shown in the picture on the blog

Thank you!

When Mission Planner asks “check for new firmware from the Internet” you must answer No. Then you can upload the new firmware.

I’m still seeing a slightly different list of options - no PRX1_ADDR in particular - but it’s much closer.

(Might be related to changes not being saved when I change the port and PRX1 types - they keep reverting)

Like someone else, I had troubles flashing the firmware and changes sticking when using Mission Planner, but Drone Can GUI did work out.

Unfortunately, I couldn’t make the Lidar cooperate. I was able to make a GPS work with the CAN adapter.

Ultimately I went with the serial interface for the Cygbot, and that’s working - thank you.

I took note that you angled the Lidar down to avoid the props.

I’ve installed mine on a rover, and have it angled up a bit but it seems I need to angle it further - it sees tall grass as an obstacle to avoid.

As I read the code, it is initialized with 0x01 2D and not 0x08 for 3D.

so it is curious that even angled upwards I keep finding tall-grass obstacles in ground clutter.

The device claims 120deg Horizontal and 60deg Vertical in 3D, but 120deg horizontal and only 0.75 deg of vertical when in 2D mode.

I have read your POC project with the TF-Mini and CYGBOT and am excited.
I bought 4 x MR72 Nano-Radar arduino mega to realize a POC 360GRad coverage. Datasheet you can find in the attachment of MR72.

MR72 obstacle avoidance radar user manual.zip (925.3 KB)

I have patched the firmware as described in the datasheet and set the parameters. With 1 radar facing forward the object avoidance works very well. The MR72 radar has a 3 zohnen coverage but is operated as a 360 degree radar. 315deg / D8 0deg / D0 and 45deg / D2. The remaining data fields are filled with 0xFFFF. The driver used is the 360deg TeraRangerTower Treier as shown in instructions from the manufacturer. To realize a POC with MR72 I ordered an arduino mega with 4 serial interfaces. My idea is to use 4 MR72 radars to realize a complete deletion. Programmatically I will read the 4 MR72 radars and the angular mass of each radar D8,D0 and D2 always.

In the last section, a Vritual Serial Port with 57600Baut sends the data packet via Mavlink to the Ardupilot. The data also arrives and I can also view it via the radar view of proximity sensors. Avoidance is also active at 2 meters with the option to stop. I would finish the project with you if possible if it suits you.

If I remember correctly, I think @rishabsingh3003 worked with the integration of these with ArduPilot and the result where not really satisfactory as it generate a lot of false positives. Maybe he can comment

I guess @geofrancis could have some interest in it as well.

1 Like

Om sounds good. If @geofrancis and @rishabsingh3003 are also motivated to support me on this, then I will share my coding with the parameters here tomorrow.

what kind of vehicle are you wanting to use the radar on? from what I have found, radars are best used when there is nothing around. so things like aircraft or boats where there is usually nothing but air or water around you. with ground rovers its really hard to eliminate ground reflections so data becomes unreliable.

We would like to use real estate inspection with the copter. So everything that is roof, wall should be avoided. We need a solution that is reliable in daylight and covers 360 degrees. What can we use here?

Radar would not have been my first choice for that. The issue is that the radar will only see things that reflect radar, so it would just fly into plastic tarpaulin or mesh as it’s invisible to radar.

What would be your first choice to solve this problem?

You could still use radar but have lidar sensors as backup, but a 360 TOF lidar would probably be a better option.