SITL: correct use of uninitialised stack data in SIM_Gimbal
This commit is contained in:
parent
93cb56b5f2
commit
05c996bfcc
@ -229,7 +229,7 @@ struct gimbal_param *Gimbal::param_find(const char *name)
|
||||
void Gimbal::param_send(const struct gimbal_param *p)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
mavlink_param_value_t param_value;
|
||||
mavlink_param_value_t param_value{};
|
||||
strncpy_noterm(param_value.param_id, p->name, sizeof(param_value.param_id));
|
||||
param_value.param_value = p->value;
|
||||
param_value.param_count = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user