APM: fixed wheeled takeoff with Jons new controllers

This commit is contained in:
Andrew Tridgell 2012-08-22 17:34:01 +10:00
parent c730d9072e
commit c35530c362
1 changed files with 10 additions and 9 deletions

View File

@ -173,20 +173,21 @@ static void calc_throttle()
// ---------------------------------------------------------------------------------------- // ----------------------------------------------------------------------------------------
static void calc_nav_yaw(float speed_scaler, float ch4_inf) static void calc_nav_yaw(float speed_scaler, float ch4_inf)
{ {
if (hold_course != -1) {
// steering on or close to ground
g.channel_rudder.servo_out = g.pidWheelSteer.get_pid(bearing_error_cd) + g.kff_rudder_mix * g.channel_roll.servo_out;
return;
}
#if APM_CONTROL == DISABLED #if APM_CONTROL == DISABLED
// always do rudder mixing from roll // always do rudder mixing from roll
g.channel_rudder.servo_out = g.kff_rudder_mix * g.channel_roll.servo_out; g.channel_rudder.servo_out = g.kff_rudder_mix * g.channel_roll.servo_out;
if (hold_course != -1) {
// steering on or close to ground
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) // a PID to coordinate the turn (drive y axis accel to zero)
Vector3f temp = imu.get_accel(); Vector3f temp = imu.get_accel();
int32_t error = -temp.y*100.0; int32_t error = -temp.y*100.0;
g.channel_rudder.servo_out += g.pidServoRudder.get_pid(error, speed_scaler); g.channel_rudder.servo_out += g.pidServoRudder.get_pid(error, speed_scaler);
}
#else // APM_CONTROL == ENABLED #else // APM_CONTROL == ENABLED
// use the new APM_Control library // use the new APM_Control library
g.channel_rudder.servo_out = g.yawController.get_servo_out(speed_scaler, ch4_inf < 0.25) + g.channel_roll.servo_out * g.kff_rudder_mix; g.channel_rudder.servo_out = g.yawController.get_servo_out(speed_scaler, ch4_inf < 0.25) + g.channel_roll.servo_out * g.kff_rudder_mix;