2010-08-28 13:07:33 -03:00
|
|
|
|
/*
|
|
|
|
|
www.ArduCopter.com - www.DIYDrones.com
|
|
|
|
|
Copyright (c) 2010. All rights reserved.
|
|
|
|
|
An Open Source Arduino based multicopter.
|
|
|
|
|
|
|
|
|
|
File : Attitude.pde
|
|
|
|
|
Version : v1.0, Aug 27, 2010
|
|
|
|
|
Author(s): ArduCopter Team
|
|
|
|
|
Ted Carancho (aeroquad), Jose Julio, Jordi Muñoz,
|
|
|
|
|
Jani Hirvinen, Ken McEwans, Roberto Navoni,
|
|
|
|
|
Sandro Benigno, Chris Anderson
|
|
|
|
|
|
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
|
|
|
|
|
|
* ************************************************************** *
|
|
|
|
|
ChangeLog:
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
* ************************************************************** *
|
|
|
|
|
TODO:
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
* ************************************************************** */
|
|
|
|
|
|
|
|
|
|
/* ************************************************************ */
|
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////
|
2010-09-13 06:07:31 -03:00
|
|
|
|
// Function : Attitude_control_v3()
|
2010-08-28 13:07:33 -03:00
|
|
|
|
//
|
|
|
|
|
// Stable flight mode main algoritms
|
|
|
|
|
//
|
|
|
|
|
// Parameters:
|
|
|
|
|
// - none
|
|
|
|
|
//
|
|
|
|
|
// Returns : - none
|
|
|
|
|
//
|
|
|
|
|
// Alters :
|
|
|
|
|
// err_roll, roll_rate
|
|
|
|
|
//
|
|
|
|
|
// Relies :
|
|
|
|
|
// Radio input, Gyro
|
|
|
|
|
//
|
|
|
|
|
|
2010-09-13 06:07:31 -03:00
|
|
|
|
/* ************************************************************ */
|
2010-08-28 13:07:33 -03:00
|
|
|
|
// STABLE MODE
|
2010-09-13 06:07:31 -03:00
|
|
|
|
// PI absolute angle control driving a P rate control
|
2010-08-28 13:07:33 -03:00
|
|
|
|
// Input : desired Roll, Pitch and Yaw absolute angles. Output : Motor commands
|
2010-10-11 11:12:44 -03:00
|
|
|
|
void Attitude_control_v3(int command_roll, int command_pitch, int command_yaw)
|
2010-08-28 13:07:33 -03:00
|
|
|
|
{
|
2010-11-09 17:38:54 -04:00
|
|
|
|
#define MAX_CONTROL_OUTPUT 250
|
2010-09-13 06:07:31 -03:00
|
|
|
|
float stable_roll,stable_pitch,stable_yaw;
|
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
|
// ROLL CONTROL
|
2010-10-11 11:12:44 -03:00
|
|
|
|
err_roll = command_roll - ToDeg(roll);
|
2010-09-13 06:07:31 -03:00
|
|
|
|
err_roll = constrain(err_roll,-25,25); // to limit max roll command...
|
|
|
|
|
|
|
|
|
|
roll_I += err_roll*G_Dt;
|
|
|
|
|
roll_I = constrain(roll_I,-20,20);
|
2010-08-28 13:07:33 -03:00
|
|
|
|
|
2010-09-13 06:07:31 -03:00
|
|
|
|
// PID absolute angle control
|
2010-10-11 11:12:44 -03:00
|
|
|
|
stable_roll = KP_QUAD_ROLL*err_roll + KI_QUAD_ROLL*roll_I;
|
2010-09-13 06:07:31 -03:00
|
|
|
|
|
|
|
|
|
// PD rate control (we use also the bias corrected gyro rates)
|
|
|
|
|
err_roll = stable_roll - ToDeg(Omega[0]); // Omega[] is the raw gyro reading plus Omega_I, so it´s bias corrected
|
|
|
|
|
control_roll = STABLE_MODE_KP_RATE_ROLL*err_roll;
|
2010-11-09 17:38:54 -04:00
|
|
|
|
control_roll = constrain(control_roll,-MAX_CONTROL_OUTPUT,MAX_CONTROL_OUTPUT);
|
2010-09-13 06:07:31 -03:00
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
|
// PITCH CONTROL
|
2010-10-11 11:12:44 -03:00
|
|
|
|
err_pitch = command_pitch - ToDeg(pitch);
|
2010-09-13 06:07:31 -03:00
|
|
|
|
err_pitch = constrain(err_pitch,-25,25); // to limit max pitch command...
|
|
|
|
|
|
|
|
|
|
pitch_I += err_pitch*G_Dt;
|
|
|
|
|
pitch_I = constrain(pitch_I,-20,20);
|
|
|
|
|
|
|
|
|
|
// PID absolute angle control
|
2010-10-11 11:12:44 -03:00
|
|
|
|
stable_pitch = KP_QUAD_PITCH*err_pitch + KI_QUAD_PITCH*pitch_I;
|
2010-09-13 06:07:31 -03:00
|
|
|
|
|
|
|
|
|
// P rate control (we use also the bias corrected gyro rates)
|
|
|
|
|
err_pitch = stable_pitch - ToDeg(Omega[1]);
|
|
|
|
|
control_pitch = STABLE_MODE_KP_RATE_PITCH*err_pitch;
|
2010-11-09 17:38:54 -04:00
|
|
|
|
control_pitch = constrain(control_pitch,-MAX_CONTROL_OUTPUT,MAX_CONTROL_OUTPUT);
|
2010-09-13 06:07:31 -03:00
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
|
// YAW CONTROL
|
2010-10-11 11:12:44 -03:00
|
|
|
|
err_yaw = command_yaw - ToDeg(yaw);
|
2010-08-28 13:07:33 -03:00
|
|
|
|
if (err_yaw > 180) // Normalize to -180,180
|
2010-09-13 06:07:31 -03:00
|
|
|
|
err_yaw -= 360;
|
2010-08-28 13:07:33 -03:00
|
|
|
|
else if(err_yaw < -180)
|
|
|
|
|
err_yaw += 360;
|
2010-09-13 06:07:31 -03:00
|
|
|
|
err_yaw = constrain(err_yaw,-60,60); // to limit max yaw command...
|
|
|
|
|
|
|
|
|
|
yaw_I += err_yaw*G_Dt;
|
|
|
|
|
yaw_I = constrain(yaw_I,-20,20);
|
|
|
|
|
|
|
|
|
|
// PID absoulte angle control
|
|
|
|
|
stable_yaw = KP_QUAD_YAW*err_yaw + KI_QUAD_YAW*yaw_I;
|
|
|
|
|
// PD rate control (we use also the bias corrected gyro rates)
|
|
|
|
|
err_yaw = stable_yaw - ToDeg(Omega[2]);
|
|
|
|
|
control_yaw = STABLE_MODE_KP_RATE_YAW*err_yaw;
|
2010-11-09 17:38:54 -04:00
|
|
|
|
control_yaw = constrain(control_yaw,-MAX_CONTROL_OUTPUT,MAX_CONTROL_OUTPUT);
|
2010-08-28 13:07:33 -03:00
|
|
|
|
}
|
|
|
|
|
|
2010-09-13 06:07:31 -03:00
|
|
|
|
// ACRO MODE
|
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////
|
|
|
|
|
// Function : Rate_control()
|
|
|
|
|
//
|
|
|
|
|
// Acro mode main algoritms
|
|
|
|
|
//
|
|
|
|
|
// Parameters:
|
|
|
|
|
// - none
|
|
|
|
|
//
|
|
|
|
|
// Returns : - none
|
|
|
|
|
//
|
|
|
|
|
// Alters :
|
|
|
|
|
// err_roll, roll_rate
|
|
|
|
|
//
|
|
|
|
|
// Relies :
|
|
|
|
|
// Radio input, Gyro
|
|
|
|
|
//
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// ACRO MODE
|
2010-09-13 06:07:31 -03:00
|
|
|
|
void Rate_control_v2()
|
2010-08-28 13:07:33 -03:00
|
|
|
|
{
|
|
|
|
|
static float previousRollRate, previousPitchRate, previousYawRate;
|
|
|
|
|
float currentRollRate, currentPitchRate, currentYawRate;
|
2010-09-13 06:07:31 -03:00
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
|
// ROLL CONTROL
|
2010-09-13 06:07:31 -03:00
|
|
|
|
currentRollRate = ToDeg(Omega[0]); // Omega[] is the raw gyro reading plus Omega_I, so it´s bias corrected
|
|
|
|
|
err_roll = ((ch_roll- roll_mid) * xmitFactor) - currentRollRate;
|
|
|
|
|
roll_I += err_roll*G_Dt;
|
|
|
|
|
roll_I = constrain(roll_I,-20,20);
|
|
|
|
|
roll_D = (currentRollRate - previousRollRate)/G_Dt;
|
|
|
|
|
previousRollRate = currentRollRate;
|
2010-08-28 13:07:33 -03:00
|
|
|
|
// PID control
|
2010-09-13 06:07:31 -03:00
|
|
|
|
control_roll = Kp_RateRoll*err_roll + Kd_RateRoll*roll_D + Ki_RateRoll*roll_I;
|
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
|
// PITCH CONTROL
|
2010-09-13 06:07:31 -03:00
|
|
|
|
currentPitchRate = ToDeg(Omega[1]); // Omega[] is the raw gyro reading plus Omega_I, so it´s bias corrected
|
2010-08-28 13:07:33 -03:00
|
|
|
|
err_pitch = ((ch_pitch - pitch_mid) * xmitFactor) - currentPitchRate;
|
2010-09-13 06:07:31 -03:00
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
|
pitch_I += err_pitch*G_Dt;
|
|
|
|
|
pitch_I = constrain(pitch_I,-20,20);
|
|
|
|
|
|
2010-09-13 06:07:31 -03:00
|
|
|
|
pitch_D = (currentPitchRate - previousPitchRate)/G_Dt;
|
2010-08-28 13:07:33 -03:00
|
|
|
|
previousPitchRate = currentPitchRate;
|
2010-09-13 06:07:31 -03:00
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
|
// PID control
|
|
|
|
|
control_pitch = Kp_RatePitch*err_pitch + Kd_RatePitch*pitch_D + Ki_RatePitch*pitch_I;
|
2010-09-13 06:07:31 -03:00
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
|
// YAW CONTROL
|
2010-09-13 06:07:31 -03:00
|
|
|
|
currentYawRate = ToDeg(Omega[2]); // Omega[] is the raw gyro reading plus Omega_I, so it´s bias corrected;
|
|
|
|
|
err_yaw = ((ch_yaw - yaw_mid)* xmitFactor) - currentYawRate;
|
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
|
yaw_I += err_yaw*G_Dt;
|
2010-09-13 06:07:31 -03:00
|
|
|
|
yaw_I = constrain(yaw_I,-20,20);
|
2010-08-28 13:07:33 -03:00
|
|
|
|
|
2010-09-13 06:07:31 -03:00
|
|
|
|
yaw_D = (currentYawRate - previousYawRate)/G_Dt;
|
2010-08-28 13:07:33 -03:00
|
|
|
|
previousYawRate = currentYawRate;
|
2010-09-13 06:07:31 -03:00
|
|
|
|
|
2010-08-28 13:07:33 -03:00
|
|
|
|
// PID control
|
|
|
|
|
control_yaw = Kp_RateYaw*err_yaw + Kd_RateYaw*yaw_D + Ki_RateYaw*yaw_I;
|
|
|
|
|
}
|
2010-10-11 10:32:23 -03:00
|
|
|
|
|