V2.2 - ACRO PID implementation is wrong, right?

This forum is dedicated to software development related to MultiWii.
It is not the right place to submit a setup problem.
Software download
alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

Hello!
Here's my schematic (sorry for that - made in hurry) of current PID implementation for ACRO mode. Red - variables names.
Новый рисунок (9).gif

1. comment says, that it takes into account the cycle time, but in fact, there's no such thing.
2. why there is 32-bit division?

Code: Select all

else error = ((int32_t)rcCommand[axis]<<6)/conf.P8[axis]
why not replace with multiplication on constant and precalculate it on startup and P8 change?
3. Why P8 is added to I component? also, see 4.
4. P8 for I component and P8dyn for P are in the feedback part of the loop, not the forward part. This means, that changing these variables would not only change the open loop gain, but would also alter the total system amplification (in this case - gyro scaling). I can't bear the fact, that when I increase P in GUI, the rate to stick position scaling is decreased. Is that done intentionally? I don't feel like it's a good thing.
5. When dynamic P adjustment takes place (P8dyn is decreased) the scaling for P and I component becomes different - they start to try maintaining the different rate values. I don't think that it helps. Initial idea was to change not the open loop gain (as well as I and D), but just change the scaling corresponding to the throttle, right?
6.

Code: Select all

if (abs(gyroData[axis])>640) errorGyroI[axis] = 0;
This not only shuts off the I component when rate exceeds some value, but also zeroes the accumulated I value. Why?
7. D component doesn't take into account stick position at all. That's why it doesn't make the control sharper - it just tries to dampen fast angle changes of the body, and that's it.
I'm currently testing the rewritten version, where classic PID controller is implemented - P I and D are in the forward part of the loop, so no scaling problem present and other, supposedly, problems are fixed. But first I would like to hear the opinion, do I get it all right, or some/all of listed facts serve the useful purpose?

P.S. Forgot to say - "deltasum" includes difference calculation, moving average of 3 elements that code does and multiplication by dynD8

EmmeDi8
Posts: 18
Joined: Thu Sep 06, 2012 5:15 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by EmmeDi8 »

Hi,
in this days I play with PID controller too.
IMO acro PID is not wrong is only super optimized for fast execution.
Reading the code is easy to see various method to save byte (cast to 32 bit only where is needed) and cpu time, such as lsb (<<) or rsb(>>) instead of regular multiply or division.
Maybe there is other margin, but is very hard optimize further. I try to reply to your question and I'm not an engineer, so have patience if the answers are not precise.

1. comment says, that it takes into account the cycle time, but in fact, there's no such thing.


Yes, I think consider cycle time is the optimum. But, maybe Alex have place on the balance CPU vs RESULT, and maybe more complex software can have too long cycle time.

2. why there is 32-bit division?

rcCommand can be 500 then * 64 = 32000 at max.
However, precalculate imo is good idea.

6. This not only shuts off the I component when rate exceeds some value, but also zeroes the accumulated I value. Why?

I term after some time, can drift to the max value. Any little error is always sum to the I term. Maybe on large movement this must be cleared.

7. D component doesn't take into account stick position at all

D term is at the end of the function, is not calculated into account of stick position, but by the velocity of error changes.

The next my experiments is on "I" term. The idea is copy/past "angle mode" code to "horzion mode" without "I" sum.
So I would try to hover in angle mode and when quadcopter is stable, switch to horizon mode. I'm expect to see less drift.

When available if you can share your code I can test with my little multirotor.
Last edited by EmmeDi8 on Mon Jun 10, 2013 11:03 pm, edited 1 time in total.

chris_kmn
Posts: 31
Joined: Sun Jun 09, 2013 11:11 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by chris_kmn »

I'm also a friend of a good control loop integration and would love to test the result too with my test'o'copter :)

There is something like a demo application for a PID controller at the atmel.com site. Maybe that could give some hints.

And here is another example:

https://code.oregonstate.edu/svn/appliedrobotics/ExampleCode/pid_demo/pid.c
Attachments
image.jpg

User avatar
shikra
Posts: 783
Joined: Wed Mar 30, 2011 7:58 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by shikra »

Starting point - MultiWii ACRO is already considered one of the best if not the best performance in acro. (when tuned). Good luck to improve!

1 - true - intention is to run with fastest loop time possible. I think that is what words mean. There is option to run fixed loop time I think - or maybe that is baseflight port.

2 - as above!

3 Where is this? I am not clear here.

4 Yes, but does it matter in flight - can you notice?

5 - intentional - default is 0 throttle compensation. PID rates reduce from mid throttle to full throttle to compensate for the motors generating proportionally more power to change. It does help reduce wobble full throttle in acro. I use it and it helps. I think what concerns you does not matter in real flight. Multiwii is based on many approximations that perfect theory is not noticeable to us human flyers. Maybe Warthox can tell!

6 - assumption is high value means fast angular change. Hence I is not needed - and too slow to give good input. I is more to help maintain / force to desired position if not reaching quickly.

7 - indirectly it does. more stick input=larger error angle = stronger force to return = faster attitude change=larger D.
I think there is potential here. Fast ACRO fliers may want a large D value only when fast angular change only approaching 0 error angle. For very fast, sharp snappy control. I posted a level mode variant of that a whole back. It was very effective. I'd like to revisit to get it added one day.

alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

