135 _loiter_rad(parms.loiter_radius),
136 _throttle_suppressed(true)
184 gcs().
send_text(MAV_SEVERITY_INFO,
"Thermal weak, recommend quitting: W %f R %f th %f alt %f Mc %f", (
double)
_ekf.
X[0], (
double)
_ekf.
X[1], (
double)thermalability, (
double)alt, (
double)
McCready(alt));
187 gcs().
send_text(MAV_SEVERITY_ALERT,
"Out of allowable altitude range, beginning cruise. Alt = %f", (
double)alt);
210 const float init_q[4] = {cov_q1, cov_q2, cov_q2, cov_q2};
248 *dx -= *wind_drift_x;
249 *dy -= *wind_drift_y;
273 for (i = 0; i < 4; i++) {
276 for (i = 0; i < 4; i++) {
282 DataFlash_Class::instance()->
Log_Write(
"SOAR",
"TimeUS,nettorate,dx,dy,x0,x1,x2,x3,lat,lng,alt,dx_w,dy_w",
"QfffffffLLfff",
virtual void reset_pitch_I(void)=0
unsigned long _thermal_start_time_us
#define EXPECTED_THERMALLING_SINK
void get_wind_corrected_drift(const Location *current_loc, const Vector3f *wind, float *wind_drift_x, float *wind_drift_y, float *dx, float *dy)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define AP_PARAM_FLAG_ENABLE
#define INITIAL_RADIUS_COVARIANCE
static const struct AP_Param::GroupInfo var_info[]
virtual bool get_position(struct Location &loc) const =0
Interface definition for the various Ground Control System.
virtual Vector3f wind_estimate(void) const =0
#define AP_GROUPINFO(name, idx, clazz, element, def)
#define INITIAL_STRENGTH_COVARIANCE
float McCready(float alt)
unsigned long _prev_update_time
AP_SpdHgtControl & _spdHgt
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
bool _throttle_suppressed
bool check_init_thermal_criteria()
int32_t lat
param 3 - Latitude * 10**7
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
void Log_Write(const char *name, const char *labels, const char *fmt,...)
void update_thermalling()
bool check_thermal_criteria()
static DataFlash_Class * instance(void)
void send_text(MAV_SEVERITY severity, const char *fmt,...)
#define INITIAL_THERMAL_RADIUS
ExtendedKalmanFilter _ekf
unsigned long _cruise_start_time_us
int32_t lng
param 4 - Longitude * 10**7
void reset(const VectorN< float, N > &x, const MatrixN< float, N > &p, const MatrixN< float, N > q, float r)
AP_Float thermal_distance_ahead
static uint16_t get_radio_in(const uint8_t chan)
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)
#define INITIAL_POSITION_COVARIANCE
virtual void get_relative_position_D_home(float &posD) const =0
void update(float z, float Vx, float Vy)
#define INITIAL_THERMAL_STRENGTH
void update(const float polar_K, const float polar_CD0, const float polar_B)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)