Welcome, Guest. Please Login or Register
YaBB - Yet another Bulletin Board
09.02.2010 at 19:09:06
News: Server upgrade went fine, you are now at the new system


Pages: 1 2 
ArduCopter V1 Beta (Read 23949 times)
jordi
Full Member
***
Offline

Tururu!

Posts: 109
Baja California and California
Gender: male
ArduCopter V1 Beta
07.11.2007 at 06:27:12
 
[url]http://www.flickr.com/photos/18257187@N08/1895501655/[/url]

1: English is not my firts language, sorry if i made mistakes trying to describe this project.

I made an autopilot for my RC helicopter (Sabre, i bought it in Hobbie People USA) with acelerometers extracted from the NunChuck of nintendo Wii. Now i just a beta, i will change the Arduino Decimila for the mini version, you know, for weight reasons.
Arduino just control the Axis X and Y of the helicopter, but i able to read signals coming from my RC, an order to arduino to move my helicopter, easy and smoothly in that axis (X & Y), i only have to control the rotation and altitude, the rotation is not a big deal because the heli is stabilized by build-in "Gyros".  I recycled the joystick axis of NunChuck, to adjust the servos with out touching the code. To se more pictures enter here http://www.flickr.com/photos/18257187@N08/

The code:
Code:
#include <Wire.h>
#include <string.h>
#include <stdio.h>

uint8_t outbuf[6];		// array to store arduino output
int cnt = 0;
int ledPin = 13;
int voltPin = 2;
int apX = 0;
int apY = 0;
int minWii = 330;
int maxWii = 694;
/////////////////

int axisX = 0;    //Acelerometer axis X
int axisY = 0;    //Acelerometer axis Y
int axisZ = 0;    //Acelerometer axis Z
int adjustX = 127;	 // adjust axis X
int adjustY = 127;	 // adjust axis X
int contador = 0;     //Contador del ciclo FOR

////////////////////Read RC
int xPin = 7;	    //Pin IN of servo Axis X
int yPin = 8;	    //Pin IN of servo Axis Y
int timeX = 0;  //Show the readed control position
int timeY = 0;
long lastPulseX = 0;    // the time in milliseconds of the last pulse
long lastPulseY = 0;
long mstime = 0;     // reads the time in miliseconds
long hptime = 0;     // Reads the time in Microseconds

///////////////////Write Servos
int minPulse = 800;   // Minimum servo position
int maxPulse = 2200;  // Maximum servo position
int refreshTime = 20; // the time needed in between pulses
int servoXPin = 2;
int servoYPin = 4;
long lastPulseWriteX = 0;    // the time in milliseconds of the last pulse
long lastPulseWriteY = 0;    // the time in milliseconds of the last pulse
int pulseX = 0;	  // Amount to pulse the servo X
int pulseY = 0;
////////////////////////////////////
extern volatile unsigned long timer0_overflow_count; // Sistema de conteo en microsegundos

unsigned long hpticks (void)
{
  return (timer0_overflow_count << 8) + TCNT0;
}
///////////////////////////////////
void setup ()
{
  pinMode(servoXPin, OUTPUT);  // Set servo pin as an output pin
  pinMode(servoYPin, OUTPUT);  // Set servo pin as an output pin
  pinMode(xPin, INPUT); //The R/C signal pin as an input pin
  pinMode(yPin, INPUT);
  pulseX = minPulse;	     // Set the motor position value to the minimum
  pulseY = minPulse;	     // Set the motor position value to the minimum
  beginSerial (38400);
  Serial.print ("Finished setup\n");
  Wire.begin ();		// join i2c bus with address 0x52
  nunchuck_init (); // send the initilization handshake
}
void loop ()
{
  Wire.requestFrom (0x52, 6);	// request data from nunchuck
  while (Wire.available ())
  {
    outbuf[cnt] = nunchuk_decode_byte (Wire.receive ());	// receive byte as an integer
    digitalWrite (ledPin, HIGH);	// sets the LED on
    cnt++;
  }

  // If we recieved the 6 bytes, then go print them
  if (cnt >= 5)
  {
    print ();
    AutoPilot();
    updateServo();
    Serial.print ("\r\n");
  }
  cnt = 0;
  send_zero (); // send the request for next bytes
  delay(5);
}

