After some research I was able to control all four brushless motors from the arduino board with four speed controllers, one for each motor. The sketch can be seen in detail below.
 |
Figure 1 |
The figure 1 shows the arduino development environment. In the left window (Serial Monitor) you can see the result of the instructions sent to the arduino board via serial port (USB-serial device). When the quadcopter is switch on must be sent the character "s" to initialize the speed controllers. After the controllers initialized, do not re-send the character "s" in any circumstance, if you send the motors immediately accelerated to full speed in less than 1 second. If you have placed the propellers in the motors of the quadcopter, then you'll see him being sent to the deep sky if you're a lucky guy. Here is the warning to anyone wishing to use this sketch. To increase the speed the character "+" is sent to the serial port and the character "-" to decrement the speed. To stop the motors the character "0" is sent.
 |
Figure 2 |
The figure 2 shows how the speed controllers are attached to the side panels.
 |
Figure 3 |
The figure 3 shows the cable connections of the speed controllers on board (Sorry for the bad image quality). When I have time I do a diagram of all connections.
#include <Servo.h>
#define MAXANGLE 160
typedef struct {
int pinpwm;
int range[2];
} ESCRecord;
ESCRecord escconf[4];
Servo escservos[4];
int angle = 0;
void config() {
escconf[0] = (ESCRecord) {3, {836, 2400}};
escconf[1] = (ESCRecord) {9, {836, 2400}};
escconf[2] = (ESCRecord) {10, {836, 2400}};
escconf[3] = (ESCRecord) {11, {836, 2400}};
}
void arm() {
for(int esc = 0; esc < 4; esc++) {
escservos[esc].attach(escconf[esc].pinpwm, \
escconf[esc].range[0], \
escconf[esc].range[1]);
escservos[esc].write(0);
delay(15);
}
}
void cycle() {
Serial.print("Cycle ESC Number ");
for(int esc = 0; esc < 4; esc++) {
Serial.print(esc);
for(int angle = 0; angle <= MAXANGLE; angle++) {
escservos[esc].write(angle);
delay(15);
}
for(int angle = MAXANGLE; angle >= 0; angle--) {
escservos[esc].write(angle);
delay(15);
}
}
Serial.println("");
}
void setup() {
delay(1000);
Serial.begin(9600);
Serial.println("Wait for your input! [s] to init...");
while(Serial.available() <= 0)
delay(1000);
int incomingByte = Serial.read();
Serial.println("Start the system...");
config();
arm();
delay(5000);
if(incomingByte == 115) {
Serial.println("Traverses all angles upward and downward.");
cycle();
delay(1000);
}
Serial.println("Start loop...");
}
void setspeed(int angles[4]) {
for(int esc = 0; esc < 4; esc++) {
escservos[esc].write(angles[esc]);
delay(120);
}
}
void loop() {
if(Serial.available() > 0) {
int incomingByte = Serial.read();
if(incomingByte == 43) // sends the character '+'
angle++; // increases the speed
else if(incomingByte == 45) // sends the character '-'
angle--; // decreases the speed
else if(incomingByte == 48) // sends the character '0'
angle = 0; // set the speed to zero
if(angle < 0)
angle = 0;
if(angle > MAXANGLE)
angle = MAXANGLE;
Serial.print("Set the angle to: ");
Serial.println(angle);
}
int angles[4] = {angle, angle, angle, angle};
setspeed(angles);
}