Quadcopter – home made


29 Mar 2011 – V2 is here !

Latest and greatest version, not that light but not too heavy either...

Quadcopter V2

Now I know it was all useless, but until 2 days ago, I still thought the only problem with my quad was the frame/motors and the huge vibrations they generated…

2 days ago, on Sunday night, I finally had the courage to face the truth : it could be my fault, it could be my code ! πŸ™‚

Actually while looking at theΒ http://www.multiwii.com/ site (huge thanks Alexandre, and really great stuff !!!) it occurred to me that their code should support my configuration out of the box.

To be honest, I’ve always though that it might be a problem with my code, but the only options to check this would have been:

  1. buy an ardupilot or some other verified system and install it
  2. modify the ardupilot or some other verified code to make it run on my configuration

None of the above options were easy and they could have introduced new problems by themselves…

But the multiwii code, looked like it should work with barely a few lines of change !!!

And indeed it WORKS ! Or at least it balances muuuuch more steadily on 1 axis !

This seems to prove that while I do have quite a lot of vibrations they don’t stop the quad from flying.

I still don’t know what the exact problem was with my code, I will have a look into the details once I manage to fly for real with the new code…

For now, here are some pictures of the whole re-factoring to V2, while I still though it was a mechanical problem:

Dismount the quad, show all the pieces

New frame with carbon fibre centre plates

Foam tape for IMU

IMU (Razor 9DOF + Wii motion plus) on foam tape

The Arduino is in place too...

Front & rear motor mounts - adjustable angle

Left & right motor mounts - fixed angle

5 Mar 2011

Final version, outside...

First …. and last flight…

Last night I “finished” balancing the “beast” on the pitch axis… I put “finished” between quotes, as I’m not too happy with the result, it’s definitely less stable than on the roll axis… I’m not sure why, but it seems that 1 of the motors on this axis (the front one) vibrates much more than the others…

I can’t wait any more, I need to see it flying…

But firstly, I need to weigh it…

Final weigh, before combat...

After a few attempts to take off, in which it would start to flip over, I decided I had had enough, I have attached it to the floor with a cord of approx 1.5m length, and then went to half throttle…. !

And here’s the result, it flipped and crashed IMMEDIATELY !

One propeller is broken and 3 motor mounts are bent…

After the crash...

This is the end for now, as I feel I need a break before starting again “from scratch”… un-mount the motors, replace the propeller, re-start balancing on each axis, and worse of all, deal with vibrations, which I think are too big…Β Right now, I don’t feel like starting replacing motors again…

All mounted ! ready for a 1st pseudo-flight test (no taking off, just spinning the propellers...;) )

27 Feb 2011

Balancing video 1 and video 2.

After a well deserved break, due mainly to week-ends being busy with other stuff like city breaks and skiing, here I am, back to work… as my wife said the other day “I’m not a quitter” πŸ™‚

Finally, after plenty of issues, both frustrating andΒ intellectuallyΒ challenging, I managed to have a IMU board, composed of the burned Razor 9DOF IMU and a Wii Motion Plus for gyroscopes, both glued together. This was actually the state in which I left the project more than 1 month ago…

So pretty much the same state as before I burned the IMU…:) but a lot wiser myself, especially that I’ve now realised that the un-responsiveness problem was coming from the fact that the DCM transformation smooths the variation of the angle to reduce noise.Β Β Which is all very good and actually the whole purpose of the DCM thingie, but you need something more reactive for proper balancing.

Hence using the RAW GYROS data for the D term of the PID control algorithm.

I now have much better results, with the raw data is used for the D term for “stiffness”: the gyros don’t tell you if you’re in the right position, but stop the aircraft from moving to quickly, giving it some sort of “inertia”.

The Euler angles obtained from the DCM transformation are used to keep the whole at a given angle (passed to the P and I terms). They react slowly, and that’s ok, you want a smooth transition when you turn left or right…

It’s still not flying for real, but I can now feel that moment approaching, and hence started worrying about practical issues like knowing when the battery is getting low, as there’s nothing worse that this happening in mid flight… πŸ™‚

