ArduPlane: enable soaring in LOITER and GUIDED modes#32034
Conversation
9fe3fb6 to
b744013
Compare
b744013 to
71378a2
Compare
|
Thank you @magicrub for the quick review, I applied the suggested changes with some explanation about |
|
Its not clear why the goal is here, you explain very well what the PR does but not the why, what is the extra functionality that this change gives? |
|
We found that in practice we control the fixed-wing mostly by "click on map to fly there". Currently that is Guided mode. Endurance would improve if soaring were available there, even climb and glide without getting thermals seems to be beneficial on our glider. If there is another way to get that result, I'm happy to rework this feature, possibly with some adjustments in ground control software, but for now that's what we found. Auto mode isn't a good solution for us, because for fixed-wing (where soaring is applicable), there is some considerable effort in planning the landing, so the operator doesn't modify the mission ad hoc. |
|
Re: @IamPete1 I don't think accepting target position in Thermal mode would be the same, because when there's no lift to be found the autopilot will exit this mode, and we're interested in gliding along a route as well. |
Georacer
left a comment
There was a problem hiding this comment.
The motivation of this PR and the way it's done seams reasonable to me.
I'm speaking as a non-soaring expert here, of course.
But we definitely need some new autotests for this functionality, or edits in the existing autotest for soaring.
| #endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED | ||
| { | ||
| #if HAL_SOARING_ENABLED | ||
| plane.set_soaring_altitude(); |
There was a problem hiding this comment.
I'm a bit hesitant with this. In FBWB and CRUISE the pilot files VLOS or at least VLOS.
But with LOITER and GUIDED, terrain becomes an issue. How will this play nice with a terrain where ALT_CUTOFF+10+<home_alt> is still lower than the terrain elevation?
There was a problem hiding this comment.
Perhaps an answer to my question would be "the same way this is treated in AUTO".
There was a problem hiding this comment.
All altitudes SOAR_ALT_MIN, SOAR_ALT_CUTOFF and SOAR_ALT_MAX are relative to home. Currently there no exceptions to that, including AUTO mode.
If we were to support a terrain height check, I think we should make it follow the present Terrain Following feature. Add another bit to TERRAIN_FOLLOW for Soaring and then check SOAR_ALT_MIN against terrain instead of home if that bit is set. But I think that both regarding code and user experience that is a separate feature that we can discuss in a separate Issue/PR if you think it's a requirement for GUIDED
| const char *name() const override { return "Loiter"; } | ||
| const char *name4() const override { return "LOIT"; } | ||
|
|
||
| bool does_automatic_thermal_switch() const override { return true; } |
There was a problem hiding this comment.
Move this down to the other does method declarations - similarly in other file
There was a problem hiding this comment.
There were more modes with that ordering in the same file, I moved them around as you suggested. I don't know what other file you were referring to, I'd like you to confirm this
| plane.update_fbwb_speed_height(); | ||
| } else { | ||
| plane.calc_nav_pitch(); | ||
| #if HAL_SOARING_ENABLED |
There was a problem hiding this comment.
Copy/paste problem - make a method in the base class
There was a problem hiding this comment.
I moved as much logic as I can to the set_soaring_altitude function of Plane, but the modes manage their internal state a bit differently, I don't think I can factor it out anymore.
Now the function has considerably more complicated return value, but it's documented at declaration and all call sites.
71378a2 to
b0b53fe
Compare
|
@Georacer, @peterbarker I extended the existing Soaring autotest. In the section without thermals, I added the following changes related to this PR:
Verified that it succeeds on my machine with: |
88b99bc to
bed74a2
Compare
|
@Maarrk the soaring test does seem to fail. Perhaps something slipped through? |
…de on exit. Co-authored-by: Julian <53869112+zyromskij@users.noreply.github.com> Reviewed-by: Peter Barker <pbarker@barker.dropbear.id.au>
…n exit. Co-authored-by: Julian <53869112+zyromskij@users.noreply.github.com> Reviewed-by: Peter Barker <pbarker@barker.dropbear.id.au>
|
It turns out that the simulation hit terrain at 62m relative altitude. Probably an unfortunate timing of exiting some circling towards a mountain. I fixed it by increasing SOAR_ALT_MIN above that height (which a regular user should do in mountainous terrain). Also adjusted the "maintain altitude when disabling soaring" checks to wait longer but have a wider altitude tolerance, for more repeatable tests. |
Georacer
left a comment
There was a problem hiding this comment.
I think this PR indeed does what it advertises and doesn't break existing functionality.
BUT it really needs the corresponding wiki changes. The introduced functionality, albeit useful is a bit complex and needs good documentation.
| // Just stopped soaring in this mode | ||
|
|
||
| // Continue flying with current altitude | ||
| plane.set_target_altitude_current(); |
There was a problem hiding this comment.
Let me see if I get this right.
Before:
- If soaring was active
- and throttle was suppressed, we would maintain altitude.
- otherwise we would climb to min soaring alt.
- Otherwise do nothing.
Now:
- (entering
set_soaring_altitude()) If soaring is not active, then return True the first time.- Set the altitude target to the current altitude.
- The second time over, nothing will happen. Alt. control goes as usual.
- If soaring is active
- and throttle is suppressed, then let altitude glide down.
- otherwise climb to min soaring alt.
- FINALLY return false (returned to
update_fbwb_speed_height()and do nothing more.
It's a bit complicated, but right now I don't have an alternative at hand.
There was a problem hiding this comment.
Before:
If soaring was active
and throttle was suppressed, we would maintain altitude.
We would actually let the aircraft glide down, since throttle is suppressed.
otherwise we would climb to min soaring alt.
This code was moved to set_soaring_altitude because previously the same logic was in a bunch of places.
I know this call site got a bit more involved, but on the request of @peterbarker now the switching logic is provided from only one place. The return value of the function is there to allow the mode calling it to know "we just ended soaring". I couldn't do the "maintain current altitude" feature from soaring itself, because it's a bit different for each supported flight mode. Most importantly, the behaviour is not complicated from end user's perspective:
In supported modes (not AUTO) the vehicle will maintain current altitude when soaring is disabled.
quoted from ArduPilot/ardupilot_wiki#7457)
I feel that this is easy to understand, but also makes sense that we don't lose all the energy we saved on powered climb to what FBWB happened to be flying before a thermal was detected.
BUT it really needs the corresponding wiki changes.
Completely agree, and I think it would be fair to introduce "Merge on wiki completion" policy for user-facing features. But that's a discussion for another day :)
|
The wiki is written in ArduPilot/ardupilot_wiki#7457, I believe I already addressed all code suggestions, can I get some update what's blocking the merge? |
|
Hi @Maarrk, I've added it to the DevCall agenda so it'll at least be reviewed then |
|
@rmackay9 if you mean the call on 2026-05-11, that starts on my midnight but I'll see if I manage to attend. Thanks for your consideration! |
|
Hi @Maarrk, Alternatively we could add it to the EUDevCall which is at 4pm JST time on Wednesdays. The timing of the dev calls is on this wiki page. |
|
Thanks @rmackay9, but funnily enough Wednesday morning doesn't work for me, I'll see you on Monday with caffeine by my side |
IamPete1
left a comment
There was a problem hiding this comment.
I think we should add a soaring parameter with bits (maybe even the enable param) to enable/disable soaring in these modes. If I understand correctly once this is merged everyone with soaring enabled will get soaring in loiter and guided if they want it or not.
| plane.set_target_altitude_current(); | ||
| plane.next_WP_loc.set_alt_cm(plane.target_altitude.amsl_cm, Location::AltFrame::ABSOLUTE); |
There was a problem hiding this comment.
I don't think this will work correctly if terrain following is enabled? I see we follow the same pattern for nav-scripting, but that might well be wrong too.
To test make sure that terrain following works before and after soaring kicks in.
There was a problem hiding this comment.
I haven't done any work with terrain following, I will familiarise myself with this feature and test/autotest it, thanks for the hint
| // through SOAR_ALT_CUTOFF, thus triggering throttle suppression and return to glide. | ||
| target_altitude.amsl_cm = 100 * (plane.g2.soaring_controller.get_alt_cutoff() + 10) + AP::ahrs().get_home().alt; | ||
| } | ||
| soaring_was_active = true; |
There was a problem hiding this comment.
This flag is only kept upto date in the new modes, it needs to be cleared when changing to a mode that does not support soaring. Maybe clear it in the init_cruising function?
Your understanding is correct @IamPete1, I agree we should put it behind some bitmask:
|
These changes are motivated by practical usage of Soaring functionality in a @FlyfocusUAV airplane. We would benefit a lot from having it available when using "click on map to fly there". I understand that changes to mode behaviour should not be enabled by default, and instead controlled with some configuration. My first choice is a new
FlightOptionbut I'd like to hear some input on that.The behavior was tested in SITL and works as intended. The changes compile for all targets with
Tools/scripts/build_all.sh, and commit was made withTools/gittools/git-subsystems-split.