Is it your personal experience, about best performance? What boards did you compare it to? I compared to KK2.0 board and was disappointed. I love multiwii and really want it to be the best, that's why I started this thread. A little disclaimer - I don't want to make someone's work look less valuable, but I feel that I can help improve something.
2. - division is the slowest thing EVER (float math not included). How, in your opinion, does it help to improve processing time?
1. The main loop is processed for different time (sometimes there is a GPS package to process, sometimes there isn't, for example). Thus, D difference ('delta' variable) coresponds to different dt and would be different each time, resulting in different D component each time. That's why, I suppose, moving average was introduced for D. Hardware multiplication needed for different dt correction takes only 2 cycles for 8 bit - 0.125 uS. 1 or 2 microsecond - is this such a horrible sacrifice? I suspect correction would help to remove moving average or make if of 2 points, not 3 - that would result in comparable performance. Also, fixing point 2 of the discussion (removing division) would instantly improve overall performance. Second impact of uncompensated loop processing time is on I. It is not sensible to jitter. But, different builds would have different average loop processing time (GPS on and off, for example), so I component would accumulate with different speed, resulting in different meaning for I value in each build. This effect might be acceptable.
3. it's to the left of sum block for I on my diagram.
4. Yes, and I didn't like that so much. First, I flied with 5ah battery - quad flied long, but was heavy. I swapped to 2200 and retuned PIDs. Stick scaling changed. Not good feel at all. Nothing of the sort happened on my KK2.0 - retune, feel the same.
Point 5 and 6 takes start from misunderstanding the PID control, sorry if that's a bit rude. The formula for calculating the closed loop gain (not inside the loop like open loop gain, but from input to output) is ForwardGain/(1+ForwardGain*FeedbackGain). In current version, forward gain is not adjusted, but the FeedbackGain is changed - it is reduced. Substitute to the formula and you'll see, that overall gain from sticks to quad angle rate is increased - that was the idea, and actually, this is the same, as simple expo curve, which also increases scaling in extreme positions. At the same time, the precision of the closed loop is decreased (it is proportional to open loop gain) and that's a bad thing. Nonlinear control systems utilize quite opposite approach - increase gain when the error is big to make system move toward the desired point faster and decrease it when system arrives to desired point to prevent oscillations. I tried this approach in my PhD dissertation (resonant mode power supply was controlled, but whatever) and it worked excellent! A little diclaimer here - dissertation was mostly in power electronics, not control systems, so I do not claim myself to be a guru of control systems, even though I have a great experience in them.
Same for I. Imagine the system, where the motors, ESCs are slow and start to introduce the dynamical influence early - this multirotor would be stable on very low P. I gain though can still be raised relatively high. When you move the stick, first, some force is applied because of P, then I is accumulated and applies some force as well. Rate is increased, until this condition (to shut off the I) is met. So, what's the point? Imo if it works as I described, nothing except great error would happen. Yes, in some systems, I component would slow down the response. But, once again, gain increasing approach is so much better - just increase the I gain (before integrator - to help it accumulate faster) when error is too big - problem solved. To limit I influence there's classic Imax value, why not use?
7. wrong. more stick input=larger angle rate (not error - I remind that stick position is not taken into account in current implementation) = stronger system opposes to such a change - no matter, whether the angle change is introduced from outside (D does a good thing) or is it from stick change (current D implementation opposes this one). And last statement about big P only when error is small - it's only because of current, let's say self-scaling, implementation. If I think right, classic implementation (especially with non-linear additions) would be much better.

Also, do anyone have a video confirming this high-power instability everybody talking about? Quad wobbles during making a loop (sticks on extreme), are you sure? From control systems theory that's not logical - motors loose efficiency when approaching to the maximum speed, which would result in open loop gain reduction and increment in stability. I'm not 100% sure, because propellers have their own nonlinearity, which is not quite obvious to me. Anyway, my multirotors if wobble, do that noticeably only during hover.

User avatar
Hamburger
Posts: 2578
Joined: Tue Mar 01, 2011 2:14 pm
Location: air
Contact:

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by Hamburger »

interesting. The best way to tell would be to have an alternate second implementation. As the code section is relatively small and contained, it should be easy enough to swap it for testing or even keep it in parallel.
AlexK, are you going to implement your alternate pid handling? If you provide a unified diff, I will test fly it, promise.

alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

Oh wow, thanks! I've made the alternative implementation, including nonlinear I adjustment (the most simple single-step increment for now). Didn't have enough time yesterday evening to even pick all the divisions in code so, that gains (ACRO: P, I and D) more or less correspond to current (v2.2) values - it was so hard for me to discover the ranges/scales of the signals (especially the gyro), that I decided to just pick all from practical experiment. Hope to finish today evening and then I would post the code here.

User avatar
alll
Posts: 220
Joined: Fri Dec 07, 2012 9:53 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alll »

Since I and D are time driven, it is very important that they are precisely called at regular intervals!
http://www.pidstop.com/index.php?r_id=999
If we could have this “behavior” for all PID implementations of multiwii (knowing what the error and reference are for each pid control) it would be wonderful:

And as said before, no need of physical values are needed, just increasing/decreasing P, I and D would be enough in the gui (0..100%), the code should do the conversion math and deal with the physical sensor data units / ranges. (my whish list ;)

User avatar
shikra
Posts: 783
Joined: Wed Mar 30, 2011 7:58 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by shikra »

Best performance board - views will be biased here...! I think its what is best for you that is important.

I use KK, MultiWii, Baseflight and Openpilot. I have flown others too. I will not say multiwii is the best.... I think they are all pretty close when set up. I think KK is sharpest, but for my style that is not the best. I think for some it would be. I just prefer slightly softer Wii. When set up correctly they are all excellent.

Great to have you on board and hope to see some results from testing. If I get chance I'll try some out. The challenge is when you see Warthox flying - how to make something better than he can demonstrate the Wii is capable!!

1 - yes - it is what it is. I could be wrong, but I recall in IMU there may be averaging of last 2 readings - might be worth checking. And yes - individual tuning for perfection. In practice I haven't really notice much difference when enabling / disabling features. Maybe the loops are still so fast that the overall averages are enough for humans...

2 - agree, it doesn't help. I have wondered about the multiple divisions / multipliers to get to end result.

3 - OK - I was looking at code. Could not see diagram on PC. Will take a look.

4 - OK - I don't vary batteries so maybe not see this

5+6 very rude! LOl ;) I do agree with you on the non linear element. However bear in mind that for practical flying, sometimes it is not best to have fast instantaneous change. that is why the D component in level PID was introduced - to provide a more controlled return to position accross the range. But we are talking ACRO here - so I am with you...

7 -OK - I understand what you say - I agree it does not affect D value - I was thinking of the impact of D value - this is how I was mentored for PID tuning. I care only for impact analysis - the effect of D is larger for larger error angles by inference of faster angular change. Importantly, I agree on end result as you put it - simply dampens fast angular changes. !

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by Alexinparis »

