New Servo Flap System by K.Kakuta
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
(Ch1 aileron stick) and Vertical (Ch2 elevator stick)
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
Please use “Serial.print” and Serial monitor on
PC
Please not use “Serial.print” at Flight ( Execution
speed of CODE becomes slow)
PPM Receiver-- RX PPM signal input to D2 pin
Servo right --D5 pin
Servo left --D6 pin
Ground -GND pin
6V -RAW pin ( 6-6.2V from Step down DC converter
or Step up DC converter ) -for 6V servo(-- more power)
or
5V -VCC pin
2cellLipo to 5V : iFlight BEC 2-8S 5V 2A
https://www.banggood.com/fr/IFlight-...r_warehouse=CN
My setting
Lipo: 70-120mAh1cell Lipo battery
Servo: BLUEARROW AF D43S-6.0-MG Micro Metal Gear
Digital Servo
https://www.aliexpress.com/item/33033558575.html?spm=a2g0s.9042311.0.0.43364c4d6lqbJw
https://www.aliexpress.com/item/4001120547325.html?spm=a2g0s.9042311.0.0.43364c4d6lqbJw
Arduino Pro mini board
DC stepup converter from 1cell Lipo 3.7V to 6V
output
----7W
mini DC DC Boost Step-up Converter 2.6-5.5V to 5V 6V 9V 12V Voltage Regulator
Module for LED Motor
https://www.aliexpress.com/item/1005001419105670.html?spm=a2g0s.9042311.0.0.27424c4dTyeLKp
PPM receiver: OrangeRx R616XN DSM2 / DSMX 6CH CPPM
Caution: After first connection to battery,
sometimes, Servo have stopped at an abnormal position and not move normally.
By pushing several times Reset Switch on Arduino
Board, servo move normally.
Set your transmitter Throttle 3ch End point to Max(140-150%)
at low and high stick position
********
2022/04/23 Changing of Wiring for 5V PPMRX
Wire 5V power supply from Pro Mini Board VCC to 5V PPMRX
Arduino Code Zip File
01/10/2024 Updated PPMReader to the latest version, V1.2.0
Nikkilae/PPM-reader https://github.com/Nikkilae/PPM-reader
dimag0g/PPM-reader https://www.arduinolibraries.info/libraries/ppm-reader
https://github.com/dimag0g/PPM-reader
ServoFlapDriveSystem 2servo Arduino CODE Zip File with PPMReader Zip File
//210521 Rudder ElevatorUP FlapAmp-UP delaytime
control PPMRX Ch1-4 writeMicroseconds(1000-2000uS) use by K.Kakuta
#include <Servo.h>
#include <PPMReader.h>
//#include <InterruptHandler.h>//
2022/01/27 Delete for more good move
//#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 = 6;
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;//Ch1
volatile int ch2value = 1500;//Ch2
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(1);//Ch1
ch2value = ppm.rawChannelValue(2);//Ch2
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
}
}
Version2
dtとelapsed timeを使った、delay(この場合、羽ばたきの最初のみ送信機の情報を拾う)をつかわないCODEの製作
羽ばたきの最中も送信機の情報を拾うので、動作が機敏になる可能性がある。
I changed CODE that Flapping system work by
time not “delay” code.
In the previous CODE, transmitter
information was read only once at the beginning of flapping.
The new CODE constantly reads information
from the transmitter while flapping its wings, so it can respond to sudden
changes in Ornithopter's attitude.
Therefore, the Ornithopter can fly with
agile attitude changes even in strong winds.
When the voltage of the Lipo drops, the
flapping frequency increases, so it is necessary to cancel the flight and set
it again, or to set it again during the flight.
“delay” CODEを使わず、”時間”を使って羽ばたきを行うArduinoCODEに変更した。
以前のCODEでは送信機の情報は羽ばたきの最初に1回だけ読み込んでいた。
新しいCODEでは、羽ばたきの間常に送信機の情報を読んでいるので、Ornithopterの姿勢の急激な変化に対応ができる。
したがって、強風の中でも機敏に姿勢の変化をしてOrnithopterは飛行ができる。
Lipoの電圧が落ちてくると、羽ばたきの周波数が多くなるため、飛行を中止して設定しなおすか、飛行中に再設定する必要がある。
//221207 Version2 Rudder ElevatorUP FlapAmp-UP
delaytime control PPMRX Ch1-4 writeMicroseconds(1000-2000uS) use dt and elapsed
time by K.Kakuta
#include <Servo.h>
#include <PPMReader.h>
//#include <InterruptHandler.h>//
2022/01/27 Delete for more good move
//#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 = 6;
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 float
delaytime = 100;// Servo speed low-increase Servo speed high-decrease this.
// unit: micro second
float elapsed_time =
0;
float dt;
unsigned long
current_time, prev_time;
volatile int ch3value = 1000;//Ch3
volatile int ch1value = 1500;//Ch1
volatile int ch2value = 1500;//Ch2
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() {
prev_time = current_time;
current_time = micros();
dt = (current_time - prev_time)/1000000.0;
elapsed_time = elapsed_time + dt; // total
time spent in the main loop since beginning one upstroke/downstroke
ch3value = ppm.rawChannelValue(3);//Ch3
ch1value = ppm.rawChannelValue(1);//Ch1
ch2value = ppm.rawChannelValue(2);//Ch2
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) {
if (elapsed_time <
delaytime/1000) {
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
if ((elapsed_time
> delaytime/1000) && ( elapsed_time < (delaytime +
delaytime)/1000)) {
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
}
if (elapsed_time
> (delaytime + delaytime)/1000) {// one full flap is finisheddt
elapsed_time = 0; // start next
flapping cycle
}
}