2サーボ駆動&2サーボエレボン型羽ばたき機のArduino CODE(2ServoFlap&2servoElevon)
Arduino CODE for ServoFlapOrnithopter 2servoFlap&2servoElevon
                

New Servo Flap System by K.Kakuta
                                                                                 

New Servo Flap System by K.Kakuta


ServoFlapOrnithopter Flap by 2servo and 2Servo – Elevon (Aileron & Elevator)

2ServoFlap 2ServoElevon system ( Ch1 and Ch2 is other servo for Elevon)




1 Bilateral Servo Flap between Max high point and Max low point
- change max flap point (throttle stick) and change Flapping frequency(5chLS)
3 Change center of Flapping angle Horizontal (Ch6 Right Volume)and Vertical (Ch7 any switch)
4 Change flapping amplitude on each Servo (Ch4 rudder stick)
Increase flap amplitude of one servo and decrease flap amplitude of another servo
Setting : Set elevator and rudder and aileron stick Center-- 1500microsesond
Set 5Ch at Left Slider or other switch
Set throttle stick and 5CH at low max --1000 microsecond

5 6CH Elevator trim (volume)
6 7CH Aileron trim (switch)
7 Ch1(Aileron stick) and Ch2(Elevator stick) is for other 2 servos (Elevon setting on Transmitter)
送信機のRudder4chのScaleは30-70%など少しの作動でOK.
    例えば Scale100ではMaxで反対側の翼も動いてしまい、差動が効かなくなる。
Throttle 3chはEnd point Max 70-80 または140-150などStick最下位-最高位できちんと動くように設定する


PPM Receiver-- RX PPM signal input to D2 pin
Servo right --D5 pin
Servo left --D6 pin

2Servo+2servo



Arduino Pro mini board
Ground -GND pin
5-9V -RAW pin (5V from Step down DC converter or Step up DC converter or directly from 2sellLipo)

DC converter 2cellLipo7.4V to 5V for Elevator and Aileron and RX:
Ex. iFlight BEC 2-8S 5V 2A
https://www.banggood.com/fr/IFlight-...r_warehouse=CN


Lipo: 2cell Lipo battery
Servo: KTS MR320HV(need converter 2cell 7.4V to 6V) or MS320HV(2cell) or other
Arduino Pro mini board
DC converter 2cell to 5V
PPM receiver: 8ch
FS-RX2A RX2AproV1 PPM out
https://ja.aliexpress.com/item/1005002992822970.html?spm=a2g0o.productlist.0.0.102d5af0Z5OvVn&algo_pvid=0eb76674-2d5c-46ef-bfa1-725d406b9d8e&algo_exp_id=0eb76674-2d5c-46ef-bfa1-725d406b9d8e-7&pdp_ext_f=%7B%22sku_id%22%3A%2212000023115744207%22%7D&pdp_pi=-1%3B741.0%3B-1%3B-1%40salePrice%3BJPY%3Bsearch-mainSearch
Or other

SPP-S SBUS PPM PWM Signal Conversion Module
https://www.aliexpress.com/item/1005002992939836.html?spm=a2g0o.order_list.0.0.5a13585anHwU3R&gatewayAdapt=glo2jpn

Library PPMReader.h
Nikkilae/PPM-reader https://github.com/Nikkilae/PPM-reader

220306
Avoid abnormal positions at startup-wait 2 second until RX starts220306
Add “delay(2000);”
void setup() {
Serial.begin(9600);

pinMode(servo_left_pin, OUTPUT);
pinMode(servo_right_pin, OUTPUT);

servo_left.attach(servo_left_pin);//output pin No
servo_right.attach(servo_right_pin); //output pin No
 delay(2000);//Avoid abnormal positions at startup-wait 2 second until RX starts220306

}

Arduino CODE

ServoFlapSystem and Elevon 2ServoFlap&2servo Arduino CODE with PPMReader ZipFile

//220806 from 220310 2ServoFlap2ServoElevon ch6Elevator ch7Ailron 8chPPMRX Ch1-7 writeMicroseconds(1000-2000uS) use by K.Kakuta
#include <Servo.h>
#include <PPMReader.h>

//#define DOPRINTS // if you print on PC screen Data, delete”//”
// In use of Flap system,cut "Serial.print "(put ”//”)
//and write code to Arduino board.
int interruptPin = 2;
int channelAmount = 8;
PPMReader ppm(interruptPin, channelAmount);

int servo_left_pin = 6;
int servo_right_pin = 5;