So with 3 resistors and 1 available analog port, I’ve programmed a voltage monitor. The only silly issue is that I can’t make any noise to signal this to the user, as the tone() function in Arduino uses the timer2, which is already used for getting the PPM signal from the remote (you don’t want to know how many hours I lost on this silly problem, wondering why the remote signal wasn’t working…;( lol…).

The plan right now is :

  1. make it fly with the hardware that is has right now, buy adding the pitch and yaw PID (using the Razor board magnetometer for the yaw drift correction)
  2. add another board (maybe the initial .net Fez Domino) as a “master controller” to monitor the battery, make noises, have an US distance sensor, etc. … Actually even before flying, I know that taking off and especially landing are the most difficult parts, so an auto-pilot for these 2 would be great !

Also, worth noting, that I had to change the board with another one that has an Atmega328 on it, as the code went beyond the 16KB mark (I’m programming it using an ISP programmer rather than the default Arduino serial protocol, to save the ~2KB occupied by the Arduino bootloader).

8 Jan 2011

This is the end…

As I said a few days ago, this new year’s resolution was to replace the FEZ board with a simple AtMega168 and check that my balancing problems are not coming from the .net micro framework not being real time…

After a lot of time spent in hacking the Razor IMU 9DOF to connect directly to its I2C bus (as the AtMega has only 1 serial port which I want to use for debugging) everything was looking good…

I wired everything together, basically :

– the main AtMega168 controlling the ESC and the PPM signal from the FM receiver and connected as slave to the I2C bus

– the Razor IMU doing the exact same thing as before, being the master of the common I2C bus and sending data through it to the main board

And … the balancing is as bad as before…

So the problem must be either :

– the very sensors on the Razor IMU (too sensitive to vibrations as one guy was saying on the internet)

– or, the data transformations done on the Razor which basically smoothens too much the data from the sensors, and makes the quad not reactive enough

I can’t do anything about the former, so let’s try and look if it’s the latter… I started updating the firmware on the IMU to basically make it output the raw data from the gyros too… but all of a sudded it stopped working… yes, that’s it, I have no idea what happened, no smoke nothing…

I’ve subsequently tried and managed to successfully access both the accelerometer and the magnetometer on the Razor board, directly through the I2C bus, so it looks like it’s the AtMega328 on the Razor board that is broken… so frustrating…

Here is the latest version of the Arduino code (and some C++ code to have objects for ESCs and PID controllers),Β  in case anybody finds this useful:

– ESC signal

– PID controller (or some very basic form of it)

– PPM signal decoder from the FM receiver

– I2C data retrieval from the Razor IMU

ESC.h

#ifndef ESC_h
#define ESC_h

#include "WProgram.h"
#include <Servo.h>
#include "util.h"

#define MIN_US 1000
#define MAX_US 1900
#define THROTTLE_RANGE 1000

class ESC {
private:
 Servo _servo;

public:
 void attach(byte);
 void setThrottle(int);
};

void ESC::attach(byte pin){
 _servo.attach(pin);
 // arm it lower than the min, so that the motor start spinning immediately a min + little
 _servo.writeMicroseconds(MIN_US - 100);
 delay(2000);
};

void ESC::setThrottle(int throttle){
 // Formula ((MaxPulse - MinPulse)/(MaxThrottle - MinThrottle)) * realThrottle + MinPulse
 _servo.writeMicroseconds(scale(throttle, 0, THROTTLE_RANGE, MIN_US, MAX_US));
}

#endif

PID.h

#ifndef PID_h
#define PID_h

#include "util.h"
#include <math.h>

class PID {
private:
 double _setPoint, _lastErr, _err;
 double _P, _I, _D, _integralErr, _result;

public:
 void init(double, double, double);
 void setPoint(double);
 double doPID(double, double);
};

void PID::init(double p, double i, double d){
 _P = p;
 _I = i;
 _D = d;
}

void PID::setPoint(double newSP){
 _setPoint = newSP;
}

double PID::doPID(double procVar, double dt){
 _err = cstrain(procVar - _setPoint, -30.0, 30.0);
 _integralErr = cstrain(_integralErr + _err * dt, -50.0, 50.0);
 _result = _P * _err + _I * _integralErr + _D * (_err - _lastErr) / dt;
 _lastErr = _err;
 return _result;
}

#endif

util.h

#ifndef util_h
#define util_h

#include <math.h>

int modulo(int input, int minimum, int maximum){
 if (input < minimum) return modulo(maximum - (minimum - input), minimum, maximum);
 if (input > maximum) return modulo(minimum + (input - maximum), minimum, maximum);
 return input;
}

int cstrain(int input, int minimum, int maximum){
 if (input < minimum) return minimum;
 if (input > maximum) return maximum;
 return input;
}

double cstrain(double input, double minimum, double maximum){
 if (input < minimum) return minimum;
 if (input > maximum) return maximum;
 return input;
}

int scale(int input, int inMin, int inMax, int outMin, int outMax){
 return (int)lround(((cstrain(input, inMin, inMax) - inMin) / (double)(inMax - inMin)) * (outMax - outMin)) + outMin;
}

#endif

radio.pde (PPM)

#define PPM_PINΒ Β Β  Β 2Β Β Β Β Β Β Β Β Β  // External Interrupt 0 - Input Capture Pin (PPM Rx signal reading)
const byte TIMER_MULT = 16;Β Β Β Β Β Β Β  // has to correspond to the prescaler we set in TCCR2B
#define TIMER_COUNT TCNT2
#define MIN_IN_PULSE_WIDTH 750Β  //a valid pulse must be at least 750us
#define MAX_IN_PULSE_WIDTH 2250 //a valid pulse must be less thanΒ  2250us

volatile int8_tΒ  _rx_ch = 0;
volatile unsigned int _pulses[MAX_CHANNELS + 1];Β  // pulses width in ticks for performance

void setup_radio(){
 // PPM signal initialisation
 pinMode(PPM_PIN, INPUT);

 // TIMER 2Β Β  Pins 5 & 6Β  will have PPM disabledΒ  TCNT2 increments every 16uS
 TCCR2A = 0x00;
 TCCR2B = 1 << CS22 | 1 << CS21; // prescaler /256 (16MHz => 16usec)
 TIMSK2 = 1 << TOIE2; //Timer2 Overflow Interrupt Enable

 // whenever there is a raise in the PPM signal, deal with it
 attachInterrupt(0, changeInSignalISR, RISING);
}

// Timer2 Overflow
ISR(TIMER2_OVF_vect){
 // turns out that with our prescaler, the timer gets overflown every 4ms (8 bit counter so 256 x 16 us each tick = 4096. So every 4096us the counter gets re-set...)
 // which is definitely more than a normal pulse, so we can consider this as a sync gap, between a new PPM signal
 _rx_ch = 0;
}

void changeInSignalISR(){
 if(_rx_ch >= 0) _pulses[_rx_ch ++] = TIMER_COUNT;
 // always re-init the times as we always start counting "something" on a rising change
 TIMER_COUNT = 0;

 // this should be the last pulse, don't accept oter pulses until we get a new SYNC signal
 if(_rx_ch > MAX_CHANNELS) _rx_ch = -1;
}

int rxGetChannelPulseWidth( uint8_t channel){
 unsigned int result = _pulses[channel] * TIMER_MULT; // do the multiplication only now when it's requested, for performance

 // Out of range?
 if ((result > MIN_IN_PULSE_WIDTH) && (result < MAX_IN_PULSE_WIDTH))Β  return result;
 else return -1;
}

boolean isPulseDifferent(int pulseA, int pulseB){
 int delta = pulseA - pulseB;
 return delta < -30 || delta > 30;
}

RazorIMU.pde

#include <Wire.h>

#define I2C_SLAVE_ADDR 0x2A
#define MSG_SIZE 29
byte _buff[MSG_SIZE], _ck;

void setup_RazorIMU(){
 Wire.begin(I2C_SLAVE_ADDR); // start as slave
 Wire.onReceive(IMUDataHandler); // what to call when new IMU data has arrived
}

void IMUDataHandler(int numBytes){
 _imuDataStatus = -1;

 if(MSG_SIZE == numBytes) {
 for(uint8_t i = 0; iΒ  < MSG_SIZE; i++) _buff[i] = Wire.receive();

 // the checksum is simply the sum module 256 of all the data (excluding itself πŸ™‚ )
 _ck = 0;
 for(uint8_t i = 0; i < MSG_SIZE - 1; i ++) _ck += _buff[i];

 // last byte is the check sum, it should match !!!
 _imuDataStatus = -2;
 if (_ck == _buff[MSG_SIZE - 1]){
 _roll = getDoubleFromArray(_buff, 0);
 _pitch = getDoubleFromArray(_buff, 4);
 _yaw = getDoubleFromArray(_buff, 8);

 _gyroX = getDoubleFromArray(_buff, 12);
 _gyroY = getDoubleFromArray(_buff, 16);
 _gyroZ = getDoubleFromArray(_buff, 20);

 _magHeading = getDoubleFromArray(_buff, 24);

 // data updated correctly
 _imuDataStatus = 1;
 }
 }
}

double getDoubleFromArray(byte buff[], byte pos){
 long temp = buff[pos + 3];
 temp = (temp << 8) | buff[pos + 2];
 temp = (temp << 8) | buff[pos + 1];
 temp = (temp << 8) | buff[pos];
 return temp / 10000.0;
}

quadcopter.pde

#include <Servo.h>
#include "ESC.h"
#include "PID.h"

#define MAX_CHANNELSΒ Β Β  4Β Β Β Β Β Β  // Number of radio channels to read. Has to be <= to what the receiver outputs in its PPM signal

double _roll, _pitch, _yaw, _gyroX, _gyroY, _gyroZ, _magHeading;
int _imuDataStatus = -9;
int currValue, i;

int _radioValues[MAX_CHANNELS];

ESC _frontESC, _rearESC, _leftESC, _rightESC;
PID _rollPID, _pitchPID, _yawPID;

double rPID, pPID, yPID;
long currMicros, prevMicros;
double dt, throttle = 70;

void setup(){
 Serial.begin(115200);

 setup_RazorIMU();
 //setup_radio();

 //_frontESC.attach(4);
 //_rearESC.attach(5);
 _leftESC.attach(6);
 _rightESC.attach(7);

 _rollPID.init(3.0, 0.0, 0.0);
 _pitchPID.init(0.3, 0.1, 0.2);
 _yawPID.init(0.05, 0.005, 0.05);

 while(_imuDataStatus != 1) delay(10);
 _imuDataStatus = 0;

 _rollPID.setPoint(_roll);
 _pitchPID.setPoint(_pitch);
 _yawPID.setPoint(_yaw);

 prevMicros = micros();
}

void loop(){

//Β Β Β  // 1. RADIO data
//Β Β Β  for(int i=0; i<MAX_CHANNELS; i++){
//Β Β Β Β Β  currValue = rxGetChannelPulseWidth(i+1);
//Β Β Β Β Β  if(isPulseDifferent(currValue, _radioValues[i])){
//Β Β Β Β Β Β Β Β Β  _radioValues[i] = currValue;
//Β Β Β Β Β  }
//Β Β Β  }

 int ch = Serial.read();
 if(ch >= 0) {
 double newP = (ch - 48) / 100.0;
 _rollPID.init(0.03, 0.0, newP);
 Serial.println(newP);
 }

 // 2. IMU data
 if(_imuDataStatus == 1){
 _imuDataStatus = 0;

 // 3. TIME management
 currMicros = micros();
 dt = (currMicros - prevMicros) / 1000000.0;
 prevMicros = currMicros;

 // 4. PID control
//Β Β Β Β Β Β Β  rPID = _rollPID.doPID(_roll, dt);
//Β Β Β Β Β Β Β  pPID = _pitchPID.doPID(_pitch, dt);
//Β Β Β Β Β Β Β  yPID = 0;//_yawPID.doPID(_yaw, dt);

 //Serial.print(rPID); Serial.print(" - ");Serial.print(pPID); Serial.print(" - ");Serial.println(yPID);

 Serial.print(dt); Serial.print(" / ");Serial.print(_roll); Serial.print(" - ");Serial.print(_pitch); Serial.print(" - ");Serial.println(_yaw);
 //Serial.print(dt); Serial.print(" / ");Serial.print(_gyroX); Serial.print(" - ");Serial.print(_gyroY); Serial.print(" - ");Serial.println(_gyroZ);

 // 5. MOTORS update
//Β Β Β Β Β Β Β  _leftESC.setThrottle(throttle + rPID - yPID);
//Β Β Β Β Β Β Β  _rightESC.setThrottle(throttle - rPID - yPID);
 //_frontESC.setThrottle(throttle + pPID + yPID);
 //_rearESC.setThrottle(throttle - pPID + yPID);
 }
}

3 Jan 2011

Not much done besides working on the Graupner RC emitter/receiver, except modifying the ESC wires to remove the VCC. The reason is that the Arduino will get its power from elsewhere, and we don’t want the BECs from the 4 ESC to be connected all together.

Removing and isolating VCC from ESC wires

1 Jan 2011

Happy New Year !

New year’s resolution : move away from the super powerful but not real time FEZ Domino board, to a simple ATmega 168 based Arduino.

It’s not clear if this will help, but I’m really not satisfied with the accuracy of the balancing, and as a last resort I’m changing the board…

Most people (this is not to say “many”, as there are few discussions about C# boards for quadcopters) say it’s not good due to C# being managed code and hence the garbage collector kicking in unexpectedly… I’ve timed it, and with “clean” code (ie not too many threads and object creations) the GC kicks in every 5-10 seconds and lasts 3-6ms. This would be more than acceptable, even for a quadcopter… or at least theoretically…

However, I’ve found an interesting discussion about the fact that .net micro framework, uses a hardcoded 20ms interval, to swap threads ! So if you have more than 1 thread (and you will always have, as there must be “hidded” library threads) then the main one piloting the motors for example, will eventually get interrupted every 20ms, and won’t eventually resume for another 20ms or more !

This is NOT acceptable, and MIGHT explain my lousy results with the balancing… or maybe, it’s just my code… wow, I’m keen on finding out !

31 Dec 2010

For once, we’ll stay home during the new year, and will just go out for the night in a club… again, good news for the quadcopter !

It’s been a while since I saw and really liked these “rusty’s” motor mounts : really simple concept and much more adaptable (you can change the position along the arm and especially the angle of the motor, going back to my initial idea of using only 1 type of propellers) and also go well with my (rather less usual) design based on round tubes.

So here’s my own version of the mounts, after having ordered some white Delrin last week:

Cutting the Delrin motor mounts

Finished Delrin motor mounts

They are not so nicely cut, but seem to do the job. Here’s the new test setup, which should teoretically allow me to test balancing on ALL the 3 axis simultaneously…

New test setup (using new motor mounts) with all 3 degrees of freedom

It uses one of these from Farnell :

Ball joint used for the new test setup

28 Dec 2010

Back from Christmas holiday in France with the family… it was nice but too short !

Now I need to test the last balancing, on the yaw axis:

Yaw balancing test setup

Yaw balancing test setup 2

20 Dec 2010

More work on the quad…

 

Custom made headers for servo like connectors (going to Arduino like female headers on the FEZ Domino)

Setup for balancing tests on 1 axis

Here’s finally some proper balancing (not the most stable I admit, but stil…) and remote controlled position and throttle.

And here’s the finalized quadcopter, all mounted and nice, its very first test, all working nicely, BUT not yet flying as the throttle is electronically limited to 25%… I need a full week-end, after coming back from holidays, to have the courage to make it fly for real…

I also have a a feeling that it’s now that the hard part begins, as all the tweaking and crashing will commence ! πŸ™‚

19 Dec 2010

We spend all day yesterday at the airport to go on holiday…Β  but it snowed quite heavily for a few hours here in London, and guess what.. all the flights were cancelled… what a pity ! .. but what a good news for my quad ! This gives me 2 extra days of work on it, before Tuesday when we have our replacement flight.

And after a few more tries, Eureka !!! It does work, the quad can balance with 2 motors… I even managed to connect the IR remote control and control the throttle and direction ! wow…

17 Dec 2010

Too much vibration… or at least that’s what I think the reason for the instability is…

I’ve ordered new motors, and this time I tried to go with the “safest bet”, ie the ones recommended here by seemingly quite knowledgeable people (a BIG thank you guys !) : KDA 20-22L

Today, I managed to solder and mount them

KDA20-22L motors - soldering bullet connectors

New motor fixed on same old but updated mount

and here’s the result: there are definitely LESS vibrations, but it still doesn’t balance… so it’s probably something in my software ! (or the IMU too sensitive or too tightly mounted on the frame, maybe some vibration absorbing foam could help … ?)

IMU Roll, with 2 new motors mounted (KDA 20-22L)

12 Dec 2010

I’m really at a loss as to what the heck is wrong… could either be

1) some stupid problem in the code (unlikely, as there isn’t that much code for a simple PID controller)

I’ve updated the code on the IMU, and now it outpus data as quickly as it can, which is around every 10ms, or roughly twice as fast as previously (50Hz).

2) or, more likely, a problem with vibrations

