Fordulatszám szabályzó két motoros hajó részére

Az oldal röviden bemutatja hogyan készíthetünk kész modulokból egy olyan szabályzót, amely a távirányító PPM jele alapján meghajtja a hajónk két motorját, és dinamikusan választhatunk vezérlési üzemmódok között.

Központi egység: Arduino Nano, ATMEGA328 processzorral
Teljesítmény illesztő: dual H-hidas kínai modul, IRF3205 nFET-tel


Oldal utolsó módosítása: 2021.03.15

Frissült a leírás, ver.:0.5

ekucko_proj_sc_dual_arduino_ppm

A videó röviden bemutatja az egyes működési üzemmódokat. Ezek a következők:

  • Normál üzemmód

  • A két motor független vezérlése

  • A két motor kormány állásszögétől függő vezérlése

Forráskód, főprogram

/*

* Modell távirányító PPM csatornájának mérése

*

*/



/* Fordítási definíciók

*/

//#define _szu_RcRx_Int0_ChGaz // a gáz 1 csatornás mérése az Int0 megszakítással (tipikusan egy motoros vezérléshez)

#define _szu_RcRx_Int0_Ppm // PPM jelsor mérése az Int0 megszakítással

//#define _szu_HBridge_China_IMS2B // Egy motoros HBridge 5-13V/43A, kínai (leírás a jegyzetben)

#define _szu_HBridge_China_Dual_DirPwm // két motoros HBridge 5-36V/10A, kínai, álló nFET (leírás a jegyzetben)




struct struct_RcChxData {

uint8_t chIndex; // hanyas csatorna legyen, ha PPM sorozat mérése után egy soros->párhuzamos átalakítást végzek

uint8_t PpmIndex; // Ppm jelsorban hanyas számú (0-tól kezdődik a sorszámozás, ahogyan a tömb is)

//unsigned char chName[6];

uint16_t chValue; // csatorna mért és feldolgozott értéke

uint16_t chBotLow; // elfogadható legrövidebb impulzus szélesség

uint16_t chBotNat; // középálláshoz tartozó impulzus szélesség

uint16_t chBotHigh; // elfogadható leghosszabb impulzus szélesség

};



struct struct_MotorCtrl {

int8_t rcCtrl_Dir; // távirányító által előírt forgásirány (-1, 0, 1)

uint8_t rcCtrl_Pwm; // távirányító által előírt PWM szélesség (ha bírja a uP, ezt módosítani kell 16 bitre)

uint32_t rcCtrl_TimeSpin; // távirányító által előírt egy fordulathoz tartozó idő [usec]

int8_t motor_Dir; // motor beállítása szerint a valós forgásirány (így látható, ha a vezérben forgásirányt kell módosítani

uint8_t motor_Pwm; // motor meghajtás aktuális jelszélessége (különösen lágy indítás, vagy fordulatszám tartás esetén van jelentősége)

uint32_t motor_TimeSpin_Start; // a motor egy fordulatához tartozó mérés kezdő időpillanta [usec]

uint32_t motor_TimeSpin; // a motor egy fordulatához tartozó idő az utolsó mérés szerint [usec]

};



#include "D:\arduinoprog\nano_rc_ppm\tab_convert_rcx.ino"



const byte intPin_Int0 = 2; // Int0 láb

const byte pinTestOscOut= 7; // teszt impulzus kimenet oszcilloszkópos méréshez


#if defined( _szu_HBridge_China_IMS2B )

const byte pinPwm_Rev = 5; // Hátra Pwm jel kimenete ( OC0B /PD5/D5 láb)

const byte pinPwm_Nor = 6; // Előre Pwm jel kimenete ( OC0A /PD6/D6 láb)

const byte pinDir_Nor = 14; // Előre irány kimenete ( ADC0 /PC0/A0 láb)

const byte pinDir_Rev = 15; // Hátra irány kimenete ( ADC1 /PC1/A1 láb)

const byte pinLedDir_Nor= 18; // Előre irány LED kijelzése ( ADC4 /PC4/A4 láb)

const byte pinLedDir_Rev= 19; // Hátra irány LED kijelzése ( ADC5 /PC5/A5 láb)

#endif


#if defined( _szu_HBridge_China_Dual_DirPwm )

const byte pinPwm_M1 = 5; // M1 (bal) motor Pwm jel kimenete ( OC0B /PD5/D5 láb)

const byte pinPwm_M2 = 6; // M2 (jobb) motor Pwm jel kimenete ( OC0A /PD6/D6 láb)

const byte pinDir_M1 = 14; // M1 motor irány kijelölő kimenete (H-előre) ( ADC0 /PC0/A0 láb)

const byte pinDir_M2 = 15; // M2 motor irány kijelölő kimenete ( ADC1 /PC1/A1 láb)

const byte pinLedDirM1_Nor= 16; // M1 motor Előre irány LED kijelzése ( ADC2 /PC2/A2 láb)

const byte pinLedDirM1_Rev= 17; // M1 motor Hátra irány LED kijelzése ( ADC3 /PC3/A3 láb)

const byte pinLedDirM2_Nor= 18; // M2 motor Előre irány LED kijelzése ( ADC4 /PC4/A4 láb)

const byte pinLedDirM2_Rev= 19; // M2 motor Hátra irány LED kijelzése ( ADC5 /PC5/A5 láb)

#endif




uint32_t time_usec, time_msec, time_msec_last;

uint32_t rcpwm_usec_start= 0;

uint32_t rcpwm_usec_stop= 0;

uint32_t rcpwm_usec_last= 0;

bool rcpwm_edge_LH= 0;

bool rcpwm_edge_HL= 0;


uint16_t timer_1sec= 0;

uint16_t timer_RcRxSafely= 0;

uint16_t cnt_samemsec= 0;


struct struct_RcChxData rcChGazB, rcChKorm, rcChGazJ, rcChUzemMod;

struct struct_MotorCtrl motorLeft, motorRight;



#if defined(_szu_RcRx_Int0_Ppm)

uint8_t timer_PpmSync= 0; // minden msec-ban növelem, s törlöm, ha jön egy PPM HL él

uint8_t rcppm_chnumber= 0; // éppen hanyas csatorna mérése történik a PPM jelsorban (0- szinkron utáni állapot)

uint16_t aRcPpmChPw[12]; // ebbe a tömbbe töltöm az utolsó mérés szerint ch impulzus szélességet (a megszakítás által feltöltött nyers adat)

#endif



//************************************************************************


