อ่านค่ารีโมทจากรีซีปแบบสายเส้นเดียวได้ค่า 8 Ch
ค่าสเป็คจากรีซีปรับสัญญานรีโมท
Specification:
Channels: 4 (8 in CPPM)+ FSH connector + A2 connectors ( + A1 internal reading)
Dimension: 40*22.5 *6 mm
Weight: 5.8 grams only!
Full Range like bigger Rx ! >1,5Km
2 antennas
Operating Voltage Range: 3.5V-10V
Operating Current: 60mA
Features:
1) Lighter weight and physically smaller than D8 and D6FR
2) RSSI (PWM) and CPPM output - If CH3 and CH4 are connected by a jumper, CH1 will output RSSI (PWM), and CH2 will output CPPM for CH1~CH8
ต้องอัพเดทเฟิร์มแวร์ตามวีดีโอนี้
จะต้องทราบภาพนี้ก่อน
เป็นการส่งพัลซ์ทั้ง 8 ช่องในสายเส้นเดียว
ตัวอย่างโค๊ต
/*
project_Quad 32 bit
1. Read PPM
by: tinnakon kheowree
0860540582
tinnakon_za@hotmail.com
tinnakonza@gmail.com
date: 13-05-2557(2014) Read_sensor2_mpu6050_V4
support: arduino-1.5.7 Arduino Due
• Atmel SAM3X8E ARM Cortex-M3 CPU 32-bit a 84 MHz clock, ARM core microcontroller
• MPU6050C Gyro Accelerometer //400kHz nois gyro +-0.05 deg/s , acc +-0.04 m/s^2
• MS561101BA Barometer
• HMC5883L Magnetometer //400kHz
Quad-X
pin 9 FRONTL M1CW M2CCW FRONTR pin 7
\ /
\ --- /
| |
/ --- \
/ \
pin 6 motor_BackL M4 CCW M3 CW motor_BackR pin 8
----------rx-----------
CPPM => A8
Aileron => A8
Elevator => A9
Throttle => A10
Ruder => A11
Aux1 => A7
Aux2 => --
*/
//#define CHIP_FREQ_CPU_MAX (84000000UL)
#include
#include "multi_rx_sam3x8e.h"
void setup()
{
Serial.begin(115200);//38400
pinMode(13, OUTPUT);//pinMode (30, OUTPUT);pinMode (31, OUTPUT);//pinMode (30, OUTPUT);pinMode (31, OUTPUT);//(13=A=M),(31=B=STABLEPIN),(30=C,GPS FIG LEDPIN)
digitalWrite(13, HIGH);
configureReceiver();//multi_rx_sam3x8e.h
delay(500);
RC_Calibrate();//multi_rx_sam3x8e.h
Serial.print("TK_Quadrotor32Bit_Run_Roop_400Hz");Serial.println("\t");
}
void loop()
{
computeRC();//multi_rx_sam3x8e.h
roop++;
digitalWrite(13, LOW);
if(roop > 10)//roop print TASK_10HZ
{
roop = 0;
digitalWrite(13, HIGH);
Serial.print(CH_THR);Serial.print("\t");
Serial.print(CH_AIL);Serial.print("\t");
Serial.print(CH_ELE);Serial.print("\t");
Serial.print(CH_RUD);Serial.print("\t");
Serial.print(AUX_1);Serial.print("\t");
//Serial.print(AUX_2);Serial.print("\t");
//Serial.print(AUX_3);Serial.print("\t");
//Serial.print(AUX_4);Serial.print("\t");
Serial.print("\n");
}//end roop 5 Hz
delay(20);//delay 20 ms = 50 Hz
}//end void loop()
ไฟล์ multi_rx_sam3x8e.h
//#include "multi_rx2560.h"
//project_Quad 32 bit Arduino Due
//1. stabilized quadrotor
//by: tinnakon kheowree
//0860540582
//tinnakon_za@hotmail.com
//tinnakonza@gmail.com
#define MIDRC 1500
#define MINCHECK 1100
#define MAXCHECK 1900
int CH_THR = 1000;
int CH_AIL = 1500;
int CH_ELE = 1500;
int CH_RUD = 1500;
float CH_AILf = 1500;
float CH_ELEf = 1500;
float CH_RUDf = 1500;
int CH_AIL_Cal = 1500;
int CH_ELE_Cal = 1500;
int CH_RUD_Cal = 1500;
int AUX_1 = 1000;
int AUX_2 = 1000;
int roop = 0;
float tarremote = 0.065;
//RX PIN assignment inside the port
//SET YOUR PINS! TO MATCH RECIEVER CHANNELS
#define CHAN1PIN 62 // RECIEVER 1 PPM
//#define CHAN2PIN 63 // RECIEVER 2
//#define CHAN3PIN 64 // RECIEVER 3
//#define CHAN4PIN 65 // RECIEVER 4
//#define CHAN5PIN 61 // RECIEVER 5
//#define CHAN6PIN 67 //not used at the moment
//#define CHAN7PIN 50 //not used at the moment
//#define CHAN8PIN 51 //not used at the moment
#define ROLL 0
#define PITCH 1
#define YAW 3
#define THROTTLE 2
#define AUX1 5
#define AUX2 4
//#define CAMPITCH 6
//#define CAMROLL 7
//volatile unsigned long pwmLast[8];
volatile unsigned long last = 0;
uint8_t chan1 = 0;
volatile uint16_t rcValue[8] = {1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502}; // interval [1000;2000]
// Arduino Due RX PPM
void pwmHandler(int ch, int pin) {
///PPM/////////////////
unsigned long now,diff;
now = micros();
diff = now - last;
last = now;
if(diff>3000) chan1 = 0;
else {
if(900
rcValue[chan1] = diff;
}
chan1++;
}
}
void ch1Handler() { pwmHandler(0, CHAN1PIN); }
//void ch2Handler() { pwmHandler(1, CHAN2PIN); }
//void ch3Handler() { pwmHandler(2, CHAN3PIN); }
//void ch4Handler() { pwmHandler(3, CHAN4PIN); }
//void ch5Handler() { pwmHandler(4, CHAN5PIN); }
void configureReceiver() {
for (uint8_t chan = 0; chan < 8; chan++){
for (uint8_t a = 0; a < 4; a++){
rcValue[a] = 1500;
}
}
attachInterrupt(CHAN1PIN,ch1Handler,RISING);//RISING FALLING CHANGE
//attachInterrupt(CHAN2PIN,ch2Handler,CHANGE);
//attachInterrupt(CHAN3PIN,ch3Handler,CHANGE);
//attachInterrupt(CHAN4PIN,ch4Handler,CHANGE);
//attachInterrupt(CHAN5PIN,ch5Handler,CHANGE);
}
void computeRC() {
CH_THR = rcValue[THROTTLE];
CH_AIL = rcValue[ROLL];
CH_ELE = rcValue[PITCH];
CH_RUD = rcValue[YAW];
AUX_1 = rcValue[AUX1];
AUX_2 = rcValue[AUX2];
CH_AILf = CH_AILf + (CH_AIL - CH_AILf)*0.02/tarremote;//Low pass filter
CH_ELEf = CH_ELEf + (CH_ELE - CH_ELEf)*0.02/tarremote;
CH_RUDf = CH_RUDf + (CH_RUD - CH_RUDf)*0.02/tarremote;
}
//By tinnakon
void RC_Calibrate(){
Serial.print("RC_Calibrate");Serial.println("\t");
for (int i = 0; i < 10; i++) {
computeRC();
delay(20);
}
CH_AIL_Cal = CH_AIL;
CH_ELE_Cal = CH_ELE;
CH_RUD_Cal = CH_RUD;
Serial.print(CH_AIL_Cal);Serial.print("\t");//-0.13
Serial.print(CH_ELE_Cal);Serial.print("\t");//-0.10
Serial.print(CH_RUD_Cal);Serial.println("\t");//0.03
}