mavlink: param_get proper type to silence errors

This commit is contained in:
Daniel Agar
2021-11-19 15:55:11 -05:00
parent e997a5f384
commit a749c787ca
+17 -6
View File
@@ -516,20 +516,31 @@ MavlinkParametersManager::send_param(param_t param, int component_id)
return 1;
}
mavlink_param_value_t msg;
mavlink_param_value_t msg{};
/*
* get param value, since MAVLink encodes float and int params in the same
* space during transmission, copy param onto float val_buf
*/
float param_value{};
if (param_type(param) == PARAM_TYPE_INT32) {
int32_t param_value;
if (param_get(param, &param_value) != OK) {
return 2;
if (param_get(param, &param_value) != OK) {
return 2;
}
memcpy(&msg.param_value, &param_value, sizeof(param_value));
} else {
float param_value;
if (param_get(param, &param_value) != OK) {
return 2;
}
msg.param_value = param_value;
}
msg.param_value = param_value;
msg.param_count = param_count_used();
msg.param_index = param_get_used_index(param);