void setup() {

// initialize digital pin LED_BUILTIN as an output.

pinMode(intPin_Int0, INPUT_PULLUP);

pinMode(LED_BUILTIN, OUTPUT);

digitalWrite(LED_BUILTIN, LOW);

pinMode( pinTestOscOut, OUTPUT); // szkóp felé kimeneti jel teszt állapot kijelzéshez

digitalWrite( pinTestOscOut, LOW);

#if defined( _szu_HBridge_China_IMS2B )

pinMode( pinPwm_Rev, OUTPUT); // hátra irány PWM jele

digitalWrite( pinPwm_Rev, LOW);

pinMode( pinPwm_Nor, OUTPUT); // normál irány PWM jele

digitalWrite( pinPwm_Nor, LOW);

pinMode( pinDir_Rev, OUTPUT); // hátra irány engedélyező/kijelölő jele

digitalWrite( pinDir_Rev, LOW);

pinMode( pinDir_Nor, OUTPUT); // normál irány engedélyező/kijelölő jele

digitalWrite( pinDir_Nor, LOW);

pinMode( pinLedDir_Nor, OUTPUT); // piros led

digitalWrite( pinLedDir_Nor, LOW);

pinMode( pinLedDir_Rev, OUTPUT); // zöld led

digitalWrite( pinLedDir_Rev, LOW);

#endif

#if defined( _szu_HBridge_China_Dual_DirPwm )

pinMode( pinPwm_M1, OUTPUT); // M1 motor pwm jele

digitalWrite( pinPwm_M1, LOW);

pinMode( pinPwm_M2, OUTPUT); // M2 motor pwm jele

digitalWrite( pinPwm_M2, LOW);

pinMode( pinDir_M1, OUTPUT); // M1 motor forgásirány kijelölő láb

digitalWrite( pinDir_M1, HIGH); // előre menet lesz az alapértelmezett

pinMode( pinDir_M2, OUTPUT); // M2 motor forgásirány kijelölő láb

digitalWrite( pinDir_M2, HIGH);

pinMode( pinLedDirM1_Nor, OUTPUT); // M1 motor forgásirány kijelző láb

digitalWrite( pinLedDirM1_Nor, HIGH); // előre menet lesz az alapértelmezett

pinMode( pinLedDirM1_Rev, OUTPUT);

digitalWrite( pinLedDirM1_Rev, LOW);

pinMode( pinLedDirM2_Nor, OUTPUT); // M2 motor forgásirány kijelző láb

digitalWrite( pinLedDirM2_Nor, HIGH); // előre menet lesz az alapértelmezett

pinMode( pinLedDirM2_Rev, OUTPUT);

digitalWrite( pinLedDirM2_Rev, LOW);

#endif

time_usec= 0;

time_msec= millis();

//time_msec_last= time_msec;

timer_1sec= 0;

set_DefaultValue();

Serial.begin(57600);

#if defined(_szu_RcRx_Int0_ChGaz)

attachInterrupt(digitalPinToInterrupt(intPin_Int0), irq_handler_Int0, CHANGE);

#endif

#if defined( _szu_RcRx_Int0_Ppm )

attachInterrupt(digitalPinToInterrupt(intPin_Int0), irq_handler_Int0, FALLING);

#endif

//vedelem_RcAlaphelyzet(); // addig várakozik, amíg a távirányító karok nincsenek alaphelyzetben

}



//************************************************************************


void loop() {

#if defined(_szu_RcRx_Int0_ChGaz) // ha 1 csatornás Rc jelet mérek, akkor ez a rész bekerül a kódba

//---- RC PWM jel kiértékelése --------

if ( rcpwm_edge_LH && rcpwm_edge_HL ) {

// törlöm a jelzőbiteket

rcpwm_edge_LH= 0;

rcpwm_edge_HL= 0;

int8_t valasz;

valasz= InpChxPWCtrl_Gaz( (uint32_t)(rcpwm_usec_stop- rcpwm_usec_start) ); // távirányítóról érkező gáz csatorna PW szélességének feldolgozása

if (valasz>=0) {

timer_RcRxSafely= 0; // a vétel timer újraindítása, mivel értékes impulzus érkezett

//--- vétel kijelző LED vezérlése, amely most a beépített LED

if (!digitalRead(LED_BUILTIN)) // ha nem világít a vétel kijelző LED, akkor bekapcsolódik

digitalWrite(LED_BUILTIN, HIGH); // turn the LED on

}

} // End of RC PWM jel kiértékelése

#endif // End of [if defined(_szu_RcRx_Int0_ChGaz) ]


//---- valós időalaphoz kötött feladatok kezelése ---------

if ( time_msec != millis() ) {

time_msec= millis(); // új idő értékének megőrzése

//---- 1msec-onként végrehajtandó műveletek

++timer_1sec; // timer számláló értékének növelése

#if defined(_szu_RcRx_Int0_Ppm) // ha Rc PPM jelet mérek, akkor ez a rész bekerül a kódba

if (timer_PpmSync>0) {

// egy aktív él valamikor kimozdította az időzítőt a szinkron jelszünet óta

if (timer_PpmSync>4) {

// ha hosszú ideig nem érkezik aktív él, akkor az a szinkronizációs jelszünetet jelenti

timer_PpmSync= 0;

rcppm_chnumber= 0;

digitalWrite( pinTestOscOut, LOW);

if (InpPpmCtrl_To_RcChxData() >= 0) { // távirányítótól érkező PPM jelsor csatornákba ültetése, és feldolgozása

timer_RcRxSafely= 0; // a vétel timer újraindítása, mivel értékes impulzus érkezett

//--- vétel kijelző LED vezérlése, amely most a beépített LED

if (!digitalRead(LED_BUILTIN)) // ha nem világít a vétel kijelző LED, akkor bekapcsolódik

digitalWrite(LED_BUILTIN, HIGH); // turn the LED on

}

}

else {

++timer_PpmSync;

}

}

#endif // End of [ if defined(_szu_RcRx_Int0_Ppm) ]

//---- vétel kiesés figyelése ---------

++timer_RcRxSafely;

if (600<timer_RcRxSafely) {

// ha hosszú ideig kimarad a vétel, akkor leállítom a motor kihajtás

motorLeft.rcCtrl_Dir= 0;

motorLeft.rcCtrl_Pwm= 0;

motorLeft.motor_Dir= 0;

motorLeft.motor_Pwm= 0;

Motor_Off_Left();

#if defined( _szu_HBridge_China_Dual_DirPwm )

Motor_Off_Right();

#endif

timer_RcRxSafely= 0; // törlöm a kiesés figyelő timert, hiszen most állítottam le a motort

digitalWrite(LED_BUILTIN, LOW); // turn the LED off

}

if ((timer_1sec & (uint16_t)15) == 0) {

//--- 16msec-onként végrehajtásra kerülő feladatok

Motor_Set_DirPwm_Left();

#if defined( _szu_HBridge_China_Dual_DirPwm )

Motor_Set_DirPwm_Right();

#endif

}

switch (timer_1sec)

{

case 999:

//---- letelt az 1 sec

timer_1sec= 0; // timer számláló feltöltése alapértelmezés szerinti értékkel

/* Működés ellenőrzéséhez a tesztekhez

//Serial.println( "Nosza" );

//Serial.println( rcpwm_usec_start );

*/

/* PPM jelsor mérési eredmények megjelenítése a tesztekhez

Serial.print( aRcPpmChPw[0] );

Serial.print( "\t" );

Serial.print( aRcPpmChPw[1] );

Serial.print( "\t" );

Serial.println( aRcPpmChPw[2] );

*/

Serial.print( rcChKorm.chValue );

Serial.print( "\t" );

Serial.print( rcChGazJ.chValue );

Serial.print( "\t" );

Serial.print( rcChGazB.chValue );

Serial.print( "\t" );

Serial.print( rcChUzemMod.chValue );

Serial.print( "\t" );

Serial.print( motorLeft.rcCtrl_Dir );

Serial.print( "\t" );

Serial.print( motorLeft.rcCtrl_Pwm );

Serial.print( "\t" );

Serial.print( motorRight.rcCtrl_Dir );

Serial.print( "\t" );

Serial.println( motorRight.rcCtrl_Pwm );

break;

case (100):

//---- minden másodperc 100. msec-ban bekövetkező esemény

//digitalWrite(LED_BUILTIN, LOW); // turn the LED off

break;

} // end of [switch (timer_1sec)]

cnt_samemsec= 0; // a gyorsaság mérő törlése (1msec alatt mennyi üres járat volt, mennyire szabad a uP)

}

else {

++cnt_samemsec;

} // end of "if ( time_msec != millis() )"

} // End of Loop







//================ Függvények, eljárások =======================




//---- A hívó által küldött RC chx időzítés alapján

// a Tab_RcGazBand[] táblából megállapítja az intervallum sorszámát, s visszaküldi ----

uint8_t get_idx_RcGazPwBand( uint16_t tmp_RcGazPw )

{

uint16_t sav_min, sav_max; // ebbe olvasom be az intervallum értéket

uint8_t k; // ezzel szaladok majd végig a táblázat sorain

uint8_t d; // ez mutatja, hogy hány sávot fog át a lépés

const uint8_t rowOfTable= sizeof(Tab_RcGazBand) / sizeof(Tab_RcGazBand[0]);

const uint8_t k_tablakozep= rowOfTable/2;

//2020.12.20: egyenlőre még csak végig lépkedek a sorokon, nem felezős közelítést csinálok

k= k_tablakozep;

d= k; // elsőre ennyi intervallum volt az átlépés

sav_min= pgm_read_word_near( Tab_RcGazBand +k ); // kb. a táblázat közepén lévő sáv, mint alsó határérték bekerül a RAM változóba a program memóriából

sav_max= pgm_read_word_near( Tab_RcGazBand + k+1);

while ( !( sav_min<=tmp_RcGazPw && tmp_RcGazPw<sav_max ) ) // kiugrik, ha a sávba esik a hívó által megadott érték

{

// mivel sávon kívüli, el kell dönteni, hogy merre kell módosítani vizsgálati sávot

d= (d>1) ? d/2 : 1; // nem lehet 0 a változás, különben végtelen ciklus lehetne

k= (tmp_RcGazPw<sav_min) ? k-d : k+d;

// mutatott sávértékek betöltése (lehetne a feltétel vizsgálatba is egyből, de így olvashatóbb a kód)

sav_min= pgm_read_word_near( Tab_RcGazBand +k );

sav_max= pgm_read_word_near( Tab_RcGazBand + k+1);

}

return k;

}

//-------------------------------------------------------------------








//---- A hívó által küldött RC chx időzítés alapján

// a Tab_RcKorBand[] táblából megállapítja az intervallum sorszámát, s visszaküldi ----

uint8_t get_idx_RcKorPwBand( uint16_t tmp_RcKorPw )

{

uint8_t k= 4; // ha valami gomd lenne, akkor a tábla közepével tér vissza, amikor a kormány nem befolyásol semmit

uint16_t sav_min, sav_max; // ebbe olvasom be az intervallum értéket

const uint8_t rowOfTable= sizeof(Tab_RcKorBand) / sizeof(Tab_RcKorBand[0]);

//2020.12.20: csak végig lépkedek a sorokon, nem felezős közelítést csinálok, mert rövid a tábla

sav_min= pgm_read_word_near( Tab_RcKorBand + 0); // a 0. sáv alsó határértéke bekerül a RAM változóba a program memóriából

for (k=1; k< rowOfTable; k++) {

sav_max= pgm_read_word_near( Tab_RcKorBand + k); // a k. sáv határértéke bekerül a RAM változóba a program memóriából, mint a vizsgált sáv felső határértéke

if ( sav_min<=tmp_RcKorPw && tmp_RcKorPw<sav_max ) {

--k;

return k;

}

sav_min= sav_max; // a következő vizsgálatnál az eddig max. érték lesz a min érték, így nem kell a program memóriát ismét olvasni

}

return k;

}

//-------------------------------------------------------------------









//---- Gáz csatorna RC jel feldolgozása ------------------

/* A hívó által usec-ban megadott impulzus szélesség feldolgozása, átkonvertálsa MotorPwm értékre

* Visszatérési érték:

* -1, ha tartományon kívüli a RcPwm jel szélessége

* 0 , ha megegyezik az előző, már feldolgozott értékkel, így nem kell ismételten kiértékelni

* 1, ha minden rendben

*/

int8_t InpChxPWCtrl_Gaz( uint32_t tmp_rcpwm ) {

rcpwm_usec_last= tmp_rcpwm; // eltárolom a kijelzéshez

if (tmp_rcpwm<rcChGazB.chBotLow || rcChGazB.chBotHigh<tmp_rcpwm) {

// ha túl keskeny vagy széles, akkor valószínűleg rossz volt a mérés, zavar volt

return -1;

}

if (tmp_rcpwm == (uint32_t) rcChGazB.chValue) // ha nem változott az előző méréshez képest, akkor nincs mit tenni

return 0;


rcChGazB.chValue= tmp_rcpwm; // eltárolom a mért értéket



//---- a csatorna időzítés alapján a Tab_RcGazBand[] táblából megállapítom az intervallum sorszámát

// amelyből utána meg lehet határozni motor vezérlő PWM jel szélességét

uint8_t tmp_irany, tmp_gazpwm; // ebbe fogom beolvasni a progmem -ből az irány és a pwm értéket

uint8_t sorszam= get_idx_RcGazPwBand( rcChGazB.chValue );

//if ( sorszam<0 ) // gond esetén leáll a további kiértékelés

// return -21;

tmp_irany= pgm_read_byte_near( Tab_RcGazBand_MotorDirPwm[sorszam] ) ;

tmp_gazpwm= pgm_read_byte_near( Tab_RcGazBand_MotorDirPwm[sorszam]+1 ) ;

//---- motorLeft.rcCtrl_Dir feltötése -----

// kell egy konverzió, mert a táblázat szerint 9, 0, 1 érték lehet, míg a további feldolgozó -1,0,1 értéket vár

motorLeft.rcCtrl_Dir= (tmp_irany>1) ? -1 : tmp_irany;

//motorRight.rcCtrl_Dir= motorLeft.rcCtrl_Dir;

//---- motorLeft.rcCtrl_Pwm feltöltése -----

motorLeft.rcCtrl_Pwm= tmp_gazpwm;

//motorRight.rcCtrl_Pwm= tmp_gazpwm;

return 1;

}

//-------------------------------------------------------------------







//---- távirányítótól érkező PPM jelsor csatornákba ültetése, és feldolgozása -----

/* aRcPpmChPw[] tömbben tárolt x usec impulzus szélességek feldolgozása,

* és átkonvertálsa MotorPwm értékre az üzemmódnak és a kormánynak megfelelően

* Visszatérési érték:

* -1, ha tartományon kívüli valamelyik csatorna mért impulzusának szélessége

* 0 , ha megegyezik az előző, már feldolgozott értékkel, így nem kell ismételten kiértékelni

* 1, ha minden rendben, legalább egy csatornának változott a jel szélessége

*/

int8_t InpPpmCtrl_To_RcChxData( void ) {

int8_t valasz= 0;

byte k;

//const byte rowOfTable= sizeof(aRcPpmChPw) / sizeof(aRcPpmChPw[0]);

const byte rowOfTable= 4; // !!!kihasználom, hogy tudom mennyi csatornát használok fel!!!!

uint16_t usec_ChPw;

//---- mérési eredmények ellenőrzése és bemásolása a dedikált csatornák tárolójába -----------

for (k=0; k<rowOfTable; k++ ) { // végig vizsgálom a mérési eredményeket

usec_ChPw= aRcPpmChPw[k]; // a k. sorszámú csatorna mért időzítése a PPM jelsor alapján

//---- megkeresem/beazonosítom, hogy melyik csatorna struct_RcChxData.PpmIndex mutat egyezőséget a ppm sorszámmal

// , hogy a megfelelő helyre tegyem a vezérléseknél

if (rcChKorm.PpmIndex== k) { // vizsgálom, hogy a kormány csatornáról van-e szó a sorszám alapján

if (usec_ChPw<rcChKorm.chBotLow || rcChKorm.chBotHigh<usec_ChPw) {

// ha túl keskeny vagy széles, akkor valószínűleg rossz volt a mérés, zavar volt

return -1;

}

if (usec_ChPw != rcChKorm.chValue) {

rcChKorm.chValue= usec_ChPw; // eltárolom a mért értéket

valasz= 1; // változott az előző méréshez képest, majd jelzem a visszatéréskor

}

}

else if (rcChGazJ.PpmIndex== k) { // vizsgálom, hogy a jobb gáz csatornáról van-e szó a sorszám alapján

if (usec_ChPw<rcChGazJ.chBotLow || rcChGazJ.chBotHigh<usec_ChPw) {

// ha túl keskeny vagy széles, akkor valószínűleg rossz volt a mérés, zavar volt

return -1;

}

if (usec_ChPw != rcChGazJ.chValue) {

rcChGazJ.chValue= usec_ChPw; // eltárolom a mért értéket

valasz= 1; // változott az előző méréshez képest, majd jelzem a visszatéréskor

}

}

else if (rcChGazB.PpmIndex== k) { // vizsgálom, hogy a bal gáz csatornáról van-e szó a sorszám alapján

if (usec_ChPw<rcChGazB.chBotLow || rcChGazB.chBotHigh<usec_ChPw) {

// ha túl keskeny vagy széles, akkor valószínűleg rossz volt a mérés, zavar volt

return -1;

}

if (usec_ChPw != rcChGazB.chValue) {

rcChGazB.chValue= usec_ChPw; // eltárolom a mért értéket

valasz= 1; // változott az előző méréshez képest, majd jelzem a visszatéréskor

}

}

else if (rcChUzemMod.PpmIndex== k) { // vizsgálom, hogy az üzemmód csatornáról van-e szó a sorszám alapján

if (usec_ChPw<rcChUzemMod.chBotLow || rcChUzemMod.chBotHigh<usec_ChPw) {

// ha túl keskeny vagy széles, akkor valószínűleg rossz volt a mérés, zavar volt

return -1;

}

if (usec_ChPw != rcChUzemMod.chValue) {

rcChUzemMod.chValue= usec_ChPw; // eltárolom a mért értéket

valasz= 1; // változott az előző méréshez képest, majd jelzem a visszatéréskor

}

}

//2020.12.23: most csak 4 csatornát definiáltam , a többivel nem foglalkozom!!!

}

if (valasz==0) {

// ha egyetlen csatorna időzítése sem módosult, akkor nem kell további műveletet végezni

return 0;

}

//---- üzemmódtól függően a ctrl értékek feltöltése, kiszámítása ----------

/* Az üzemmód vezérlés 3 állapotot vehet fel, s ennek megfelelően 3 módon valósulhat meg a két motor vezérlése:

* - Ha magas értéken áll az időzítés, akkor kormánytól függő vezérlést valósítok meg

* (ekkor a fordulás szerinti belső motor fordulatszámát és/vagy irányát módosítom)

* - Ha középállásban van, akkor egy motoros vezérlésként, azonos módon vezérlődnek a motorok.

* (ekkor rcCtrl_Dir és rcCtrl_Pwm mindkét motornál azonos lesz)

* - Ha alacsony értéken áll, akkor két független szabályzót valósítok meg

* (ekkor a bal függő a bal, a jobb függő pedig a jobb motort vezérli)

*/

const uint16_t ChUzemMod_TrigMin= 1300; // ha ezen érték alatt van az üzemmód csatorna, akkor kormánytól függő vezérlést alkalmazok

const uint16_t ChUzemMod_TrigMax= 1700; // ha ezen érték alatt van az üzemmód csatorna, akkor kormánytól függő vezérlést alkalmazok

uint8_t tmp_irany, tmp_gazpwm; // ebbe fogom beolvasni a progmem -ből az irány és a pwm értéket

int8_t i= 0;

uint8_t sorszam;

uint8_t tmp_kormodM1, tmp_kormodM2;

if (ChUzemMod_TrigMax < rcChUzemMod.chValue) { // ha magas az érték

//---- a kormány csatorna időzítése alapján a Tab_RcKorBand[] táblából megállapítom az intervallum sorszámát

// amelyből utána meg lehet határozni, hogyan kell a motor vezérlő PWM jel szélességét módosítani

// A gáz jel meghatározása a bal függő kar pozícióján alapul, a jobb függőnek most nincs jelentősége.

sorszam= get_idx_RcKorPwBand( rcChKorm.chValue );

tmp_kormodM1= pgm_read_byte_near( Tab_RcKorBand_M1M2[sorszam] ) ;

tmp_kormodM2= pgm_read_byte_near( Tab_RcKorBand_M1M2[sorszam]+1 ) ;

//---- a bal gáz csatorna időzítés alapján a Tab_RcGazBand[] táblából megállapítom az intervallum sorszámát

// amelyből utána meg lehet határozni bal motor vezérlő PWM jel szélességét

sorszam= get_idx_RcGazPwBand( rcChGazB.chValue );

tmp_irany= pgm_read_byte_near( Tab_RcGazBand_MotorDirPwm[sorszam] ) ;

tmp_gazpwm= pgm_read_byte_near( Tab_RcGazBand_MotorDirPwm[sorszam]+1 ) ;

i= (tmp_irany>1) ? -1 : tmp_irany; // kell egy konverzió, mert a táblázat szerint 9, 0, 1 érték lehet, míg a további feldolgozó -1,0,1 értéket vár

//---- motorLeft.rcCtrl_Dir és rcCtrl_Pwm feltötése -----

i= (tmp_irany>1) ? -1 : tmp_irany; // kell egy konverzió, mert a táblázat szerint 9, 0, 1 érték lehet, míg a további feldolgozó -1,0,1 értéket vár

switch (tmp_kormodM1) {

case 0: // ha nem kell módosítani a táblázatból beolvasott értéket, mert a kormány állása nem befolyásolja a fordulatot

motorLeft.rcCtrl_Dir= i;

motorLeft.rcCtrl_Pwm= tmp_gazpwm;

break;

case 1: // azonos irányba, de felezett PWM jel kell

motorLeft.rcCtrl_Dir= i;

motorLeft.rcCtrl_Pwm= tmp_gazpwm>>1;

break;

case 2: // azonos irány, de kikapcsolt PWM jel kell

motorLeft.rcCtrl_Dir= i;

motorLeft.rcCtrl_Pwm= 0;

break;

case 3: // fordított irányba, és felezett PWM jel kell

motorLeft.rcCtrl_Dir= -1*i;

motorLeft.rcCtrl_Pwm= tmp_gazpwm>>1;

break;

case 4: // fordított irányba, és azonos PWM jel kell

motorLeft.rcCtrl_Dir= -1*i;

motorLeft.rcCtrl_Pwm= tmp_gazpwm;

break;

}

//---- motorRight.rcCtrl_Dir és rcCtrl_Pwm feltötése -----

switch (tmp_kormodM2) {

case 0: // ha nem kell módosítani a táblázatból beolvasott értéket, mert a kormány állása nem befolyásolja a fordulatot

motorRight.rcCtrl_Dir= i;

motorRight.rcCtrl_Pwm= tmp_gazpwm;

break;

case 1: // azonos irányba, de felezett PWM jel kell

motorRight.rcCtrl_Dir= i;

motorRight.rcCtrl_Pwm= tmp_gazpwm>>1;

break;

case 2: // azonos irány, de kikapcsolt PWM jel kell

motorRight.rcCtrl_Dir= i;

motorRight.rcCtrl_Pwm= 0;

break;

case 3: // fordított irányba, és felezett PWM jel kell

motorRight.rcCtrl_Dir= -1*i;

motorRight.rcCtrl_Pwm= tmp_gazpwm>>1;

break;

case 4: // fordított irányba, és azonos PWM jel kell

motorRight.rcCtrl_Dir= -1*i;

motorRight.rcCtrl_Pwm= tmp_gazpwm;

break;

}

}

else if (ChUzemMod_TrigMin < rcChUzemMod.chValue) { // ha közepes az érték

//---- a bal gáz csatorna időzítés alapján a Tab_RcGazBand[] táblából megállapítom az intervallum sorszámát

// amelyből utána meg lehet határozni motor vezérlő PWM jel szélességét

sorszam= get_idx_RcGazPwBand( rcChGazB.chValue );

tmp_irany= pgm_read_byte_near( Tab_RcGazBand_MotorDirPwm[sorszam] ) ;

tmp_gazpwm= pgm_read_byte_near( Tab_RcGazBand_MotorDirPwm[sorszam]+1 ) ;

//---- motorY.rcCtrl_Dir feltötése, hiszen a két motort azonos módon forgatom most -----

// kell egy konverzió, mert a táblázat szerint 9, 0, 1 érték lehet, míg a további feldolgozó -1,0,1 értéket vár

motorLeft.rcCtrl_Dir= (tmp_irany>1) ? -1 : tmp_irany;

motorRight.rcCtrl_Dir= motorLeft.rcCtrl_Dir;

//---- motorY.rcCtrl_Pwm feltöltése -----

motorLeft.rcCtrl_Pwm= tmp_gazpwm;

motorRight.rcCtrl_Pwm= tmp_gazpwm;

}

else { // ha alacsony az érték

//---- a bal gáz csatorna időzítés alapján a Tab_RcGazBand[] táblából megállapítom az intervallum sorszámát

// amelyből utána meg lehet határozni bal motor vezérlő PWM jel szélességét

sorszam= get_idx_RcGazPwBand( rcChGazB.chValue );

tmp_irany= pgm_read_byte_near( Tab_RcGazBand_MotorDirPwm[sorszam] ) ;

tmp_gazpwm= pgm_read_byte_near( Tab_RcGazBand_MotorDirPwm[sorszam]+1 ) ;

//---- motorLeft.rcCtrl_Dir és rcCtrl_Pwm feltötése -----

// kell egy konverzió, mert a táblázat szerint 9, 0, 1 érték lehet, míg a további feldolgozó -1,0,1 értéket vár

motorLeft.rcCtrl_Dir= (tmp_irany>1) ? -1 : tmp_irany;

motorLeft.rcCtrl_Pwm= tmp_gazpwm;

//---- a jobb gáz csatorna időzítés alapján a Tab_RcGazBand[] táblából megállapítom az intervallum sorszámát

// amelyből utána meg lehet határozni a jobb motor vezérlő PWM jel szélességét

sorszam= get_idx_RcGazPwBand( rcChGazJ.chValue );

tmp_irany= pgm_read_byte_near( Tab_RcGazBand_MotorDirPwm[sorszam] ) ;

tmp_gazpwm= pgm_read_byte_near( Tab_RcGazBand_MotorDirPwm[sorszam]+1 ) ;

//---- motorRight.rcCtrl_Dir és rcCtrl_Pwm feltötése -----

// kell egy konverzió, mert a táblázat szerint 9, 0, 1 érték lehet, míg a további feldolgozó -1,0,1 értéket vár

motorRight.rcCtrl_Dir= (tmp_irany>1) ? -1 : tmp_irany;

motorRight.rcCtrl_Pwm= tmp_gazpwm;

}

return valasz;

}

//-------------------------------------------------------------------








//---- Bal motor és vezérlőjelei kikapcsolása (a távirányító jeleit nem befolyásolja ------

void Motor_Off_Left( void )

{

#if defined( _szu_HBridge_China_IMS2B )

// pwm jel 0-ra

digitalWrite( pinDir_Rev, LOW );

digitalWrite( pinDir_Nor, LOW );

analogWrite( pinPwm_Rev, 0 );

analogWrite( pinPwm_Nor, 0 );

//---- rcCtrlLed kikapcsolása --------

digitalWrite( pinLedDir_Nor, LOW);

digitalWrite( pinLedDir_Rev, LOW);

#endif

#if defined( _szu_HBridge_China_Dual_DirPwm )

analogWrite( pinPwm_M1, 0 );

//digitalWrite( pinLedDirM1_Rev, LOW );

//digitalWrite( pinLedDirM1_Nor, LOW );

//digitalWrite( pinDir_M1, LOW ); // ezt lehet, nem kellene gyorsan átváltani, mert gond lehet???

#endif

motorLeft.motor_Dir= 0; // állapot beállítása

motorLeft.motor_Pwm= 0; // eltárol a Pwm kikapcsolását

return;

}

//-------------------------------------------------------------------








//---- Jobb motor és vezérlőjelei kikapcsolása (a távirányító jeleit nem befolyásolja ------

void Motor_Off_Right( void )

{

#if defined( _szu_HBridge_China_Dual_DirPwm )

analogWrite( pinPwm_M2, 0 );

//digitalWrite( pinLedDirM2_Rev, LOW );

//digitalWrite( pinLedDirM2_Nor, LOW );

//digitalWrite( pinDir_M2, LOW ); // ezt lehet, nem kellene gyorsan átváltani, mert gond lehet???

#endif

motorRight.motor_Dir= 0; // állapot beállítása

motorRight.motor_Pwm= 0; // eltárol a Pwm kikapcsolását

return;

}

//-------------------------------------------------------------------







//---- Bal motor és vezérlőjelei bekapcsolása (a távirányító jeleit nem befolyásolja ------

void Motor_On_Left( void )

{

if (motorLeft.rcCtrl_Dir == 0) {

// csak védelmi célból hagytam itt ezt az if utasítást

return;

}

if (motorLeft.rcCtrl_Dir == 1) {

#if defined( _szu_HBridge_China_IMS2B )

//---- előre irány bekapcsolása ----------

digitalWrite( pinDir_Rev, LOW );

digitalWrite( pinDir_Nor, HIGH );

motorLeft.motor_Dir= 1;

//---- megfelelő rcCtrlLed világítás beállítása --------

digitalWrite( pinLedDir_Rev, LOW);

digitalWrite( pinLedDir_Nor, HIGH);

//---- Pwm jel bekapcsolása --------------------

analogWrite( pinPwm_Rev, 0 );

motorLeft.motor_Pwm= motorLeft.rcCtrl_Pwm;

analogWrite( pinPwm_Nor, motorLeft.motor_Pwm );

#endif

#if defined( _szu_HBridge_China_Dual_DirPwm )

//---- előre irány bekapcsolása ----------

digitalWrite( pinDir_M1, HIGH );

motorLeft.motor_Dir= 1;

//---- megfelelő rcCtrlLed világítás beállítása --------

digitalWrite( pinLedDirM1_Rev, LOW);

digitalWrite( pinLedDirM1_Nor, HIGH);

//---- Pwm jel bekapcsolása --------------------

motorLeft.motor_Pwm= motorLeft.rcCtrl_Pwm;

analogWrite( pinPwm_M1, motorLeft.motor_Pwm );

#endif

return;

}

if (motorLeft.rcCtrl_Dir == -1) {

#if defined( _szu_HBridge_China_IMS2B )

//---- hátra irány bekapcsolása ----------

digitalWrite( pinDir_Nor, LOW );

digitalWrite( pinDir_Rev, HIGH );

motorLeft.motor_Dir= -1;

//---- megfelelő rcCtrlLed világítás beállítása --------

digitalWrite( pinLedDir_Nor, LOW);

digitalWrite( pinLedDir_Rev, HIGH);

//---- Pwm jel bekapcsolása ----------------------

analogWrite( pinPwm_Nor, 0 );

motorLeft.motor_Pwm= motorLeft.rcCtrl_Pwm;

analogWrite( pinPwm_Rev, motorLeft.motor_Pwm );

#endif

#if defined( _szu_HBridge_China_Dual_DirPwm )

//---- hátra irány bekapcsolása ----------

digitalWrite( pinDir_M1, LOW );

motorLeft.motor_Dir= -1;

//---- megfelelő rcCtrlLed világítás beállítása --------

digitalWrite( pinLedDirM1_Nor, LOW);

digitalWrite( pinLedDirM1_Rev, HIGH);

//---- Pwm jel bekapcsolása --------------------

motorLeft.motor_Pwm= motorLeft.rcCtrl_Pwm;

analogWrite( pinPwm_M1, motorLeft.motor_Pwm );

#endif

return;

}

}

//-------------------------------------------------------------------








//---- Jobb motor és vezérlőjelei bekapcsolása (a távirányító jeleit nem befolyásolja ------

void Motor_On_Right( void )

{

if (motorRight.rcCtrl_Dir == 0) {

// csak védelmi célból hagytam itt ezt az if utasítást

return;

}

if (motorRight.rcCtrl_Dir == 1) {

#if defined( _szu_HBridge_China_Dual_DirPwm )

//---- előre irány bekapcsolása ----------

digitalWrite( pinDir_M2, HIGH );

motorRight.motor_Dir= 1;

//---- megfelelő rcCtrlLed világítás beállítása --------

digitalWrite( pinLedDirM2_Rev, LOW);

digitalWrite( pinLedDirM2_Nor, HIGH);

//---- Pwm jel bekapcsolása --------------------

motorRight.motor_Pwm= motorRight.rcCtrl_Pwm;

analogWrite( pinPwm_M2, motorRight.motor_Pwm );

#endif

return;

}

if (motorRight.rcCtrl_Dir == -1) {

#if defined( _szu_HBridge_China_Dual_DirPwm )

//---- hátra irány bekapcsolása ----------

digitalWrite( pinDir_M2, LOW );

motorRight.motor_Dir= -1;

//---- megfelelő rcCtrlLed világítás beállítása --------

digitalWrite( pinLedDirM2_Nor, LOW);

digitalWrite( pinLedDirM2_Rev, HIGH);

//---- Pwm jel bekapcsolása --------------------

motorRight.motor_Pwm= motorRight.rcCtrl_Pwm;

analogWrite( pinPwm_M2, motorRight.motor_Pwm );

#endif

return;

}

}

//-------------------------------------------------------------------







//---- Motor (bal oldali) vezérlő jelek PWM beállítása az RC jelek változása miatt ---------

void Motor_Set_DirPwm_Left( void )

{

if ( motorLeft.rcCtrl_Dir!=motorLeft.motor_Dir ) {

//---- ha különbség van az irányban -----

switch (motorLeft.rcCtrl_Dir) {

case 0:

//---- az RC ki szeretné kapcsolni a forgást ----

Motor_Off_Left();

break;

case -1:

//---- hátra felé szeretné hajtani az RC ----

// de csak akkor lehet hátra, ha előtte ki volt kapcsolva!!!

if (motorLeft.motor_Dir==0) {

Motor_On_Left();

}

else {

// kapásból nem lehet irányt váltani, így előbb kikapcsolás lesz, s majd a következő ütemben bekapcsolom a pwm jelet

Motor_Off_Left();

}

break;

case 1:

//---- előre szeretné hajtani az RC ----

// de csak akkor lehet előre, ha előtte ki volt kapcsolva!!!

if (motorLeft.motor_Dir==0) {

Motor_On_Left();

}

else {

// kapásból nem lehet irányt váltani, így előbb kikapcsolás lesz, s majd a következő ütemben bekapcsolom a pwm jelet

Motor_Off_Left();

}

break;

} // end of switch


/* ha nem a megfelelő irányba forgott a motor,

* akkor most nem lehet mást tenni, várakozni kell, amíg a tranziensek le nem csillapodnak,

* és a pwm jel bizotsan kikapcsolt lesz.

* Így most nem lehet már mit csinálni, majd a következő összehasonlításban elindulhat a motor

*/

return;

} // end of forgásirány változás tesztelés

if ( motorLeft.rcCtrl_Pwm!=motorLeft.motor_Pwm && motorLeft.motor_Dir!=0 ) {

/* ha ide került, akkor

* az irány megegyezik, csak a pwm szélesség eltérő

*/

motorLeft.motor_Pwm= motorLeft.rcCtrl_Pwm;

#if defined( _szu_HBridge_China_IMS2B )

if (motorLeft.motor_Dir==1) {

analogWrite( pinPwm_Nor, motorLeft.motor_Pwm );

}

else {

analogWrite( pinPwm_Rev, motorLeft.motor_Pwm );

}

#endif

#if defined( _szu_HBridge_China_Dual_DirPwm )

analogWrite( pinPwm_M1, motorLeft.motor_Pwm );

#endif

}

return;

}

//-------------------------------------------------------------------







//---- Motor (jobb oldali) vezérlő jelek PWM beállítása az RC jelek változása miatt ---------

void Motor_Set_DirPwm_Right( void )

{

if ( motorRight.rcCtrl_Dir!=motorRight.motor_Dir ) {

//---- ha különbség van az irányban -----

switch (motorRight.rcCtrl_Dir) {

case 0:

//---- az RC ki szeretné kapcsolni a forgást ----

Motor_Off_Right();

break;

case -1:

//---- hátra felé szeretné hajtani az RC ----

// de csak akkor lehet hátra, ha előtte ki volt kapcsolva!!!

if (motorRight.motor_Dir==0) {

Motor_On_Right();

}

else {

// kapásból nem lehet irányt váltani, így előbb kikapcsolás lesz, s majd a következő ütemben bekapcsolom a pwm jelet

Motor_Off_Right();

}

break;

case 1:

//---- előre szeretné hajtani az RC ----

// de csak akkor lehet előre, ha előtte ki volt kapcsolva!!!

if (motorRight.motor_Dir==0) {

Motor_On_Right();

}

else {

// kapásból nem lehet irányt váltani, így előbb kikapcsolás lesz, s majd a következő ütemben bekapcsolom a pwm jelet

Motor_Off_Right();

}

break;

} // end of switch


/* ha nem a megfelelő irányba forgott a motor,

* akkor most nem lehet mást tenni, várakozni kell, amíg a tranziensek le nem csillapodnak,

* és a pwm jel bizotsan kikapcsolt lesz.

* Így most nem lehet már mit csinálni, majd a következő összehasonlításban elindulhat a motor

*/

return;

} // end of forgásirány változás tesztelés

if ( motorRight.rcCtrl_Pwm!=motorRight.motor_Pwm && motorRight.motor_Dir!=0 ) {

/* ha ide került, akkor

* az irány megegyezik, csak a pwm szélesség eltérő

*/

motorRight.motor_Pwm= motorRight.rcCtrl_Pwm;

#if defined( _szu_HBridge_China_Dual_DirPwm )

analogWrite( pinPwm_M2, motorRight.motor_Pwm );

#endif

}

return;

}

//-------------------------------------------------------------------




//---- Indítás utáni alapértékek beállítása ----------

void set_DefaultValue() {


//---- csatornák alapbeállításai ---------

//---- gázJ csatorna beállítása (jobb függőleges bot)

rcChGazJ.chIndex= 1;

rcChGazJ.PpmIndex= 1;

//rcChGazJ.chName= {"GazJ "};

rcChGazJ.chValue= 1500;

rcChGazJ.chBotLow= 950;

rcChGazJ.chBotNat= 1500;

rcChGazJ.chBotHigh= 2100;

//---- kormány csatorna beállítása (jobb vízszintes bot)

rcChKorm.chIndex= 2;

rcChKorm.PpmIndex= 0;

//rcChKorm.chName= {"Korm "};

rcChKorm.chValue= 1500;

rcChKorm.chBotLow= 950;

rcChKorm.chBotNat= 1500;

rcChKorm.chBotHigh= 2100;

//---- gáz (Bal oldali függőleges bot) csatorna beállítása

rcChGazB.chIndex= 3;

rcChGazB.PpmIndex= 2;

//rcChGazB.chName= {"GazB "};

rcChGazB.chValue= 1500;

rcChGazB.chBotLow= 950;

rcChGazB.chBotNat= 1500;

rcChGazB.chBotHigh= 2100;

//---- üzemmód csatorna beállítása (bal oldali vízszintes bot)

rcChUzemMod.chIndex= 4;

rcChUzemMod.PpmIndex= 3;

//rcChUzemMod.chName= {"UzMod"};

rcChUzemMod.chValue= 1500;

rcChUzemMod.chBotLow= 950;

rcChUzemMod.chBotNat= 1500;

rcChUzemMod.chBotHigh= 2100;

//---- Motor állapot változók beállítása ----

//---- bal oldali motor állapota ------------

motorLeft.rcCtrl_Dir= 0; // távirányító által előírt forgásirány (-1, 0, 1)

motorLeft.rcCtrl_Pwm= 0; // távirányító által előírt PWM szélesség (ha bírja a uP, ezt módosítani kell 16 bitre)

motorLeft.rcCtrl_TimeSpin= 0; // távirányító által előírt egy fordulathoz tartozó idő

motorLeft.motor_Dir= 0; // motor beállítása szerint a valós forgásirány (így látható, ha a vezérben forgásirányt kell módosítani

motorLeft.motor_Pwm= 0; // motor meghajtás aktuális jelszélessége (különösen lágy indítás, vagy fordulatszám tartás esetén van jelentősége)

motorLeft.motor_TimeSpin_Start= 0;

motorLeft.motor_TimeSpin= 0; // a motor egy fordulatához tartozó idő az utolsó mérés szerint

//---- jobb oldali motor állapota ------------

motorRight.rcCtrl_Dir= 0; // távirányító által előírt forgásirány (-1, 0, 1)

motorRight.rcCtrl_Pwm= 0; // távirányító által előírt PWM szélesség (ha bírja a uP, ezt módosítani kell 16 bitre)

motorRight.rcCtrl_TimeSpin= 0; // távirányító által előírt egy fordulathoz tartozó idő

motorRight.motor_Dir= 0; // motor beállítása szerint a valós forgásirány (így látható, ha a vezérben forgásirányt kell módosítani

motorRight.motor_Pwm= 0; // motor meghajtás aktuális jelszélessége (különösen lágy indítás, vagy fordulatszám tartás esetén van jelentősége)

motorRight.motor_TimeSpin_Start= 0;

motorRight.motor_TimeSpin= 0; // a motor egy fordulatához tartozó idő az utolsó mérés szerint


return;

}

//-------------------------------------------------------------------






//---- addig várakozik, amíg a távirányító karok nincsenek alaphelyzetben -------

void vedelem_RcAlaphelyzet(void) {

uint8_t nRcImp=0; // számolom, hogy egymás után mennyi helyes pw jel érkezik a távirányítótól

uint32_t tmp_rcpwm; // távirányítótól érkező impulzus szélesség számításához

while (nRcImp<50) { // addig a ciklusban marad, amíg legalább n db közepes időzítés nem érkezik

#if defined( _szu_HBridge_China_IMS2B )

//---- RC PW jel kiértékelése --------

if ( rcpwm_edge_LH && rcpwm_edge_HL ) {

// törlöm a jelzőbiteket

rcpwm_edge_LH= 0;

rcpwm_edge_HL= 0;

tmp_rcpwm= rcpwm_usec_stop- rcpwm_usec_start;

// ha egy középállásnak megfelelő impulzus érkezett, akor növelem a számlálót, különben törlöm azt

nRcImp= (1450<tmp_rcpwm && tmp_rcpwm<1550) ? ++nRcImp : 0;

} // End of RC PW jel kiértékelése

if ( 50 < (millis()-time_msec) ) {

//---- 50 msec időként lefutó folyamatok -----

time_msec= millis(); // új érték megőrzése

//---- időközönként állapotot váltanak a led-ek a felhasználó tájékoztatására ----

if (digitalRead( pinLedDir_Nor)) {

digitalWrite( pinLedDir_Nor, LOW);

digitalWrite( pinLedDir_Rev, HIGH);

}

else {

digitalWrite( pinLedDir_Rev, LOW);

digitalWrite( pinLedDir_Nor, HIGH);

}

}

#endif

}

#if defined( _szu_HBridge_China_IMS2B )

//---- led kijelzés törlése visszatérés előtt ---------

digitalWrite( pinLedDir_Nor, LOW);

digitalWrite( pinLedDir_Rev, LOW);

time_msec= millis(); // új érték megőrzése

rcpwm_edge_LH= 0; // törlöm a jelzőbiteket, mivel ettől kezdve éles az impulzus mérés

rcpwm_edge_HL= 0;

#endif

return; // indulhat a főprogram

}

//-------------------------------------------------------------------






//================ Megszakítás kezelések ========================


void irq_handler_Int0() {

//bool pinLevel_Int0;

//pinLevel_Int0 = digitalRead(intPin_Int0); // read the input pin

#if defined(_szu_RcRx_Int0_ChGaz) // 1 csatornás márás esetén ez kerül a kódba

if (digitalRead(intPin_Int0)) { // Int0 láb szintjének beolvasása, ha H szintű, akkor ....

rcpwm_edge_HL= 0; // mivel most történt LH él, akkor a HL biztosan nem következett még be

rcpwm_edge_LH= 1; // jelzem a főprogramnak, hogy érkezett egy LH él az utolsó feldolgozás óta

rcpwm_usec_start= micros(); // impulzus kezdeti időpontjának lekérdezése, tárolása

}

else { // L szint esetén

rcpwm_edge_HL= 1; // jelzem a főprogramnak, hogy érkezett egy HL él az utolsó feldolgozás óta

rcpwm_usec_stop= micros(); // impulzus kezdeti időpontjának lekérdezése, tárolása

}

#endif // End of [ if defined(_szu_RcRx_Int0_ChGaz) ]

#if defined(_szu_RcRx_Int0_Ppm) // PPM jelsor mérése esetén ez kerül a kódba

// nem kell a láb szintjével foglalkozni, mert IT úgy lett definiálva, hogy csak az egyik élre generálódik megszakítás

rcpwm_usec_stop= micros(); // impulzus kezdeti időpontjának lekérdezése, tárolása

digitalWrite( pinTestOscOut, HIGH);

if (rcppm_chnumber>0) { // ha korábban már elkezdődött egy csatorna mérése egy aktív éllel

// Megtörént egy csatorna mérése, amely a két aktív él közötti idő

// A megszakításban nem töltöm az időt kiértékeléssel, csak eltárolom az eredményt

aRcPpmChPw[rcppm_chnumber-1]= (uint16_t) (rcpwm_usec_stop - rcpwm_usec_start); // ha helyes volt a mérés, akkor eredményenk el kel férnie 16 biten

}

rcpwm_usec_start= rcpwm_usec_stop; // elmentem a kezdő időpontot, amely ugye megegyezik az előző leállás időpontjával

rcppm_chnumber= (rcppm_chnumber<11) ? ++rcppm_chnumber : 11; // kijelölöm a következő mért csatornát, ha az még nincs túl a tömb nagyságán (pld rádió zavar)

timer_PpmSync= 1; // szinkron időzítő törlése, de figyelő állapotba helyezése, hiszen érkezett aktív él

#endif // End of [ if defined(_szu_RcRx_Int0_Ppm) ]

}


Forráskód, konverziók táblák

#if !defined(_szu_SC_TabConvRcx_)

#define _szu_SC_TabConvRcx_

/* A RC gáz csatorna intervallumának sávjai

* Ebben a táblázatba definiálom, hogy a gáz csatorna jelét

* - hány intervallumra osztom

* - milyen értékek az intervallum határok.

* A program meg tudja majd keresni, hogy hanyas sorszámú intervallumba esik a mért gáz pw szélesség

* és utána azzal a sorszámmal tudja majd kikerseni egy másik táblából,

* hogy mekkora pwm értéket és irányt kell beállítani a motor vezérléshez.

* A táblázat a program memóriában van tárolva jelenleg, onnan kell majd kikeresni.

* Ez egyben azt is jelenti, hogy ha módosítani szeretnénk rajta, akkor fordítani, és újra programozni kell az arduino panelt.

* Figyelni az elemek számára, mert a kapcsolódó dir & pwm táblában is ennyi sor kell majd!!!

* A táblázatban az értékeknek folyamatos növekvő sorrenben kell lenniük!!!

*/

const uint16_t Tab_RcGazBand[] PROGMEM {

800, // Tab-21 0 Biztonságból csinálok ilyen tág sávot. Elméletileg a mérés kiértékelés kidobja az ilyen hamis értéket

1050, // Tab-20 1

1070, // Tab-19 2

1090, // Tab-18

1110, // Tab-17

1130, // Tab-16 5

1150, // Tab-15

1170, // Tab-14

1190, // Tab-13

1210, // Tab-12 9

1230, // Tab-11 10

1250, // Tab-10

1275, // Tab-09

1300, // Tab-08

1325, // Tab-07

1350, // Tab-06 15

1375, // Tab-05

1400, // Tab-04

1425, // Tab-03

1450, // Tab-02

1475, // Tab-01 20

1490, // Tab000 Az [1490-1510] sávban teljes kikapcsolás lesz, ha esetleg olyan lenne a teljesítmény panel

1510, // Tab+01 22

1525, // Tab+02

1550, // Tab+03

1570, // Tab+04 25

1590, // Tab+05

1610, // Tab+06

1630, // Tab+07

1650, // Tab+08

1670, // Tab+09 30

1690, // Tab+10

1710, // Tab+11

1730, // Tab+12

1750, // Tab+13

1765, // Tab+14 35

1780, // Tab+15

1795, // Tab+16

1810, // Tab+17

1825, // Tab+18

1840, // Tab+19 40

1850, // Tab+20 41

1860, // Tab+21 42

2200 // Tab+22 44 Biztonságból csinálok ilyen tág sávot. Elméletileg a mérés kiértékelés kidobja az ilyen hamis értéket, de kell a sávos határértékhez

};

/* A táblázat megadja, hogy az RC gáz csatorna intervallumának sorszáma szerint

* mi a kívánt forgásirány

* mekkora legyen a Motor PWM jele

*

* Annyi sornak kell lennie a táblázatban, amennyi a Tab_RcGazBand[] táblázatban is van!!!

* Mivel táblazat elemi a uint8_t típusúak, így az irány kódok a következők:

* 0- kikapcsolt motor, nincs irány definiálva, szabadon futó a motor

* 1- előre menet

* 9- hátra menet

*/

const uint8_t Tab_RcGazBand_MotorDirPwm[][2] PROGMEM {

{ 9, 245 }, // Tab-21

{ 9, 230 }, // Tab-20

{ 9, 215 }, // Tab-19

{ 9, 200 }, // Tab-18

{ 9, 185 }, // Tab-17

{ 9, 170 }, // Tab-16

{ 9, 155 }, // Tab-15

{ 9, 140 }, // Tab-14

{ 9, 125 }, // Tab-13

{ 9, 110 }, // Tab-12

{ 9, 95 }, // Tab-11

{ 9, 80 }, // Tab-10

{ 9, 70 }, // Tab-09

{ 9, 60 }, // Tab-08

{ 9, 50 }, // Tab-07

{ 9, 40 }, // Tab-06

{ 9, 35 }, // Tab-05

{ 9, 30 }, // Tab-04

{ 9, 20 }, // Tab-03

{ 9, 10 }, // Tab-02

{ 9, 0 }, // Tab-01

{ 0, 000 }, // Tab000

{ 1, 0 }, // Tab+01

{ 1, 10 }, // Tab+02

{ 1, 20 }, // Tab+03

{ 1, 30 }, // Tab+04

{ 1, 35 }, // Tab+05

{ 1, 40 }, // Tab+06

{ 1, 50 }, // Tab+07

{ 1, 60 }, // Tab+08

{ 1, 70 }, // Tab+09

{ 1, 80 }, // Tab+10

{ 1, 95 }, // Tab+11

{ 1, 110 }, // Tab+12

{ 1, 125 }, // Tab+13

{ 1, 140 }, // Tab+14

{ 1, 155 }, // Tab+15

{ 1, 170 }, // Tab+16

{ 1, 185 }, // Tab+17

{ 1, 200 }, // Tab+18

{ 1, 215 }, // Tab+19

{ 1, 230 }, // Tab+20

{ 1, 245 }, // Tab+21

{ 1, 245 } // Tab+22

};

/* A RC Kormány csatorna intervallumának sávjai

* Ebben a táblázatba definiálom, hogy a kormány csatorna jelét

* - hány intervallumra osztom

* - milyen értékek az intervallum határok.

* A program meg tudja majd keresni, hogy hanyas sorszámú intervallumba esik a mért kormány pw szélesség

* és utána azzal a sorszámmal tudja majd kikerseni egy másik táblából,

* hogyan kell módosítani a motor pwm értéket és irányt vezérléshez.

* A táblázat a program memóriában van tárolva jelenleg, onnan kell majd kikeresni.

* Ez egyben azt is jelenti, hogy ha módosítani szeretnénk rajta, akkor fordítani, és újra programozni kell az arduino panelt.

* Figyelni az elemek számára, mert a kapcsolódó dir & pwm táblában is ennyi sor kell majd!!!

* A táblázatban az értékeknek folyamatos növekvő sorrenben kell lenniük!!!

* Azért kell a kormánynak külön tábla, mert hajó kormány beállításai eltérhetnek a középtől a mechanikus beépítések miatt.

* Így egyszerűbb utána a paraméterezés, módosítás.

*/

const uint16_t Tab_RcKorBand[] PROGMEM {

800, // Tab-04 0.

1120, // Tab-03 1.

1180, // Tab-02 2.

1280, // Tab-01 3.

1380, // Tab000 4. Az [1380-1620] sávban a kormány semmit semmit befolyásol a motor vezérlésbe

1620, // Tab+01 5.

1720, // Tab+02 6.

1800, // Tab+03 7.

1900, // Tab+04 8.

2200 // Tab+05 9.

};

/* A táblázat megadja, hogy az RC kormány csatorna intervallumának sorszáma szerint

* hogyan kell módosítani az M1 (0.oszlop, bal) és az M2 (1.oszlop, jobb) motor vezérlését

*

* Annyi sornak kell lennie a táblázatban, amennyi a Tab_RcKorBand[] táblázatban is van!!!

* A táblazat kódolva szerepelnek a módosítások. Ezek jelentése a következő:

* 0- a kormány nincs hatással az oszlop szerinti motor vezérlésére

* 1- az oszlop szerinti motor fordulatát felezni kell

* 2- az oszlop szerinti motort ki kell kapcsolni

* 3- az oszlop szerinti motor felezett fordulaton, de az ellenkező irányba kell vezérelni

* 4-az oszlop szerinti motor azonos pwm mellett, de az ellenkező irányba kell vezérelni

*/

// ha a kormány bot időzítése balra húzva növekszik, akkor ez a tábla kell

/*

const uint8_t Tab_RcKorBand_M1M2[][2] PROGMEM {

{ 0, 4 }, // Tab-04 0.

{ 0, 3 }, // Tab-03 1.

{ 0, 2 }, // Tab-02 2.

{ 0, 1 }, // Tab-01 3.

{ 0, 0 }, // Tab000 4.

{ 1, 0 }, // Tab+01 5.

{ 2, 0 }, // Tab+02 6.

{ 3, 0 }, // Tab+03 7.

{ 4, 0 }, // Tab+04 8.

{ 4, 0 } // Tab+05 9.

};

*/

// ha a kormány bot időzítése jobbra húzva növekszik, akkor ez a tábla kell

const uint8_t Tab_RcKorBand_M1M2[][2] PROGMEM {

{ 4, 0 }, // Tab-04 0.

{ 3, 0 }, // Tab-03 1.

{ 2, 0 }, // Tab-02 2.

{ 1, 0 }, // Tab-01 3.

{ 0, 0 }, // Tab000 4.

{ 0, 1 }, // Tab+01 5.

{ 0, 2 }, // Tab+02 6.

{ 0, 3 }, // Tab+03 7.

{ 0, 4 }, // Tab+04 8.

{ 0, 4 } // Tab+05 9.

};

#endif