sim- / tgy

tgy -- Open Source Firmware for ATmega-based Brushless ESCs
http://0x.ca/tgy/
688 stars 387 forks source link

Tarot 4006/620KV out of sync on quick throttle-up #50

Closed dave-cz- closed 10 years ago

dave-cz- commented 10 years ago

Hello Simon,

my setup:

Afro 30A ESC (afro_nfet), Tarot 4006/620KV 22-pole motor, 1355 carbon prop, 4S LiPo.

All goes smooth after slow throttle changes, but once I quickly push the throttle, motor loses sync (red LED blinks, weird sound, loss of power and rpm).

The problem is much more present when using 400Hz input (Naza controller). When using 50Hz input (raw RX output), it is hard to reproduce, but is still there.

I will very very very appreciate any advice.

Dave

dave-cz- commented 10 years ago

I tried following options in tgy.asm (and their combinations):

SLOW_THROTTLE 0/1 COMP_PWM 0/1 MOTOR_ADVANCE 22,24,26,28,30

But no luck so far. There was slightly better reaction to throttle with higher MOTOR_ADVANCE, but not significantly.

SilviuDadus commented 10 years ago

Hello Dave, have you tried setting the slow_throttle on and changing the motor advance to below 10? My NTM motor behaves the same way, very smooth with slow acceleration but completely dies or stutters with hard acceleration. Did you experience this problem when accelerating from 0 to high rpm or from a very low running rpm to high rpm? Don't know why but above a certain threshold (around 20% of max speed) the motor works OK but only for very low rpm jumps the motor gets out of sync (poor BEMF signal I guess).

dave-cz- commented 10 years ago

I haven't tested motor_advance below default value. I never accelerate from 0, flight controller keeps motors running on slow rpm after arming, so it's accelerating from low rpm to high rpm everytime. I'll try slow_throttle with low motor_advance and let you know.

dave-cz- commented 10 years ago

Tested slow_throttle in combination with motor_advance from 16 to 4 step by 2, then from 4 to 1 step by 1. The problem is slightly better at values below 12, but never disappears. At values below 8 motor becomes very hot even after only short period of test (several tens of seconds).

Later I tested motor_advance back to 15 and comp_pwm=1. No success.

Later I played a bit with power_range, got into audible PWM frequency, but sync loss still there.

I'm desperate. I'm giving it a break and trying BLHeli-multi. It's a pity, SimonK fw looked so promising.

dave-cz- commented 10 years ago

Looks like it will work much better on 3S. 4S puts too much power and the motor can't handle it, despite what the manufacturer says. With 3S i need only COMP_PWM=1 and the rest of setup is in default values. Works smooth on the table, I hope I'll see it in the air tomorrow.

sim- commented 10 years ago

Oof. :) Did you ever try BLHeli on the board? If it works there, that would be an interesting data point.

Note that the refresh rate should not matter at all for testing. You should be able to reproduce it even at 50Hz. The best way would be to mix in a switch or similar so you can jump suddenly from slow to full power. Also, did you happen to check what date code you have on the ATmega8?

dave-cz- commented 10 years ago

BLHeli worked better than SK, but not perfect. There was still sync issues, with very fast recovery. But the motor overheated massively. It was unusable. Best performance was achieved with Demag Compensation=Low, PWM Frequency=Low, Motor Timing=Medium, PPM_Min=1000, PPM_Max=2000 (forced, no TX programming), Throttle Change Rate=64. But due the overheating I couldn't use it anyway.

About that refresh rate - I could reproduce it very easily with throttle curve set to 0% at first half and 100% set at second half of throttle input. Direct connection to RX (50Hz) - worked almost fine, connected via Naza (400Hz) - sync problems. I don't know why.

How do I check the date code of ATmega8?

sim- commented 10 years ago

Hmm. I ask about the date code since I think there was a batch with dodgy comparators that might be affecting the timing sensing. There should be a four digit code which should be a two digit year and two digit week number. Is it around something like 1336? Different chip, but an example: https://www.sparkfun.com/news/350

dave-cz- commented 10 years ago

I can't check the datecode. There is paper label on chip with "09/14" text on it. I tried to remove one, but couldn't read anything under it. ESC are new, buyed this month from Hobbyking.

sim- commented 10 years ago

Ok, when the motor is spinning, and you turn off the power, does the red LED light for a significant portion of the time whlie the motor is slowing down, or only once it has nearly stopped?

dave-cz- commented 10 years ago

