Developer

One ESC is not like the others. Why?

I've been having a lot of fun with my new ArduCopter. My initial flight was interesting - due to me switching flight modes with the throttle up it jumped off the floor and flew straight at me. I now have a nice scar on my shoulder as a memento of that first flight :-)

3689392108?profile=originalSince then I've been taking things a bit more carefully. The above photo shows the copter tied down to a 20 litre tin of paint, so it can only rise about 10cm off the tin. It will be released from its string prison once I've got some of the glitches out.

The particular glitch that has me puzzled at the moment is ESC callibration. During some testing I suspected that the motors were not all running at the same speed, so I wrote this little tester and hacked it into the ArduCopterMega trunk:

static void run_testmode(void)
{
Serial.println("Running motor test");
for (uint16_t thr=1100; thr<=2000; thr += 100) {
for (unsigned char i=0; i<4; i++) {
Serial.printf_P(PSTR("motor test %u thr=%u\n"),
(unsigned)i, (unsigned)thr);
APM_RC.OutputCh(i, thr);
delay(1000);
APM_RC.OutputCh(i, 1000);
delay(1000);
if (Serial.read() != -1) {
Serial.println("terminating motor test");
for (unsigned char j=0; j<4; j++) {
APM_RC.OutputCh(j, 1000);
}
return;
}
}
}
Serial.println("Finished motor test");
}

The code runs each of the motors in turn, starting at a PWM value of 1100 and rising to 2000. As I suspected, it showed that one of the ESCs (the one driving the front motor) is calibrated quite differently from the other 3. The front

ESC runs at 1100, when the other 3 don't run at all, and doesn't run at all at 1900 or 2000, while the other 3 do run up to and incuding at 2000.

I have been through ESC calibration, using this bit of code, which is based on some code from the ArduPirates tree:


static void calibrate_ESCs(void)
{
Serial.println("Disconnect battery then hit enter");

while (Serial.read() == -1) ;

Serial.println("Now connect your battery. After beep beep, hit enter");

while(1) {
APM_RC.OutputCh(0, 2000);
APM_RC.OutputCh(1, 2000);
APM_RC.OutputCh(2, 2000);
APM_RC.OutputCh(3, 2000);
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out2_Out3();
delay(20);
if (Serial.read() != -1) break;
}
Serial.println("wait for beep then hit enter again");
while(1) {
APM_RC.OutputCh(0, 900);
APM_RC.OutputCh(1, 900);
APM_RC.OutputCh(2, 900);
APM_RC.OutputCh(3, 900);
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out2_Out3();
delay(20);
if (Serial.read() != -1) break;
}
Serial.println("disconnect your battery and then hit enter again");

while (Serial.read() == -1) ;
}

If I understand correctly, that should have calibrated all 4 ESCs to the same value, but it didn't seem to work.

Does anyone have any suggestions? Is it just a matter of replacing the ESC that is out of kilter with the others?

 

UPDATE: I've solved it! The problem was I had misunderstood the importance of the timing in the ESC calibration instructions. I read the ESC manual, and noticed that the procedure for entering programming mode is actually the same as the initial steps for doing throttle callibration. The only difference is how long you wait after connecting the battery the first time. I was beiing "conservative" and waiting several seconds, and the ESCs were entering programming mode instead of doing throttle calibration.

I now have my 4 ESCs calibrated correctly, and it hovers quite nicely in its string prison. I will be able to try a real flight now, and see if it lasts a bit longer than the first one!

 

E-mail me when people leave their comments –

You need to be a member of diydrones to add comments!

Join diydrones

