VTOL: initialize fds struct

This commit is contained in:
Lorenz Meier 2016-01-05 22:10:32 +01:00
parent e9865071fa
commit 2ce3ef1caa

View File

@ -559,7 +559,7 @@ void VtolAttitudeControl::task_main()
_vtol_type->set_idle_mc();
/* wakeup source*/
px4_pollfd_struct_t fds[3]; /*input_mc, input_fw, parameters*/
px4_pollfd_struct_t fds[3] = {}; /*input_mc, input_fw, parameters*/
fds[0].fd = _actuator_inputs_mc;
fds[0].events = POLLIN;