mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Param: update users of AP_Param for ParamToken
This commit is contained in:
parent
f30c721886
commit
1fc24b506e
@ -127,7 +127,7 @@ private:
|
||||
///
|
||||
AP_Param *_queued_parameter; ///< next parameter to be sent in queue
|
||||
enum ap_var_type _queued_parameter_type; ///< type of the next parameter
|
||||
uint16_t _queued_parameter_token; ///AP_Param token for next() call
|
||||
AP_Param::ParamToken _queued_parameter_token;///AP_Param token for next() call
|
||||
uint16_t _queued_parameter_index; ///< next queued parameter's index
|
||||
uint16_t _queued_parameter_count; ///< saved count of parameters for queued send
|
||||
|
||||
|
@ -1617,7 +1617,7 @@ GCS_MAVLINK::_count_parameters()
|
||||
// if we haven't cached the parameter count yet...
|
||||
if (0 == _parameter_count) {
|
||||
AP_Param *vp;
|
||||
uint16_t token;
|
||||
AP_Param::ParamToken token;
|
||||
|
||||
vp = AP_Param::first(&token, NULL);
|
||||
do {
|
||||
|
@ -127,7 +127,7 @@ private:
|
||||
///
|
||||
AP_Param *_queued_parameter; ///< next parameter to be sent in queue
|
||||
enum ap_var_type _queued_parameter_type; ///< type of the next parameter
|
||||
uint16_t _queued_parameter_token; ///AP_Param token for next() call
|
||||
AP_Param::ParamToken _queued_parameter_token;///AP_Param token for next() call
|
||||
uint16_t _queued_parameter_index; ///< next queued parameter's index
|
||||
uint16_t _queued_parameter_count; ///< saved count of parameters for queued send
|
||||
|
||||
|
@ -1970,7 +1970,7 @@ GCS_MAVLINK::_count_parameters()
|
||||
// if we haven't cached the parameter count yet...
|
||||
if (0 == _parameter_count) {
|
||||
AP_Param *vp;
|
||||
uint16_t token;
|
||||
AP_Param::ParamToken token;
|
||||
|
||||
vp = AP_Param::first(&token, NULL);
|
||||
do {
|
||||
|
@ -106,7 +106,7 @@ void setup() {
|
||||
compass.save_offsets();
|
||||
|
||||
// full testing of all variables
|
||||
uint16_t token;
|
||||
AP_Param::ParamToken token;
|
||||
for (AP_Param *ap = AP_Param::first(&token, &type);
|
||||
ap;
|
||||
ap=AP_Param::next(&token, &type)) {
|
||||
|
Loading…
Reference in New Issue
Block a user