S15: Drone

From Embedded Systems Learning Academy
Revision as of 06:59, 25 May 2015 by Proj user20 (talk | contribs) (Remote Controller)

(diff) ← Older revision | Latest revision (diff) | Newer revision → (diff)
Jump to: navigation, search

DRONE

Objectives

The idea is to design an Quadcopter capable of sustaining a stable flight via wireless communication. The goals of the project can be divided mainly into the following four parts:

  1. To interface IMU 10-dof sensor to SJ-One Board and decode the readings coming from sensor.
  2. To interface the 8Channel Turnigy receiver with our SJ-One and normalize and scale those readings.
  3. To use SJ-One Board as the Flight control board which takes readings continuously from the sensor and the receiver to compute the PID values.
  4. To give the computed PWM values to all the four ESCs.

This should enable the Quadcopter to have a balanced flight.

Team Members & Responsibilities

1. Bhushan Gopala Reddy

  • PID tuning and Software analysis

2. Karthik Govindaswamy

  • Sensors and report

3. Rishikesh Nagare

  • Report and PWM design

4. Mayur Salve

  • Mechanical design and PID analysis

5. Manuj Shinkar

  • Mechanical design, code integration and Remote controller interface

Introduction

Basics of Quadcopter


Fig 1. Rotating directions
  • This figure shows the Yaw, Pitch and Roll movement of a quadcopter.
  • Rotation around the front-to-back axis is called roll.
  • Rotation around the side-to-side axis is called pitch.
  • Rotation around the vertical axis is called yaw.
Fig 2. Setup
  • Our Quadcopter is implemented in the '+' orientation.
  • The motors are named North, South , East and West motor.
  • FigureX shows the ESC and motor setup where CW is clockwise and CCW means counter-clockwise.
  • The CW and CCW setup of the motor and propellers is very important to have control over the yaw parameter.
Fig 3. Quad's Movement
  • FORWARD movement:

Motor1 will spin faster and Motor3 will spin slower resulting in an forward tilt of the Quadcopter.

  • BACKWARD movement:

Motor1 will spin slower and Motor3 will spin faster resulting in an backward tilt of the Quadcopter.

  • LEFT movement:

Motor2 will spin faster and Motor4 will spin slower resulting in an leftward tilt of the Quadcopter.

  • RIGHT movement:

Motor2 will spin slower and Motor4 will spin faster resulting in an rightward tilt of the Quadcopter.

Arming/Disarming the Quadcopter


Arming/disarming facility in Quadcopters is a precautionary measure provided to prevent the motors from spinning accidentally. Imagine if the transmitter is on full throttle and we switch on the power supply. Quadcopter propellers are the last thing you want to be near. Arming/disarming facility is quintessential to prevent anyone from getting hurt as well as to prevent damage to the quadcopter.

The gear channel is used to arm or disarm the Quadcopter. A simple toggle switch on the transmitter is used to switch between these modes.

Schedule

Sl.No Start Date End Date Task Status Actual Completion Date
1 03/17/2015 03/24/2015 Order parts for quad-copter Completed 03/24/2015
2 03/25/2015 03/27/2015 Assemble quad-copter Completed 03/27/2015
3 03/28/2015 03/31/2015 Test quad-copter design and stability with the help of flight control board(KK 2.1.5) Completed 03/31/2015
4 04/01/2015 04/07/2015 Study quad-copter's software framework provided by Preet Completed 04/07/2015
5 04/08/2015 04/09/2015 Calibrate all the ESC's Completed 04/09/2015
6 04/10/2015 04/14/2015 Interface Motors and RC to SJ-One Board and testing Completed 04/14/2015
7 04/15/2015 04/18/2015 Scale the throttle,pitch,roll and yaw to the appropriate range Completed 04/18/2015
8 04/19/2015 04/21/2015 Understand the behavior of 10DOF IMU sensor and code flow. Completed 04/21/2015
9 04/22/2015 04/25/2015 Interface and test the orientation of the all the senor values using Spark-fun IMU Razor 9DOF AHRS code Completed 04/25/2015
10 04/26/2015 05/30/2015 Understand PID and it's implementation Completed 05/30/2015
11 05/01/2015 05/24/2015 Tune PID for pitch, roll and yaw. Final testing! Ongoing 05/24/2015

Parts List & Cost

