From 832c5e996e8fb492b078a4612428745e18b70dcd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 20 Sep 2012 07:42:46 +1000 Subject: [PATCH] APM: make it possible to fetch parameters by index --- ArduPlane/GCS_Mavlink.pde | 22 +++++++++++++--------- 1 file changed, 13 insertions(+), 9 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 9d9f4fd168..15b80b37fa 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1328,16 +1328,20 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) mavlink_param_request_read_t packet; mavlink_msg_param_request_read_decode(msg, &packet); if (mavlink_check_target(packet.target_system,packet.target_component)) break; - if (packet.param_index != -1) { - gcs_send_text_P(SEVERITY_LOW, PSTR("Param by index not supported")); - break; - } - enum ap_var_type p_type; - AP_Param *vp = AP_Param::find(packet.param_id, &p_type); - if (vp == NULL) { - gcs_send_text_fmt(PSTR("Unknown parameter %s"), packet.param_id); - break; + AP_Param *vp; + if (packet.param_index != -1) { + vp = AP_Param::find_by_index(packet.param_index, &p_type); + if (vp == NULL) { + gcs_send_text_fmt(PSTR("Unknown parameter index %d"), packet.param_index); + break; + } + } else { + vp = AP_Param::find(packet.param_id, &p_type); + if (vp == NULL) { + gcs_send_text_fmt(PSTR("Unknown parameter /%s"), packet.param_id); + break; + } } char param_name[ONBOARD_PARAM_NAME_LENGTH]; vp->copy_name(param_name, sizeof(param_name), true);