From 455e088c9f744023875aeac9250daddf3b259ebb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 15 Aug 2012 16:28:59 +1000 Subject: [PATCH] APM: rename RDRSTEER to WHEELSTEER thanks to Jon for the suggestion --- ArduPlane/Attitude.pde | 2 +- ArduPlane/Parameters.h | 6 +++--- ArduPlane/Parameters.pde | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 76fe1d2fc4..8f7429c462 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -177,7 +177,7 @@ static void calc_nav_yaw(float speed_scaler) if (hold_course != -1) { // steering on or close to ground - g.channel_rudder.servo_out += g.pidRdrSteer.get_pid(bearing_error_cd); + g.channel_rudder.servo_out += g.pidWheelSteer.get_pid(bearing_error_cd); } else { // a PID to coordinate the turn (drive y axis accel to zero) Vector3f temp = imu.get_accel(); diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index b3f14e9927..ff035d7f09 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -198,7 +198,7 @@ public: k_param_pidServoRudder, k_param_pidTeThrottle, k_param_pidNavPitchAltitude, - k_param_pidRdrSteer, + k_param_pidWheelSteer, // 254,255: reserved }; @@ -344,7 +344,7 @@ public: PID pidServoRudder; PID pidTeThrottle; PID pidNavPitchAltitude; - PID pidRdrSteer; + PID pidWheelSteer; Parameters() : // variable default @@ -372,7 +372,7 @@ public: pidServoRudder (SERVO_YAW_P, SERVO_YAW_I, SERVO_YAW_D, SERVO_YAW_INT_MAX), pidTeThrottle (THROTTLE_TE_P, THROTTLE_TE_I, THROTTLE_TE_D, THROTTLE_TE_INT_MAX), pidNavPitchAltitude (NAV_PITCH_ALT_P, NAV_PITCH_ALT_I, NAV_PITCH_ALT_D, NAV_PITCH_ALT_INT_MAX_CM), - pidRdrSteer (0, 0, 0, 0) + pidWheelSteer (0, 0, 0, 0) {} }; diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde index cd80adb1ca..ebaad7dc5d 100644 --- a/ArduPlane/Parameters.pde +++ b/ArduPlane/Parameters.pde @@ -515,7 +515,7 @@ const AP_Param::Info var_info[] PROGMEM = { GGROUP(pidServoRudder, "YW2SRV_", PID), GGROUP(pidTeThrottle, "ENRGY2THR_", PID), GGROUP(pidNavPitchAltitude, "ALT2PTCH_", PID), - GGROUP(pidRdrSteer, "RDRSTEER_", PID), + GGROUP(pidWheelSteer, "WHEELSTEER_",PID), // variables not in the g class which contain EEPROM saved variables