forked from Archive/PX4-Autopilot
MAVLink app: Use right lookup function
This commit is contained in:
parent
36ca62ece9
commit
76ce611e84
|
@ -130,7 +130,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
|
|||
|
||||
} else {
|
||||
/* when index is >= 0, send this parameter again */
|
||||
send_param(param_for_index(req_read.param_index));
|
||||
send_param(param_for_used_index(req_read.param_index));
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -192,6 +192,7 @@ MavlinkParametersManager::send(const hrt_abstime t)
|
|||
/* look for the first parameter which is used */
|
||||
param_t p;
|
||||
do {
|
||||
/* walk through all parameters, including unused ones */
|
||||
p = param_for_index(_send_all_index);
|
||||
_send_all_index++;
|
||||
} while (p != PARAM_INVALID && !param_used(p));
|
||||
|
|
Loading…
Reference in New Issue