Hi,

Let’s focus first in the ACRO mode for understanding.
The scheme is mainly correct.

a small code could be:

Code: Select all

PTerm = rcCommand – gyroData* dynPcoef / 2^6

error = rcCommand * 2^6 / Pcoef – gyroData
errorI += error
If(gyroData>limit) errorI = 0
ITerm = (errorI / 2^7 * Icoef) / 2^6

DTerm = sum_last_3_delta(gyroData) * dynDcoef / 2^5

PID = P+I-D



1) comment says, that it takes into account the cycle time, but in fact, there's no such thing.


Where did you see this comment ?
I believe an accurate cycle time is very important for integration of gyro to get an accurate angle (in IMU part).
The theory says: it’s needed for I and D term, but I don’t believe it makes a lot of differences for ACRO PID.

2. why there is 32-bit division?

To minimize cycle time when possible (8bit computation vs 32bit)

why not replace with multiplication on constant and precalculate it on startup and P8 change?

Right,
There is still room for cycle time reduction here.
I expected a full fixed point algorithm, and a float * is probably faster here.


3. Why P8 is added to I component? also, see 4.


The theory:
error = command – measure
P = Pcoef * error

Here:
command = rcCommand/Pcoef
measure = gyroData / 2^6
error = rcCommand/Pcoef - gyroData / 2^6
=> P = rcCommand – gyroData* Pcoef / 2^6

The theory:
errorI = errorI + error*dT

Here:
errorI = errorI +error (no variable dT)
windup limit on errorI
I = errorI * Icoef

4. P8 for I component and P8dyn for P are in the feedback part of the loop, not the forward part. This means, that changing these variables would not only change the open loop gain, but would also alter the total system amplification (in this case - gyro scaling). I can't bear the fact, that when I increase P in GUI, the rate to stick position scaling is decreased. Is that done intentionally? I don't feel like it's a good thing.

Basically, I follow the PID scheme defined here:
http://en.wikipedia.org/wiki/PID_controller

What is surprising and introduces confusion is maybe command = rcCommand/Pcoef
I agree it could be changed for a constant stick feeling whatever the settings.

5. When dynamic P adjustment takes place (P8dyn is decreased) the scaling for P and I component becomes different - they start to try maintaining the different rate values. I don't think that it helps. Initial idea was to change not the open loop gain (as well as I and D), but just change the scaling corresponding to the throttle, right?

The basic idea behind dynP&dynD is to decrease the PID and sensor influence when huge command is required to tend toward PID = rcCommand. There is no math model behind, just empirical tests.
Iterm is not affected because:
/ Pcoef could lead to division by zero
Iterm is zeroed in case of huge command
Iterm impact is anyway limited regarding its weight in P I D

6 This not only shuts off the I component when rate exceeds some value, but also zeroes the accumulated I value. Why?

The I term is important in static position mainly to counter drift. It is useless in case of huge rotation rate.
The accumulated I is zeroed in order to “memorize” the position where quick stick stop order is required. With a remaining accumulatedI, I think there would be a small drift after each sudden rate deceleration.

7. D component doesn't take into account stick position at all. That's why it doesn't make the control sharper - it just tries to dampen fast angle changes of the body, and that's it.

Theory:
D = (error - previous_error)/dT

Here:
we estimate the command term of error in negligible in this equation.
See:
http://en.wikipedia.org/wiki/PID_controller
“In most commercial control systems, derivative action is based on PV rather than error.”
=> D = (measure – previous_measure) * Dcoef (no variable dT)
+ a little averaging over it

alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

Ok, let me make my point clear. Drawbacks of current version:
First and IMO the main - sticks scaling change when PIDs are adjusted. Do everyone agree? All the other mini-drawbacks I find insignificant and I wouldn't start my implementation if this issue wasn't present.
2.
Theory: D = (error - previous_error)/dT

Totally agree! But in current (v2.2) code, the D term is calculated not from error, like it should, but from gyro alone. Let me cite the code to ensure proper understanding:
delta = gyroData[axis] - lastGyro[axis]; // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800
lastGyro[axis] = gyroData[axis];
deltaSum = delta1[axis]+delta2[axis]+delta;
delta2[axis] = delta1[axis];
delta1[axis] = delta;

DTerm = ((int32_t)deltaSum*dynD8[axis])>>5; // 32 bits is needed for calculation

I hope now it's obvious (let me focus the issue once again), that there's no rcCommand variable in D calculation at all, so D is calculated only based on gyro output and tries to dampen ANY changes of angle rates, including these induced by moving the sticks.
it should look like this:

Code: Select all

delta          = error - lastError[axis];
    lastError[axis] = error;

3. I agree, that I control alone may introduce overshoot. But combined with limiting the I value (it is already present in code! but to some unadjustable 16000 values) and presence of P and D this would be insignificant. I component really helps in extreme controls on bad quads like one of my multirotors - the P just can not be set high enough to have good control. I agree - for good systems where influence of ESCs, motors etc are far on the high frequencies this doesn't matter, but these systems fly well with almost any control - I think that main focus should be on making the bad frames fly as good.
4. I hope everyone agree, that current implementation has RATE impacts the stick scaling and that's why the control seem more sharp when RATE is increased?
Last remark. To increase the quality of control, we should provide as small error as possible. Current approach with reducing the gain doesn't look good, IMO. I don't think, that it significantly impacts anything though.

I've tested my implementation. P and I work really well, also I don't see any overshoot even without limiting I value at all. There's no obvious improvement over current version (which was obvious from the beginning), but now I'm really comfortable with swapping the battery and retuning - all the sticks scaling is still the same. D needs tweaking still. Nonlinear control didn't have a good test yet. Also, I've found plenty of scientific articles on multirotor advanced control algorithms (who could think that these are being made at all!). Trying to figure out what can be applied to ACRO mode. Most of them are on navigation, but that's another topic.

Phil S.
Posts: 32
Joined: Fri Apr 26, 2013 7:59 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by Phil S. »