By "turn off the power" you mean throttle down to zero or disconnect the battery while the motor is spinning? When I throttle down from full to zero, the red LED blinks only a few times just before motor stops, immediately followed by constant green.

sim- commented 10 years ago

Ok, that sounds like not a dodgy comparator, then. I'm out of other ideas if you are working with the newest git version. Of course, I don't have that particular motor...

owenduffy commented 10 years ago

There are some motors that are challenging to SimonK, and there was a honeymoon period where BLHeli was not attracting problem reports... but it seems that although some motors will work better on one or other, there are some motors that feature in problem reports for both types of FW.

As Simon suggested, if BLHeli works properly, then there is an easy solution, but if it doesn't there is an unsolved problem with the drive configuration.

dave-cz- commented 10 years ago

Simon, If you are ready to investigate this issue and possibly find some bug in the code, I can pay one set of ESC, motor and prop for you. You could consider it as my little contribution to this project, as I cannot contribute to the development directly. What do you say? :-)

dave-cz- commented 10 years ago

Hi Simon,

I was wrong. The problem is still there even with 3S battery. I couldn't find out it yesterday, because I used old weak battery. Today I brought new strong 3S Lipo and the problem is the same as on 4S. Massive out of sync event on fast throttle-up. I did further investigation and found out, that the problem is not present while controlling the ESC directly from Futaba RX. It definitely has something to do with input PWM frequency. My measurements:

Futaba RX: PWM freq. 62.32 Hz motor off duty cycle 6.304% = 1.01ms motor idle duty cycle 7.356% = 1.18ms motor full duty cycle 12.09% = 1.94ms

Naza v2 controller: PWM freq. 399.95 Hz motor off duty cycle 37.60% = 0.94ms motor idle duty cycle 47.77% = 1.19ms motor full duty cycle 77.77% = 1.94ms

I set up throttle control on 2-position switch of TX. Low position set to idle, high position set to full. With Futaba RX i can switch between idle and full anytime. It is always smooth and steady acceleration to full rpm, regardless of battery (3S or 4S). With Nata controller, once I arm the motors (they go to idle rpm) and switch throttle to full on TX, it is always massive out-of-sync event. I can record it on video and post it on YT if you want.

Any idea about reason of this behaviour (based on PWM frequency)?

sim- commented 10 years ago

Hi Dave,

I think I have too many other motors and such people have sent already that I still need to get to. :| You could send me one maybe if we can't figure anything else out.

The only thing that more updates will do is take a bit of CPU time, but it shouldn't be anywhere near significant. The interrupt is already about as optimized as it can be. If the input is not changing other than during the one update even when the step occurs, nothing should behave any differently. However...

A while ago, around the time I was speaking with Owen about the motors he was testing, I developed a power step test program that emitted pulses through a parallel port, timed by the CPU TSC, timed by a C program. (This could easily run on a microcontroller with proper GPIO instead, but it was originally written to read from a USB scale at the same time to do thrust profiling.) Anyway, during that testing, I started debugging what looked like timing loss, but was actually a ground offset problem that was corrupting the logic signal received by ATmega8 due to the offset induced by the resistance of the ground path.

I actually couldn't fix the problem in my setup (with my bench supply and parallel port), so I actually just made the program output one full power pulse, then pause for a bit (but not long enough for the ESC to time out), then continue sending pulses at the normal rate. This solved the problem.

I wonder if something similar is happening in your case. I'm not sure what the best setup would be to prove this one way or another. Perhaps a differential probe on the logic input at the ESC combined with an inductive current probe to watch the output current, or look at the three phases to see the PWM duty cycle and/or timing. Maybe it would be easier to make a variant of the program that just lights the green LED or something whenever the ICP interrupt receives what it thinks is a full power request (and turn it off otherwise), and then just trigger from and watch that to make sure the edge is solid and that it doesn't flap around at all.

Thoughts? :)

owenduffy commented 10 years ago

