mirror of https://github.com/ArduPilot/ardupilot
Copter: correct AFS terminate-via-land for Copter
In the case we're terminating via land it's a good idea to continue to constantly adjust our motor outputs for stabilization and the like....
This commit is contained in:
parent
254ef4f0ae
commit
ac0e126099
|
@ -303,7 +303,10 @@ void Copter::motors_output()
|
|||
// OBC rules
|
||||
if (g2.afs.should_crash_vehicle()) {
|
||||
g2.afs.terminate_vehicle();
|
||||
return;
|
||||
if (!g2.afs.terminating_vehicle_via_landing()) {
|
||||
return;
|
||||
}
|
||||
// landing must continue to run the motors output
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -83,7 +83,11 @@ public:
|
|||
|
||||
// for holding parameters
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
||||
bool terminating_vehicle_via_landing() const {
|
||||
return _terminate_action == TERMINATE_ACTION_LAND;
|
||||
};
|
||||
|
||||
protected:
|
||||
// setup failsafe values for if FMU firmware stops running
|
||||
virtual void setup_IO_failsafe(void) = 0;
|
||||
|
|
Loading…
Reference in New Issue