Here’s a graph of the roll angle as it comes from the IMU (in hundreth’s of degree and roughly every 10ms, but not exactly).

To be honest, it looks OK, there’s some noise but the overall shape is quite clean, the Arduino code on the IMU is doing quite a good job at filtering … !Β  Or so at least I think, as I’m far from being an expert…

Roll angle for around 2000 x 10ms periods

Actually, here’s the same king of graph, his time with NO motors running….

Roll (in 100ths of degrees) by units of 10ms

Can you see how much smoother it is !? You can’t even see the garbage collector (remember this is managed code running on top of .net micro framework) that takes 2-5ms every 3-5 seconds….

Still doesn’t stabilise so today I’ve spent some time building a test wooden frame. Yes it feels quite necessary give the number of times the propellers have already hit my hands or some wires…

Cutting on the terrace... what a lovely day for December in London ... !

Seems like an easy task, but even getting these few bits of wood together at the right angles and solidly screwed together, requires some planning and simple calculations…

Cut, screwed together and sanded...

The final result

11 Dec 2010

The only good news for now, is that I successfully managed to repair the FEZ Domino board, by soldering a new voldtage divider (5V -> 3.3V). Quite ugly, as I’m really bad at surface mount soldering and also there wasn’t much room… anyhow, quite happy to have salvaged this 50Β£ board !

