mirror of
https://github.com/pascallanger/DIY-Multiprotocol-TX-Module.git
synced 2025-02-04 16:38:12 +00:00
PPM: add MIN_PPM_CHANNELS and MAX_PPM_CHANNELS
This commit is contained in:
parent
29a5397491
commit
d7076f5295
@ -19,7 +19,7 @@
|
||||
#define VERSION_MAJOR 1
|
||||
#define VERSION_MINOR 1
|
||||
#define VERSION_REVISION 6
|
||||
#define VERSION_PATCH_LEVEL 19
|
||||
#define VERSION_PATCH_LEVEL 20
|
||||
//******************
|
||||
// Protocols
|
||||
//******************
|
||||
|
@ -478,6 +478,7 @@ uint8_t Update_All()
|
||||
if(mode_select==MODE_SERIAL && IS_RX_FLAG_on) // Serial mode and something has been received
|
||||
{
|
||||
update_serial_data(); // Update protocol and data
|
||||
update_channels_aux();
|
||||
INPUT_SIGNAL_on; //valid signal received
|
||||
last_signal=millis();
|
||||
}
|
||||
@ -485,7 +486,7 @@ uint8_t Update_All()
|
||||
#ifdef ENABLE_PPM
|
||||
if(mode_select!=MODE_SERIAL && IS_PPM_FLAG_on) // PPM mode and a full frame has been received
|
||||
{
|
||||
for(uint8_t i=0;i<NUM_CHN;i++)
|
||||
for(uint8_t i=0;i<MAX_PPM_CHANNELS;i++)
|
||||
{ // update servo data without interrupts to prevent bad read in protocols
|
||||
uint16_t temp_ppm ;
|
||||
cli(); // disable global int
|
||||
@ -496,11 +497,11 @@ uint8_t Update_All()
|
||||
Servo_data[i]= temp_ppm ;
|
||||
}
|
||||
PPM_FLAG_off; // wait for next frame before update
|
||||
update_channels_aux();
|
||||
INPUT_SIGNAL_on; //valid signal received
|
||||
last_signal=millis();
|
||||
}
|
||||
#endif //ENABLE_PPM
|
||||
update_channels_aux();
|
||||
update_led_status();
|
||||
#if defined(TELEMETRY)
|
||||
#if ( !( defined(MULTI_TELEMETRY) || defined(MULTI_STATUS) ) )
|
||||
@ -1222,7 +1223,7 @@ static uint32_t random_id(uint16_t adress, uint8_t create_new)
|
||||
else
|
||||
if(Cur_TCNT1>4840)
|
||||
{ //start of frame
|
||||
if(chan>3)
|
||||
if(chan>=MIN_PPM_CHANNELS)
|
||||
PPM_FLAG_on; // good frame received if at least 4 channels have been seen
|
||||
chan=0; // reset channel counter
|
||||
bad_frame=0;
|
||||
@ -1231,7 +1232,7 @@ static uint32_t random_id(uint16_t adress, uint8_t create_new)
|
||||
if(bad_frame==0) // need to wait for start of frame
|
||||
{ //servo values between 500us and 2420us will end up here
|
||||
PPM_data[chan]= Cur_TCNT1>>1;;
|
||||
if(chan++>=NUM_CHN)
|
||||
if(chan++>=MAX_PPM_CHANNELS)
|
||||
bad_frame=1; // don't accept any new channels
|
||||
}
|
||||
Prev_TCNT1+=Cur_TCNT1;
|
||||
|
@ -38,6 +38,14 @@
|
||||
#define PPM_MIN_125 1150 // 125%
|
||||
#endif
|
||||
|
||||
// Walkera PL0811-01H
|
||||
#if defined(TX_WALKERA)
|
||||
#define PPM_MAX_100 1800 // 100%
|
||||
#define PPM_MIN_100 1000 // 100%
|
||||
#define PPM_MAX_125 1900 // 125%
|
||||
#define PPM_MIN_125 900 // 125%
|
||||
#endif
|
||||
|
||||
//Serial MIN MAX values
|
||||
#define SERIAL_MAX_100 2012 // 100%
|
||||
#define SERIAL_MIN_100 988 // 100%
|
||||
|
@ -129,3 +129,16 @@
|
||||
#error BIND_CH must be below or equal to 16.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if MIN_PPM_CHANNELS>16
|
||||
#error MIN_PPM_CHANNELS must be below or equal to 16. The default for this value is 4.
|
||||
#endif
|
||||
#if MIN_PPM_CHANNELS<2
|
||||
#error MIN_PPM_CHANNELS must be larger than 1. The default for this value is 4.
|
||||
#endif
|
||||
#if MAX_PPM_CHANNELS<MIN_PPM_CHANNELS
|
||||
#error MAX_PPM_CHANNELS must be higher than MIN_PPM_CHANNELS. The default for this value is 16.
|
||||
#endif
|
||||
#if MAX_PPM_CHANNELS>16
|
||||
#error MAX_PPM_CHANNELS must be below or equal to 16. The default for this value is 16.
|
||||
#endif
|
||||
|
@ -177,6 +177,7 @@
|
||||
//#define TX_SPEKTRUM //Spektrum (1100<->1900µs)
|
||||
//#define TX_HISKY //HISKY (1120<->1920µs)
|
||||
//#define TX_MPX //Multiplex MC2020 (1250<->1950µs)
|
||||
//#define TX_WALKERA //Walkera PL0811-01H (1000<->1800µs)
|
||||
//#define TX_CUSTOM //Custom
|
||||
|
||||
// The lines below are used to set the end points in microseconds (µs) if you have selected TX_CUSTOM.
|
||||
@ -192,6 +193,13 @@
|
||||
#define PPM_MIN_125 1000 // 125%
|
||||
#endif
|
||||
|
||||
// The line below is used to set the minimum number of channels which the module should receive to consider a PPM frame valid.
|
||||
// The default value is 4 to receive at least AETR for flying models but you could also connect the PPM from a car radio which has only 3 channels by changing this number to 3.
|
||||
#define MIN_PPM_CHANNELS 4
|
||||
// The line below is used to set the maximum number of channels which the module should work with. Any channels received above this number are discarded.
|
||||
// The default value is 16 to receive all possible channels but you might want to filter some "bad" channels from the PPM frame like the ones above 6 on the Walkera PL0811.
|
||||
#define MAX_PPM_CHANNELS 16
|
||||
|
||||
//The table below indicates which protocol to run when a specific position on the dial has been selected.
|
||||
//All fields and values are explained below. Everything is configurable from here like in the Serial mode.
|
||||
//Example: You can associate multiple times the same protocol to different dial positions to take advantage of the model match (RX_Num)
|
||||
|
Loading…
x
Reference in New Issue
Block a user