upped rate loop to 250hz

This commit is contained in:
Jason Short 2012-02-17 15:20:39 -08:00
parent 62b104cbfa
commit 0075901f77
2 changed files with 3 additions and 2 deletions

View File

@ -824,8 +824,8 @@ void loop()
uint32_t timer = micros(); uint32_t timer = micros();
// We want this to execute fast // We want this to execute fast
// ---------------------------- // ----------------------------
if ((timer - fast_loopTimer) >= 5000) { if ((timer - fast_loopTimer) >= 4000) {
Log_Write_Data(13, (int32_t)(timer - fast_loopTimer)); //Log_Write_Data(13, (int32_t)(timer - fast_loopTimer));
//PORTK |= B00010000; //PORTK |= B00010000;
G_Dt = (float)(timer - fast_loopTimer) / 1000000.f; // used by PI Loops G_Dt = (float)(timer - fast_loopTimer) / 1000000.f; // used by PI Loops

View File

@ -144,6 +144,7 @@
// Rate // Rate
#define CH6_RATE_KP 4 #define CH6_RATE_KP 4
#define CH6_RATE_KI 5 #define CH6_RATE_KI 5
#define CH6_RATE_KD 21
#define CH6_YAW_RATE_KP 6 #define CH6_YAW_RATE_KP 6
// Altitude rate controller // Altitude rate controller
#define CH6_THROTTLE_KP 7 #define CH6_THROTTLE_KP 7