SITL: fix may-be-used-uninitialised error in thermalling code

This commit is contained in:
Peter Barker 2022-01-28 15:56:24 +11:00 committed by Andrew Tridgell
parent 56761cccf0
commit af1a454820
1 changed files with 5 additions and 0 deletions

View File

@ -35,6 +35,7 @@
#include <AP_Declination/AP_Declination.h>
#include <AP_Terrain/AP_Terrain.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
using namespace SITL;
@ -1033,6 +1034,8 @@ float Aircraft::get_local_updraft(const Vector3d &currentPos)
int n_thermals = 0;
switch (scenario) {
case 0:
return 0;
case 1:
n_thermals = 1;
thermals_w[0] = 2.0;
@ -1054,6 +1057,8 @@ float Aircraft::get_local_updraft(const Vector3d &currentPos)
thermals_x[0] = -180.0;
thermals_y[0] = -260.0;
break;
default:
AP_BoardConfig::config_error("Bad thermal scenario");
}
// Wind drift at this altitude