Drone not avoiding obstacles

I am trying to perform obstacle avoidance with my drone, I have a proximity sensor configured and connected to it but when I take it towards the obstacles, it doesn’t react at all.

I’ve tried flying in AltHold, PosHold, and Stabilizes modes but it doesn’t in either of these modes.

Here is my Param Config:

AVOID_ENABLE: 3
AVOID_MARGIN: 1
AVOID_DIST_MAX: 5
AVOID_BEHAVE: 0
AVOID_BACKUP_SPF: 0.75
AVOID_BACKUP_DZ: 0.1
AVOID_ANGLE_MAX: 1000
AVOID_ALT_MIN: 0
AVOID_ACCEL_MAX: 3

OA_TYPE: 3

I am constantly monitoring the Proximity Obstacle Viewer over telemetry and I made sure that it is detecting the obstacle.

PRX1_TYPE: 5 ( I am using LUA Scripts )
PRX1_ORIENT: 0
Everything Else to 0.

What could be the problem? Also How do I set the OA to Simple Avoidance, does setting it to disable does the job?

Simple avoidance only works in loiter

But documentation says AltHold and Loiter?

Hi @wkpatil,

Simple avoidance does “work” in AltHold mode as described here on the simple avoidance wiki page and again here on the Developer focused object avoidance page.

I’ve re-tested it in SITL and it appears to be working correctly with the vehicle ping-ponging off of obstacles.

If you’re not seeing the ping-pong behaviour then the issue could be in data being provided to the proximity sensor library (maybe it’s timing out?). We’d need to see an onboard log to investigate further.

By the way, this ping-pong behaviour is the best we can do in AltHold because this mode does not rely on the GPS (or more accurately the EKF’s estimated velocity of the vehicle). This is why we recommend using Loiter instead.

As a bit of an editorial, we added this ping-pong version of object avoidance mostly to save developers from wasting their time re-inventing this feature only to discover that it doesn’t actually work very well. We saw at least three different implementations.

The OA_TYPE parameter is for enabling BendyRuler or Dijkastras (aka AStar) path planning around obstacles. This is really for auto mode (not Loiter or AltHold).

1 Like

@rmackay9
Okay I tried few things in simulation,

In AltHold mode, the drone has very weak response, which I think is expected after reading your response.

In loiter mode, The drone resists the pitch command at AVOID_MARGIN.

I also tried AUTO and GUIDED modes, but nothing seems to happen.

The parameters are same. I tried using DISTANCE_SENSOR and OBSTACLE_DISTANCE_3D over mavelink.

Do I need different param config for GPS based modes?

Also why doesn’t it work for PosHold mode where the drone velocities are know?

Sorry, I should have been clearer.
We have two types of “Simple Avoidance” -
The one I prefer using is only meant for Loiter at the moment.

The other one which Randy mentions as “Ping Pong” does work for Alt hold but we don’t really recommend using it.

1 Like

Hi @wkpatil,

Simple avoidance doesn’t work in PosHold because the pilot controls the vehicle’s lean angles (just like AltHold). The velocity of the vehicle is only controlled during the slowdown.

In general we recommend users use Loiter instead of PosHold where possible.

Auto and Guide modes implement path planning (e.g. BendyRuler and Dijkstras/AStar) to fly around obstacles instead of stopping. There is an enhancement underway to also implement simple avoidance in Auto and Guided but only using Proximity sensors and it hasn’t completed the peer review yet. I expect this will be included in 4.6.0.

1 Like

@rmackay9
I set the OA to Bendy Ruler and tried in Auto and Guided mode but the drone ran into the obstacles.

Hi @wkpatil,

If you’ve got a log we can try and have a look.

The problem with object avoidance is normally not in the algorithms (e.g. Bendy Ruler) it is the quality of the lidar data provided to them. You should actually see little red circles on the MP map highlighting where AP thinks there are obstacle.

Here are the logs:
Guided Mode with Bendy Rules ( OA_TYPE = 1)

Guided Mode with Dijkstra and Bendy Ruler( OA_TYPE=3)

Works fine in Auto Mode.

@wkpatil for it to work in guided mode, you need to set the 6th bit in GUID_OPTIONS: Complete Parameter List — Copter documentation

2 Likes

@wkpatil,

Sorry for not including that parameter change requirement on the wiki. I’ve created a wiki PR to update this so it should be easier for the next person who hits this issue.

Thanks @rishabsingh3003 for clearing that up.

1 Like

Thanks @rishabsingh3003 and @rmackay9 now everything works great.

Summary:

Simple Avoidance Works in robustly in Loiter mode, In AltHold mode it’ll work but can be overridden by Pilot.

Bendy Ruler and Dijkstra’s Works robustly in Auto and Guided Modes.
GUID_OPTIONS needs to be set to 6th bit or “Waypoint navigation used for position targets”

1 Like