Item# Part Desciption Manufacturer Qty Cost
1 SJ One Board 1 $80.00
1 Motors and Propellers Tiger Motors 1 $89.99
1 10-DOF IMU Sensor Adafruit 1 $29.95
2 Afro ESC 30 Amp Speed Controller (SimonK Firmware) Turnigy 4 $56
3 Turnigy 9X 9Ch Transmitter w/ Module & 8ch Receiver (Mode 2) (v2 Firmware) Turnigy 1 $59.99
4 Turnigy nano-tech 4000mAh 3S1P 25-50C Lipo Pack Turnigy 1 $26.90
5 Hobbyking SK450 Glass Fiber Quadcopter Frame 450mm Hobbyking 1 $17.99
6 Landing Kit set Hobbyking 1 $9.49
7 Hobbyking Quadcopter Power distribution board Hobbyking 1 $3.39
8 Hobbyking Lipoly low voltage alarm Hobbyking 1 $2.15
9 Turnigy Battery Strap Turnigy 1 $1.59
13 3.5 mm bullet heads for power break distribution board Hobbyking 1 $1.83
14 iMax B6 Battery Charger iMax 1 $33.46
15 UART to USB serial cable 1 $6.99
TOTAL $419.72

Backup Parts List & Cost

Item# Part Desciption Manufacturer Qty
1 Motors and Propellers Tiger Motors 1
2 Afro ESC 30 Amp Speed Controller (SimonK Firmware) Turnigy 2
3 Turnigy nano-tech 3000mAh 3S1P 25-50C Lipo Pack Turnigy 1
4 Hobbyking SK450 Glass Fiber Quadcopter Frame 450mm Hobbyking 1
5 KK2.1 Flight Controller Board (for testing) Hobbyking 1

Design & Implementation

This section describes the hardware and software implementation. The quadcopter consist of the main frame, flight controller board (SJ-One Board), motors with ESC and the battery system. The Airframe used in this project is Hobbyking SK450 Glass Fiber Quadcopter Frame 450mm.

System Design

Fig 4. System Block Diagram

The quadcopter's flight controller system is discussed in the block diagram shown on the left. The subsystem consists of following:

  • SJ-One Board
  • Turnigy Transmitter and Receiver
  • Adafruit 10-DOF IMU sensor
  • Brushless Motors
  • ESC(Electronic Speed Control)

The power is fed to the motors using the power distribution board. The power comes from 3 Cell 11.1V LIPO battery Pack.

Hardware

Frame


Fig 5. Frame

The Quadcopter frame must be symmetrical to make the code simpler to implement and avoid any unnecessary complications. Ours is the SK450 Glass Fiber Frame of size 450mm. This is a high quality glass fiber frame while the arms are constructed from ultra durable polyamide nylon. This quad not only looks great, its very well thought out as well. Assembly is a breeze with pre-threaded brass sleeves for all of the frame bolts, so no lock-nuts are required. It utilizes one size of bolt for the entire build, making the hardware very easy to keep in order and only requiring one size of hex wrench to assemble.

SJ-One Board


Fig 6. SJ-One Board

The flight control board used for this project is SJ-One Board. This control board will receive values continuously from the sensor and remote. The values applied from the RC and the current sensor values are used to calculate the values to be applied to the propellers. The SJ-One board uses ARM Cortex -M3 MPU to calculate few hundred times a second.

Brushless Motors and Propellers


Fig 7.Brushless Motors

Brushless motors are the best when it comes to speed and low power consumption. The motors used for this project are AIR Gear 350 brushless motors. These motors have 920Kv rating and have low noise and high speed response. The propellers used came with the same motors and were self tightening and bullets holders. The motors are made of good quality material and are suitable for 1400-1700 g quadcopter. The propellers dimensions are as follows:
Diameter - 9.4 inch
Thread Pitch - 4.5 inch

ESC(Electronic speed control)


Fig 8. AfroESC using SimonK Firmware

The PWM signals generated by the Flight control board is fed to the ESC's which provide signal to the motors. The ESCs are running on SimonK firmware which gives a smooth power response and is suitable for multi-rotor use without the need to program or adjust settings.

Calibration

The calibration of the ESC's were done manually. Below is the step wise discussion of manual calibration method.

  • First, remove all propellers! Disconnect the power to the ESCs. Connect the ESC PWM input directly to the receiver's throttle channel, or to a servo tester.
  • Set the radio throttle or servo tester to the highest position, then connect power to the ESC. The motor should produce a series of initialization beeps increasing in pitch, followed by another beep

matching the pitch of the last initialization beep. This indicates that the calibration mode has been entered, and the pulse length has been learned.

  • Move the stick or knob to the lowest position. Two beeps of the same pitch should be emitted. This indicates that the low pulse length has been learned. If the RC Car-style reversible mode has been

