AP_HAL_SITL: send vehicle velocity to sitl vicon class

This commit is contained in:
Randy Mackay 2020-05-15 11:14:22 +09:00
parent c8f6cb233b
commit 630bc01101

View File

@ -563,6 +563,7 @@ void SITL_State::_fdm_input_local(void)
sitl_model->get_attitude(attitude);
vicon->update(sitl_model->get_location(),
sitl_model->get_position(),
sitl_model->get_velocity_ef(),
attitude);
}
if (benewake_tf02 != nullptr) {