SITL: fix may-be-used-uninitialised error in thermalling code
This commit is contained in:
parent
56761cccf0
commit
af1a454820
@ -35,6 +35,7 @@
|
|||||||
#include <AP_Declination/AP_Declination.h>
|
#include <AP_Declination/AP_Declination.h>
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.h>
|
||||||
#include <AP_Scheduler/AP_Scheduler.h>
|
#include <AP_Scheduler/AP_Scheduler.h>
|
||||||
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
|
|
||||||
using namespace SITL;
|
using namespace SITL;
|
||||||
|
|
||||||
@ -1033,6 +1034,8 @@ float Aircraft::get_local_updraft(const Vector3d ¤tPos)
|
|||||||
int n_thermals = 0;
|
int n_thermals = 0;
|
||||||
|
|
||||||
switch (scenario) {
|
switch (scenario) {
|
||||||
|
case 0:
|
||||||
|
return 0;
|
||||||
case 1:
|
case 1:
|
||||||
n_thermals = 1;
|
n_thermals = 1;
|
||||||
thermals_w[0] = 2.0;
|
thermals_w[0] = 2.0;
|
||||||
@ -1054,6 +1057,8 @@ float Aircraft::get_local_updraft(const Vector3d ¤tPos)
|
|||||||
thermals_x[0] = -180.0;
|
thermals_x[0] = -180.0;
|
||||||
thermals_y[0] = -260.0;
|
thermals_y[0] = -260.0;
|
||||||
break;
|
break;
|
||||||
|
default:
|
||||||
|
AP_BoardConfig::config_error("Bad thermal scenario");
|
||||||
}
|
}
|
||||||
|
|
||||||
// Wind drift at this altitude
|
// Wind drift at this altitude
|
||||||
|
Loading…
Reference in New Issue
Block a user