I have continued to use my Aurdino servo ramp generator (see http://owenduffy.net/blog/?p=92). The current script includes Simon;s 'jump test' and it behaves well for me, and my test scenario should not have the noise problem that Simon has experienced in his test setup.

There are a bunch of articles under the RC category on my blog which report measurements using eLogger of some different drive combinations driven by this common excitation scenario which allows objective comparison of the handling of various aspects of the test scenario.

I have not tried changing the servo update rate, but it could be done.

I have come to the conclusion when observing drive response, that update rates at close to 500Hz are unlikely to improve performance, the drives I have tested do not respond anywhere near that fast (that small motors with small props will be faster)..

Owen

owenduffy commented 10 years ago

I hear Simon's comment of servo refresh rate and offer the though that IF it seems to make a difference, it might suggest that there are small changes flowing from the FC... such as you might expect if there is frame vibration feeding 'noise' into the process.

Owen

dave-cz- commented 10 years ago

I could write a small arduino sketch simulating Naza signal to eliminate possible signal changes caused by frame vibrations. I've got some spare Uno here, so it should be no problem.

Any other tests will be a bit complicated as my equipment is not good enough for this type of testing. At least I would need a storage oscilloscope to check the signal incoming to ESC for possible interference coming from power leads or maybe some logic level offset.

dave-cz- commented 10 years ago

Hi, I wrote one really short arduino sketch simulating Naza pulses at 400 Hz, 940us for 5s, 1190us for 3s, 1940us for 1s and loop forever. Connected to ESC, applied power and ... oh my god it works! So it is definitely Naza dependent and no, it is not caused by frame vibrations, I holded Naza separated from frame, so no vibrations at all. Now it looks like signal from Naza is kinda weak or something and distorted by high currents of power leads during quick acceleration. At the moment I'm trying to get some oscilloscope to compare signal output from Naza with signal input to ESC.

owenduffy commented 10 years ago

Interesting observation. I can't help thinking that the root cause of at least some of the reported problems is not the ESC+motor, but some system problem, be some form of electromagnetic compatiblity, vibration, FC control loop issues etc.

I see some online experts advising connection topologies that are likely to be susceptible to noise. Think about your power feed plan and the way in which the -ve is distributed to minimise the risk of noise. On the other hand, som experts advise fully segregated control power that seems unecessary in the majority of implementations.

Hobbyists with limited understanding are sucders for product hype, like the term "opto ESC" that rarely means it uses an opto coupler (for noise immunity), but rather that it is simply BEC-less.

Note that the signal from the receiver to FC and FC to ESC is (usually) a 5V CMOS signal, so there is quite a bit of margin for noise on the signal... but that is no reason for consuming that margin with sloppy grounding practice.

If you have erratic behaviour, it is a prompt to review the grounding scheme.

Owen

SilviuDadus commented 10 years ago

Hey Owen what you say makes sense for very very high frequency signals and if the sensing lines are right above/beneath the MOSFETs which can cause some switching noise. Even so on my DIY ESC power GND is separated from the digital GND and the BEMF signals are shielded through a sandwich GND style design. However I have the exact same issues with a NTM motor and I can show you some plots made with a Lecroy oscilloscope with very low capacity probes. The ESC input PWM signal, uC signals that feed the gate drivers and the phase signals look very well. Yet the NTM 35301400kv motor won't work correctly with SimonK or BLHeli whilst another motor (EMAC CF2820 I think) runs without any issues whatsoever. So it mostly is a ESC+motor combination issue. If this was a ESC design flaw all motors would have shared the same issues.

dave-cz- commented 10 years ago

Hi,

some pictures follow. First, arduino output of full throttle signal: ardu_full Now here is Naza output of full throttle signal, with ESC not connected: naza_full And now, the same signal measured directly on ESC while the motor was accelerating from idle rpm: naza-esc

We can see that the main difference is in voltage of log.1 (Arduino=5V, Naza=3.1V). Additionally there is some interference coming from power wires of ESC. I think this is the problem. I'll try to replace the servo cable of ESC by twisted one and test again.

Dave

dave-cz- commented 10 years ago

Hi,

problem solved. I tried to replace one of the servo cables by twisted one and sync issues have gone. Now it works on both 3S and 4S batteries. Thanks for all your support and ideas.

Dave

sim- commented 10 years ago

Hmm. Well, perhaps this a good reason for having a reasonable RC filter on the receiving end!

Incidentally, where did you have the scope grounded? Since your scope is showing signals lower then its ground, it would appear you were grounding the scope near the ESC ground, and perhaps the Naza ground is closer to the battery (or perhaps the average of all ESCs).

I wonder why the noise frequency is about 4kHz. Have you changed POWER_RANGE to about 4000?

It might be possible to catch this sort of noise in software and discard it, but it seems curious... That's a very short spike. The ATmega8 suffers from a lack of hardware PWM capture and instead supports only hardware edge capture (on AfroESCs), or just a plain software edge interrupt (everything else not using the ICP pin), so it will mess up if the edges are too close for it to see both of them. It might, however, be useful to at least detect such edges and report this as a problem so as to not mix it up with actual motor timing issues, at the very least.

sim- commented 10 years ago

By the way, did you ever capture a video of what this sounds like? In theory, losing and recovering the RC signal shouldn't actually ever cause the red LED to blink...So this might be a separate bug. I had also a separate program to alternate and add noise to the PWM input, but last I checked it worked as expected (other than signal + gaussian noise having the likely-undesired effect of having average higher output).

sim- commented 10 years ago

I suppose without a significant signal filter, noise could flow through the ATmega8 protection diodes (in both directions, below ground or above Vcc) and start affecting the comparator and other sensitive areas. The Afros should have 330R on the PWM input pin, however, so it shouldn't be much unless it's a ground noise issue.

dave-cz- commented 10 years ago

You're right, the scope was grounded just by the ESC and Naza was closer to the battery.

POWER_RANGE was at default value.

Unfortunately I've got no video. I asked if I should shoot the video 5 days ago, but nobody responded, so I didn't bother. Sorry. It sounded like "rrrrrrrr" of very low pitch while the red LED blinked very fast. RPM was stable (very low), maybe slightly went up. I didn't try to wait long in that state as the motor was overheating very quickly.

sim- commented 10 years ago

Hmm, so not a squeal like in the video here: http://fpvlab.com/forums/showthread.php?31275-T-MOTOR-U8-and-ESC-compatibility-issues-ANY-EXPERIENCE&p=528648#post528648

So, am I reading the time-scale incorrectly? What frequency are those spikes happening at? I wonder where they're coming from.

In theory, if the signal is staying just a signal and not influencing anything else electrically at the ATmega8, the only change from the input signal is that the output PWM should follow. The "main loop" does not exit (unless MOTOR_BRAKE is set) until timing with the motor is lost, which is usually only expected to happen once it stops.

Ah, however, if "invalid" pulses are received (< MIN_RC_PULS or >= MAX_RC_PULS), rcpint_fail clears rc_timeout, and we jump to restart_control if wait_for_edge detects this state. This is supposed to turn off power, re-initialize everything, wait for non-zero power, and then go through the usual start procedure, which is supposed to start with power off so that it can learn timing that would otherwise be too fast that starting would fail, and then drop directly back into running mode. If this was oscillating (not working correctly), it could certainly sound like low frequency rather than a squeal.

I actually did re-implement the "powerskip" starting feature in a C project recenty, and found some problems with my earlier approach. I should probably revisit the way I did it back in asm. It worked when I tested at the time, but there are probably some corner cases. I'll check this.

dave-cz- commented 10 years ago

Right, not a squeal, just low frequency whirr. The time scale is 500us/div, so the frequency of spikes is almost exactly 4kHz. The red LED blinked fast, but it was visible by bare eye, so about 10Hz or less. Red pulses were not of the same length, some were longer, some were shorter. The green LED never flashed.

One more information - the issue was also present while using BLHeli firmware, but the effect was more devastating. At 90% times the acceleration went OK, in the rest of the cases the ESC somehow "locked up" at certain controlling signal and the motor stayed running at relatively high throttle. The ESC no longer responded to control signal until I disconnected the battery or servo cable. I looks like the spikes somehow got into resonance with control signal and the ESC recognized it like high-throttle. The issue was much worse when I disconnected "ground" wire from servocable at Naza side.

repairsdji commented 9 years ago

Hello Simon,

I am building a Tarot FY680 Hexa for a friend. Flashed Afro 30A with SimonK AfroNFET 2014-06-18 firmware Tarot 4006 620Kv Motors 13x5.5 T-style Props 4S Lipo ESC's mounted under the Motors.

RED and GREEN LED's flash when the sync issue is prevailing Oscilloscope probes are connected to the -Ve terminal at the ESC, and the PWM Signal Input. This is to show the Pulse width I'm controlling with the TX ( Futaba 14SG ). The noise you see is probably induced from the 30cm or so Power Lines to the main Distro. Power cables were twisted axially with drill to reduce magnetic signature. All cables pass from inside CF tube of the Tarot frame.

When scope is connected to +Ve and -Ve terminals of the esc, the supply shows 0.5V ripple at the switching frequency. When Motor picks up, the supply is clean.( not shown..but I can make video )

YouTube Video of issue - http://youtu.be/NeEgmdf2fsE

BTW.... I am not a DJI representative and have absolutely no DJI connection. I just happen to repair and fix a lot of DJI troubles for local customers..... long story "short" :/

sim- commented 9 years ago

Hmm, I bet you have some interesting DJI trouble stories. :)