void AutoPilot()
{

    pulseX =((((axisX - minWii) * ((maxPulse-minPulse)/(maxWii-minWii))))+minPulse)-127;
    pulseY =((((axisY - minWii) * ((maxPulse-minPulse)/(maxWii-minWii))))+minPulse)-127;

    pulseX = pulseX + adjustX;
    pulseY = pulseY + adjustY;
    pulseY = maxPulse - (pulseY - minPulse);

	if(axisZ <= 754)//just a test
    {
	if(axisX <= 500)
	{
	  pulseX = pulseX - 300;
	}
	if(axisX >= 560)
	{
	  pulseX = pulseX + 300;
	}
    }



    Serial.print ("SrvX");
    Serial.print (pulseX);
    Serial.print ("\t");
    Serial.print ("SrvY");
    Serial.print (pulseY);
    Serial.print ("\t");



}

void RadioControl()
{
  /////////////////////////
  if(millis() - lastPulseX >= 200) //Read Axis X every 5 milis
  {
    while(!digitalRead(xPin) == HIGH) //Waits for signal coming from axis X
    {
	continue;
    }
    mstime = millis();
    hptime = hpticks()*4; //When the signal arrives, here we going to record the start time of reciving
    while(!digitalRead(xPin) == LOW){
	continue;
    }
    mstime = millis();
    timeX = (hpticks()*4) - hptime;  //Here takes the diferences of  the Start and finish times, the result is the signal from RC.
    hptime = 0;
    Serial.print ("CtrX");
    Serial.print (timeX);
    Serial.print ("\t");
    lastPulseX = millis();
  }

  ///////////////////////////The same, but now for axis Y

  if(millis() - lastPulseY >= 200)
  {
    while(!digitalRead(yPin) == HIGH){
	continue;
    }
    mstime = millis();
    hptime = hpticks()*4;
    while(!digitalRead(yPin) == LOW){
	continue;
    }
    mstime = millis();
    timeY = (hpticks()*4) - hptime;
    Serial.print ("CtrY");
    Serial.print (timeY);
    Serial.print ("\t");
    hptime = 0;
    lastPulseY = millis();
  }
}

//Continue
 

Back to top
 
 
View Profile | MSN   IP Logged
jordi
Full Member
***
Offline

Tururu!

Posts: 109
Baja California and California
Gender: male
Re: ArduCopter V1 Beta
Reply #1 - 07.11.2007 at 06:28:54
 
//code continue

Code:
void updateServo(){

if (millis() - lastPulseWriteX >= refreshTime) {
	  digitalWrite(servoXPin, HIGH);   // Turn the motor on
	  delayMicroseconds(pulseX);	 // Length of the pulse sets the motor position
	  digitalWrite(servoXPin, LOW);    // Turn the motor off
	  lastPulseWriteX = millis();	     // save the time of the last pulse
	}

if (millis() - lastPulseWriteY >= refreshTime) {
	  digitalWrite(servoYPin, HIGH);   // Turn the motor on
	  delayMicroseconds(pulseY);	 // Length of the pulse sets the motor position
	  digitalWrite(servoYPin, LOW);    // Turn the motor off
	  lastPulseWriteY = millis();	     // save the time of the last pulse
	}

}
// Print the input data we have recieved
// accel data is 10 bits long
// so we read 8 bits, then we have to add
// on the last 2 bits.  That is why I
// multiply them by 2 * 2
void print ()
{
  int joy_x_axis = outbuf[0];
  int joy_y_axis = outbuf[1];
  int accel_x_axis = outbuf[2] * 2 * 2;
  int accel_y_axis = outbuf[3] * 2 * 2;
  int accel_z_axis = outbuf[4] * 2 * 2;

  int z_button = 0;
  int c_button = 0;

  // byte outbuf[5] contains bits for z and c buttons
  // it also contains the least significant bits for the accelerometer data
  // so we have to check each bit of byte outbuf[5]
  if ((outbuf[5] >> 0) & 1)
  {
    z_button = 1;
  }
  if ((outbuf[5] >> 1) & 1)
  {
    c_button = 1;
  }

  if ((outbuf[5] >> 2) & 1)
  {
    accel_x_axis += 2;
  }
  if ((outbuf[5] >> 3) & 1)
  {
    accel_x_axis += 1;
  }

  if ((outbuf[5] >> 4) & 1)
  {
    accel_y_axis += 2;
  }
  if ((outbuf[5] >> 5) & 1)
  {
    accel_y_axis += 1;
  }

  if ((outbuf[5] >> 6) & 1)
  {
    accel_z_axis += 2;
  }
  if ((outbuf[5] >> 7) & 1)
  {
    accel_z_axis += 1;
  }
  axisX = accel_x_axis;
  axisY = accel_y_axis;
  axisZ = accel_z_axis;
  adjustX = joy_x_axis;
  adjustY = joy_y_axis;

  Serial.print ("JoyX");
  Serial.print (joy_x_axis, DEC);
  Serial.print ("\t");

  Serial.print ("JoyY");
  Serial.print (joy_y_axis, DEC);
  Serial.print ("\t");

  Serial.print ("AclX");
  Serial.print (accel_x_axis, DEC);
  Serial.print ("\t");

  Serial.print ("AclY");
  Serial.print (accel_y_axis, DEC);
  Serial.print ("\t");

  Serial.print ("AclZ");
  Serial.print (accel_z_axis, DEC);
  Serial.print ("\t");

  Serial.print ("btnZ");
  Serial.print (z_button, DEC);
  Serial.print ("\t");

  Serial.print ("btnC");
  Serial.print (c_button, DEC);
  Serial.print ("\t");


}

