How To Make RC Quadrotor Helicopter Part - 2


Step 10Preparing the Microcontroller

Preparing the Microcontroller
i
If you don't have the Arduino IDE, download it and install it. I am using version 0022.

This page is just a really short summary of what is already in the above wiki article!

The Arduino bootloader should be programmed into the microcontroller first. This step requires the use of an AVR programmer. However, after the bootloader is flashed into the microcontroller, you will only need an USB-to-serial cable (such as an FTDI cable) to upload code from the Arduino IDE.

The bootloader (I've attached it) is modified slightly since I'm using the ATmega644P instead of the usual Arduino's ATmega328P. The files are provided. The fuse-bits need to be written to the correct values as well.

AVRDUDE is the utility that we use to flash the bootloader .hex file into the microcontroller. The AVRDUDE commands you'll need is

"avrdude -c programmer_name -p atmega644p -U flash:w:bootloader_filename.hex -U lfuse:w:0xFF:m -U hfuse:w:0xD8:m"

Pay attention to the programmer_name and the bootloader_filename! The fuses are to get the ATmega to use the 16 MHz resonator, set the bootloader size, enable the bootloader, disable JTAG and enable SPI downloading.

Also copy the bootloader folder "Ro4Copter_Boot" (remember to rename it without the date version) as .../arduino-0022/hardware/arduino/bootloaders/Ro4Copter_Boot.

Also, download the Arduino "core" I've provided here (called Ro4Copter_Core, remember to rename it without the date version), and place it into the "core" directory within Arduino so you get .../arduino-0022/hardware/arduino/cores/Ro4Copter_Core . Also modify the boards.txt file to include an entry to use this core. This will allow the Arduino IDE to compile for the ATmega644P instead of the original Arduino's ATmega328P. Be sure to select the correct board entry inside the Arduino IDE menus. For more details on this step, check out the wiki page I linked above.

The board.txt entry:
Ro4Copter.name=Ro4Copter
Ro4Copter.upload.protocol=stk500
Ro4Copter.upload.maximum_size=57344
Ro4Copter.upload.speed=57600
Ro4Copter.bootloader.low_fuses=0xFF
Ro4Copter.bootloader.high_fuses=0xD8
Ro4Copter.bootloader.extended_fuses=0xFF
Ro4Copter.bootloader.path=Ro4Copter_Boot
Ro4Copter.bootloader.file=Ro4Copter_Boot_arduino.hex
Ro4Copter.bootloader.unlock_bits=0x3F
Ro4Copter.bootloader.lock_bits=0x0F
Ro4Copter.build.mcu=atmega644p
Ro4Copter.build.f_cpu=16000000L
Ro4Copter.build.core=Ro4Copter_Core


Here's a screenshot to show you where all these folders are:

The sketch you need to compile is provided in step 26. Compile it and upload it to the ATmega644P using the bootloader later.

The next few steps will help you understand what exactly the code is doing. Skip them if you don't care.

Step 11Explaination of Source Code

Explaination of Source Code
i
As with all Arduino sketches, there is a setup routine and a main loop. The setup initializes everything, and the main loop performs the input, calculation, and output.

The PWM signals from the RC radio receiver is taken in using "pin change interrupts". When the voltage on the input pin changes, the interrupt routine is called, and a time stamp is taken. The pulse width is calculated from the differences between the time stamps.

The PWM signal output to the ESCs is generated using several timers with "compare match outputs", which means the pulse width is set, and the timer will automatically pulse the pin for the set period of time.

The sensors communicate using the I2C bus, which is a synchronous data bus that has excellent support for multiple devices communicating using only 2 wires.

The main loop is divided into tasks, each of which is executed at a different frequency. This gives each task a priority. The code that keeps the quadcopter stable has the most priority. Stuff like communicating with the computer has less priority. It is possible for you to add GPS navigation code if it is given lower priority.

The later steps will have demonstrations that specifically demonstrate each technique and technology individually.

Step 12Arduino Demo: PWM Input

Arduino Demo: PWM Input
i
  • radio_signals.PNG
  •  
  • servo-signal-explaination.png
  •  
  • DSC07418 (Small).JPG
  •  
  • pwmindemo_screen.PNG
Here is a Arduino sketch that shows you exactly how pin-change-interrupts and a timer is used to read in pulse widths from several signal wires. Whenever a change in pin state is detected, the interrupt vector records a timestamp using the timer, and the difference between timestamps is the pulse width.

Also I've attached a logic analyzer screenshot to show you what the signals from my RC radio receivers look like. Each one of those pulses have a pulse width between 1000 and 2000 microseconds, the period is about 20 milliseconds.

For more information, research:
  • PWM
  • Servo Signals
  • ISRs in AVR (Interrupt Service Routine)
  • PCINT, Pin Change Interrupt
  • 16 bit timers in AVR


Here is the code:

void setup()
{
  DDRC = 0; // pins as input

  // enable PCINT 18 to 23
  PCICR |= (1 << PCIE2);
  PCMSK2 = 0xFC;

  Serial.begin(115200);
}

typedef struct {
  byte edge;
  unsigned long riseTime;
  unsigned long fallTime;
  unsigned int  lastGoodWidth;
} tPinTimingData;
volatile static tPinTimingData pinData[6 + 1];
volatile static uint8_t PCintLast;

ISR(PCINT2_vect)
{
  uint8_t bit;
  uint8_t curr;
  uint8_t mask;
  uint32_t currentTime;
  uint32_t time;

  // get the pin states for the indicated port.
  curr = PINC & 0xFC;
  mask = curr ^ PCintLast;
  PCintLast = curr;

  currentTime = micros();

  // mask is pcint pins that have changed.
  for (uint8_t i=0; i < 6; i++) {
    bit = 0x04 << i;
    if (bit & mask) {
      // for each pin changed, record time of change
      if (bit & PCintLast) {
        time = currentTime - pinData[i].fallTime;
        pinData[i].riseTime = currentTime;
        if ((time >= 10000) && (time <= 26000))
          pinData[i].edge = 1;
        else
          pinData[i].edge = 0; // invalid rising edge detected
      }
      else {
        time = currentTime - pinData[i].riseTime;
        pinData[i].fallTime = currentTime;
        if ((time >= 800) && (time <= 2200) && (pinData[i].edge == 1)) {
          pinData[i].lastGoodWidth = time;
          pinData[i].edge = 0;
        }
      }
    }
  }
}

void loop()
{
  Serial.println();
  for (byte i = 0; i < 6; i++) {
    Serial.print("C");
    Serial.print((int)i + 1);
    Serial.print(": ");
    Serial.print(pinData[i].lastGoodWidth);
    Serial.print(", ");
  }

  delay(500);
}

Step 13Arduino Demo: PWM Output

Arduino Demo: PWM Output
i
  • servo-signal-explaination.png
  •  
  • pwmoutdemo_logic.png
Attached is an Arduino sketch that shows you how our code generates PWM signals so each ESC knows how fast to spin the motor.
The timer compare output feature of the timer is used to generate PWM signals. When the timer reaches 0, it turns on a pin, when it reaches a certain number (that we specify), it turns off the pin. This generates a square wave with a variable duty cycle.

Although normal servo signals usually have a period of about 20 ms (meaning a frequency of about 50 Hz), the output from our microcontroller have a shorter period (thus a higher frequency, about 250 to 300 Hz). The Turnigy Plush ESCs (and the HobbyKing brand clones) have been reported to be able to handle the higher frequency, and thus more adjustments in motor speed can be made per second, therefor the quadrocopter will become more stable.

I've also attached screenshots from my logic analyzer to show you what the 4 signals look like.

Here is the code:

#define PWM_FREQUENCY 300 // in Hz
#define PWM_PRESCALER 8
#define PWM_COUNTER_PERIOD (F_CPU/PWM_PRESCALER/PWM_FREQUENCY)

void setup()
{
  // pins as output
  DDRD |= (1 << 4) | (1 << 5) | (1 << 6) | (1 << 7);

  // default to 1000 microsecond pulse width
  OCR1A = 1000 * 2 ;
  OCR1B = 1000 * 2 ;
  OCR2A = 1000 / 16 ;
  OCR2B = 1000 / 16 ;

  // the setup is:
  // Clear OCnA/OCnB on compare match, set OCnA/OCnB at BOTTOM (non-inverting mode)

  // setup timer 1
  TCCR1A = (1<<WGM11)|(1<<COM1A1)|(1<<COM1B1);
  TCCR1B = (1<<WGM13)|(1<<WGM12)|(1<<CS11);
  ICR1 = PWM_COUNTER_PERIOD;

  // setup timer 2
  TCCR2A = (1<<WGM20)|(1<<WGM21)|(1<<COM2A1)|(1<<COM2B1);
  TCCR2B = (1<<CS22)|(1<<CS21);
  // the period is fixed for timer 2, it's about 244 Hz

  // note that timer1 is a 16-bit timer and timer2 is a 8-bit timer
}

void loop()
{
  int pw;
  for (pw = 1000; pw <= 2000; pw += 20)
  {
    OCR1A = pw * 2 ;
    OCR1B = pw * 2 ;
    OCR2A = pw / 16 ;
    OCR2B = pw / 16 ;
    delay(10);
  }

  for (pw = 2000; pw >= 1000; pw -= 20)
  {
    OCR1A = pw * 2 ;
    OCR1B = pw * 2 ;
    OCR2A = pw / 16 ;
    OCR2B = pw / 16 ;
    delay(10);
  }
}


Other nice pages to read:

Step 14Arduino Demo: Sensor Reading

Arduino Demo: Sensor Reading
i
  • arduinodemosensorreading.png
  •  
  • sensordemo_screen.PNG
  •  
  • i2c_waveform_screen.png
This step contains an Arduino sketch that will take readings from the two sensors (BMA180 accelerometer and ITG-3200 gyro).

These two sensors are connected to your microcontroller using a I2C bus. This type of bus is designed to allow multiple devices to communicate together using only two wires.

I've also attached the logic analyzer waveforms of the I2C bus signals. (both screenshot and Saleae Logic 1.1.8 session file)

For more information:
The flight controller software will initialize the accelerometer by first resetting it, then setting up a 10 Hz low-pass filter and setting the read range to +/- 2 G. Read its datasheet and see my demo code for more details about how to do this. There are other features such as interrupts, tap detection, etc, that we are not using.

The flight controller software will initialize the gyro sensor by first resetting it, then setup its 10 Hz low-pass filter, and telling it to use its own internal oscillator. Read its datasheet and see my demo code for more details about how to do this. This sensor allows you to use an external oscillator and also has digital temperature outputs, but we don't use those features.

Here is the code:

#include <Wire.h>

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

  Serial.println("Demo started, initializing sensors");

  AccelerometerInit();
  GyroInit();

  Serial.println("Sensors have been initialized");
}