volatile int elevator = 0;
volatile int flapamp = 0;
volatile int delaytime = 100;// Servo speed low-increase Servo speed high-decrease this.
// unit: micro second
volatile int ch3value = 1000;//Ch3
volatile int ch1value = 1500;//Ch1changetoCh7
volatile int ch2value = 1500;//Ch2changetoCh6
volatile int ch4value = 1500;//Ch4: Set Scale of 4ch of TX to 70%
volatile int ch5value = 1500;//Ch5
static int servo_comm1 = 0;// Left or Right Servo high point and low point
static int servo_comm2 = 0; // Left or Right Servo high point and low point
volatile int rudder = 0;
float glide_deg = 0; // Gliding angle 0=0 degree 500=90degree
static float servo_zero1 = 0;//flap angle adjust
static float servo_zero2 = 0; //flap angle adjust

Servo servo_left, servo_right; // create servo object to control a servo

void setup() {
Serial.begin(9600);

pinMode(servo_left_pin, OUTPUT);
pinMode(servo_right_pin, OUTPUT);

servo_left.attach(servo_left_pin);//output pin No
servo_right.attach(servo_right_pin); //output pin No
delay(2000);//Avoid abnormal positions at startup-wait 2 second until RX starts220306
}

void loop() {
ch3value = ppm.rawChannelValue(3);//Ch3
ch1value = ppm.rawChannelValue(7);//Ch1change to 7
ch2value = ppm.rawChannelValue(6);//Ch2change to 6
ch4value = ppm.rawChannelValue(4);//Ch4
ch5value = ppm.rawChannelValue(5);//Ch5


#ifdef DOPRINTS
Serial.print("ch3value ");Serial.print(ch3value);
Serial.print(",\t");
Serial.print("ch1value ");Serial.print(ch1value);
Serial.print(",\t");
Serial.print("ch2value ");Serial.print(ch2value);
Serial.print(",\t");
Serial.print("ch4value ");Serial.print(ch4value);
Serial.print(",\t");
Serial.print("ch5value ");Serial.print(ch5value);
Serial.println(",\t");
#endif

rudder=(int)(ch1value-1500);//Ch1 Flap angle incline-- AileronStick
elevator=(int)(ch2value-1500);//Ch2 Flap Angle bilateral UP&Down
flapamp=(int)(ch4value-1500);//Ch4 Right and left Flap angle difference from3to2
delaytime=(int)((ch5value-950)/5);//Ch5 Flapping frequency
// you can change UP or Down direction by your transmitter Reverse setting of each Channel

#ifdef DOPRINTS
//Serial.print("rudder");Serial.print(rudder);
//Serial.print(",\t");
//Serial.print("elevator");Serial.print(elevator);
//Serial.print(",\t");
//Serial.print("flapamp");Serial.print(flapamp);
//Serial.print(",\t");
//Serial.print("delaytime");Serial.print(delaytime);
//Serial.print(",\t");
#endif

if (ch3value > 1080) {

servo_comm1 = (int)( (ch3value -1000)/2+1500 + rudder - elevator+ servo_zero1+ flapamp);
servo_comm2 = (int)(1000 + (2000 - ((ch3value -1000)/2+1500)) + rudder + elevator- servo_zero2+flapamp);

servo_left.writeMicroseconds(servo_comm1); // servo position in variable 'pos'
servo_right.writeMicroseconds(servo_comm2); // servo position in variable 'pos'

delay(delaytime); //Wait 1second=1000mseconds

servo_comm1 = (int)( (ch3value -1000)/2+1500 + rudder + elevator+ servo_zero1-flapamp);
servo_comm2 = (int)(1000 + (2000 - ((ch3value -1000)/2+1500)) + rudder - elevator- servo_zero2-flapamp);

servo_left.writeMicroseconds(servo_comm2); // servo position in variable 'pos'
servo_right.writeMicroseconds(servo_comm1); // servo position in variable 'pos'

#ifdef DOPRINTS
//Serial.print("servo_comm1");Serial.print(servo_comm1);
//Serial.print(",\t");
//Serial.print("servo_comm2");Serial.print(servo_comm2);
//Serial.println(",\t");
#endif

delay(delaytime); //Wait 1second=1000mseconds

}
else{

servo_comm1=(int)(1500+rudder-elevator+glide_deg);
servo_comm2=(int)(1500+rudder+elevator-glide_deg);

servo_left.writeMicroseconds(servo_comm1); // servo position in variable 'pos'
servo_right.writeMicroseconds(servo_comm2); // servo position in variable 'pos'

#ifdef DOPRINTS
//Serial.print("servo_comm1");Serial.print(servo_comm1);
//Serial.print(",\t");
//Serial.print("servo_comm2");Serial.print(servo_comm2);
//Serial.println(",\t");
#endif

}

}