// Encode data to format that most wiimote drivers except
// only needed if you use one of the regular wiimote drivers
char
nunchuk_decode_byte (char x)
{
  x = (x ^ 0x17) + 0x17;
  return x;
}
void nunchuck_init ()
{
  Wire.beginTransmission (0x52);	// transmit to device 0x52
  Wire.send (0x40);		// sends memory address
  Wire.send (0x00);		// sends sent a zero.
  Wire.endTransmission ();	// stop transmitting
}

void send_zero ()
{
  Wire.beginTransmission (0x52);	// transmit to device 0x52
  Wire.send (0x00);		// sends one byte
  Wire.endTransmission ();	// stop transmitting
} 



//Remember i just a BETA, letter ill upload video,
Back to top
 
 
View Profile | MSN   IP Logged
trialex
God Member
*****
Offline



Posts: 522

Re: ArduCopter V1 Beta
Reply #2 - 07.11.2007 at 07:26:24
 
Very impressive! I can imagine the first time you fired it up would have been scary!
Back to top
 
 
View Profile   IP Logged
MikMo
God Member
*****
Offline

Do it !

Posts: 1596

Re: ArduCopter V1 Beta
Reply #3 - 07.11.2007 at 08:47:09
 
Thats a very impressive project.

You absolutely have to post a video of this thing flying Smiley
Back to top
 
 
View Profile | WWW   IP Logged
Cheater
God Member
*****
Offline



Posts: 593
Brisbane, Australia
Gender: male
Re: ArduCopter V1 Beta
Reply #4 - 07.11.2007 at 09:07:45
 
Now all you need is a GPS from SparkFun and a compass.
Then you'll be able to do waypointing.
Back to top
 
 
View Profile | WWW   IP Logged
Syvwlch
Full Member
***
Offline

Ard at work

Posts: 192
New Jersey
Gender: male
Re: ArduCopter V1 Beta
Reply #5 - 07.11.2007 at 18:05:34
 
Careful with the compass, it will need to be tilt compensated which is not trivial.
Back to top
 
 
View Profile | WWW   IP Logged
CrashingDutchman
Senior Member
****
Offline



Posts: 355
Netherlands
Gender: male
Re: ArduCopter V1 Beta
Reply #6 - 08.11.2007 at 09:29:47
 
I am 'addicted' to r/c (airplanes) and this is one of the most impressive projects I have seen in while! Did you post this at http://www.rcgroups.com?
Back to top
 
 
View Profile   IP Logged
Cheater
God Member
*****
Offline



Posts: 593
Brisbane, Australia
Gender: male
Re: ArduCopter V1 Beta
Reply #7 - 08.11.2007 at 11:46:29
 
