HAL_SITL: pass in wind speed to C++ simulators

This commit is contained in:
Andrew Tridgell 2015-05-23 11:04:13 +10:00
parent 091a1e7fe0
commit e7f3716e8c
1 changed files with 12 additions and 0 deletions

View File

@ -382,6 +382,18 @@ void SITL_State::_simulator_servos(Aircraft::sitl_input &input)
_apply_servo_filter(deltat);
// pass wind into simulators, using a wind gradient below 60m
float altitude = _barometer?_barometer->get_altitude():0;
float wind_speed = _sitl->wind_speed;
if (altitude < 0) {
altitude = 0;
}
if (altitude < 60) {
wind_speed *= altitude / 60;
}
input.wind.speed = wind_speed;
input.wind.direction = _sitl->wind_direction;
for (i=0; i<11; i++) {
if (pwm_output[i] == 0xFFFF) {
input.servos[i] = 0;