APM: make it possible to fetch parameters by index

This commit is contained in:
Andrew Tridgell 2012-09-20 07:42:46 +10:00
parent e761645e24
commit 832c5e996e
1 changed files with 13 additions and 9 deletions

View File

@ -1328,17 +1328,21 @@ 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;
enum ap_var_type p_type;
AP_Param *vp;
if (packet.param_index != -1) {
gcs_send_text_P(SEVERITY_LOW, PSTR("Param by index not supported"));
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;
}
enum ap_var_type p_type;
AP_Param *vp = AP_Param::find(packet.param_id, &p_type);
} else {
vp = AP_Param::find(packet.param_id, &p_type);
if (vp == NULL) {
gcs_send_text_fmt(PSTR("Unknown parameter %s"), packet.param_id);
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);