mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: pass in wind speed to C++ simulators
This commit is contained in:
parent
091a1e7fe0
commit
e7f3716e8c
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue