Cześć,
Czy w FS-th9x lub Turnigy 9x można zrobić miks na kanale z sygnałem wchodzącym na port trenera? Klikam i klikam i nie widzę... Google też nie pomaga, albo mam pomroczność...
Chodzi o kanał 5 i sygnał z przełącznika 6 trybów lotu na Arduino.
TH9X / 9x- mikser z p.trenera, Przełącznik trybów Arduino
Moderatorzy: marbalon, moderatorzy2014, moderatorzy
TH9X / 9x- mikser z p.trenera, Przełącznik trybów Arduino
Ostatnio zmieniony środa 16 sty 2019, 21:37 przez labo, łącznie zmieniany 1 raz.
Re: FlySky TH9X (Turnigy 9x)- mikser z sygnałem z portu tren
Na oryginalnym sofcie czy er9x/opentx?
Re: FlySky TH9X (Turnigy 9x)- mikser z sygnałem z portu tren
Na oryginalnym. :)
EDIT: Jakoś podpinali do TGY 9x: https://stefan.gofferje.net/uav/19-ardu ... ch-for-apm
EDIT2: Rozwiązanie trywialne (jeszcze nie przetestowałem), a ja całą apkę po mikserach itp. przeszukiwałem... http://courty.fr/connecter-un-arduino-a ... sibilites/
EDIT: Jakoś podpinali do TGY 9x: https://stefan.gofferje.net/uav/19-ardu ... ch-for-apm
EDIT2: Rozwiązanie trywialne (jeszcze nie przetestowałem), a ja całą apkę po mikserach itp. przeszukiwałem... http://courty.fr/connecter-un-arduino-a ... sibilites/
Re: TH9X / 9x- mikser z p.trenera, Przełącznik trybów Arduin
Nie zadziałało. Program generuje sygnał zmienny dla pierwszego kanału, a na apce nie zmiksuję (przynajmniej nie znalazłem solucji dla stockowego firmware) kanału 1 z portu trenera na kanał 5. Dodatkowo "oscyloskop" z karty dźwiękowej wykazał, że generator na Arduino i sygnał PPM z na porcie trenera miały odwrócone polaryzacje. Po zmianie polaryzacji i drobnej zmianie programu aby generował zmienny sygnał na kanale 5 a nie na 1, na wyświetlaczu aparatury działa. W Mission Plannerze jeszcze nie sprawdzałem.
Może komuś przyda się kod:
Może komuś przyda się kod:
Kod: Zaznacz cały
/*
APM Mode Switch - Set flight mode for ArduPilot Mega autopilots via
an RC transmitter's PPM (trainer) input
Version 1.0
(C) 2013 Stefan Gofferje - http://stefan.gofferje.net/
This program is free software; you can redistribute it and/or
modify it under the terms of the GNU General Public License
as published by the Free Software Foundation; either
version 2 of the License, or (at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU General Public License
along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
Usage:
Connect the PPM out of the board to the PPM in / trainer port of your
transmitter, as well as ground from the board to ground on the PPM /
trainer port of your transmitter. In mixes, assign trainer / PPM
channel 1 to the respective TX channel (e.g. channel 5 for APM:Copter).
*/
// Basic config
#define numchan 8 // number of chanels in PPM stream
#define servo_default 1500 // default servo value (1500 = center)
#define PPM_FrLen 22500 // PPM frame length in microseconds
#define PPM_PulseLen 300 // PPM pulse length
#define PPM_Polarity 0 // PPM polarity - 0 = neg, 1 = pos
#define PPM_outPin 10 // PPM output pin
// I/O-Pins
const byte LED[]={0,2,3,4,5,6,7};
const byte BUTTON[]={0,17,16,15,14,12,11};
// Channel PWM values
int ppm[numchan];
void setup(){
Serial.begin(9600);
for (int i=0;i<=6;i++) {
pinMode(LED[i],OUTPUT);
digitalWrite(LED[i],HIGH);
delay(100);
digitalWrite(LED[i],LOW);
}
for (int i=0;i<=6;i++) {
pinMode(BUTTON[i],INPUT);
digitalWrite(BUTTON[i],HIGH);
}
setled(-1);
delay(50);
setled(0);
delay(100);
setled(-1);
delay(50);
setled(0);
// All others to center
for(int i=0; i<numchan; i++){
ppm[i]= servo_default;
}
ppm[4]=2000; // We start in Mode 6
pinMode(PPM_outPin, OUTPUT);
digitalWrite(PPM_outPin, !PPM_Polarity);
// Set up timer interrupt
cli();
TCCR1A = 0;
TCCR1B = 0;
OCR1A = 100;
TCCR1B |= (1 << WGM12);
TCCR1B |= (1 << CS11);
TIMSK1 |= (1 << OCIE1A);
sei();
}
void setled(int nr) {
if (nr==0) {
for (int i=0;i<=6;i++) {
digitalWrite(LED[i],LOW);
}
}
else if (nr==-1) {
for (int i=0;i<=6;i++) {
digitalWrite(LED[i],HIGH);
}
}
else {
for (int i=0;i<=6;i++) {
digitalWrite(LED[i],LOW);
}
digitalWrite(LED[nr],HIGH);
}
}
void loop() {
if (digitalRead(BUTTON[1])==LOW) ppm[4]=1000;
else if (digitalRead(BUTTON[2])==LOW) ppm[4]=1296;
else if (digitalRead(BUTTON[3])==LOW) ppm[4]=1426;
else if (digitalRead(BUTTON[4])==LOW) ppm[4]=1556;
else if (digitalRead(BUTTON[5])==LOW) ppm[4]=1686;
else if (digitalRead(BUTTON[6])==LOW) ppm[4]=2000;
if ((ppm[4] > 0) && (ppm[4] < 1230)) setled(1);
else if ((ppm[4] > 1231) && (ppm[4] < 1360)) setled(2);
else if ((ppm[4] > 1361) && (ppm[4] < 1490)) setled(3);
else if ((ppm[4] > 1491) && (ppm[4] < 1620)) setled(4);
else if ((ppm[4] > 1621) && (ppm[4] < 1750)) setled(5);
else if (ppm[4] > 1750) setled(6);
Serial.println(ppm[4]);
}
ISR(TIMER1_COMPA_vect){
static boolean state = true;
TCNT1 = 0;
if(state) {
digitalWrite(PPM_outPin, PPM_Polarity);
OCR1A = PPM_PulseLen * 2;
state = false;
}
else{
static byte channel;
static unsigned int rest;
digitalWrite(PPM_outPin, !PPM_Polarity);
state = true;
if(channel >= numchan){
channel = 0;
rest = rest + PPM_PulseLen;
OCR1A = (PPM_FrLen - rest) * 2;
rest = 0;
}
else{
OCR1A = (ppm[channel] - PPM_PulseLen) * 2;
rest = rest + ppm[channel];
channel++;
}
}
}