FEZ Domino repaired !

Very frustrating start of the week-end… I’m simply unable to stabilise the frame with only 2 motors on it… no chance it can fly or stabilise with all 4 motors !

Everything attached properly

I also mounted a 2nd motor on the frame, hoping this would help… but to no avail…

Finally mounted a 2nd motor on the frame

6 Dec 2010

my “workshop”… thanks to my wife for not getting mad at me doing all this in our flat…

My "workshop"

5 Dec 2010

It’s Sunday, so I only did some annoying soldering… annoying because I don’t have the high power solder iron required for such thick wires and contacts…

the power rail, using Dean connectors

and another motor connected to its ESC… these are the cheapest motors out there, so come without bullet connector or anything else…

Another motor soldered to its ESC

Also I decided that parsing the strings that the IMU is sending me is not only slow (using String objects and split() in C#) but also generates a lot of objects and garbage collections.

So I modified the Arduino IMU code to output directly binary : 2 bytes for each number roll, pitch and yaw. Les bytes than before and no parsing on the receiver !

  // make everything positive (+ 200 ) and include first 2 decimals ( * 100)
 tempint=(ToDeg(roll) + 200) * 100;Β  //Roll (degrees) * 100 in 2 bytes
 _buffer[0]=tempint & 0xff;
 _buffer[1]=(tempint >> 8) & 0xff;

 tempint=(ToDeg(pitch) + 200) * 100;Β Β  //Pitch (degrees) * 100 in 2 bytes
 _buffer[2]=tempint & 0xff;
 _buffer[3]=(tempint >> 8) & 0xff;

 tempint=(ToDeg(yaw) + 200) * 100;Β  //Yaw (degrees) * 100 in 2 bytes
 _buffer[4]=tempint & 0xff;
 _buffer[5]=(tempint >> 8) & 0xff;

 ck = 0;
 for (int i=0; i<6; i++) {
   Serial.print (_buffer[i]);
   ck += _buffer[i];Β  //Calculates checksum
 }
 Serial.print(ck);

And on the receiver side:

private void ReadSerialPortIntoVariables()
{
  while (true)
  {
     // wait for beginning of message
     while(_buff[0] != '!') _UART.Read(_buff, 0, 1);
     // read the whole
     count = _UART.Read(_buff, 0, 7);

     if (count == 7)
     {
        ck = 0;
        for (i = 0; i < 6; i++) ck += _buff[i];

        // last byte is the check sum, it should match !!!
        if (ck == _buff[6])
        {
           _roll = (_buff[0] | _buff[1] << 8) - 20000;
           _pitch = (_buff[2] | _buff[3] << 8) - 20000;
           _yaw = (_buff[4] | _buff[5] << 8) - 20000;
        }
     }
   }
 }

4 Dec 2010

One week later and I’ve decided that the structure of the frame has unnecessary complexity and weight to it.

Here’s the new result after some more hole drilling and aluminium profile cutting… I think I’ve had enough of this for now…

New lighter frame

Frame with the Razor IMU and the FEZ Domino stacked

Things are coming nicely together, it’s lighter than before, sturdier and has this lunch box that can be closed hermetically to protect the electronics inside.

Here is the first everΒ  balance test ! … didn’t work obviously, it’s really hard to balance with only 1 motor, there’s too much inertia and momentul…

First ever (unsuccessful) balance test

Then, things got less funny when I burnt my FEZ Domino card ! I was preparing for buying a new one, hesitating between a FEZ Panda and Netduino to be more exact, as the Domino is quite expensive, when I realised that I only burnt 5V-3.3V regulator as I was powering it on its 5V output (which I assume was a mistake πŸ™‚ ).

Anyhow, after 20 minutes of pain to de-solder the surface mounted LM1117MP-3.3, I’ve now already ordered it from farnell.com, so should be able to fix everything this week.

For now, the board still works if I supply it directly into the 3.3V line… which I do, from 3 AA batteries.

Burnt voltage regulator - LM1117MP-3.3

27 Nov 2010

It’s past midnight now… after a full day of work on this project, I deserved some rest… I went to the pub in Edgware Road to meet a friend around some food and 2 Hoegardens, and then back to work…

Now it’s time to solder some more motors to their ESC… but, something is wrong, the motor makes strange noises and doesn’t turn…

Oops... the ESC has some problems...

Have no idea what the problem was... is it the ESC that was defective ? or the motor ? Or neither, and it's because I did something wrong .... ?

Finally Saturday ! This whole week-end is dedicated to building !

I’m so excited that I wake up at 6am ! I start by preparing the tools (drill, saw, screw drivers, etc. …). The initial plan is to work on the terrace, but after the first 20 minutes I realise that when it’s < 0Β°C your fingers become numb and it’s impossible to do any delicate mechanical work. So I move back inside, with the vacuum cleaner next to me, to limit the impact πŸ™‚

Preparing the workbench

I literally have not seen the first 6 hours flying by… when the first items started to be finished, it was already 1pm…

Motor mounts (4 of them, not yet separated)

Same mounts, after separation, together with 1 of the 2 main tubes

First test of a motor mounted

Pieces for the nacelle (which serves to rigidify the structure too)

The nacelle being screwed together

The main tube structure, the mounted nacelle and 1 motor mounted

26 Nov 2010

It’s Friday night and instead of being at the pub I’ve just stopped by HomeBase, bought a 1m aluminium tube, some profiles and other tools and now I’m measuring and preparing for this week-end-s cut session…

Measuring for the Aluminium frame

25 Nov 2010

Things start to move…

First, one entire evening spent to learn how to deal (charge) with LiPo batteries… I didn’t realise one had to be so careful !

Also it was a pain tu cut the initial plug and re-solder a Deans connector instead (was really afraid of shorting the charged battery in the process)

Charging a LiPo battery can be confusing...

Then let’s do the 1st test: control a motor using its ESC which in turn is controlled by the FEZ Domino

FEZ Domino -> ESC -> Brushless Outrunner Motor

24 Nov 2010

Youpi !!! I don’t know others, but when I receive stuff ordered from the internet, it feels like Christmas… πŸ™‚

The stuff I ordered on Sunday has already arrived (actually it arrived yesterday, but at my office and I was working from home…:) Thank you both guys from coolcomponents and giantcod, they are really great with their deliveries !!! )

