mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
upped rate loop to 250hz
This commit is contained in:
parent
62b104cbfa
commit
0075901f77
@ -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
|
||||||
|
@ -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
|
||||||
|
Loading…
Reference in New Issue
Block a user