Comments

  • Developer

    GroundLoop,

    I'm running the ArduCopter "heavy lift" kit, which means 880kv motors. I think they use the same ESCs as the 'normal' kit though. They are AC20-1.0 ESCs.

    In case it is just a faulty ESC I've ordered another one today.

    Cheers, Tridge

    PS: yes, I did the original rsync, although I'm not the maintainer these days.

     

  • I'm going to re-cal later today, since now you have me wondering. If I remember correctly, 900 is "off" and around 1050 is idle/armed/spinning? I know my low-end is calibrated correctly since they all start spinning at the same speed and same time (arming). It's just the top-end that's wonky, so I will redo.

    I agree that letting the APM send precise calib values is a better process than using a stand-alone Tx/Rx.

    Are you running the standard kit arducopter drivetrain (m2mPower AC20 / 10x45 props, AC2830 850kv motor)? If so I can take some RPM readings and see how they compare.

    (Andrew Tridgell, as in... rsync Andrew Tridgell??)
  • Developer

    Thanks for all the comments everyone! \

    Some responses:

     

     - I confirmed it is the ESC and not another component in 2 ways. I switched which motor the ESCs connect to, and I separately switched which APM output went to each ESC. The 'bad' ESC remained the same in each case.

     

     - Ryan, I'm curious what you saw with the bad solder joint. Can a bad joint cause an ESC to run faster than it should? I would expect it to run slower if it doesn't get the current it needs. The odd-man-out ESC in my case runs faster than the other 3, so either I consistently botched the soldering on 3 of the power board joints, or the odd-man-out really is odd.

     

     - Sebastian, I chose 900 as that is what the ArduPirates code used. (see CALIB_Esc() in CLI.pde). I was a little surprised by the 900 value, but went with it assuming the pirates know what they are doing (they seem to get everything else right!).

    - Silverfox, I have tried calibrating the errant ESC separately, but not with a RC trasmitter. I just disconnected the other 3 ESCs, and went through the same calibration I showed above. It did beep in a manner that suggested that it was working. The calibration I'm using should be sending precise PWM values, which I couldn't get via a RC receiver.

     

    I've also ordered a laser tachometer from ebay which I hope to use to measure the actual speed of each motor, so I can see the real RPM curve. That may give me some hints.

     

    btw, does anyone know of a video of the calibration of the actual ESCs used in the ArduCopter kits? Matching the beep descriptions in the ESC manual to the actual sounds you hear is a bit hit and miss. If I could listen to someone elses ESC (with the same model) going through calibration I could confirm that its the same set of beeps I'm getting.

     

  • calibration should be done with CLI

    but it's just like you would use a 4-way Y cable (it puts out what it gets from the RX, no calculations or stuff in there)

     

    your lowest point  should be around 1100 (not 900 that's too low)

  • I had the exact same issue.  I did calibrate one by one as desceibed but found the culpret to be cold solder joints on the bayonett connectors (I actually managed to pull it out!!).  Re-flowed with a hot (800) iron and added enough solder to fill in the connector.  The one ESC that was giving me greif is all good now (I did all of them).

    I would highly recommend the a la carte calibration as it's real world.

    I would actually hope that the throttel curve comming out of my RX to the APM is whats going to the ESC's, I'm fairly certain that it should be the same.

    Cheers

  • Should have read first then posted later :)...

    I agree that the calibration above should be about the same outcome as in the video, but instead of using your transmitters throttle, its being set by APM code. you could try calibrating them by bypassing APM, using a 4-way Y cable on throttle signal from RX to the 4 motor esc's. and see if they all run at the same rpm through your transmitters directly. it would certianly eliminate alot of possibilities and narrow your issue down to a few components.

  • I used the CLI ESC calibration, which I assume is superior because it calibrates the throttle curve to the actual range from APM, rather than the range from the Tx (which seems unrelated). Is this not correct?
  • Have you tried to calibrate each ESC seperatley? That is recommended in the Arducopter manual.  Here is the link to that page:

    http://code.google.com/p/arducopter/wiki/Quad_ESC

     

  • Sure would be great if the Send Motor Command in Configurator actually worked. ;)

    Anyone know what the disconnect there is?

  • In multiple esc environments, Its been suggested to sync the throttle range on the esc's. I dont know about the ones your using, but this may be the issue. here is a short video I recall watching they did on syncing two speed controllers on a multi motor edf jet

    Throttle Calibration Video for the Su-34 Fullback.
     

This reply was deleted.