shikra wrote:MultiWii ACRO is already considered one of the best if not the best performance in acro. (when tuned).

Don´t know who considers! I usually fly CCP helicopters (not too well, but a bit of that Parkinson like 3D stuff) and agree to what Alex (Khoroshko) said. Even a 15.-$ HobbyKing copy of a KK5.5 FC performs a lot better flying acro.

I spent hours on tuning my quads using MultiWii and MegapirateNG on AIOPs and Arducopter on a APM 2.5. Ardu tuning is a lot easier by using CH6 of the radio, modifying one parameter in flight and immediately getting the response of what this parameter changes. So IMO in matters of acro flying Ardupilot (or MegapirateNG) performs a bit better than MultiWii apart from not flipping or flying loops over pitch axis. But in the end I always switched back to a cheap piezo FC on my fun copter (Gaui 500X) to get the real feeling of control. Using MW or AP or MP, there is always someone else steering my quad!

I opened a thread in this forum some weeks ago. I had (and still have) the problem that I cannot get sufficient yaw rates with MultiWii. (With MP on the same board and with an APM or a piezo FC on the same copter I can!) I hope I understood correctly what Alex said in terms of stick scaling and turning rates, but from a pilots point of view ist seems quite strange to me as well that I have to reduce Ps and Ds (permanently by lowering the values or relative to stick travel by using RATE) to increase turning rates, sacrificing stabilitiy in manuevers they obviously need it more than just hovering around. As far as yaw ist concerned it simpy just doesn´t work this way!

scrat
Posts: 925
Joined: Mon Oct 15, 2012 9:47 am
Location: Slovenia

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by scrat »

Phil S. wrote:
shikra wrote:MultiWii ACRO is already considered one of the best if not the best performance in acro. (when tuned).

Don´t know who considers! I usually fly CCP helicopters (not too well, but a bit of that Parkinson like 3D stuff) and agree to what Alex (Khoroshko) said. Even a 15.-$ HobbyKing copy of a KK5.5 FC performs a lot better flying acro.

I spent hours on tuning my quads using MultiWii and MegapirateNG on AIOPs and Arducopter on a APM 2.5. Ardu tuning is a lot easier by using CH6 of the radio, modifying one parameter in flight and immediately getting the response of what this parameter changes. So IMO in matters of acro flying Ardupilot (or MegapirateNG) performs a bit better than MultiWii apart from not flipping or flying loops over pitch axis. But in the end I always switched back to a cheap piezo FC on my fun copter (Gaui 500X) to get the real feeling of control. Using MW or AP or MP, there is always someone else steering my quad!

I opened a thread in this forum some weeks ago. I had (and still have) the problem that I cannot get sufficient yaw rates with MultiWii. (With MP on the same board and with an APM or a piezo FC on the same copter I can!) I hope I understood correctly what Alex said in terms of stick scaling and turning rates, but from a pilots point of view ist seems quite strange to me as well that I have to reduce Ps and Ds (permanently by lowering the values or relative to stick travel by using RATE) to increase turning rates, sacrificing stabilitiy in manuevers they obviously need it more than just hovering around. As far as yaw ist concerned it simpy just doesn´t work this way!


Set in EEPROM.ino and you'll double stick rates--I have a lot more response now and I'm using P 7.0 I 56 and D 68 for pitch and roll. But Yaw is still very slow.

for(i=0;i<6;i++) {
lookupPitchRollRC[i] = 2* (2500+conf.rcExpo8*(i*i-25))*i*(int32_t)conf.rcRate8/2500;

Phil S.
Posts: 32
Joined: Fri Apr 26, 2013 7:59 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by Phil S. »

Response on roll and pitch is not the issue. yaw is.

With MultiWii roll and pitch always feels kind of flying in gusty winds although conditions are perfectly calm. There is not that kind of clear reaction as with KK5.5 or similar simple FCs, rolling or pitching if you steer and no movement at all when sticks are centered. You get certainly used to that MultiWii style after a while, but when you switch back to piezo you instantly know how real control feels like!

Another issue is:
I am a pilot, I do not want to dig into codes, GUI has to solve my problems!

scrat
Posts: 925
Joined: Mon Oct 15, 2012 9:47 am
Location: Slovenia

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by scrat »

I have kk blackboard 5.5 and hk kk green board v2.1 and KK2.0 and I know what are you saying. But I'm telling you how to increase stick response and you will get instant response from mwii like kk boards. And I know that Yaw is an issue.

If you're just a pilot...then mwii is not for you.

alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

Guys, wait, don't panic!
Here's my firmware with totally rewritten PIDs.
Changes:
-The sticks scaling is no more affected by PID coefficients. Rates (to the right of the PIDs in GUI) now work as stick scaling. Default is zero (minor response) to 1.00 (totally insane scaling).
-D term revised (based on error now). Both D and I are CycleTime corrected. I has WindUp protection, independent from I coefficient.
-Nonlinear control is there, but commented out. Worked relatively well for my bad quad, but has very significant drawback - wrong tuning can lead to fatal oscillation when applying extreme sticks. Some really hard work should be done to make this control good and safe for everyone.
-Angle and Horizon modes use ACRO PID for control now. Their implementation became MUCH shorter. Because of that, level mode is controlled only by P coefficient (no I needed because the system is integrating by itself).
-I've changed the horizon mode, sorry. Before, it was just level mode with acro addition at extreme sticks. I changed the concept (because I have no idea, where can old horizon mode used - addition of ACRO only allows for flips, but they are better flown acro mode). Now it is done another way - it's acro, but slowly drifts toward horizontal position. This concept doesn't change any extreme piloting stuff making at the same time hovering easier. This is how I like it for FPV - I don't have to hold the stick all the way forward like in angle mode, but it's much easier to hover. The speed of drift towards horizontal position is determined by I coefficient of level mode
-All top-level modes like horizon, level, GPS etc don't change with stick scaling (they are connected to PID after scaling) so nothing needs adjusting when changing the scaling.

I changed the default values to the ones from my config. Just reset the settings and you'll see them.
WARNING! I've tested only the ACRO PID well. Level and horizon work, but I didn't test them in all possible ways. I had no chance to test the other modes at all, though they should work. Do not consider this sketch a ready to fly version! Test it, and do it very VERY carefully.
Attachments
multiwii alex.khoroshko edited.zip
(138.13 KiB) Downloaded 1576 times
Last edited by alex.khoroshko on Fri Jun 14, 2013 2:42 pm, edited 1 time in total.

timecop
Posts: 1880
Joined: Fri Sep 02, 2011 4:48 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by timecop »

Here's a diff, for those who would prefer to see what was actually changed
Attachments
alex.zip
(5.88 KiB) Downloaded 1228 times

alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

Oh wow, how did you do that? :)

