APM:Libraries
AP_Soaring.h
Go to the documentation of this file.
1 /*
2  Soaring Controller class by Samuel Tabor
3 
4  Provides a layer between the thermal centring algorithm and the main
5  code for managing navigation targets, data logging, tuning parameters,
6  algorithm inputs and eventually other soaring strategies such as
7  speed-to-fly. AP_TECS libary used for reference.
8 */
9 
10 #pragma once
11 
12 #include <AP_AHRS/AP_AHRS.h>
13 #include <AP_Param/AP_Param.h>
14 #include <DataFlash/DataFlash.h>
15 #include <AP_Math/AP_Math.h>
16 #include "ExtendedKalmanFilter.h"
17 #include "Variometer.h"
19 
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
26 
27 
33 
34  // store aircraft location at last update
36 
37  // store time thermal was entered for hysteresis
38  unsigned long _thermal_start_time_us;
39 
40  // store time cruise was entered for hysteresis
41  unsigned long _cruise_start_time_us;
42 
43  // store time of last update
44  unsigned long _prev_update_time;
45 
46  float _loiter_rad;
48 
49  float McCready(float alt);
50  void get_wind_corrected_drift(const Location *current_loc, const Vector3f *wind, float *wind_drift_x, float *wind_drift_y, float *dx, float *dy);
51  void get_altitude_wrt_home(float *alt);
52 
53 protected:
54  AP_Int8 soar_active;
55  AP_Int8 soar_active_ch;
56  AP_Float thermal_vspeed;
57  AP_Float thermal_q1;
58  AP_Float thermal_q2;
59  AP_Float thermal_r;
61  AP_Int16 min_thermal_s;
62  AP_Int16 min_cruise_s;
63  AP_Float polar_CD0;
64  AP_Float polar_B;
65  AP_Float polar_K;
66  AP_Float alt_max;
67  AP_Float alt_min;
68  AP_Float alt_cutoff;
69 
70 public:
72 
73  // this supports the TECS_* user settable parameters
74  static const struct AP_Param::GroupInfo var_info[];
75  void get_target(Location & wp);
76  bool suppress_throttle();
78  bool check_cruise_criteria();
80  void init_thermalling();
81  void init_cruising();
82  void update_thermalling();
83  void update_cruising();
84  bool is_active() const;
86  {
87  return _throttle_suppressed;
88  }
89  void set_throttle_suppressed(bool suppressed)
90  {
91  _throttle_suppressed = suppressed;
92  }
93  float get_vario_reading() const
94  {
95  return _vario.displayed_reading;
96  }
97 
98  void update_vario();
99 };
AP_Float alt_max
Definition: AP_Soaring.h:66
unsigned long _thermal_start_time_us
Definition: AP_Soaring.h:38
void get_wind_corrected_drift(const Location *current_loc, const Vector3f *wind, float *wind_drift_x, float *wind_drift_y, float *dx, float *dy)
Definition: AP_Soaring.cpp:239
float get_vario_reading() const
Definition: AP_Soaring.h:93
AP_Float thermal_q1
Definition: AP_Soaring.h:57
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
float displayed_reading
Definition: Variometer.h:37
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Soaring.h:74
AP_Int8 soar_active
Definition: AP_Soaring.h:54
AP_AHRS & _ahrs
Definition: AP_Soaring.h:30
void set_throttle_suppressed(bool suppressed)
Definition: AP_Soaring.h:89
float McCready(float alt)
Definition: AP_Soaring.cpp:318
unsigned long _prev_update_time
Definition: AP_Soaring.h:44
AP_Int16 min_cruise_s
Definition: AP_Soaring.h:62
AP_Float polar_K
Definition: AP_Soaring.h:65
AP_SpdHgtControl & _spdHgt
Definition: AP_Soaring.h:31
AP_Int8 soar_active_ch
Definition: AP_Soaring.h:55
bool _throttle_suppressed
Definition: AP_Soaring.h:47
bool check_init_thermal_criteria()
Definition: AP_Soaring.cpp:194
AP_Float thermal_r
Definition: AP_Soaring.h:59
A system for managing and storing variables that are of general interest to the system.
AP_Float alt_min
Definition: AP_Soaring.h:67
generic speed & height controller interface
AP_Int16 min_thermal_s
Definition: AP_Soaring.h:61
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
void update_thermalling()
Definition: AP_Soaring.cpp:257
AP_Float polar_CD0
Definition: AP_Soaring.h:63
bool get_throttle_suppressed() const
Definition: AP_Soaring.h:85
bool check_thermal_criteria()
Definition: AP_Soaring.cpp:169
AP_Float alt_cutoff
Definition: AP_Soaring.h:68
AP_Float polar_B
Definition: AP_Soaring.h:64
ExtendedKalmanFilter _ekf
Definition: AP_Soaring.h:29
unsigned long _cruise_start_time_us
Definition: AP_Soaring.h:41
Variometer _vario
Definition: AP_Soaring.h:32
AP_Float thermal_q2
Definition: AP_Soaring.h:58
AP_Float thermal_distance_ahead
Definition: AP_Soaring.h:60
bool check_cruise_criteria()
Definition: AP_Soaring.cpp:178
struct Location _prev_update_location
Definition: AP_Soaring.h:35
void get_target(Location &wp)
Definition: AP_Soaring.cpp:141
bool is_active() const
Definition: AP_Soaring.cpp:324
bool suppress_throttle()
Definition: AP_Soaring.cpp:147
SoaringController(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, const AP_Vehicle::FixedWing &parms)
Definition: AP_Soaring.cpp:131
void get_altitude_wrt_home(float *alt)
Definition: AP_Soaring.cpp:252
AP_Float thermal_vspeed
Definition: AP_Soaring.h:56