20 #define EXPECTED_THERMALLING_SINK 0.7 21 #define INITIAL_THERMAL_STRENGTH 2.0 22 #define INITIAL_THERMAL_RADIUS 30.0 //150.0 23 #define INITIAL_STRENGTH_COVARIANCE 0.0049 24 #define INITIAL_RADIUS_COVARIANCE 2500.0 25 #define INITIAL_POSITION_COVARIANCE 300.0 91 _throttle_suppressed = suppressed;
unsigned long _thermal_start_time_us
void get_wind_corrected_drift(const Location *current_loc, const Vector3f *wind, float *wind_drift_x, float *wind_drift_y, float *dx, float *dy)
float get_vario_reading() const
static const struct AP_Param::GroupInfo var_info[]
void set_throttle_suppressed(bool suppressed)
float McCready(float alt)
unsigned long _prev_update_time
AP_SpdHgtControl & _spdHgt
bool _throttle_suppressed
bool check_init_thermal_criteria()
A system for managing and storing variables that are of general interest to the system.
generic speed & height controller interface
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
void update_thermalling()
bool get_throttle_suppressed() const
bool check_thermal_criteria()
ExtendedKalmanFilter _ekf
unsigned long _cruise_start_time_us
AP_Float thermal_distance_ahead
bool check_cruise_criteria()
struct Location _prev_update_location
void get_target(Location &wp)
SoaringController(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms)
void get_altitude_wrt_home(float *alt)