From 704a43107044f7d148d223bc39e253020b76c34a Mon Sep 17 00:00:00 2001 From: Michael Jakob Date: Mon, 26 Jan 2015 19:26:44 +0100 Subject: [PATCH 1/2] PID contoller documentation update (MultiWii23 and MultiWiiHybrid) --- docs/PID tuning.md | 18 +++++++++++++++++- src/main/config/config.c | 2 +- 2 files changed, 18 insertions(+), 2 deletions(-) diff --git a/docs/PID tuning.md b/docs/PID tuning.md index 99c770d78..2caf2c847 100644 --- a/docs/PID tuning.md +++ b/docs/PID tuning.md @@ -104,4 +104,20 @@ only the gyros. The default is 75% For example, at a setting of "100" for "sensitivity_horizon", 100% self-leveling strength will be applied at center stick, 50% self-leveling will be applied at 50% stick, and no self-leveling will be applied at 100% stick. If sensitivity is decreased to 75, 100% self-leveling will be applied at center stick, 50% will be applied at 63% -stick, and no self-leveling will be applied at 75% stick and onwards. \ No newline at end of file +stick, and no self-leveling will be applied at 75% stick and onwards. + +### PID controller 3, "MultiWii23" (default for the ALIENWIIF1 and ALIENWIIF3 targets) + +PID Controller 3 is an direct port of the PID controller from MultiWii 2.3 and later. + +The algorithm is handling roll and pitch differently to yaw. users with problems on yaw authority should try this one. + +For the ALIENWII32 targets the gyroscale is removed for even more yaw authority. This will provide best performance on very small multicopters with brushed motors. + +### PID controller 4, "MultiWiiHybrid" + +PID Controller 3 is an hybrid version of two MultiWii PID controllers. Roll and pitch is using the MultiWii 2.2 algorithm and yaw is using the 2.3 algorithm. + +This PID controller was initialy implementd for testing purposes but is also performing quite well. + +For the ALIENWII32 targets the gyroscale is removed for more yaw authority. This will provide best performance on very small multicopters with brushed motors. diff --git a/src/main/config/config.c b/src/main/config/config.c index a357a870d..c5e53d52b 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -470,7 +470,7 @@ static void resetConf(void) masterConfig.escAndServoConfig.maxthrottle = 2000; masterConfig.motor_pwm_rate = 32000; masterConfig.looptime = 2000; -// currentProfile->pidController = 3; + currentProfile->pidController = 3; currentProfile->pidProfile.P8[ROLL] = 36; currentProfile->pidProfile.P8[PITCH] = 36; currentProfile->failsafeConfig.failsafe_delay = 2; From cc65a446249a287c6cb5cc6768570046c734104f Mon Sep 17 00:00:00 2001 From: Michael Jakob Date: Mon, 26 Jan 2015 19:37:00 +0100 Subject: [PATCH 2/2] Minor documentation fix --- docs/PID tuning.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/PID tuning.md b/docs/PID tuning.md index 2caf2c847..8380bd193 100644 --- a/docs/PID tuning.md +++ b/docs/PID tuning.md @@ -116,7 +116,7 @@ For the ALIENWII32 targets the gyroscale is removed for even more yaw authority. ### PID controller 4, "MultiWiiHybrid" -PID Controller 3 is an hybrid version of two MultiWii PID controllers. Roll and pitch is using the MultiWii 2.2 algorithm and yaw is using the 2.3 algorithm. +PID Controller 4 is an hybrid version of two MultiWii PID controllers. Roll and pitch is using the MultiWii 2.2 algorithm and yaw is using the 2.3 algorithm. This PID controller was initialy implementd for testing purposes but is also performing quite well.