APM: rename RDRSTEER to WHEELSTEER

thanks to Jon for the suggestion
This commit is contained in:
Andrew Tridgell 2012-08-15 16:28:59 +10:00
parent c652538516
commit 455e088c9f
3 changed files with 5 additions and 5 deletions

View File

@ -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();

View File

@ -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)
{}
};

View File

@ -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