mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_HAL_SITL: Add SIM_WIND_DIR_Z parameter for SITL
This controls the vertical pitch of the 3d wind vector, allowing futher control of the wind using systems like dronekit. This change directly effects the calcuation of the wind vector
This commit is contained in:
parent
8094198767
commit
8b08e9388d
@ -343,10 +343,12 @@ void SITL_State::_simulator_servos(SITL::Aircraft::sitl_input &input)
|
||||
float altitude = _barometer?_barometer->get_altitude():0;
|
||||
float wind_speed = 0;
|
||||
float wind_direction = 0;
|
||||
float wind_dir_z = 0;
|
||||
if (_sitl) {
|
||||
// The EKF does not like step inputs so this LPF keeps it happy.
|
||||
wind_speed = _sitl->wind_speed_active = (0.95f*_sitl->wind_speed_active) + (0.05f*_sitl->wind_speed);
|
||||
wind_speed = _sitl->wind_speed_active = (0.95f*_sitl->wind_speed_active) + (0.05f*_sitl->wind_speed);
|
||||
wind_direction = _sitl->wind_direction_active = (0.95f*_sitl->wind_direction_active) + (0.05f*_sitl->wind_direction);
|
||||
wind_dir_z = _sitl->wind_dir_z_active = (0.95f*_sitl->wind_dir_z_active) + (0.05f*_sitl->wind_dir_z);
|
||||
}
|
||||
|
||||
if (altitude < 0) {
|
||||
@ -359,6 +361,7 @@ void SITL_State::_simulator_servos(SITL::Aircraft::sitl_input &input)
|
||||
input.wind.speed = wind_speed;
|
||||
input.wind.direction = wind_direction;
|
||||
input.wind.turbulence = _sitl?_sitl->wind_turbulance:0;
|
||||
input.wind.dir_z = wind_dir_z;
|
||||
|
||||
for (i=0; i<SITL_NUM_CHANNELS; i++) {
|
||||
if (pwm_output[i] == 0xFFFF) {
|
||||
|
Loading…
Reference in New Issue
Block a user