Question on distances array in OBSTACLE_DISTANCE

Hello. I am trying to setup collision prevention using distance information from ultrasonic sensors. I have a flight management unit (FMU) running PX4 and a microcontroller sending MAVLink messages to the FMU.

I’ve got a question regarding how I should fill the OBSTACLE_DISTANCE message. I have 6 ultrasonic sensors, and I plan to distribute them evenly around the drone. So I assume increment should be 60. I notice that the array distances is of size 72 but I only have 6 sensors. If I put the measurements from ultrasonic sensors in the first 6 elements, what values should I assign to the rest? Would PX4 firmware only consider the first 6 elements of the array and ignore the rest?

Any help will be appreciated.

1 Like

it depends on the field of view of your sensors, at which angles do you get sensor coverage? And how is the data reported, e.g do you get one value per sensor at each timestep or do you actually get a range scan per sensor (and what would be the resolution of that).

But as an example:
I assume you have 6 sensors with fov 10deg, which all report one value per timestep. sensor 1 is located to the front of the drone and they are evenly spaced.

then you should fill the message as follows:
msg.frame = MAV_FRAME_BODY_FRD
msg.increment = 10 (degrees, resolution)
msg. angle_offset = -5 (degrees to shift, such the the fov of the first sensor is centered to the front of the drone)
msg.distances = [data1, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX
data2, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
data3, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
data4, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
data5, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX,
data6, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX, UINT16_MAX]

put UINT16_MAX where you do not have any sensor coverage. The drone will refuse to fly these directions
msg.

@baumanta Thank you so much for the detailed explanation. I am planning to place 6 sensors evenly around. So assuming the front is at 0deg, they will be at 0deg, 60deg, 120deg, 180deg, 240deg, and 300deg. I will need to poll the 6 sensors and each time step I will one distance value from one sensor.

I actually don’t quite know the fov of each sensor…For ultrasonic sensor, how do I usually obtain that information?

From your description, it seems that we need to provide the array with the number of elements equal (360/resolution), right? In your example, as the resolution is 10, the number of elements is 36. For the rest of the array, I could put any value there, right?

So I would choose the resolution to be the fov of your sensor (but not lower than 5deg, as the message does not support than 72 values). That way you can keep the message as lightweight as possible. The FOV should be somewhere in the sensor specs, otherwise, you’ll have to try and measure it or guess roughly. It is not too crucial probably and should be accurate to a few degrees.

The array values that are not inside the fov of any sensor, you should set to UINT16_MAX. This means that there is no sensor coverage and the vehicle will not move into those directions. Alternatively you could put any number, e.g. 300. That way the autopilot would assume an obstacle 3m form the drone and just limit the speed to be able to break in time.
To conclude, it depends on the behavior you want. If you want an absolutely safe system, put UINT16_MAX, so you can only fly where you have sensor coverage. Other wise it is up to you to tune the max speed in those directions. If you put any high value in there, the vehicle will move full speed where there are no sensors.

@baumanta You have explained it very well. Thank you for that. I am also working on drone development using same message. In my case, I am using radar sensor attached in front of drone for that, I have done my settings as below:

obstacle_distance_send(
time,
MAV_DISTANCE_SENSOR_RADAR,
dist[72],
1,
50,
4000,
0,
0,
MAV_FRAME_BODY_FRD
)
I have kept MPC_COL_PREV_D = 1 meter.

  1. I am sending dummy obstacle distances message with distance array of 72 with 100 value in it.
    I am able to send OBSTACLE_DISTANCE msg but drone is not going in north direction as if the obstacle is in north side. As per my understandings drone should not go in front direction as frame is MAV_FRAME_BODY_FRD.

  2. Settings of angle offset and increment are bit confusing. Is there any document or example from where I can read more about it. It will be helpful.
    Thank you in advance.

update 1…As @baumanta said, I have updated the distance array with data1 at 0th position and remaining all fields are UINT16_MAX but still my drone is going in all directions except north direction. And here I have given collision distance 100 cm and data1 = 150 cm. Something is not correct. Please help me.

So the flight behavior with you described values seems to be correct. If you set CP_DIST=1 then the drone should not move at all if you publish a message of data=[100 or smaller, UINT16_MAX, UINT16_MAX,…]. Because it will not fly where the data is UINT16_MAX bcause this means no data is available and it is not safe to go there (unless you specifically allow with CP_GO_NO_DATA=1) and it will not move where <100 because it is too close.

If you publish data=[150, UINT16_MAX, UINT16_MAX,…]. It should move slowly into the direction of the 150 bin and not in any other direction.

About the direction being North instead of front, it’s a bit hard to debug for me. Did you try to fill other bins to see how the fly-able direction changes? Is it still with a global reference? What firmware are you running? Maybe produce a ulog where the uOrb topics obstacle_distance_fused and your input topic are logged.

@baumanta, Thank you for the explanation. I have all flight logs (ulog) but the obstacle distance is not fused in it. I don’t know how I can fuse that message but I will try and update it here.
Now I have another question regarding this message:
I did not understand how should I place the values of increment and angle_offset in my scenario.

  1. I have only 1 sensor attached in front of drone which has FOV lets say 3 degree and I get a one value per timestamp from sensor. So as per your above explanation, should I put angle_offset = -1.5 and increment = 3, if I do so which values of distances array I need to update?
    I have added the diagram of my drone system