Syvwlch wrote on 07.11.2007 at 18:05:34:
Careful with the compass, it will need to be tilt compensated which is not trivial.

Depends on how much maths you've done I suppose.
Given a compass bearing and accelerometer data I could probably make the compass accurate without having done it before.

I had (have?) a remote control plane. It liked to nose dive and the plastic propeller didnt like it too much.
It was a cheap one though. I'm looking in to getting a pricier helicopter.
Back to top
 
 
View Profile | WWW   IP Logged
jordi
Full Member
***
Offline

Tururu!

Posts: 109
Baja California and California
Gender: male
Re: ArduCopter V1 Beta 2
Reply #8 - 17.11.2007 at 08:35:41
 


Hello people, i already have the beta 2 of arducopter, but right know i dont have time to translate (weakness), but if you wish to see more pictures and know a little bit of spanish, enter here:

http://gizmobits.com/2007/11/16/arducopter-beta-2/

by the way is my personal technology blog..
Back to top
 
 
View Profile | MSN   IP Logged
Anthony
YaBB Newbies
*
Offline

Arduino &
Freeduino rocks!

Posts: 12
Canada
Gender: male
Re: ArduCopter V1 Beta
Reply #9 - 19.11.2007 at 17:27:37
 
You're English is very good; don't worry too much about translations; a picture is worth a thousand words, and we're excited to see a video if you ever get the time to do so.  That's an excellent helicopter you put together.  It's cool that people are coming up with complex ideas and getting them to work. Cheesy
Back to top
 
 
View Profile | WWW | GTalk   IP Logged
jordi
Full Member
***
Offline

Tururu!

Posts: 109
Baja California and California
Gender: male
Re: ArduCopter V1 Beta
Reply #10 - 20.11.2007 at 11:23:43
 
Hola!
I have a video, to show that is real: http://www.youtube.com/watch?v=7xkJseQyhJA

Ok, i had a big problem, but i already solve it, the vibration of the main rotor, cause a lot of interference with the accelerometer, i almost leave this project for that. But i was googling around, and i found a group of student that try to make the same like me.. jejej here is the link: http://www.mne.psu.edu/me415/fall04/boeing4/

Well wathever, i used, i dont how to say it, in spanish are call "Ligas" links, is plastic bands. To put the accelerometer in the center and adsorb the vibrations. For my surprise i be able to reduce 90% to 95% of the vibration.

For pictures and translation of the original post (with google), enter here:
http://gizmobits.com/wp-content/uploads/2007/11/cimg0124.JPG
http://gizmobits.com/wp-content/uploads/2007/11/cimg0127.JPG

http://translate.google.com/translate?u=http%3A%2F%2Fgizmobits.com%2F2007%2F11%2...
Back to top
 
 
View Profile | MSN   IP Logged
CrashingDutchman
Senior Member
****
Offline



Posts: 355
Netherlands
Gender: male
Re: ArduCopter V1 Beta
Reply #11 - 20.11.2007 at 17:09:19
 
Can you place your accelerometer on a piece of soft foam? You might be able to get rid of more vibration...

Edit: Oops, I wrote that after watching your images... never mind (probably).
Back to top
 
 
View Profile   IP Logged
CrashingDutchman
Senior Member
****
Offline



Posts: 355
Netherlands
Gender: male
Re: ArduCopter V1 Beta
Reply #12 - 15.01.2008 at 16:49:35
 
Hola Jordi,

You made it to Make Magazine: http://blog.makezine.com/archive/2008/01/arducopter_arduino_helico.html?CMP=OTC-...

Congratulations!
Back to top
 
 
View Profile   IP Logged
jordi
Full Member
***
Offline

Tururu!

Posts: 109
Baja California and California
Gender: male
Re: ArduCopter V1 Beta
Reply #13 - 15.01.2008 at 17:25:59
 
Cheesy thanks!!
Back to top
 
 
View Profile | MSN   IP Logged
big93
Senior Member
****
Offline

Arduino rocks

Posts: 495

Re: ArduCopter V1 Beta
Reply #14 - 21.01.2008 at 08:14:08
 
is it flyable yet?
Back to top
 
 
View Profile   IP Logged
Pages: 1 2