Phil S.
Posts: 32
Joined: Fri Apr 26, 2013 7:59 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by Phil S. »

scrat wrote:If you're just a pilot...then mwii is not for you.

That´s been a bit of exaggeration. Wouldn´t be to much of a problem modifying code as you described but i am not too keen on it! On the other hand it seems to me that some of the guys programming MultiWii are good in writing code but not too keen on flying!

Guys like you and Alex doing both (at higher levels) appear to be a minority group.

Alex, did you rewrite PIDs for all three axes or just for roll and pitch?

alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

All. Yaw is totally insane (very sensitive) at full rate setting. I can not guarantee that the code is safe in all aspects (more testing needed) but it would fit your needs. If you can bear some risk, it would be great if you help testing.

Phil S.
Posts: 32
Joined: Fri Apr 26, 2013 7:59 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by Phil S. »

I will definitely try. Weather forecast ist not bad so there could be something to tell tomorrow!

Is your modification based on 2.2 final or on any dev? Which Conf resp. WinGUI version is required?

What about the problem with gyro scaling (klick) that disturbs selflevelling when you switch from acro to angle immediately after flying some flips?

Edit:
Modified my IMU as proposed by Plüschi, and this worked perfectly so far. Do you see any conflict with your code?
By the way and answering my first question, as this part of your code is identical to 2.2 final, you obviously did not work on a dev!

alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

Oh wow, it's not a release at all - just applied my ideas to see whether they are good.
What's with gyro scaling? I mean, I saw the thread, but what kind of disturbance are you talking about? If the quad is not horizontal when you turn level mode on, it moves towards stick-defined angle as fast as it can. I was unable to find any other inconsistencies in switching modes. I had no chance to try flips though, because I fly on small road near home among the power lines (that's why I couldn't test GPS as well).

Phil S.
Posts: 32
Joined: Fri Apr 26, 2013 7:59 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by Phil S. »

As I said before, Iam a user/pilot, so I can tell about setup and flying, not what particular line in the code is responsible for doing this or that.

First thing, you cannot setup MW 2.2 with MWConfig 2.1, even each dev version has its own Config or WinGUI. So as far as I understood you have too look for compatibility between firmware version and configuration software.

Second thing, when you fly lets say five, six loops in a row with 2.2, ACC looses orientation and it takes some time before it knows again what is up and down and horizontal. Switching back to angle or horizon immediately after flipping brings up unpredictable orientation of the craft, means it flips over, ends up nose down or anywhere else far from expected levelling.
My primitive understanding of the problem is that ACC has to count exactly 360 degrees for each flip to function properly, but because of this failure it counts lets say 344 or 412! Plüschis mod teached it counting correctly and from my practical point of view it does now. Did not try more than 20 or 30 flips but it is working until there.

BarneyG
Posts: 39
Joined: Tue May 07, 2013 4:42 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by BarneyG »

Alex ... any reason why you've changed the #define I2C_SPEED 400000L to #define I2C_SPEED 100000L for the Crius AIOP v1 definitions ?

chris_kmn
Posts: 31
Joined: Sun Jun 09, 2013 11:11 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by chris_kmn »

I just came back from first flight.

My first try with the new firmware was based on my original PID and scaling settings.It was almost not flyable. Insane rates and tending to oscillating. also the horizon/level was almost not working bebause I used to fly little I - values.
So for those guy who are used to "horizon-flying" you have to have higher I values in level settings.

I'll try to adapt my settings now and do some more flights.

By the way, is there any reason why the "old" version 2.20 and not 2.21 was used ?

alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

Alex ... any reason why you've changed the #define I2C_SPEED 400000L to #define I2C_SPEED 100000L for the Crius AIOP v1 definitions ?

The reason was the I2C errors I was getting - it has gone away when I've washed the board with alcohol, but I forgot to change all back (I know, I should have to). Sorry - I didn't care much because it won't be used anywhere (except for testing here).
By the way, is there any reason why the "old" version 2.20 and not 2.21 was used ?

I've downloaded it some time ago and didn't check the latest version in the repository. There's no reason for that.
It was almost not flyable

Yes, the scaling for all coefficients changed, I tried to keep them close to the original though (except for scaling, which was IMO way too low). I changed horizon mode completely, as well as both acc-based modes have another PID organization (they don't have their own pid, they confrol ACRO pid). You can save your settings via GUI and then reset the settings to defaults. I've set default values into what was good for me (except for rates, which are set to zero), it may be the good point to start.

chris_kmn
Posts: 31
Joined: Sun Jun 09, 2013 11:11 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by chris_kmn »

could you post something like a sketch of the control loop just to understand where the parameters act in what way ? that would be great and helpful to trim.

so far you did a great job !!!

chris_kmn
Posts: 31
Joined: Sun Jun 09, 2013 11:11 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by chris_kmn »

ok, I tested it with your proposed values with a good result. With the "rate" values at 0 it is absolt controlable and it's a good base to start with. But what I might not like is the horizon performance. It is really coming back to level very slowly. So for FPV it could be an issue.

Unfortunately it's very stormy here today. But I am really astonished how stable my copter is even in strong blasts ! And mine is a lightweight of only 340 grams.

crazyal
Posts: 84
Joined: Tue Sep 04, 2012 11:25 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by crazyal »

alex.khoroshko wrote:Oh wow, how did you do that? :)

In case you haven't found out how to create a patch allready.
It's really easy with tortoise svn on windows: http://tortoisesvn.net/docs/release/Tor ... patch.html
I like your new pid implementation, if I manage to fix my copter I'll probably try it next week.

alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

could you post something like a sketch of the control loop

Yes, would be done! I'm in progress of drawing the full diagram including maximum variables values etc (I like well documented projects). Would post ASAP.
So for FPV it could be an issue

You can try to increase the I gain in level settings - in my implementation it controls the horizon return rate. When this coefficient is set really high it should feel more or less alike the old horizon, though unlike the old implementation, it would try to level in extreme sticks as well. I think I should fix that (centered - goes towards horizontal position with the set rate, extreme sticks - pure ACRO). The thing is - I like horizon to help just a bit, not be the level mode at sticks centered, so I didn't think it would be needed. It would be cool to make horizon mode fit everyone's vision of it by just changing the single coefficient value.
I would be glad to hear your thoughts on horizon, what in your opinion should it be.
So, current conclusion:
1. Rates are way too high? I used it at around 0.50 value (I like sharp control). I doubt someone would need it higher, so I can scale it down.
2. autolevel shut-off at extreme sticks needed (in form of mixing - the more sticks inclination, the less autolevel).
It's really easy with tortoise svn on windows

Thank you, I'm currently reading up on SVN concept (I worked as an embedded system developer, but I was the only one code writer).

chris_kmn
Posts: 31
Joined: Sun Jun 09, 2013 11:11 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by chris_kmn »

alex.khoroshko wrote:Yes, would be done! I'm in progress of drawing the full diagram including maximum variables values etc (I like well documented projects). Would post ASAP.

Thanks for your support on this !

The thing is - I like horizon to help just a bit, not be the level mode at sticks centered, so I didn't think it would be needed. It would be cool to make horizon mode fit everyone's vision of it by just changing the single coefficient value.
I would be glad to hear your thoughts on horizon, what in your opinion should it be.


I agree that it's a good way to not having too much level for nice acro flying. I also don't like to allways counteract against level with the sticks. Maybe a deadband or so could be nice to disable level when sticks are out of center. but in that case you have to hold the value of the integrator cause it would wind up and if sticks then come back to center it is just too big.

1. Rates are way too high? I used it at around 0.50 value (I like sharp control). I doubt someone would need it higher, so I can scale it down.


I think downscaling of about 20 to 50% would be good.

2. autolevel shut-off at extreme sticks needed (in form of mixing - the more sticks inclination, the less autolevel).


I think mixing could be an issue cause the integrator could wind up and work against stick input. Maybe a small deadband could be better and then higher I-values or even I and P

Again thanks a lot for that nice contribution ! :-)

chris_kmn
Posts: 31
Joined: Sun Jun 09, 2013 11:11 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by chris_kmn »

Some flights later.....

I increased the I value up to 1 and still almost no leveling in horizon mode. How high can/should I set the I value ?

Yaw is in my opinion to hard. Due to the high rev differences between the props the whole copter is getting instable. Maybe the yaw should be scaled down more than the roll/nick scaling. I used 0.4 for yaw rate and it still was very hard.

BarneyG
Posts: 39
Joined: Tue May 07, 2013 4:42 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by BarneyG »

I just added this into my code along with the Gyro Scaling changes. Unfortunately I'd also removed the expo from the MultiWii config as I had that set up in my RX as well :roll: so it wasn't a direct comparison. I reset my PID's to the defaults set in the code after making a backup of my existing ones.

Being a beginner I fly in Angle mode most of the time and this test run was really no different also since I'm a beginner I'm not sure exactly how informed my observations are :). The sticks are loads more sensitive to input (that will be in part due to the removing of the double expo) but in the complete opposite to what I was worried about when I first discovered this it actually made it easier to control. Loads of wind here just now and while the quad was being blown about there wasn't much in the way of judder when it was compensating. There was also very little/no oscillation when it was descending slowly, through its own prop-wash, or rapidly.

Phil S.
Posts: 32
Joined: Fri Apr 26, 2013 7:59 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by Phil S. »

Alex, you are a genius!

Your mod is not less than a revolution. Control is perfect, turning rates on all axes are adjustable to any level you like, yaw is now even better than with my so far favourite, the HK copy of the KK5.5. At the same time setup is easy and far from beeing critical. I started with zeroeing I and D, and a P on roll and pitch of 2,5 (controllable but no fun to fly), from around 3,0 it went acceptable, getting better and better, started to oscillate between 4,8 and 5,0, but oscillations were slight, noncritical. The copter is now literally nailed to the sticks, has not the least tendency to pitch up at high speeds. Yo can flip on the spot or fly really big loops or everything in between. Used Plüschis IMU mod as well, so activating angle mode at any time levels perfectly. Angle mode is fast, the position of the copter follows the stick movement almost instantly. Position Hold, Coming Home, Alt Hold, really good, not as good as my ArduCopter DJI F450 (using ACC in addition to baro for Alt Hold and kind of waypoints for Coming Home resp. Return To Launch), but not far from it. There are definitely no oscillations at all, even if you try to provoke it with very fast stick input. When P and D gets too high, it becomes a bit difficult to control altitude, but it needs even higher values until oscillation begins.

Attached my current setup of my Gaui 500X with a Crius AIOP V2.0. The quad has motors and ESCs right out of the box, no SimonK upgrades, cheap plastic props out of the bag, did not balance them.

You wouldn´t think it to be possible until you fly. What you managed within a few hours is IMO a giant leap for MultiWii FCs! Thank you, Alex!
Attachments
Gaui 500X Setup.jpg

alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

Thanks for such a good response!
Here's a sketch of the implementation. I've also attached the PDF version (it's hard to read from image). I would try to increase the readablitity (increase font size or something).
pid alex.k11.png

but in that case you have to hold the value of the integrator cause it would wind up

There's no integrator for horizon mode - regulator just requests the angle rate proportionally to angle difference (I used "I" value because it was free. it should be renamed into "horizon P"). The system integrates by itself, because angle is integral from angle rate. As for horizon strength - coefficient of 16 corresponds to the same leveling strength, as 1 for "level" mode (they have equal implementation, only the scaling is different).
For the next version, I've made out the fix for that as well - I just squared the coefficient, so the more you increase GUI value, the faster real coefficient is increased. Should give very weak leveling at 1 (the way I like it) and really locked-in leveling at 4 (like in angle mode - the way you seem to want it to be). Would test myself and then post here (together with scaling fix (all modes) and extreme sticks mix-up for horizon).
Attachments
multiwii alex.K PID implementation.zip
(126.47 KiB) Downloaded 1030 times

timecop
Posts: 1880
Joined: Fri Sep 02, 2011 4:48 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by timecop »

I added this as selectable PID controller to baseflight - set pid_contoller=1 (per-profile setting) to try out.

I gave it a brief hover and it seems to work with the PIDs posted couple posts above, though rate mode was WAY too fast, and my only flying frame (iconic-x) has yaw issues where it almost drops out like a naza when you yaw too fast (it's not related to this code, it does that in general, too).

Snap back to level was much better than what I've seen in multiwii so far.

chris_kmn
Posts: 31
Joined: Sun Jun 09, 2013 11:11 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by chris_kmn »

Is there any chance to get a version based on the actual V2.21 together with this Plüschi IMU (I don't know anything about this but it seems to be helpful) ?

And then we need to find a way to get it all to an official release :-)

BarneyG
Posts: 39
Joined: Tue May 07, 2013 4:42 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by BarneyG »

Am I right in saying v 2.21 is in the trunk/MultiWii_shared folder in svn ?

-ralf-
Posts: 215
Joined: Mon Dec 03, 2012 7:08 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by -ralf- »

BarneyG wrote:Am I right in saying v 2.21 is in the trunk/MultiWii_shared folder in svn ?

You are right .... but don't forget to use the latest multiwiiconf.pde.

chris_kmn
Posts: 31
Joined: Sun Jun 09, 2013 11:11 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by chris_kmn »

is there any chance to get a tutorial how to work with the google.code site ?

which tools do I need for example to update all the releases up to r1474 (somebody references the r1474 changes to this thread) based on the last official release r1391 ?

update: I used SVN to download the _shared. Hope that that includes the r1474 . there is no reference in miltiwii.ino. just says 2.21. Is there already the new PID control loop integrated ?

And for what is the PDE file ?

meanwhile I updated the new gyro scale from Plüschi and it changed a lot for me. I can rise the PID values way more and now the I - value for horizon is working fine. I like the new implementation very much !
Last edited by chris_kmn on Sun Jun 16, 2013 1:57 pm, edited 1 time in total.

alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

Hey guys! So, what's the deal with SVN updates? How should I proceed? Take the last version and update it to my implementation, post here, if test successful commit to SVN?
Also, as multiwii aims the .c and .h files style, would anybody mind if I create separate file filters.c and move the PID (and later other filters) there? The idea is it would be possible to use one PID code for all loops in style:

Code: Select all

pPID_desc->input = var;
PID (pPID_desc);
output = pPID_desc->output;

This would save a lot of space and also increase performance (reduce processing time) a bit.

BarneyG
Posts: 39
Joined: Tue May 07, 2013 4:42 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by BarneyG »

-ralf- wrote:
BarneyG wrote:Am I right in saying v 2.21 is in the trunk/MultiWii_shared folder in svn ?

You are right .... but don't forget to use the latest multiwiiconf.pde.



In which case the IMU fix is already in place in the current _shared directory :)
Edit and I'm also very confused ... there is an awful lot of changes for a 2.2 -> 2.21 style release :) this looks more like the current dev release of 2.3 ?

and another edit :

r1474
- based on some ideas from this thread:
viewtopic.php?f=8&t=3671
- the sticks scaling is no more affected by PID coefficients
- yaw rate (to the right of the PIDs in GUI) now works as stick scaling
- default yaw rate is increased (with yaw rate at 0)
- yaw PID principle is now different from PITCH&ROLL PID:
- yaw ITerm windup is very high, allowing an 'elastic' direction return after a
manual perturbation
- yaw ITerm is also constrained with a windup independent limit
- yaw PTerm is constrained in order to counter the yaw jump effect (maybe to
refine)
- yaw ITerm is canceled if the yaw stick is not centered
Today (14 hours ago)
dubusal

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by Alexinparis »

Hi,

There are a lot of aspects in this thread.

So let's try to isolate things.

1) PITCH/ROLL acro PID update:
- PID coef must not have impact on stick scalling, OK
- cycleTime should be included in I and D Term computation. Does it really have a noticeable effect on flight performance ? For sure it has a noticeable effect on computation time.
- D component doesn't take into account stick position at all. Again, from wiki link: “In most commercial control systems, derivative action is based on PV rather than error.”. Does it really have a noticeable effect on flight performance to take error rather than PV in the equation ?
- 32bit implementation for I term: Does it really have a noticeable effect on flight performance ?

2) YAW PID update:
I think 32bit Ierror term is interresting not to gain more accuracy (from a flight performance point of view), but to gain more windup.
Is there any other approach to counter the yaw jump effect ?

3) ANGLE/HORIZON mode update
I think Horizon mode (relativly new) have good feedback so far, but why not update it
If feedbacks on it are better.

4) wrong MPU scale:
it was reported by ovaltineo
viewtopic.php?f=8&t=3480
and is corrected in _shared
It affects mainly angle calculation after many flips. Nothing to do with PID.

5) versions:
There is no 2.21 version.
The last official version is 2.2.
All other variant after are just dev version for testing purpose based on _shared repository.
And sometimes I create a zip of intermediate dev versions

6) the deal with SVN update
There are few committers that can update it, based on what they think useful.
The best way to suggest evolution is what you did: explain the mod in the forum, share a zip code and get feedbacks.

7) why so many compromises on the code ?
Because it's always a challenge to keep computation time and code size low. More than a challenge, it's also for me a fun way of coding.
I understand it could be disturbing from a theory or coder point of view.

which tools do I need for example to update all the releases up to r1474

You only need to get the last r1474 files.


Snap back to level was much better than what I've seen in multiwii so far.