So, there is definitely a bug here that I still need to fix -- after just a few invalid input pulses, we exit the run loop, light the green LED, and wait for a non-idle signal. That part is OK, but if the motor is fast enough, the code that is supposed to detect the motor rotation before applying power can exit early, and try the regular start approach, which will limit the overall speed, miss, and light the red LED, which is probably what you are seeing.

However, the cause of this is still an electrical issue, and I'm not sure we can do anything in software to avoid or ignore the noise.

Perhaps you could try twisting the servo cable, as worked for dave-cz-? It seems you have just a single separate wire, so you may need a separate run. You could also try adding a bit of capacitance at the ICP pin on the ESCs. Hmm. Not sure what else you could try.

By the way, sskaug (BLHeli) recently pointed out something I had completely missed: the ATmega8A and ATmega8(L) have very different logic transition points. The ATmega8(L) at 5V goes low at around 1.42V and high at around 1.86V, while the ATmega8A is much closer to Vcc/2. See "Pin Thresholds and Hysteresis" in the datasheets.

repairsdji commented 9 years ago

Hi Simon, so what we're seeing in my case is lack of adequate signal quality ( voltage and noise ) at the ESC's input ? I will try your suggestions, and also perhaps play with a pull up or a pull down resistor. Perhaps even a 1Khz low pass filter, to cut the noise which seems at much higher frequency than 400Hz of the Flight controller's output.