First the 9DOF Razor IMU made by SparkFun and ordered from Coolcomponents :

3 gyros & 3 accelerometers & 3 magnetometers

Then, here’s the list of stuff that I ordered from Giantcod :

5Β x Male JST connector 12cm long silicon wire Β£3.35
1Β x New Deans XT style Ultra connector Plugs x 10 pairs Β£3.85
5Β x Female JST connector 12cm long silicon wire Β£3.35
1Β x G.T. Power A606 charger Β£31.51
8Β x TGY Slow Fly Prop 9*4.7SF w/ shaft adapters Β£6.40
1Β x 5C Charge Loong max Tipple Lipo Battery 2300 3S1P 20C-30C Β£15.67
6Β x SP 18A ESC Speed controller Β£32.10
6Β x Towerpro Brushless outrunner 2410-12T 1000kv 12A Β£27.00
1Β x GTA6/IMax/Turnigy 5A Charger Adapter and Lead Β£6.36

All the RC stuff from giantcod.co.uk

23 Nov 2010

Aluminium Profiles Mounted

Aluminium Profiles Cut and Drilled

It’s Tuesday and I can’t wait any more… I go to Homebase and buy some aluminium profiles. Cut and drill them and create an + shape… it will turn out they are not rigid enough, and the more I read about quadcopters the more it seems that vibrations are a big danger !

