mirror of https://github.com/ArduPilot/ardupilot
SITL: correct use of uninitialized values in simulated gimbal
This commit is contained in:
parent
00cdf24324
commit
3296b1c7f7
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue