From 21214911971cb00c7b3b71e03d20912826bc9f25 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 19 Jul 2012 10:52:08 +1000 Subject: [PATCH] APM: rename airspeed_cruise to airspeed_cruise_cm to make the units clearer it is in cm/s, not m/s --- ArduPlane/ArduPlane.pde | 2 +- ArduPlane/Attitude.pde | 4 ++-- ArduPlane/Parameters.h | 6 +++--- ArduPlane/Parameters.pde | 2 +- ArduPlane/commands_logic.pde | 2 +- ArduPlane/navigation.pde | 2 +- ArduPlane/radio.pde | 2 +- 7 files changed, 10 insertions(+), 10 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index a68d975530..56b4fe132b 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -995,7 +995,7 @@ static void update_current_flight_mode(void) if(nav_pitch < (long)takeoff_pitch) nav_pitch = (long)takeoff_pitch; } else { - nav_pitch = (long)((float)g_gps->ground_speed / (float)g.airspeed_cruise * (float)takeoff_pitch * 0.5); + nav_pitch = (long)((float)g_gps->ground_speed / (float)g.airspeed_cruise_cm * (float)takeoff_pitch * 0.5); nav_pitch = constrain(nav_pitch, 500l, (long)takeoff_pitch); } diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index b2a2c396c3..3de9baf173 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -210,7 +210,7 @@ static void calc_nav_roll() if(airspeed.use()) { speed = airspeed.get_airspeed(); } else { - speed = g.airspeed_cruise*0.01; + speed = g.airspeed_cruise_cm*0.01; // Floor the speed so that the user can't enter a bad value if(speed < 6) { @@ -384,7 +384,7 @@ static void set_servos(void) if (control_mode == FLY_BY_WIRE_B) { flapSpeedSource = ((float)target_airspeed)/100; } else if (airspeed.use()) { - flapSpeedSource = g.airspeed_cruise/100; + flapSpeedSource = g.airspeed_cruise_cm/100; } else { flapSpeedSource = g.throttle_cruise; } diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index a5ca8da3a1..191fae6710 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -116,7 +116,7 @@ public: k_param_roll_limit, k_param_pitch_limit_max, k_param_pitch_limit_min, - k_param_airspeed_cruise, + k_param_airspeed_cruise_cm, k_param_RTL_altitude, k_param_inverted_flight_ch, k_param_min_gndspeed, @@ -336,7 +336,7 @@ public: AP_Int16 log_last_filenumber; // *** Deprecated - remove with next eeprom number change AP_Int8 reset_switch_chan; AP_Int8 manual_level; - AP_Int16 airspeed_cruise; + AP_Int16 airspeed_cruise_cm; AP_Int16 min_gndspeed; AP_Int16 pitch_trim; AP_Int16 RTL_altitude; @@ -455,7 +455,7 @@ public: log_last_filenumber (0), reset_switch_chan (0), manual_level (MANUAL_LEVEL), - airspeed_cruise (AIRSPEED_CRUISE_CM), + airspeed_cruise_cm (AIRSPEED_CRUISE_CM), min_gndspeed (MIN_GNDSPEED_CM), pitch_trim (0), RTL_altitude (ALT_HOLD_HOME_CM), diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index 5d52e1f493..9ab885f57f 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -383,7 +383,7 @@ static const AP_Param::Info var_info[] PROGMEM = { // @Description: Airspeed in cm/s to aim for when airspeed is enabled in auto mode // @Units: cm/s // @User: User - GSCALAR(airspeed_cruise, "TRIM_ARSPD_CM"), + GSCALAR(airspeed_cruise_cm, "TRIM_ARSPD_CM"), // @Param: MIN_GNDSPD_CM // @DisplayName: Minimum ground speed diff --git a/ArduPlane/commands_logic.pde b/ArduPlane/commands_logic.pde index f1fa5e4cae..11432a0da8 100644 --- a/ArduPlane/commands_logic.pde +++ b/ArduPlane/commands_logic.pde @@ -523,7 +523,7 @@ static void do_change_speed() { case 0: // Airspeed if(next_nonnav_command.alt > 0) - g.airspeed_cruise.set(next_nonnav_command.alt * 100); + g.airspeed_cruise_cm.set(next_nonnav_command.alt * 100); break; case 1: // Ground speed g.min_gndspeed.set(next_nonnav_command.alt * 100); diff --git a/ArduPlane/navigation.pde b/ArduPlane/navigation.pde index ca56092f47..10aeedb9c6 100644 --- a/ArduPlane/navigation.pde +++ b/ArduPlane/navigation.pde @@ -67,7 +67,7 @@ static void calc_airspeed_errors() float aspeed_cm = airspeed.get_airspeed_cm(); // Normal airspeed target - target_airspeed = g.airspeed_cruise; + target_airspeed = g.airspeed_cruise_cm; // FBW_B airspeed target if (control_mode == FLY_BY_WIRE_B) { diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index d2f6580f8c..a9544d3042 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -90,7 +90,7 @@ static void read_radio() if (g.channel_throttle.servo_out > 50) { if (airspeed.use()) { - airspeed_nudge = (g.flybywire_airspeed_max * 100 - g.airspeed_cruise) * ((g.channel_throttle.norm_input()-0.5) / 0.5); + airspeed_nudge = (g.flybywire_airspeed_max * 100 - g.airspeed_cruise_cm) * ((g.channel_throttle.norm_input()-0.5) / 0.5); } else { throttle_nudge = (g.throttle_max - g.throttle_cruise) * ((g.channel_throttle.norm_input()-0.5) / 0.5); }