SITL: correct use of uninitialized values in simulated gimbal

This commit is contained in:
Peter Barker 2018-11-25 09:24:47 +11:00 committed by WickedShell
parent 00cdf24324
commit 3296b1c7f7
1 changed files with 1 additions and 0 deletions

View File

@ -222,6 +222,7 @@ void Gimbal::param_send(const struct gimbal_param *p)
param_value.param_value = p->value;
param_value.param_count = 0;
param_value.param_index = 0;
param_value.param_type = MAV_PARAM_TYPE_REAL32;
mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
uint8_t saved_seq = chan0_status->current_tx_seq;