APM: send right parameter index when possible
This commit is contained in:
parent
764d86216e
commit
f0f47f929a
@ -1328,7 +1328,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
param_name,
|
param_name,
|
||||||
value,
|
value,
|
||||||
mav_var_type(p_type),
|
mav_var_type(p_type),
|
||||||
-1, -1);
|
_count_parameters(),
|
||||||
|
packet.param_index);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user