VARTest: adapt for new airspeed parameter names

This commit is contained in:
Andrew Tridgell 2013-07-18 11:57:26 +10:00
parent 3e21d0594c
commit fbdf857634
2 changed files with 6 additions and 6 deletions

View File

@ -61,8 +61,8 @@ public:
// 120: Fly-by-wire control
//
k_param_flybywire_airspeed_min = 120,
k_param_flybywire_airspeed_max,
k_param_airspeed_min = 120,
k_param_airspeed_max,
k_param_FBWB_min_altitude, // 0=disabled, minimum value for altitude in cm (for first time try 30 meters = 3000 cm)
//
@ -254,8 +254,8 @@ public:
// Fly-by-wire
//
AP_Int8 flybywire_airspeed_min;
AP_Int8 flybywire_airspeed_max;
AP_Int8 airspeed_min;
AP_Int8 airspeed_max;
AP_Int16 FBWB_min_altitude;
// Throttle

View File

@ -44,8 +44,8 @@ const AP_Param::Info var_info[] PROGMEM = {
GSCALAR(fence_maxalt, "FENCE_MAXALT", 0),
#endif
GSCALAR(flybywire_airspeed_min, "ARSPD_FBW_MIN", AIRSPEED_FBW_MIN),
GSCALAR(flybywire_airspeed_max, "ARSPD_FBW_MAX", AIRSPEED_FBW_MAX),
GSCALAR(airspeed_min, "ARSPD_FBW_MIN", AIRSPEED_FBW_MIN),
GSCALAR(airspeed_max, "ARSPD_FBW_MAX", AIRSPEED_FBW_MAX),
GSCALAR(throttle_min, "THR_MIN", THROTTLE_MIN),
GSCALAR(throttle_max, "THR_MAX", THROTTLE_MAX),