void AccelerometerInit()
{
  Wire.beginTransmission(0x40); // address of the accelerometer
  // reset the accelerometer
  Wire.send(0x10);
  Wire.send(0xB6);
  Wire.endTransmission();
  delay(10);

  Wire.beginTransmission(0x40); // address of the accelerometer
  // low pass filter, range settings
  Wire.send(0x0D);
  Wire.send(0x10);
  Wire.endTransmission();

  Wire.beginTransmission(0x40); // address of the accelerometer
  Wire.send(0x20); // read from here
  Wire.endTransmission();
  Wire.requestFrom(0x40, 1);
  byte data = Wire.receive();
  Wire.beginTransmission(0x40); // address of the accelerometer
  Wire.send(0x20);
  Wire.send(data & 0x0F); // low pass filter to 10 Hz
  Wire.endTransmission();

  Wire.beginTransmission(0x40); // address of the accelerometer
  Wire.send(0x35); // read from here
  Wire.endTransmission();
  Wire.requestFrom(0x40, 1);
  data = Wire.receive();
  Wire.beginTransmission(0x40); // address of the accelerometer
  Wire.send(0x35);
  Wire.send((data & 0xF1) | 0x04); // range +/- 2g
  Wire.endTransmission();
}

void AccelerometerRead()
{
  Wire.beginTransmission(0x40); // address of the accelerometer
  Wire.send(0x02); // set read pointer to data
  Wire.endTransmission();
  Wire.requestFrom(0x40, 6);

  // read in the 3 axis data, each one is 16 bits
  // print the data to terminal
  Serial.print("Accelerometer: X = ");
  short data = Wire.receive();
  data += Wire.receive() << 8;
  Serial.print(data);
  Serial.print(" , Y = ");
  data = Wire.receive();
  data += Wire.receive() << 8;
  Serial.print(data);
  Serial.print(" , Z = ");
  data = Wire.receive();
  data += Wire.receive() << 8;
  Serial.print(data);
  Serial.println();
}