enabled (RC_PULS_NEUTRAL), move the stick or knob to the center, and wait for three beeps. This indicates that the neutral (center) pulse length has been learned.

  • The ESC will then save the settings and exit calibration mode. If the input is still at the same position, the ESC will arm (producing a higher pitched, long beep), and function normally.

Inertial Measurement Unit


Fig 9. MPU-9150 Breakout Board

The Inertial Measurement Unit (IMU) is an integrated sensor device which measures accleration and tilt by Accelerometer, angular velocity and orientation by Gyroscope and gravitational forces by Magnetometer. Inertial Measurement Unit by Adafruit provides 10 DOF(actually 11) i.e 3-axis accelerometer, 3-axis gyroscope, 3-axis magnetometer barometric pressure sensor and temperature sensor. These values are sent to SJ-1 board over I2C, where the further processing is done by SJ-1 board to determine the angular position and orientation of the Quadcopter.






Remote Controller


Fig 10. RC Transmitter
Fig 11. RC Receiver

The new transmission module (TGY-9X) is of type FHSS (Frequency-hopping spread spectrum) and uses frequency hopping. This technique has a high transmission reliability because it is insensitive to interference. It has a plastic casing of compact type. Its handling is excellent and the sleeves are adjustable. The antenna is directional. 167x34mm LCD screen (black and white) is fairly well mixed and makes a pretty good readability in daylight. 6 keys allow access to many menus, selection and settings.










Binding Procedure

Fig 12. RC Receiver channel for binding
Fig 14. RC Test Range bind button
Fig 13. RC Receiver channel power supply


  1. Insert the special cable (loop) in the channel 'BAT' of the receiver and not in the channel 'BIND' as indicated. Connect power supply to the receiver in position 'BIND' and wait until the LED flashes red.
  2. Press the button 'Test Range bind' the transmission module (back of radio) and, without releasing it, turn on the transmitter, the LED will stop flashing and remain lit constantly.
  3. Release the button and turn off the radio module. Then remove the special cord and disconnect the receiver battery, the receiver is ready.
  4. The effect is immediate and does not allow more than 3sec button 'test range bind' button.
Pin Config for RC receiver inputs
Pin Number Function
P0.1 RC-Ch1 - Roll
P0.30 RC-Ch2 - Throttle
P0.0 RC-Ch3 - Pitch
P0.29 RC-Ch4 - Yaw
P2.6 RC-Ch5 - Gear

Note: Use a LiPo battery pack of 11.1V 2500mAh to power the transmitter. This is very convenient to use as opposed to using (8x) AA batteries which discharge quickly.

Hardware Interface

Fig 15. Hardware Interface
Sl. No Port and Pin Number Pin Type Purpose
1 P2.0 PWM North ESC
2 P2.1 PWM South ESC
3 P2.2 PWM East ESC
4 P2.3 PWM West ESC
Sl. No Port and Pin Number Pin Type Purpose
1 P0.0 GPIO Pitch (Rx Channel 3)
2 P0.1 GPIO Roll (Rx Channel 1)
3 P0.29 GPIO Yaw (Rx Channel 4)
4 P0.30 GPIO Throttle (Rx Channel 2)
5 P2.6 GPIO Arm/Disarm (Rx Channel 5)

The diagram above shows the hardware interfacing of various components with the flight controller board. The 4000mAh LiPo battery is used to supply power to SJOne board, the receiver and all the four ESCs and motors. Special care was taken to ensure a common grounding between all the components.

Software Design

Main.cpp - This is the entry point of the all the modules. There are 4 tasks running with quad-copter task with highest priority and terminal task being the next highest and so on.

The quad-copter is the main task which process all the data.

  • Initializes the Adafruit 10-DOF IMU
  • Update and Process sensor data
  • Update the flight parameters.
  • Update propeller values
  • Compute pitch, roll and yaw throttle.
  • Applying throttle values if the quad-copter is armed.
  • Indicating error if any the above process take more time.

The RC remote task is equally important

  • It is interrupt based.
  • 5 RC channels are configured. (Throttle, pitch, roll, yaw and arm/disarm)
  • Calculates the pulse width of each interrupts by configuring the rising and falling edge interrupts.
  • Scaling of the throttle, pitch, roll and yaw axis.
Fig 16. Software Code Flow

The computeThrottleValues() is used to calculate the pitch, roll and yaw throttle by using the using the PID algorithm that need to be applied to the motors.

This API uses the current values of the sensors and the applied pitch, roll and yaw values from the RC.

Fig 17.Code snippet of PID calculation for pitch, roll and yaw











This code applies the calculated pitch, roll and yaw throttle to the respective motors to stabilize the flight of the quad-copter.

Fig 18.Code snippet for applying the motor values










Flowchart

PID Controller

PID (proportional-integral-derivative) is a closed-loop control system that tries to get the actual result from IMU sensors closer to the desired result from the RC transmitter by computing the output values. The popularity of PID controllers can be attributed partly to their robust performance in a wide range of operating conditions and partly to their functional simplicity, which allows engineers to operate them in a simple, straightforward manner.

Fig 19. Block diagram of PID

PID formula

Fig 20. PID

There are 3 variables in a PID controller, namely P(Proportional), I(Integral), and D (Derivative). P depends on the present error, I on the accumulation of past errors, and D is a prediction of future errors, based on current rate of change of the Quadcopter.

The effect of P,I and D

  • Proportional Gain Coefficients

Kp = Proportional element of the PID, reduces large part of the overall error.

- Increasing Kp will overshoot and oscillate, but reach the desired state faster.

- Increasing Kp will reduce steady state error, but after a certain limit, increasing Kp will only increase the overshoot.

- Kp reduces the rise time.


  • Integral Gain Coefficients

Ki = Integral element of the PID, reduces the final error accumulated over time.

- Ki eliminates the steady state error, but after a certain limit, increasing Ki will only increase the overshoot.

- Ki reduces the rise time.


  • Derivative Gain Coefficients

Kd = Derivative element of the PID, counteracts Kp, and Ki when the output changes quickly.

- Kd decreases the overshoot.

- Kd reduces the settling time.


To obtain the control and stability of the quadcopter we do the following, for example consider we are doing it for pitch axis, the user provides some input to the quadcopter which becomes the requested value, at the same time sensor outputs the present value for the pitch axis for the quadcopter. The three alogorithms P, I and D finds the difference between the requested and the present values which is calculated as an error and apply these values on the motor which are the applied values to reduce the error. Similarly it is done for other 2 axis i.e Roll and Yaw to obtain the overall stability of the Quadcopter.

Fig 20. PID per axis

There were few parameter which were addressed while writing the PID algorithm

  1. Sample Time - The PID algorithm functions best if it is evaluated at a regular interval. If the algorithm is aware of this interval, we can also simplify some of the internal math.
  2. Derivative Kick - Not the biggest deal, but easy to get rid of, so we’re going to do just that.
  3. On-The-Fly Tuning Changes - A good PID algorithm is one where tuning parameters can be changed without jolting the internal workings.
  4. Reset Windup Mitigation -We’ll go into what Reset Windup is, and implement a solution with side benefits
  5. On/Off (Auto/Manual) - In most applications, there is a desire to sometimes turn off the PID controller and adjust the output by hand, without the controller interfering
  6. Initialization - When the controller first turns on, we want a “bumpless transfer.” That is, we don’t want the output to suddenly jerk to some new value
  7. Controller Direction - This last one isn’t a change in the name of robustness per se. it’s designed to ensure that the user enters tuning parameters with the correct sign.

Flight Controller

Fig 22. SJ-One Board
Fig 21. front view of Quadcopter
Fig 23. Top view of Quadcopter

Fight controller is a brain of any Quadcopter or multicopter. In our project, we have used SJ-One board as our flight controller, it continuously reads data from IMU sensors and inputs from RC transmitter. The flight controller performs algorithmic calculation received from sensors and RC and apply these adjustments on each rotor. Quadcopter has 4 degrees of freedom i.e pitch, roll , yaw and altitude, and with the flight controller each degree of freedom can be controlled by adjusting the thrusts on each rotor and keep the quadcopter balanced.

Implementation

This section includes implementation, but again, not the details, just the high level. For example, you can list the steps it takes to communicate over a sensor, or the steps needed to write a page of memory onto SPI Flash. You can include sub-sections for each of your component implementation.

Overall System Algorithm

  1. Initialize all the tasks
  2. If no errors arm the quadcopter by the channel 5 on RC (errors are found on LED display)
  3. Update the sensor data and send them to SJ-One board
  4. Similarly update RC input and send them to SJ-One board.
  5. Run PID algorithm continuously on sensor data and RC data to generate PID coefficients for each axis(Pitch, Roll and Yaw).
  6. Apply the PID coefficients on motors through ESC's to obtain the self balance of the quadcopter.
  7. repeat from step 3 until the quadcopter is disarmed.

