APM:Libraries
AP_Soaring.cpp
Go to the documentation of this file.
1 #include "AP_Soaring.h"
2 #include <GCS_MAVLink/GCS.h>
3 #include <stdint.h>
4 extern const AP_HAL::HAL& hal;
5 
6 
7 // ArduSoar parameters
9  // @Param: ENABLE
10  // @DisplayName: Is the soaring mode enabled or not
11  // @Description: Toggles the soaring mode on and off
12  // @Values: 0:Disable,1:Enable
13  // @User: Advanced
14  AP_GROUPINFO_FLAGS("ENABLE", 1, SoaringController, soar_active, 0, AP_PARAM_FLAG_ENABLE),
15 
16  // @Param: VSPEED
17  // @DisplayName: Vertical v-speed
18  // @Description: Rate of climb to trigger themalling speed
19  // @Units: m/s
20  // @Range: 0 10
21  // @User: Advanced
22  AP_GROUPINFO("VSPEED", 2, SoaringController, thermal_vspeed, 0.7f),
23 
24  // @Param: Q1
25  // @DisplayName: Process noise
26  // @Description: Standard deviation of noise in process for strength
27  // @Units:
28  // @Range: 0 10
29  // @User: Advanced
30  AP_GROUPINFO("Q1", 3, SoaringController, thermal_q1, 0.001f),
31 
32  // @Param: Q2
33  // @DisplayName: Process noise
34  // @Description: Standard deviation of noise in process for position and radius
35  // @Units:
36  // @Range: 0 10
37  // @User: Advanced
38  AP_GROUPINFO("Q2", 4, SoaringController, thermal_q2, 0.03f),
39 
40  // @Param: R
41  // @DisplayName: Measurement noise
42  // @Description: Standard deviation of noise in measurement
43  // @Units:
44  // @Range: 0 10
45  // @User: Advanced
46 
47  AP_GROUPINFO("R", 5, SoaringController, thermal_r, 0.45f),
48 
49  // @Param: DIST_AHEAD
50  // @DisplayName: Distance to thermal center
51  // @Description: Initial guess of the distance to the thermal center
52  // @Units: m
53  // @Range: 0 100
54  // @User: Advanced
55  AP_GROUPINFO("DIST_AHEAD", 6, SoaringController, thermal_distance_ahead, 5.0f),
56 
57  // @Param: MIN_THML_S
58  // @DisplayName: Minimum thermalling time
59  // @Description: Minimum number of seconds to spend thermalling
60  // @Units: s
61  // @Range: 0 32768
62  // @User: Advanced
63  AP_GROUPINFO("MIN_THML_S", 7, SoaringController, min_thermal_s, 20),
64 
65  // @Param: MIN_CRSE_S
66  // @DisplayName: Minimum cruising time
67  // @Description: Minimum number of seconds to spend cruising
68  // @Units: s
69  // @Range: 0 32768
70  // @User: Advanced
71  AP_GROUPINFO("MIN_CRSE_S", 8, SoaringController, min_cruise_s, 30),
72 
73  // @Param: POLAR_CD0
74  // @DisplayName: Zero lift drag coef.
75  // @Description: Zero lift drag coefficient
76  // @Units:
77  // @Range: 0 0.5
78  // @User: Advanced
79  AP_GROUPINFO("POLAR_CD0", 9, SoaringController, polar_CD0, 0.027),
80 
81  // @Param: POLAR_B
82  // @DisplayName: Induced drag coeffient
83  // @Description: Induced drag coeffient
84  // @Units:
85  // @Range: 0 0.5
86  // @User: Advanced
87  AP_GROUPINFO("POLAR_B", 10, SoaringController, polar_B, 0.031),
88 
89  // @Param: POLAR_K
90  // @DisplayName: Cl factor
91  // @Description: Cl factor 2*m*g/(rho*S)
92  // @Units: m.m/s/s
93  // @Range: 0 0.5
94  // @User: Advanced
95  AP_GROUPINFO("POLAR_K", 11, SoaringController, polar_K, 25.6),
96 
97  // @Param: ALT_MAX
98  // @DisplayName: Maximum soaring altitude, relative to the home location
99  // @Description: Don't thermal any higher than this.
100  // @Units: m
101  // @Range: 0 1000.0
102  // @User: Advanced
103  AP_GROUPINFO("ALT_MAX", 12, SoaringController, alt_max, 350.0),
104 
105  // @Param: ALT_MIN
106  // @DisplayName: Minimum soaring altitude, relative to the home location
107  // @Description: Don't get any lower than this.
108  // @Units: m
109  // @Range: 0 1000.0
110  // @User: Advanced
111  AP_GROUPINFO("ALT_MIN", 13, SoaringController, alt_min, 50.0),
112 
113  // @Param: ALT_CUTOFF
114  // @DisplayName: Maximum power altitude, relative to the home location
115  // @Description: Cut off throttle at this alt.
116  // @Units: m
117  // @Range: 0 1000.0
118  // @User: Advanced
119  AP_GROUPINFO("ALT_CUTOFF", 14, SoaringController, alt_cutoff, 250.0),
120 
121  // @Param: ENABLE_CH
122  // @DisplayName: (Optional) RC channel that toggles the soaring controller on and off
123  // @Description: Toggles the soaring controller on and off. This parameter has any effect only if SOAR_ENABLE is set to 1 and this parameter is set to a valid non-zero channel number. When set, soaring will be activated when RC input to the specified channel is greater than or equal to 1700.
124  // @Range: 0 16
125  // @User: Advanced
126  AP_GROUPINFO("ENABLE_CH", 15, SoaringController, soar_active_ch, 0),
127 
129 };
130 
132  _ahrs(ahrs),
133  _spdHgt(spdHgt),
134  _vario(ahrs,parms),
135  _loiter_rad(parms.loiter_radius),
136  _throttle_suppressed(true)
137 {
139 }
140 
142 {
144  location_offset(wp, _ekf.X[2], _ekf.X[3]);
145 }
146 
148 {
149  float alt = 0;
150  get_altitude_wrt_home(&alt);
151 
152  if (_throttle_suppressed && (alt < alt_min)) {
153  // Time to throttle up
154  _throttle_suppressed = false;
155  } else if ((!_throttle_suppressed) && (alt > alt_cutoff)) {
156  // Start glide
157  _throttle_suppressed = true;
158  // Zero the pitch integrator - the nose is currently raised to climb, we need to go back to glide.
161  // Reset the filtered vario rate - it is currently elevated due to the climb rate and would otherwise take a while to fall again,
162  // leading to false positives.
164  }
165 
166  return _throttle_suppressed;
167 }
168 
170 {
171  return (soar_active
172  && ((AP_HAL::micros64() - _cruise_start_time_us) > ((unsigned)min_cruise_s * 1e6))
174  && _vario.alt < alt_max
175  && _vario.alt > alt_min);
176 }
177 
179 {
180  float thermalability = (_ekf.X[0]*expf(-powf(_loiter_rad / _ekf.X[1], 2))) - EXPECTED_THERMALLING_SINK;
181  float alt = _vario.alt;
182 
183  if (soar_active && (AP_HAL::micros64() - _thermal_start_time_us) > ((unsigned)min_thermal_s * 1e6) && thermalability < McCready(alt)) {
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));
185  return true;
186  } else if (soar_active && (alt>alt_max || alt<alt_min)) {
187  gcs().send_text(MAV_SEVERITY_ALERT, "Out of allowable altitude range, beginning cruise. Alt = %f", (double)alt);
188  return true;
189  }
190 
191  return false;
192 }
193 
195 {
196  if (soar_active && (AP_HAL::micros64() - _thermal_start_time_us) < ((unsigned)min_thermal_s * 1e6)) {
197  return true;
198  }
199 
200  return false;
201 
202 }
203 
205 {
206  // Calc filter matrices - so that changes to parameters can be updated by switching in and out of thermal mode
207  float r = powf(thermal_r, 2);
208  float cov_q1 = powf(thermal_q1, 2); // State covariance
209  float cov_q2 = powf(thermal_q2, 2); // State covariance
210  const float init_q[4] = {cov_q1, cov_q2, cov_q2, cov_q2};
211  const MatrixN<float,4> q{init_q};
212  const float init_p[4] = {INITIAL_STRENGTH_COVARIANCE, INITIAL_RADIUS_COVARIANCE, INITIAL_POSITION_COVARIANCE, INITIAL_POSITION_COVARIANCE};
213  const MatrixN<float,4> p{init_p};
214 
215  // New state vector filter will be reset. Thermal location is placed in front of a/c
216  const float init_xr[4] = {INITIAL_THERMAL_STRENGTH,
220  const VectorN<float,4> xr{init_xr};
221 
222  // Also reset covariance matrix p so filter is not affected by previous data
223  _ekf.reset(xr, p, q, r);
224 
228 }
229 
231 {
232  if (is_active() && suppress_throttle()) {
234  // Start glide. Will be updated on the next loop.
235  _throttle_suppressed = true;
236  }
237 }
238 
239 void SoaringController::get_wind_corrected_drift(const Location *current_loc, const Vector3f *wind, float *wind_drift_x, float *wind_drift_y, float *dx, float *dy)
240 {
241  Vector2f diff = location_diff(_prev_update_location, *current_loc); // get distances from previous update
242  *dx = diff.x;
243  *dy = diff.y;
244 
245  // Wind correction
246  *wind_drift_x = wind->x * (AP_HAL::micros64() - _prev_update_time) * 1e-6;
247  *wind_drift_y = wind->y * (AP_HAL::micros64() - _prev_update_time) * 1e-6;
248  *dx -= *wind_drift_x;
249  *dy -= *wind_drift_y;
250 }
251 
253 {
255  *alt *= -1.0f;
256 }
258 {
259  struct Location current_loc;
260  _ahrs.get_position(current_loc);
261 
262  if (_vario.new_data) {
263  float dx = 0;
264  float dy = 0;
265  float dx_w = 0;
266  float dy_w = 0;
267  Vector3f wind = _ahrs.wind_estimate();
268  get_wind_corrected_drift(&current_loc, &wind, &dx_w, &dy_w, &dx, &dy);
269 
270 #if (0)
271  // Print32_t filter info for debugging
272  int32_t i;
273  for (i = 0; i < 4; i++) {
274  gcs().send_text(MAV_SEVERITY_INFO, "%e ", (double)_ekf.P[i][i]);
275  }
276  for (i = 0; i < 4; i++) {
277  gcs().send_text(MAV_SEVERITY_INFO, "%e ", (double)_ekf.X[i]);
278  }
279 #endif
280 
281  // write log - save the data.
282  DataFlash_Class::instance()->Log_Write("SOAR", "TimeUS,nettorate,dx,dy,x0,x1,x2,x3,lat,lng,alt,dx_w,dy_w", "QfffffffLLfff",
284  (double)_vario.reading,
285  (double)dx,
286  (double)dy,
287  (double)_ekf.X[0],
288  (double)_ekf.X[1],
289  (double)_ekf.X[2],
290  (double)_ekf.X[3],
291  current_loc.lat,
292  current_loc.lng,
293  (double)_vario.alt,
294  (double)dx_w,
295  (double)dy_w);
296 
297  //log_data();
298  _ekf.update(_vario.reading,dx, dy); // update the filter
299 
300  _prev_update_location = current_loc; // save for next time
302  _vario.new_data = false;
303  }
304 }
305 
307 {
308  // Reserved for future tasks that need to run continuously while in FBWB or AUTO mode,
309  // for example, calculation of optimal airspeed and flap angle.
310 }
311 
313 {
315 }
316 
317 
319 {
320  // A method shell to be filled in later
321  return thermal_vspeed;
322 }
323 
325 {
326  if (!soar_active) {
327  return false;
328  }
329  if (soar_active_ch <= 0) {
330  // no activation channel
331  return true;
332  }
333  // active when above 1700
334  return RC_Channels::get_radio_in(soar_active_ch-1) >= 1700;
335 }
AP_Float alt_max
Definition: AP_Soaring.h:66
virtual void reset_pitch_I(void)=0
unsigned long _thermal_start_time_us
Definition: AP_Soaring.h:38
#define EXPECTED_THERMALLING_SINK
Definition: AP_Soaring.h:20
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
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
AP_Float thermal_q1
Definition: AP_Soaring.h:57
#define INITIAL_RADIUS_COVARIANCE
Definition: AP_Soaring.h:24
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Soaring.h:74
float alt
Definition: Variometer.h:34
virtual bool get_position(struct Location &loc) const =0
Interface definition for the various Ground Control System.
AP_Int8 soar_active
Definition: AP_Soaring.h:54
virtual Vector3f wind_estimate(void) const =0
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
AP_AHRS & _ahrs
Definition: AP_Soaring.h:30
#define INITIAL_STRENGTH_COVARIANCE
Definition: AP_Soaring.h:23
float McCready(float alt)
Definition: AP_Soaring.cpp:318
unsigned long _prev_update_time
Definition: AP_Soaring.h:44
GCS & gcs()
float yaw
Definition: AP_AHRS.h:226
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
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
Definition: location.cpp:125
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
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
float filtered_reading
Definition: Variometer.h:36
T y
Definition: vector2.h:37
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
AP_Float alt_min
Definition: AP_Soaring.h:67
MatrixN< float, N > P
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
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 Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
#define f(i)
void update_thermalling()
Definition: AP_Soaring.cpp:257
AP_Float polar_CD0
Definition: AP_Soaring.h:63
T y
Definition: vector3.h:67
bool check_thermal_criteria()
Definition: AP_Soaring.cpp:169
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
uint64_t micros64()
Definition: system.cpp:162
AP_Float alt_cutoff
Definition: AP_Soaring.h:68
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
#define INITIAL_THERMAL_RADIUS
Definition: AP_Soaring.h:22
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
T x
Definition: vector2.h:37
Variometer _vario
Definition: AP_Soaring.h:32
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
void reset(const VectorN< float, N > &x, const MatrixN< float, N > &p, const MatrixN< float, N > q, float r)
AP_Float thermal_q2
Definition: AP_Soaring.h:58
AP_Float thermal_distance_ahead
Definition: AP_Soaring.h:60
static uint16_t get_radio_in(const uint8_t chan)
bool check_cruise_criteria()
Definition: AP_Soaring.cpp:178
bool new_data
Definition: Variometer.h:38
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
float reading
Definition: Variometer.h:35
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
#define INITIAL_POSITION_COVARIANCE
Definition: AP_Soaring.h:25
virtual void get_relative_position_D_home(float &posD) const =0
#define AP_GROUPEND
Definition: AP_Param.h:121
void update(float z, float Vx, float Vy)
T x
Definition: vector3.h:67
#define INITIAL_THERMAL_STRENGTH
Definition: AP_Soaring.h:21
VectorN< float, N > X
void update(const float polar_K, const float polar_CD0, const float polar_B)
Definition: Variometer.cpp:14
AP_Float thermal_vspeed
Definition: AP_Soaring.h:56
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214