void GyroInit()
{
  Wire.beginTransmission(0x69); // address of the gyro
  // reset the gyro
  Wire.send(0x3E);
  Wire.send(0x80);
  Wire.endTransmission();

  Wire.beginTransmission(0x69); // address of the gyro
  // low pass filter 10 Hz
  Wire.send(0x16);
  Wire.send(0x1D);
  Wire.endTransmission();

  Wire.beginTransmission(0x69); // address of the gyro
  // use internal oscillator
  Wire.send(0x3E);
  Wire.send(0x01);
  Wire.endTransmission();
}

void GyroRead()
{
  Wire.beginTransmission(0x69); // address of the gyro
  Wire.send(0x1D); // set read pointer
  Wire.endTransmission();

  Wire.requestFrom(0x69, 6);

  // read in 3 axis of data, 16 bits each, print to terminal
  short data = Wire.receive() << 8;
  data += Wire.receive();
  Serial.print("Gyro: X = ");
  Serial.print(data);
  Serial.print(" , Y = ");
  data = Wire.receive() << 8;
  data += Wire.receive();
  Serial.print(data);
  Serial.print(" , Z = ");
  data = Wire.receive() << 8;
  data += Wire.receive();
  Serial.print(data);
  Serial.println();
}

void loop()
{
  AccelerometerRead();
  GyroRead();

  delay(500); // slow down output
}

