quix-fz's Posts (6)

Sort by

supersimple esc's and quadro-update

a little info i couldnt find anywhere else. while programming my quadrocopter, i somehow messed up the throttle start and end-points of one of the esc's. the motor started only when the throttle was already in the middle. after some googling and experimenting, i found out how to reprogramm the endpoints. this will probably work with other esc's too.here's the exact procedure:- connect esc to receiver and motor, do NOT connect battery- on the (turned on) remote move to full throttle- now connect the battery- the esc will beep twice (two short beeps)- right after that, move the throttle back to idle/off/stop- the esc will now do the normal beeps (in my case 3 beeps for 3s lipo)- it can probably be used now, but i would "reboot" (disconnect battery and connect again) just to make sure it worked.this procedure fixed it. i then did this to all 4 esc's, and for the first time, all the props started moving and stopped at the same time. also got the best and most stable hover up until now.im surprisingly quickly getting to very stable results. all the axes are stabilised now. i removed the accelerator mixing for the moment (vibrations are problably making it useless right now) until i connect a display and see what's going on exactly. for short flights this isnt a problem. the quadro lifts off and stays very calm, no wobbling, no heavy vibrations (except motors of course), it's just slighty moving around, but i can control it with the remote. this probably can be stabilised with the accelerometer to.also did some hacking to the board, and connected another 4017 (to the unused output compare unit of timer 1) so i could drive the esc at 200hz, works perfectly!! love those esc's!here's the code of the PI-controller:int sens_nick = (gyro_y>>1)+(y_angle2>>10); //the current gyro data + integrated gyro data (shifting is precise enough at the moment :)int sens_roll = (gyro_x>>1)+(x_angle2>>10);int sens_yaw = (gyro_z>>1)+(z_angle2>>10);int inp_nick = -50+((serinp[1]-3750)>>3); //a little trim, plus the input from the ppm-decoder/remote-controlint inp_roll = -50+((serinp[0]-3750)>>3);int inp_yaw = -30+((serinp[3]-3750)>>3);//seradj is added to the throttle-input and passed to each esc.seradj[2] = (sens_nick-inp_nick) -inp_yaw-sens_yaw; //backseradj[3] = -(sens_nick-inp_nick) -inp_yaw-sens_yaw; //frontseradj[0] = (sens_roll-inp_roll) + inp_yaw+sens_yaw; //rightseradj[1] = -(sens_roll-inp_roll) + inp_yaw+sens_yaw; //left
Read more…

quadrocopter

a few weeks ago i decided to build a quadrocopter. this would be a real challange but still inside the capabilities of the pcb i made. i actually designed it with plane-uavs in mind. but there's no reason it wont be able to controll a quadrotor.here's the finished board connected to a display. the display i a cheapo 128x64 graphics lcd controlled by another atmega168 and connected with spi. i removed the yaw-gyro from the board to get to the spi bus (also needed for programming the main atmega)... always include a isp-port on every board involving an atmega!that was mainly build to port the arduino code (using crystalfontz serial lcd) to winavr/gcc (using my spi-display). i already had everything working on the arduino and could do some testing with gyro integration and sensor fusion with the accelerotmeter.
this is the frame. i used 10x8 cf-tubes and glued aluminium-profiles for mounting the motors and attaching them to the central gf-plate. the motors are TP 2410-09, supersimple 30A ESC and EPP1245 props.
here's the test-stand. these motors+props are very powerful, so there are 3 bottles of coke in the basket, so it doesnt lift off. getting it to stabilise was surprisingly simple, here's the code. this code is run whenever there's new data from accelerometer, that's 640 times per second. gyro-data is also read then//gyro_x is current gyro output//x_angle is current integrated gyro angle mixed (127/128 gyro, 1/128 accelerometer) with little accelerometer angle (fixed point 20.12)seradj[0]=(gyro_x>>1)+(x_angle>>10); //adjustment/stabilisation for x-axis, basicly a simple PI-controller//serinp[2] is the throttle channel, serout[0] is the ppm-output for the back rotorserout[0]=serinp[2]+seradj[0]; //the values are micro-seconds x2 for the ppm-outputserout[1]=2000; //left, currently offserout[2]=serinp[2]-seradj[0]; //frontserout[3]=2000; //right, currently offthat's stabilising it very nicely. would probably be good enough for flying. the angle it stabilises to isn't exactly 0, probably the accelerator isnt perfectly parallel w.r.t. the frame. ppm is only output for the 4 esc's, one after the other as fast as possible, thats 250hz update rate at idle and 125hz at full power. works great so far.TODO:- better mounting for the pcb, receiver and battery- connect serial display for debugging- stabilise roll and yaw- tons of currently unknown problems- fly :)
Read more…

6-legged walking roboter

slightly offtopic, but the servo-interface might be of interest to some people. here's my 6 legged walking roboter. there are 3 servos for every leg.

these are connected to two 4017 ic's (10 servos max each) and these are connected to the two timer-1-compare-outputs (pin 9 and 10) on the arduino. since i'm using the timer1 and interupts, the whole thing barely uses any cpu power. and you can still use the timer1-capture-input to read ppm from the receiver in parallel.regarding cpu usage. i got my prototype-uav running (big breadboard in the background of the photos) with 640Hz sample and update rate, with accelerator-sensor, pressure-sensor, 3-gyros, 10 servo output, ppm input and decoding, gps input and serial display output (had to add buffering to the Serial-library of arduino, but works :) ). the pcb is also on the way :-Dthe 4017 are really easy to work with. if there's interest, i can post the schematic and sourcecode.
Read more…