21 Nov 2010

Dismounting a Syma S026 (infra red controlled) toy helicopter

It’s Sunday… this past week I discovered that one of my work colleagues isΒ impassionedΒ aboutΒ quadcopters… these are sort of 4 fixed rotors helicopters… much simpler mechanics, but much more complex electronics as mechanicallyΒ unstableΒ and hence need Β continuous re-balancing…

I had already seen a few videos of these beasts but always thought it was “not my cup of tea”… now we decided we should build one together as my colleague is interested more into the programming side whereas I’m more into the electronics / mechanics of the device.

It’s Sunday evening, and all I can do is dismount a toy helicopter, hoping that I could re-use its propellers (and the ones from another identical toy) to do a prototype… too complex and too small finally…

I’ve also already ordered RC stuff (motors, ESC, propellers, etc. …) from giantcod.co.uk. It’s hard to get into this all of a sudden, without much prior knowledge…

The 9DOF Razor IMU from SparkFun is also ordered.

10 Responses to Quadcopter – home made

  1. Bhaumik says:

    Woow, Great dedication buddy.
    I wanted to know that which code is to be updated on RazorIMU 9DOF interms of receiving data from IMU back to the main controller.
    You have shared RazorIMU.h that is on receiver side. What is on the IMU side to be coded..?
    Thank You,
    Bhaumik Khamar

  2. Alonso says:

    I’m new to RC and purchased the same motors from hobbyking.
    When I got the motors I dint expect the outside of the body to turn.
    I noticed that you have tried both a downward mount using the rubbers and a top mount.
    It looks like the top mount is more stable.
    I was wondering, what type of props you are using or what type of props you recomend?

    • trandi says:

      I guess you’re talking about the KD 2213-22T 17A 924Kv motors…

      This is why they are called OUTrunners πŸ™‚
      Actually I have NOT noticed any difference in stability due to the UP / DOWN mounting. The reason for different mountings was purely mechanincal, and to do with my choice initially of not drilling a big hole in the chassis tubes, etc. …

      I’m currently using 9×4.7 slow flyers and have also tried 12×3.8 ones which turned out to be too big…
      BUT I think the manufacturer recomends 11×5.5 E-prop, check on the hobbyking website. I think that as long as you’re not too far away from specs and don’t push them to the limit it should be ok.
      Also I think that the smaller they are, the more agile… but don’t quote me on this, as there’s a whole quite complex theory around motors/propellers combination and best choice.

      hope this helps,
      dan

  3. Pingback: Kalman filter – simplified version « Robotics / Electronics / Physical Computing

  4. pete wright says:

    Hi Have you tried contra rotating props ,could be torque that is causing your problems.

    • trandi says:

      YES. It doesn’t change anything.
      Torque is taken care of anyhow by the fact that 2 of the motors are mounted at an angle. This has the same effect as having 2 counter rotating propellers (with some loss of efficiency that you get for free πŸ™‚ ).

      dan

  5. Pingback: Motor vibrations « Robotics / Electronics / Physical Computing

  6. Pingback: Wii Motion Plus gyros on LM3S8962 (I2C on CooCox) « Robotics / Electronics / Physical Computing

  7. Pingback: Razor 9DOF IMU – I2C to Arduino « Robotics / Electronics / Physical Computing

  8. zerov83 says:

    Hey, just saw your comment on my blog.
    Nice job!
    Wanna share your code? I’m very interested in how you did the first balancing.
    Maybe we could join. =)

Leave a comment