ardupilot
ardupilot copied to clipboard
ArduPlane keeps going up when the next waypoint alt is down
Bug report
Issue details
Test attached mission on SITL. You can see that when the plane cannot achieve the target alt for point 2, while point 3 has lower alt, it keeps gaining alt for long time before the alt_error is corrected then goes back down again in funny fashion
Version ArduPlane-4.6.0 But it's as old as 4.4.x
Platform [ ] All [ ] AntennaTracker [ ] Copter [ X ] Plane [ ] Rover [ ] Submarine
Airframe type Plane Fixed wing
Hardware type Any, can be reproduced in SITL. I confirmed it on real flights too.
Logs
See attached mission, easy to reproduce.
I'm not sure this isn't working as designed. If the vehicle is underperforming it still wants to meet its glide slope eventually, and I think it does actually do that.
Your waypoints are defining a vertical altitude profile your aircraft is supposed to be following - the vehicle is just making up for what it couldn't physically accomplish.
This existing behaviour could be very important for someone trying to clear terrain with waypoints, it's probably not something we could change for everyone.
If you want to make the argument that it would be useful for the Plane to have an option to just calculate its glide slope based on its current altitude rather than the waypoint altitudes, you could do that. That's a better way to accomplish what you're after vs constraining the altitude, and could look something like this:
--- a/ArduPlane/altitude.cpp
+++ b/ArduPlane/altitude.cpp
@@ -50,7 +50,12 @@ void Plane::setup_alt_slope(void)
// establish the distance we are travelling to the next waypoint,
// for calculating out rate of change of altitude
auto_state.wp_distance = current_loc.get_distance(next_WP_loc);
- auto_state.wp_proportion = current_loc.line_path_proportion(prev_WP_loc, next_WP_loc);
+ Location tmp = tmp;
+ bool flight_options_bit_says_glide_slopes_from_current_alt = true;
+ if (flight_options_bit_says_glide_slopes_from_current_alt) {
+ tmp.copy_alt_from(current_loc);
+ }
+ auto_state.wp_proportion = current_loc.line_path_proportion(tmp, next_WP_loc);
TECS_controller.set_path_proportion(auto_state.wp_proportion);
update_flight_stage();
@@ -70,7 +75,7 @@ void Plane::setup_alt_slope(void)
https://github.com/ArduPilot/ardupilot/issues/39
*/
if (above_location_current(next_WP_loc)) {
- set_offset_altitude_location(prev_WP_loc, next_WP_loc);
+ set_offset_altitude_location(tmp, next_WP_loc);
} else {
reset_offset_altitude();
}
@@ -89,7 +94,7 @@ void Plane::setup_alt_slope(void)
// gain height at low altitudes, potentially hitting
// obstacles.
if (adjusted_relative_altitude_cm() > 2000 || above_location_current(next_WP_loc)) {
- set_offset_altitude_location(prev_WP_loc, next_WP_loc);
+ set_offset_altitude_location(tmp, next_WP_loc);
} else {
reset_offset_altitude();
}
(that patch is almost certainly flawed because it is nuking terrain-relative / terrain-following stuff, at a guess).
There are other options here, however
- the Plane quad-assist itself to the correct altitude as required (increasing vertical preformance)
- The vehicle could also loiter-up to the required altitude
- add an option bit equivalent to
IMMEDIATE_CLIMB_IN_AUTO,IMMEDIATE_CLIMB_IN_AUTO; this isn't exactly what you're after in that the vehicle would immediately descend rather than follow a glide slope from its current altitude - but at least we have precedent for it!
But actually this was not arduplane behavior before 4.4.0 .. So there was actually a behavior regression since then. For this point:
Your waypoints are defining a vertical altitude profile your aircraft is supposed to be following - the vehicle is just making up for what it couldn't physically accomplish.
Actually, you can argue too that it was supposed to be able to achieve, but couldn't, due to sudden battery degradation for example which is very common, and many other similar cases. And continuation in this case is a really bad decision. If one argues that then one should RTL or LAND,, ok, my proposed regression correction allows him to RTL before burning his battery or worsening the unexpected failure. Loiter Alt UP is very dangerous in the cases where the plane could not achieve the required ALT; battery could burn, wind could stall it,... By long experience, I never recommend loiter-alt-up.. One could use loiter-time with higher alt if he really wants that.
Any way, I think adding an option bit that achieve my proposed regression correction is a good point, I'll update my pr soon.
@Ryanf55 may be interested in this one. It's a regression in 4.4.x it seems.