mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_TECS: disable bad descent for soaring
This commit is contained in:
parent
9f2f070439
commit
5fdebe23cc
@ -751,6 +751,11 @@ void AP_TECS::_detect_bad_descent(void)
|
|||||||
{
|
{
|
||||||
_flags.badDescent = false;
|
_flags.badDescent = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// when soaring is active we never trigger a bad descent
|
||||||
|
if (_soaring_controller.is_active() && _soaring_controller.get_throttle_suppressed()) {
|
||||||
|
_flags.badDescent = false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_TECS::_update_pitch(void)
|
void AP_TECS::_update_pitch(void)
|
||||||
|
@ -25,13 +25,15 @@
|
|||||||
#include <AP_SpdHgtControl/AP_SpdHgtControl.h>
|
#include <AP_SpdHgtControl/AP_SpdHgtControl.h>
|
||||||
#include <DataFlash/DataFlash.h>
|
#include <DataFlash/DataFlash.h>
|
||||||
#include <AP_Landing/AP_Landing.h>
|
#include <AP_Landing/AP_Landing.h>
|
||||||
|
#include <AP_Soaring/AP_Soaring.h>
|
||||||
|
|
||||||
class AP_TECS : public AP_SpdHgtControl {
|
class AP_TECS : public AP_SpdHgtControl {
|
||||||
public:
|
public:
|
||||||
AP_TECS(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, const AP_Landing &landing) :
|
AP_TECS(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, const AP_Landing &landing, const SoaringController &soaring_controller) :
|
||||||
_ahrs(ahrs),
|
_ahrs(ahrs),
|
||||||
aparm(parms),
|
aparm(parms),
|
||||||
_landing(landing)
|
_landing(landing),
|
||||||
|
_soaring_controller(soaring_controller)
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
}
|
}
|
||||||
@ -133,6 +135,9 @@ private:
|
|||||||
|
|
||||||
// reference to const AP_Landing to access it's params
|
// reference to const AP_Landing to access it's params
|
||||||
const AP_Landing &_landing;
|
const AP_Landing &_landing;
|
||||||
|
|
||||||
|
// reference to const SoaringController to access its state
|
||||||
|
const SoaringController &_soaring_controller;
|
||||||
|
|
||||||
// TECS tuning parameters
|
// TECS tuning parameters
|
||||||
AP_Float _hgtCompFiltOmega;
|
AP_Float _hgtCompFiltOmega;
|
||||||
|
Loading…
Reference in New Issue
Block a user