prototype of my uav-pcb

because there's no easy way to connect the arduino to a normal perf-baord (stupid 2mm space between digi7 and digi8) i decided to make it the right way from the beginning. so i downloaded eagle and played around the last few days. this is what has come out. :) i plan to use the arduino bootloader and just connect the few needed pins to a empty diecimila board for easy programming. all the traces are already handrouted.i'll use the following sensors (plugged in on the pinheaders [should be female ones on the board]):3x Gyro Breakout Board - MLX90609Triple Axis Accelerometer Breakout - LIS3LV02DQBreakout Board for MEMs Barometric Pressure Sensor - SCP1000they all run on the spi bus. there's a 74hc4050 for level-shifting 5v to 3.3V for the accelerometer and pressure sensor.- there are 4 keys based on http://www.arduino.cc/en/Tutorial/TwoSwitchesOnePin- the 4 pins on the left are i2c + power for the sparkfun-blinkm- ppm input (see my previos blog post)- ppm output (ppm and reset signal also driven by timer1) and a 4017N decoder to 10 servos. that should be enough :)the cool thing about this is that when coded correctly, this thing wont lose control when the software crashes. since the the interupts are called in hardware by the timer, as long as the crashed software doesn't modify the timer-setup-registers, the interupts will continue to be called! so you could check in the input capture interupt each time if the programm is running (increment variable for each loop or like that): if yes, use the computed servo-position, if not, directly pass the position from the receiver.the display (ttl serial crystalfontz) is pluged in for setup.the ublox (got it here http://ppzuav.com/) has a very nice software for windows. you can connect it with usb, experiment with the settings, and save the default settings to flash! so you wont need to do this on every start up. the gps is only connected with serial-in, 5V and gnd.what i noticed on the ublox is that it's not as sensitive as a sirf3! my old sirf3 easily works indoors. the ublox wont, i have to at least put it next to the window...this is just a prototype or alpha version. i connected all the stuff the way i think it should work.- ppm input works- ppm output works, but without the reset-signal at the moment (should usually work without problems, but if for some reason a pulse is skipped, all the following pulses/servo-positions will be shifted by one servo... which is not so good...)- gps works (at least with nmea messages, ublox messages will be even easier)- display with simple menu-system works- pressure sensor works (but with a simpler level shifter, have to first get the 74hc4050)todo:- connect all parts on a breadboard- read all sensors- get board made- write software....once the baord is finshed, i'll probably release the eagle files. the design is quite universal and can be used for everything! more sensors/hardware can be easily connected to i2c or spi-bus (there are 3 unused i/o pins the atmega)PS: i should probably add headers for a rf-transmitter or maybe add battery-voltage-input (voltage divider) or a sd-card slot (on the backside?) instead of eeprom.
Read more…

best way to read a servo signal on arduino

the atmega168 on the arduino has a timer1 which has input capture capability (see this application note and datasheet for atmega168 for details). using it, it's possible to do the pulse timing in completly in hardware (no errors, no jitter), and having a interupt readout the measured time.here's the code:unsigned int serinp[8]; //servo positionsvoid setup_timer1(){//disable all interuptsTIMSK1 &= ~( _BV(TOIE1) | _BV(ICIE1) | _BV(OCIE1A) | _BV(OCIE1B));//set timer modeTCCR1A &= ~( _BV(WGM11) | _BV(WGM10) );TCCR1B &= ~( _BV(WGM12) | _BV(WGM13) | _BV(ICNC1));//capture raising edgeTCCR1B |= _BV(ICES1); //capture raising edge//prescaler 1/8TCCR1B |= _BV(CS11);TCCR1B &= ~( _BV(CS12) | _BV(CS10) );//disable outputsTCCR1A &= ~( _BV(COM1A0) | _BV(COM1A1) | _BV(COM1B0) | _BV(COM1B1));//enable capture interuptTIMSK1 |= (1<<ICIE1);}ISR(TIMER1_CAPT_vect){static unsigned int lasticr; //icr at last caputrestatic unsigned char cserinp; //current input servounsigned int licr;//TCCR1B ^= _BV(ICES1);licr=ICR1-lasticr;lasticr=ICR1;if(licr>5000){ //pulse too long, means start of new framecserinp=0;}else if(licr>1000){ //pulse good, take reading, go to next channelserinp[cserinp]=licr;if(cserinp<8){cserinp++;}}else{//too short, nothing to see here}}void setup()pinMode( 8, INPUT ); //sumsetup_timer1();}void loop(){//use serinp!!!}it'll take a sum signal on pin 8. you can also connect the signal for a single servo, then just serinp[0] will be populated. the values in serinp are 2 times the microseconds, so between 2000-4000 (instead of 1000-2000), yes, there's extra accuracy in there!the timer-capture only works on digital pin 8!if you don't have access to the sum signal, a possible way to read multiple servos would be to connect them all to pin 8. since the receivers usually output the pulses one after the other, this should work (you'll have to adjust the code in the capture-interupt).
Read more…