Stopping for obstacle avoidance in AUTO mode

For agricultural drones spraying pesticides, path planning is a rastor scan. I want to avoid the obstacle and join the path again, to ensure spraying is done without loosing much field area. I’ll stop in front of an obstacle, and user can take control in loiter mode, avoid and align with main path and continue the mission. (this can later be replaced by 100% autonomy, to merge tightly with the path) This would ensure that the remaining pass to the waypoint can be sprayed autonomously
Also, once stop is implemented it gives me flexibility to modify behavior from CC.
Instead of trajectory planning (Bendy ruler/ DJikstra), I am trying to implement stop mode (like loiter) upon detecting obstacle in automission.
However AUTO controller is a bit complicated and I need help in the following respects

  1. Similar to slowing down for terrain correction using offset_z_scaler, I was thinking to implement offset_oa_scaler which varies between 0 and 1 based on distance from obstacle.
    Bits of code in AC_WPNAV.cpp which I changed are as:
    a) Adding loiter obstacle avoidance adjust_velocity function

b)adding offset_oa_scale and multiplying it with offset_z_scaler during velocity planning.


On SITL simulations the drone comes to a stop atleast when obstacle is in front and then continues the automission on removing the obstacle.
However, I dont understand if there is a better way to do it (since I am not changing the target velocity directly and how advance_wp_along_track function will affect it), and what will be the cons of those change (on auto spline planning controller, since at times offset_scaler_oa can go to 0)
c) Hence I need some help in finding resources to understand AUTO controller’s implementation, suggest if there can be better ways to implement a simple stop in auto mode ( mostly velocity based control, because I want the system to be immune to false detections ), and may be point out the cons about the implementation I have done. (AC_WPNAV.cpp file attached for reference)
AC_WPNav.cpp (40.6 KB)

@rishabsingh3003 @Leonardthall @rmackay9 Need some help/suggestions if this will be the right direction

Hi @Mihir_Salot,

I’ve created a PR here that stops in Auto, Guided and RTL if an obstacle is detected using proximity sensors.

I’ve also moved this topic to the Copter-4.5 category, hope that’s OK.

Great. Thanks for the reference Randy. Ill go through the changes and put a feedback on testing it on a real drone. Is it included in 4.5.0? I couldnot find any mention yet. If it was not included, what could have been the reasons, and where can I find them out?

Hi @Mihir_Salot,

The simple-avoidance-in-Auto PR is not included in 4.5. The normal procedure is for changes to be merged to master (aka “latest”) and then they appear in the next stable release (e.g. 4.6.0 in this case). For some bug fixes and low-risk enhancements we may back port them to the stable release (e.g. currently 4.5.x) but it’s unlikely this one will be backported to 4.5.x unless there are a number of users and/or Partner companies really asking for it. It’s very likely to be included in 4.6.0.