sim- commented 9 years ago

The only explanation for the green LED while running is that the run loop has exited and we have turned on the green LED while waiting for a valid PWM signal that requests power. The only reason for the run loop to exit before the motor has stopped is that rc_timeout has reached 0, which can only happen if the rcpint_fail branch is taken in rcp_int, or if the signal stops for at least 65.536µs (~65ms).

The fact that the motor gets stuck at a certain speed while this is happening is a separate bug.

You could try removing the "clr rc_timeout" from rcpint_fail, and then it might run "better", but it's still getting corrupted signals at the electrical level, which is what is causing the whole problem.

You could probably set your scope to trigger at on low-going pulses following a high period shorter than 50µs or so to see the signal only where the noise causes the signal to drop lower than the logic threshold on the ATmega8A (set a ~2.4V trigger level). I suspect it's in that direction and not high-going noise during the low parts, since the 8A has the higher level and ~2.4-2.6V is much closer to the 3.3V signal that is likely coming out of your flight controller.

Deiminator commented 9 years ago

Hello dave-cz,

would you mind giving me your email address and/or skype (whichever msger you use).

I'am having the same issue with exactly the same setup (Tarot 4006/620kV, Hobbywing 30A esc, 4S battery and 1355CF prop) and exactly the same problem.

I would like to contact you, but there is no way of sending a PM to you.

Regards. P.M.

dave-cz- commented 9 years ago

Hi Deiminator, try address github@trcka.net

D.

sim- commented 9 years ago

I pushed commit b13332a61 the other day which tries to report PWM edge issues at idle by beeping rapidly. I'm curious if this is enough to catch PWM corruption issues. I can trip it by pulling a servo tester's signal wire while driving the motor, but I'm not sure if it will catch the noise as above. Even with hardware ICP capture, there is no way to get the ATmega8 to measure PWM in hardware, as the software interrupt has to flip the trigger edge before the next occurs. So, anything under a few microseconds is unreliable. We can detect very short spikes if additional code is added to the interrupt to check that the current pin state matches the edge that was configured to trigger the interrupt, but that will increase output software PWM jitter, so it shouldn't be on by default at least.

AndrejInova commented 9 years ago

Hello, Another one who has the same issue here. I'm also using 4S on Tarot 4006 motors (13x5.5 carbon props) with Afro 30A ESC's (latest afro_nfet.hex). I've also notices the issue is still present with 3S (though not as bad). I've just found a solution that seems to work. I've connected the signal wire directly to the Pixhawk with no extension but that still didnt work, what I had to do was to connect the ground wire also (i read somewhere it was best practice not to connect the ground wire when it is already connected with the power wires to avoid ground loops). Now I don't even know what that is, but it sure didn't help this time... So it probably is a noisy signal issue as simon already mentioned.