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!