Step 15Control Principle

Control Principle
i
The code allows you fly the quadcopter in 2 modes:

One is where the accelerometer is ignored, and you control the helicopter's angular velocity with your joystick. This is refered to as "aerobatic" mode. In is mode, the code's job is to spin the helicopter when you want it to, and stop it from spinning when you don't. The advantage of this mode is that you can perform stunts like flips and barrel rolls.

The other mode is where the accelerometer is used with the gyro sensor to calculate the quadcopter's current angle with respect to the ground. You control the angle of the quadcopter instead. So in this mode, if you let go of the joystick, the quadcopter should stay at a horizontal level. If you move the joystick to a non-center location, the quadcopter will spin to one angle, then stay at that angle (and move since it's blowing air at an angle instead of straight down). This mode is refered to as "stable" mode or "attitude" mode. This mode requires an accelerometer to work, and will not allow you to perform flips and rolls (since your joystick does not do 360 degree rotations).

To calculate the quadcopter's current angle, the angular velocity is read using the gyro sensor. Angular velocity multiplied by time equals the amount of rotation during that time. There's a lot of error in this process due to drift and noise in the gyro sensor. To correct this error, the accelerometer is used to measure gravity, which is mixed into the calculation. For more details on this, please see:

The flight controller uses the this information along with a PID controller to control the motors. PID means "Proportional, Integral, Derivative". See these links:

To understand the "P" term, imagine you are trying to park a car. If you are very far away from the parking spot, you drive fast towards the spot. As you get closer, you should slow down. If you drive over the line, you need to reverse (and thus your velocity is negative). Speed = distance to spot * "P" in this case.

To understand the "I" term, imagine you are trying to park your car but your car is tied to a rope that won't let you reach the spot. You keep trying harder and harder until the rope snaps. Engine RPM = I term * integral of distance to spot over this period of time.

To understand the "D" term, say you moved 10 meters towards your spot, since you know you made progress, you should slow down a bit. Speed = difference between position * D term.

Now imagine instead of a parking spot and car, you use this PID controller to get your quadcopter from one angle to another angle by adjusting the difference in the rotor's spinning speed. By tuning the values of the PID terms, we can get the flight controller to make big adjustments and small adjustments accordingly, keeping the quadcopter stable in flight.

Step 16Quadcopter Assembly

Quadcopter Assembly
i
  • DSC07367 (Medium).JPG
  •  
  • DSC07445 (Medium).JPG
Since your circuit is now done, you can assemble the entire helicopter. I can't let you tune the helicopter without it being able to fly first.

Remember to unplug the battery whenever you make electrical changes (connecting and disconnecting things).

The entire frame takes several steps to assemble, there are way too many pictures for one "step" so I've divided them. I'll be going into a lot of details because the kit does not come with instructions.

Also the pictures may not follow chronological order, this is because I may have decided to re-order some steps.

Step 17Reinforce Arms

Reinforce Arms
i
  • DSC07434 (Small).JPG
  •  
  • DSC07435 (Small).JPG
The frame kit comes with the arms pre-assembled. Although the joints are glued, I found them too unreliable and prone to cracking. Also some joints have gaps which are too big.

Get some Gorilla Glue, the general purpose kind. Apply it to the joints. When this glue cures, it expands to three times its original volume, it will actually fill in the cracks for you.

By doing this, the amount of vibration in the frame is lowered, giving your sensors much better readings.

Step 18Insert ESCs in Arms

Insert ESCs in Arms
i
  • DSC07425 (Small).JPG
  •  
  • DSC07438 (Small).JPG
Stuff the ESCs into each arm. Do his before assembling anything else because I found it impossible to get the ESCs to fit if there are anything in the way.

I made the heat-sink side of the ESCs face upwards in hopes of improving the cooling due to the airflow from the propellers.

Make sure all the thick wires point down. The thin servo cable should still point up. If you got the same parts I have, all the wires should be the perfect length required.

Step 19Top Plate

Top Plate
i
  • DSC07370 (Small).JPG
  •  
  • DSC07371 (Small).JPG
  •  
  • DSC07380 (Small).JPG
  •  
  • DSC07381 (Small).JPG
  •  
  • DSC07382 (Small).JPG
  •  
  • DSC07383 (Small).JPG
  •  
  • DSC07384 (Small).JPG
  •  
  • DSC07385 (Small).JPG
  •  
  • DSC07386 (Small).JPG
  •  
Make sure you have a way of mounting your circuit board. You can design the circuit board to fit onto the holes already provided on the top plate, or drill holes into the plate yourself. My circuit uses slots to fit any square mounting pattern. I also have another design that I have prepared my top plate for.

If you drill into the top plate, you might want to drill the same holes into the bottom plate so you can use stand-offs with those holes.

Screw in all the stand-offs (I have extras since I purchased two frame kits).

Each arm piece slides onto the top plate. There should be three red arms and one that is grey. The grey one is the "front". The plate should have one side with triangles that indicate the forward direction. So make sure you mount the grey "front" arm in the forward direction.

There should be a hole for each arm that aligns with a hole on the plate. Place a screw and nut here. You can cut the nylon screw to an appropriate length to make this step easier and look nicer.

Step 1 - Step 9                                                                                    Step 20 - Step 30

0 Comments
Disqus
Fb Comments
Comments :

0 comments:

Post a Comment