PS: PX4 firmware 1.9.2 and I am using pymavlink source files.

Todays update… I have published the data as [300, UINT16_MAX,UINT16_MAX…] and lowered it to [100,UINT16_MAX,UINT16_MAX] in steps of 50 cm within the span of 8 secs. But still drone is going in all directions and not going in north direction.

Object distance msg setting:
Distances = [Data1 , others = UINT16_MAX]
Data1 = 300 – 100 in steps of 50 cm within 8 secs
Increment = 3
angle_offset = -1.5
Frame = 12

  1. I think, flight controller (PX4) not considering the frame FRAME_BODY_FRD sent by me and taking the global value of MAV_FRAME_GLOBAL.

  2. As you are saying drone should not fly in other direction when I am publishing UINT16_MAX value, that is also not happening.

Is there any other setting I need to do on flight controller side.

Do you publish your data directly on the mavlink topic, or do you publish a ROS topic and then let Mavros send the mavlink message?

I am not using ROS right now. I am just sending the OBSTACLE_DISTANCE message using python with the help of pymavlink files. I have generated the files for mavlink version 2 from common.xml file which is in dilects of V20.

Log files: I have created my profile on github and posted logs of drone testing.
Collision prevention message is present in it.

link: https://github.com/badave007/Autonomous_Drone/blob/master/log_110_2020-1-20-14-43-42.ulg

I have done firmware update from 9.2 to 10.1. I will check the results and update here.

@baumanta , After updating the firmware , I have done the setting of collision avoidance as below image:
image
And Obstacle distance message settings as :

distances = [data1= 500 to 200 , others = UINT16_MAX]
increment = 3
angle_offset = -1.5
frame = FRAME_BODY_FRD

expected result: Drone should fly only in forward directions and block other directions

actual result: It is working somewhat expected but it should be flying in front direction but it is flying in north direction.

So drone is blocking other directions but the frame argument is not considered.
please provide your insight what might be going wrong.

Hello @baumanta,

I have done the Lidar based collision prevention using ROS and MAVROS. Also I have used the mavros-extras plugins, Its working fine. Now I want to use AWR1642 radar sensor for that I created the node which receives the values from sensor but I am bit confused about filling the array of OBSTACLE_DISTANCE message, because radar sensor provides range scan data at each time stamp. Can you please help on this? e.g.How I should tell the PX4 that 1 object is on 100cm at 20 degree and other at 200 cm at 10 degree.
I am using only 1 sensor in front direction.

Thank you in advance.

Please see the first answer in this post: Question on distances array in OBSTACLE_DISTANCE

you just need to fill the array correctly with you sensor data, respecting resolution, orientation and fov of your sensor

Hello @baumanta,

Yes i have checked that and I am thankful to you, because of that answer I have implemented Lidar based collision prevention. There are few things which are not clear to me.
The obstacle distance plugin does not set the angle_offset. It was not an issue while using Lidar so much but now when I am using radar sensor, should I edit it?

@ashutosh_badave I’m not sure what is still unclear here, as the example I posted already contains how to set the angular offset. But here another example with one sensor with multiple data valued (like range sensor would report)

1 Like

@baumanta Thank you very much for the detailed answer. I did understand it from first reply. My question was related to ROS plugin code and not about what message should be send. I guess I have not asked it correctly. sorry for that.

Below is the re frame version and what I did for that.

I was unclear about angle_offset, as I am publishing Laser_scan message on /mavros/obstacle/send topic to Obstacle_distance plugin, Laser_scan message does not have provision to send angle_offset and this plugin does not set angle_offset. Because of that on flight controller side, I was receiving angle_offset as 0 every time.
But now I have edited that code, so it can consider angle_min from Laser_scan message as angle_offset for flight controller.

obstacle.angle_offset = static_cast<float_t>(req->angle_min);

Hi baumanta,

My current project is using a multicopter with 4 distance sensors for a wall following. I am currently using gazebo and mavros for my project. I created an iris model attached with 4 distance sensors and I want to publish all 4 distance sensors data to 4 ROS topics (for example: /mavros/distance_sensor/lidar0, /mavros/distance_sensor/lidar1 and etc).

However, when I am trying to use rostopic echo to check whether my data was publised to 4 ROS topics, only the “/mavros/distance_sensor/lidar0” shows the data that I wanted.

Other topics (/mavros/distance_sensor/lidar1 and etc) show me a warning which is “WARNING: no messages received and simulated is active. Is /clock being published?”
I believe that means my other distance_sensors data were not published to the topics that I wanted. Meanwhile, I also checked using Qgroundcontrol mavlink inspector and there is only 1 distance sensor data being output on the inspector.

I would appreciate some help from you if you know how to resolve this problem.

Regards,
ziimiin14

@ziimiin14 This seems to be a gazebo problem. Check again your model file and the plugin for the distance sensor.