You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
176 lines
5.5 KiB
176 lines
5.5 KiB
/* |
|
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: |
|
|
|
|
|
* ************************************************************** */ |
|
|
|
/* ************************************************************ */ |
|
|
|
////////////////////////////////////////////////// |
|
// Function : Attitude_control_v3() |
|
// |
|
// Stable flight mode main algoritms |
|
// |
|
// Parameters: |
|
// - none |
|
// |
|
// Returns : - none |
|
// |
|
// Alters : |
|
// err_roll, roll_rate |
|
// |
|
// Relies : |
|
// Radio input, Gyro |
|
// |
|
|
|
/* ************************************************************ */ |
|
// STABLE MODE |
|
// PI absolute angle control driving a P rate control |
|
// Input : desired Roll, Pitch and Yaw absolute angles. Output : Motor commands |
|
void Attitude_control_v3(int command_roll, int command_pitch, int command_yaw) |
|
{ |
|
#define MAX_CONTROL_OUTPUT 250 |
|
float stable_roll,stable_pitch,stable_yaw; |
|
|
|
// ROLL CONTROL |
|
err_roll = command_roll - ToDeg(roll); |
|
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); |
|
|
|
// PID absolute angle control |
|
stable_roll = KP_QUAD_ROLL*err_roll + KI_QUAD_ROLL*roll_I; |
|
|
|
// 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; |
|
control_roll = constrain(control_roll,-MAX_CONTROL_OUTPUT,MAX_CONTROL_OUTPUT); |
|
|
|
// PITCH CONTROL |
|
err_pitch = command_pitch - ToDeg(pitch); |
|
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 |
|
stable_pitch = KP_QUAD_PITCH*err_pitch + KI_QUAD_PITCH*pitch_I; |
|
|
|
// 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; |
|
control_pitch = constrain(control_pitch,-MAX_CONTROL_OUTPUT,MAX_CONTROL_OUTPUT); |
|
|
|
// YAW CONTROL |
|
err_yaw = command_yaw - ToDeg(yaw); |
|
if (err_yaw > 180) // Normalize to -180,180 |
|
err_yaw -= 360; |
|
else if(err_yaw < -180) |
|
err_yaw += 360; |
|
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; |
|
control_yaw = constrain(control_yaw,-MAX_CONTROL_OUTPUT,MAX_CONTROL_OUTPUT); |
|
} |
|
|
|
// ACRO MODE |
|
|
|
|
|
////////////////////////////////////////////////// |
|
// Function : Rate_control() |
|
// |
|
// Acro mode main algoritms |
|
// |
|
// Parameters: |
|
// - none |
|
// |
|
// Returns : - none |
|
// |
|
// Alters : |
|
// err_roll, roll_rate |
|
// |
|
// Relies : |
|
// Radio input, Gyro |
|
// |
|
|
|
|
|
// ACRO MODE |
|
void Rate_control_v2() |
|
{ |
|
static float previousRollRate, previousPitchRate, previousYawRate; |
|
float currentRollRate, currentPitchRate, currentYawRate; |
|
|
|
// ROLL CONTROL |
|
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; |
|
// PID control |
|
control_roll = Kp_RateRoll*err_roll + Kd_RateRoll*roll_D + Ki_RateRoll*roll_I; |
|
|
|
// PITCH CONTROL |
|
currentPitchRate = ToDeg(Omega[1]); // Omega[] is the raw gyro reading plus Omega_I, so it´s bias corrected |
|
err_pitch = ((ch_pitch - pitch_mid) * xmitFactor) - currentPitchRate; |
|
|
|
pitch_I += err_pitch*G_Dt; |
|
pitch_I = constrain(pitch_I,-20,20); |
|
|
|
pitch_D = (currentPitchRate - previousPitchRate)/G_Dt; |
|
previousPitchRate = currentPitchRate; |
|
|
|
// PID control |
|
control_pitch = Kp_RatePitch*err_pitch + Kd_RatePitch*pitch_D + Ki_RatePitch*pitch_I; |
|
|
|
// YAW CONTROL |
|
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; |
|
|
|
yaw_I += err_yaw*G_Dt; |
|
yaw_I = constrain(yaw_I,-20,20); |
|
|
|
yaw_D = (currentYawRate - previousYawRate)/G_Dt; |
|
previousYawRate = currentYawRate; |
|
|
|
// PID control |
|
control_yaw = Kp_RateYaw*err_yaw + Kd_RateYaw*yaw_D + Ki_RateYaw*yaw_I; |
|
} |
|
|
|
|