Remote Control transmitter

  1. The input is sent from RC transmitter to RC receiver.
  2. We are using 4 channels for Throttle, Pitch, Roll and Yaw and 5th channel for arming and disarming the quadcopter.
  3. All the channels from the receiver is connected to 5 GPIO pins and Interrupts are enabled for each pin.
  4. Time is recorded when there is a rising edge and the time is recorded when there is a falling edge on the corresponding pin.
  5. The difference is recorded to find the width of the pulse which is between 1 ms and 2000 ms.
  6. Normalized value is calculated using scaling factor and pulse width. Below are the range of normalized value
  • Throttle 0 to 100
  • Pitch -45 to 45
  • Roll -45 to 45
  • Yaw -45 to 45

IMU sensors

  1. calibrate the sensors and find the offset
  2. Read sensor data of accelerometer, gyroscope and magnetometer at 100HZ
  3. Add the offset to the raw data from sensors
  4. Covert the raw data into expected data required by PID algorithm before sending it to SJ-One board(for example gyro data is converted from degress per second into radians per second, accelerometer data is divided by 16)
  5. repeat from step 2

Testing & Technical Challenges

Testing of 10DOF IMU


Fig 24. IMU Razor 9DOF

We tested the IMU with an application called IMU Razor 9DOF. This application shows the simulation of our IMU sensor. It displays values of pitch, roll and yaw.


Testing of PID


Fig 25. Testing of PID

The testing of PID was done for each axis separately. We started with pitch axis. We used two wooden planks and hooks two hold the quad on the east and west so that our pitch axis is free. Slowly started to increase the value of P. At some point the pitch axis was oscillating constantly. The amplitude of oscillation should neither increase or decrease. Then we started increasing the values of D till the overshoot is reduced to an acceptable level. Then we increased the value of I till the final error is zero. The quad is very sensitive to the value of I. After the pitch axis we tuned the PID for the roll axis. We used some tuning methods such as Zeigler Nicholas and Cohen Coon to tune the PID. After the pitch and roll we tested the yaw axis. We tied the quad to a rope and held it in the air so that the quad is free in the yaw axis.





Testing the Quadcopter flight


Fig 26. Testing the Quadcopter

We tied the quad with a rope to a wooden plank. One person was holding the plank. We slowly increased the throttle so that the quadcopter lifts up. The person holding the wooden plank could control the quadcopter so the it doesn't hit somewhere and get damaged.

Issues Faced

Power supply to the SJOne Board

We could not supply power to the board from the battery pack because it had of higher current output. We supplied power to the board from one of the ESC's. The ESC's had a built in battery eliminator circuit which has an output of 5V. By adding extra source to power up the board would have increased extra weight of the quadcopter.

ESC lost calibration

One of the ESC lost the calibration and it was not responding properly to the PID values. We replaced the ESC but still the problem was there. Later we found the all the ESC's have to be calibrated at the same throttle level i.e 1064ms to 1864ms.

Glitch in one of the motor values

One of the motor was experiencing glitch. We found out that the input of roll from the transmitter is giving a spike at constant intervals. The receiver was getting a pulse of more than 2000ms. We wrote a software filter to get rid of the glitch.

I2C short in SDA and SCL

Frequently encountered I2C short, we experienced this problem till the end of the project but could not find exact reason for I2C short. We solved this problem by resetting the board 2-3 times.

Conclusion

This project provided us with practical experience on the firmware that goes into making an Unmanned Aerial Vehicle(UAV). We were able to successfully design a quadcopter assembly which used sensor readings and input from values to compute the PID values. The SJOne flight control board was programmed with this PID algorithm. We have successfully tuned the PID for pitch and roll axis. We were able to get the quadcopter in air. However, the flight was not stable because the yaw axis was not tuned.

Project Video

Upload a video of your project and post the link here.

Tuning of pitch axis for the Quadcopter https://www.youtube.com/watch?v=Ztgx5FDS018

References

Acknowledgement

Thanks a lot to Professor Preetpal Kang who provided us with the basic code framework, which helped us have a great start. Thanks to Brett Beauregard whose article PID for beginners was very helpful for writing the PID firmware.

References Used

  1. Preetpal Kang, Professor of CMPE 244, Computer Engineering, Charles W. Davidson College of Engineering, San Jose State University, Feb-May 2015.
  2. http://www.instructables.com/id/Basic-Quads-Systems-My-Easy-Quad-Build/step1/Basic-Quads-Systems-My-Easy-Quad-Build/
  3. http://www.hobbyking.com/hobbyking/store/index.asp
  4. http://brettbeauregard.com/blog/2011/04/improving-the-beginners-pid-introduction/

Project Source Code