Did you try to increase LEVEL P with the stock code ?

alex.khoroshko
Posts: 27
Joined: Sun Jun 09, 2013 9:17 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by alex.khoroshko »

- cycleTime should be included in I and D Term computation. Does it really have a noticeable effect on flight performance ?

I component: flight - no. Tune performance - well, it should be. I would try to compile the code with and without loads of functions to see, whether I meaning change when it is not time corrected. Then it would be clear, whether correction needed or not. Also, D correction is needed IMO - it feels a bit better with it, it may be placebo effect though. But it looks logical, that if dt is very different every time, D response would not be consistent.
Does it really have a noticeable effect on flight performance to take error rather than PV in the equation

Yes, at least I feel the difference. When the stick is moved rapidly it creates something like short impulse. Too high D lead to overshoot though.
- 32bit implementation for I term: Does it really have a noticeable effect on flight performance ?
Not quite sure, quite possible that no. Should be carefully tested.
YAW PID update:
I think 32bit Ierror term is interresting not to gain more accuracy (from a flight performance point of view), but to gain more windup.
Is there any other approach to counter the yaw jump effect ?

There is a limiting, which prevents from wind up. Jump effect needs fixing, I agree. Harder limiting would help (just reduce the limits separately from roll and pitch)
ANGLE/HORIZON mode update

It would work the same as old one when coefficient is set high. With low coefficient it would slowly drift towards horizontal position (how me, and, I think, some other FPVers like)
Did you try to increase LEVEL P with the stock code ?

My little comment - original code does pretty much the same as mine, except that it is now clearly arranged as one control loop inside another, internal is already fine-tuned for acro mode, external is easily tuned with single coefficient. Also, gyro-based correction was initally P-controlled only with this line:

Code: Select all

 PTerm -= ((int32_t)gyroData[axis]*dynP8[axis])>>6; 

New code in repository does the same. My version's internal loop is full PID regulator, that's why additional I for level mode is not needed.

And, what do you think about moving filters to separate file? I'm sure that it would decrease image size at least, but is it compatible with multiwii overall coding style?

P.S. I see where to save A LOT in terms of performance. The I2C transfers should be made asynchronous (interrupt driven). This would allow process I2C transfer in background while at the same time processing the main loop. Drawbacks - increased jitter for software PWM and a little increased code size. I would try and then create separate thread if it would be good.

User avatar
Plüschi
Posts: 433
Joined: Thu Feb 21, 2013 6:09 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by Plüschi »

alex.khoroshko wrote:I would be glad to hear your thoughts on horizon, what in your opinion should it be.


I would like it as you say "centered - goes towards horizontal position with the set rate, extreme sticks - pure ACRO".
Horizon as it is now allows more inclination than angle but doesent allow flips.

One thing i dont understand is running the loop as fast as i goes. My version uses a fix 3.666ms loop time, and i cant feel any difference to the jittering 2.9ms loop time the default code uses. Considering the reaction time of ESC and motors is more in the 100ms range what does 2ms loop time buy?

scrat
Posts: 925
Joined: Mon Oct 15, 2012 9:47 am
Location: Slovenia

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by scrat »

Phil S. wrote:
scrat wrote:If you're just a pilot...then mwii is not for you.

That´s been a bit of exaggeration. Wouldn´t be to much of a problem modifying code as you described but i am not too keen on it! On the other hand it seems to me that some of the guys programming MultiWii are good in writing code but not too keen on flying!

Guys like you and Alex doing both (at higher levels) appear to be a minority group.

Alex, did you rewrite PIDs for all three axes or just for roll and pitch?


Sorry for my exaggeration. It wasn't meant like that. Sorry again.

scrat
Posts: 925
Joined: Mon Oct 15, 2012 9:47 am
Location: Slovenia

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by scrat »

BarneyG wrote:Alex ... any reason why you've changed the #define I2C_SPEED 400000L to #define I2C_SPEED 100000L for the Crius AIOP v1 definitions ?


Did you know if you have Crius AIOP v1, V1.1 or v2 you can have I2C speed commented out. I have it like that and don't have I2C errors anymore.

/********************************** I2C speed ************************************/
//#define I2C_SPEED 100000L //100kHz normal mode, this value must be used for a genuine WMP
//#define I2C_SPEED 400000L //400kHz fast mode, it works only with some WMP clones

Because there is in def.h file for AIOP vX already defined:

#if defined(CRIUS_AIO_PRO_V1)
#define MPU6050
#define HMC5883
#define MS561101BA
#define ACC_ORIENTATION(X, Y, Z) {accADC[ROLL] = -X; accADC[PITCH] = -Y; accADC[YAW] = Z;}
#define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = Y; gyroADC[PITCH] = -X; gyroADC[YAW] = -Z;}
#define MAG_ORIENTATION(X, Y, Z) {magADC[ROLL] = X; magADC[PITCH] = Y; magADC[YAW] = -Z;}
#define MPU6050_I2C_AUX_MASTER // MAG connected to the AUX I2C bus of MPU6050
#undef INTERNAL_I2C_PULLUPS
#define I2C_SPEED 400000L //400kHz fast mode

BarneyG
Posts: 39
Joined: Tue May 07, 2013 4:42 pm

Post by BarneyG »

I've got a v2 ... The reason I asked is that it is the line you bolded has been changed to 100000 in Alex's code :)

Phil S.
Posts: 32
Joined: Fri Apr 26, 2013 7:59 am

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by Phil S. »

scrat wrote:Sorry for my exaggeration. It wasn't meant like that. Sorry again.

"Exaggeration" was pointed at my statement beeing just a pilot not at yours! Wanted to state that I am interested in a bit more than just banging sticks. No need to apologize, I´m not huffy at all!

User avatar
Hamburger
Posts: 2578
Joined: Tue Mar 01, 2011 2:14 pm
Location: air
Contact:

Re: V2.2 - ACRO PID implementation is wrong, right?

Post by Hamburger »

Plüschi wrote:Horizon as it is now allows more inclination than angle but doesent allow flips.

Plain wrong. I do it all the time.

Post Reply