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 :-)
Since 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!
Comments
I see the pandaboard next to the quad... I was thinking of going that direction for 802.11g, but I see that it will not fit at all. The beageboard is going to get a TiW (WLink module) sometime at the end of the month...
Are you going to use the pandaboard?
First successful flight! My mother in law came over and offered to hold the camera for me. This is the first time I've flown a RC aircraft without having to buy new parts afterwards :-)
http://photos.tridgell.net/v/CanberraUAV/arducopter/VID_20110304_13...
hopefully I'll learn how to control it a bit better with a few more flights. I think some time on the simulator would be worthwhile :-)
Hi Jani,
The reason I calibrate with a function hacked into the ACM code and not with my transmitter is that one of my aims is to fly the copter with no RC transmitter. Doug has accepted a patch from me which allows control of the RC input channels over mavlink, and I have a program called mavproxy that allows me to precisely control the PWM values of each channel using a keyboard.That program has commands like "arm", "disarm", "throttle N", "roll N" etc, and can also control flight modes by doing things like "switch 3" to switch to flight mode 3.
The UAV project I'm involved in needs completely automated flight, with control from a ground station at a range well beyond what a normal 2.4GHz RC transmitter can do. That project is using a plane, but I'm testing out the software with my copter.
I'm now quite happily flying my copter in stable or FBW mode with keyboard control, with commands going over mavlink via an Xbee. So far its flying within a little "string prison", but it will soon be let off its leash (I'd like another person to be getting a movie of it when I first take off, which is why I'm not out flying it now).
The principal problem I had with calibration was the timing. I waited too long after the initial beeps when calibrating before dropping the PWM values being sent to the motors. I didn't recognise the little sing song beep series that I heard as "ESC is entering programming mode", and assumed that it was the right set of beeps for setting throttle range. It all became clear when I carefully read the ESC manual and realised that the procedure for entering ESC programming mode and the procedure for doing throttle calibration is so similar - it just differs by timing.
It might be an idea to have a mp3 of the noises that the ArduCopter ESCs make for setting throttle range, and the noise that it makes when entering programming mode on the ESC calibration page on the wiki. I'm sure someone else will eventually hit the same problem as me :-)
Cheers, Tridge
No problems, our pleasure.
On ACM code ESC calibration goes in the way that you naturally take propellers off. Go to setup mode and calibrate first your Radio then you can start 'motors' test function.
While motors test is running, disconnect your battery, put full throttle from your radio, connect battery, wait normal ESC reboot tilutilulei sounds and that after that there will be double Beep Beep sound. Now move your throttle to minimum and ESC's should say Beeeep.
Calibration is done. After that you can start playing with motor finder feature and test that all motors are spinning equal speed. This calibration procedure works with official ArduCopter ESC's, it might work with some others too but not with all.
If you move your right stick to up (pitch down) front motor starts, stick to left (ail left) and left motor starts and so on. This stick order is naturally for Mode 2 radios so you need to test it on your radio.
You might want to try Mode 2 due it's easier for Heli's. But if you are confident on flying with Mode 1, use it.
I hope you have many happy flights with your ArduCopter.
Thanks Jani, I'll put the dome center the right way up. Unfortunately using the ublox means it doesn't fit snugly like the mtek would. I initially ordered a mtek, then in my eagerness to open my nice box from jdrones I must have thrown it out with the packing peanuts! The mtek was then out of stock, so I went for a ublox, and now open jdrones boxes more carefully :-)
On the props, I did do initial testing without props, and I thought it was all behaving as described in the manual, but obviously my ESC calibration was all wrong. For someone like me who hasn't flown RC gear before I guess my ear just isn't used to telling motor speeds apart.
Anyway, the copter now hovers quite nicely while tied down to the paint tin with string, and it does reasonable pitch, yaw and roll within the constraints of the string, so I think it is time to let it out of its prison and fly properly. First I'll hack the ArduCopterQuad code to support throttle on the right of the transmitter for arming though - on the advice of the local model club, my transmitter is setup for planes in Australia which use mode1.
btw, thanks for all your efforts in putting this kit together. Best birthday present I've had in a long time :-)
Andrew, your dome center is upside down.. You cannot mount your GPS under that ring.. just as a hint. And yes you should never mount propellers while testing your quad, something can always go wrong.. Trust me, I know :)
yep, same ESC, but different motor, and I use 12x45 props.
Interesting idea to put a scope on the ESC output! I can use a scope from the local hacker space on Saturday to try this.
For the RPM measurement, I am hoping to do this with props removed, assuming the sticker on the motor gives enough contrast for the tachometer to get a fix. I'm not sure how good the cheap ebay tachometers are :-)
Something else I can try for cal is to put a scope probe on the ESC outputs. That at least can give me a numeric translation from pulse width input to motor speed. I was hoping to do this with Prop removed, but I think a tach is actually more accurate for loaded speed.