mirror of
https://github.com/pascallanger/DIY-Multiprotocol-TX-Module.git
synced 2025-07-03 12:07:52 +00:00
Update to last Pascal mod.
This commit is contained in:
parent
9df79e400f
commit
2c3b64cde8
@ -21,7 +21,7 @@
|
||||
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#define STM32_board
|
||||
#undef __cplusplus
|
||||
//#undef __cplusplus
|
||||
#if defined STM32_board
|
||||
#include "Multiprotocol_STM32.h"
|
||||
#include <EEPROM.h>
|
||||
@ -462,8 +462,8 @@ void loop()
|
||||
}
|
||||
|
||||
|
||||
void Update_All()
|
||||
{
|
||||
void Update_All()
|
||||
{
|
||||
#ifndef STM32_board
|
||||
TX_ON;
|
||||
NOP();
|
||||
@ -511,21 +511,21 @@ void loop()
|
||||
NOP();
|
||||
TX_OFF;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Update Servo_AUX flags based on servo AUX positions
|
||||
static void update_aux_flags(void)
|
||||
{
|
||||
// Update Servo_AUX flags based on servo AUX positions
|
||||
static void update_aux_flags(void)
|
||||
{
|
||||
Servo_AUX=0;
|
||||
for(uint8_t i=0;i<8;i++)
|
||||
if(Servo_data[AUX1+i]>PPM_SWITCH)
|
||||
Servo_AUX|=1<<i;
|
||||
}
|
||||
}
|
||||
|
||||
// Update led status based on binding and serial
|
||||
static void update_led_status(void)
|
||||
{
|
||||
// Update led status based on binding and serial
|
||||
static void update_led_status(void)
|
||||
{
|
||||
if(blink<millis())
|
||||
{
|
||||
if(cur_protocol[0]==0) // No valid serial received at least once
|
||||
@ -545,10 +545,10 @@ void loop()
|
||||
blink+=BLINK_BIND_TIME; //blink fastly during binding
|
||||
LED_TOGGLE;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
inline void tx_pause()
|
||||
{
|
||||
inline void tx_pause()
|
||||
{
|
||||
#ifdef TELEMETRY
|
||||
#ifdef XMEGA
|
||||
USARTC0.CTRLA &= ~0x03 ; // Pause telemetry by disabling transmitter interrupt
|
||||
@ -562,11 +562,11 @@ void loop()
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
inline void tx_resume()
|
||||
{
|
||||
inline void tx_resume()
|
||||
{
|
||||
#ifdef TELEMETRY
|
||||
if(!IS_TX_PAUSE_on)
|
||||
#ifdef XMEGA
|
||||
@ -579,11 +579,11 @@ void loop()
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#ifdef STM32_board
|
||||
void start_timer2(){
|
||||
void start_timer2(){
|
||||
// Pause the timer while we're configuring it
|
||||
timer.pause();
|
||||
TIMER2_BASE->PSC = 35;//36-1;for 72 MHZ /0.5sec/(35+1)
|
||||
@ -593,12 +593,12 @@ void loop()
|
||||
// Refresh the timer's count, prescale, and overflow
|
||||
timer.refresh();
|
||||
timer.resume();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// Protocol scheduler
|
||||
static void CheckTimer(uint16_t (*cb)(void))
|
||||
{
|
||||
// Protocol scheduler
|
||||
static void CheckTimer(uint16_t (*cb)(void))
|
||||
{
|
||||
uint16_t next_callback,diff;
|
||||
#ifdef XMEGA
|
||||
if( (TCC1.INTFLAGS & TC1_CCAIF_bm) != 0)
|
||||
@ -690,11 +690,11 @@ void loop()
|
||||
}
|
||||
while(diff&0x8000); // Callback did not took more than requested time for next callback
|
||||
// so we can let main do its stuff before next callback
|
||||
}
|
||||
}
|
||||
|
||||
// Protocol start
|
||||
static void protocol_init()
|
||||
{
|
||||
// Protocol start
|
||||
static void protocol_init()
|
||||
{
|
||||
uint16_t next_callback=0; // Default is immediate call back
|
||||
remote_callback = 0;
|
||||
|
||||
@ -934,10 +934,10 @@ void loop()
|
||||
#endif
|
||||
#endif
|
||||
BIND_BUTTON_FLAG_off; // do not bind/reset id anymore even if protocol change
|
||||
}
|
||||
}
|
||||
|
||||
static void update_serial_data()
|
||||
{
|
||||
static void update_serial_data()
|
||||
{
|
||||
RX_DONOTUPDTAE_on;
|
||||
RX_FLAG_off; //data has been processed
|
||||
if(rx_ok_buff[0]&0x20) //check range
|
||||
@ -1011,10 +1011,10 @@ void loop()
|
||||
UCSR0B |= (1<<RXCIE0) ; // RX interrupt enable
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void modules_reset()
|
||||
{
|
||||
void modules_reset()
|
||||
{
|
||||
#ifdef CC2500_INSTALLED
|
||||
CC2500_Reset();
|
||||
#endif
|
||||
@ -1031,11 +1031,11 @@ void loop()
|
||||
//Wait for every component to reset
|
||||
delayMilliseconds(100);
|
||||
prev_power=0xFD; // unused power value
|
||||
}
|
||||
}
|
||||
|
||||
#ifndef STM32_board
|
||||
int16_t map( int16_t x, int16_t in_min, int16_t in_max, int16_t out_min, int16_t out_max)
|
||||
{
|
||||
int16_t map( int16_t x, int16_t in_min, int16_t in_max, int16_t out_min, int16_t out_max)
|
||||
{
|
||||
// return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||
long y ;
|
||||
x -= in_min ;
|
||||
@ -1043,65 +1043,65 @@ void loop()
|
||||
y *= x ;
|
||||
x = y / (in_max - in_min) ;
|
||||
return x + out_min ;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
// Channel value is converted to 8bit values full scale
|
||||
uint8_t convert_channel_8b(uint8_t num)
|
||||
{
|
||||
// Channel value is converted to 8bit values full scale
|
||||
uint8_t convert_channel_8b(uint8_t num)
|
||||
{
|
||||
return (uint8_t) (map(limit_channel_100(num),servo_min_100,servo_max_100,0,255));
|
||||
}
|
||||
}
|
||||
|
||||
// Channel value is converted to 8bit values to provided values scale
|
||||
uint8_t convert_channel_8b_scale(uint8_t num,uint8_t min,uint8_t max)
|
||||
{
|
||||
// Channel value is converted to 8bit values to provided values scale
|
||||
uint8_t convert_channel_8b_scale(uint8_t num,uint8_t min,uint8_t max)
|
||||
{
|
||||
return (uint8_t) (map(limit_channel_100(num),servo_min_100,servo_max_100,min,max));
|
||||
}
|
||||
}
|
||||
|
||||
// Channel value is converted sign + magnitude 8bit values
|
||||
uint8_t convert_channel_s8b(uint8_t num)
|
||||
{
|
||||
// Channel value is converted sign + magnitude 8bit values
|
||||
uint8_t convert_channel_s8b(uint8_t num)
|
||||
{
|
||||
uint8_t ch;
|
||||
ch = convert_channel_8b(num);
|
||||
return (ch < 128 ? 127-ch : ch);
|
||||
}
|
||||
}
|
||||
|
||||
// Channel value is converted to 10bit values
|
||||
uint16_t convert_channel_10b(uint8_t num)
|
||||
{
|
||||
// Channel value is converted to 10bit values
|
||||
uint16_t convert_channel_10b(uint8_t num)
|
||||
{
|
||||
return (uint16_t) (map(limit_channel_100(num),servo_min_100,servo_max_100,1,1023));
|
||||
}
|
||||
}
|
||||
|
||||
// Channel value is multiplied by 1.5
|
||||
uint16_t convert_channel_frsky(uint8_t num)
|
||||
{
|
||||
// Channel value is multiplied by 1.5
|
||||
uint16_t convert_channel_frsky(uint8_t num)
|
||||
{
|
||||
return Servo_data[num] + Servo_data[num]/2;
|
||||
}
|
||||
}
|
||||
|
||||
// Channel value is converted for HK310
|
||||
void convert_channel_HK310(uint8_t num, uint8_t *low, uint8_t *high)
|
||||
{
|
||||
// Channel value is converted for HK310
|
||||
void convert_channel_HK310(uint8_t num, uint8_t *low, uint8_t *high)
|
||||
{
|
||||
uint16_t temp=0xFFFF-(4*Servo_data[num])/3;
|
||||
*low=(uint8_t)(temp&0xFF);
|
||||
*high=(uint8_t)(temp>>8);
|
||||
}
|
||||
}
|
||||
|
||||
// Channel value is limited to PPM_100
|
||||
uint16_t limit_channel_100(uint8_t ch)
|
||||
{
|
||||
// Channel value is limited to PPM_100
|
||||
uint16_t limit_channel_100(uint8_t ch)
|
||||
{
|
||||
if(Servo_data[ch]>servo_max_100)
|
||||
return servo_max_100;
|
||||
else
|
||||
if (Servo_data[ch]<servo_min_100)
|
||||
return servo_min_100;
|
||||
return Servo_data[ch];
|
||||
}
|
||||
}
|
||||
|
||||
// void Serial_write(uint8_t data){
|
||||
// return;
|
||||
// }
|
||||
// void Serial_write(uint8_t data){
|
||||
// return;
|
||||
// }
|
||||
|
||||
static void Mprotocol_serial_init()
|
||||
{
|
||||
static void Mprotocol_serial_init()
|
||||
{
|
||||
|
||||
#ifdef XMEGA
|
||||
|
||||
@ -1143,29 +1143,29 @@ void loop()
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(TELEMETRY)
|
||||
void PPM_Telemetry_serial_init()
|
||||
{
|
||||
void PPM_Telemetry_serial_init()
|
||||
{
|
||||
initTXSerial( SPEED_9600 ) ;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
// Convert 32b id to rx_tx_addr
|
||||
static void set_rx_tx_addr(uint32_t id)
|
||||
{ // Used by almost all protocols
|
||||
// Convert 32b id to rx_tx_addr
|
||||
static void set_rx_tx_addr(uint32_t id)
|
||||
{ // Used by almost all protocols
|
||||
rx_tx_addr[0] = (id >> 24) & 0xFF;
|
||||
rx_tx_addr[1] = (id >> 16) & 0xFF;
|
||||
rx_tx_addr[2] = (id >> 8) & 0xFF;
|
||||
rx_tx_addr[3] = (id >> 0) & 0xFF;
|
||||
rx_tx_addr[4] = 0xC1; // for YD717: always uses first data port
|
||||
}
|
||||
}
|
||||
|
||||
#if defined STM32_board
|
||||
static uint32_t random_id(uint16_t adress, uint8_t create_new)
|
||||
{
|
||||
static uint32_t random_id(uint16_t adress, uint8_t create_new)
|
||||
{
|
||||
uint32_t id;
|
||||
uint8_t txid[4];
|
||||
pinMode(PB0, INPUT_ANALOG); // set up pin for analog input
|
||||
@ -1191,11 +1191,11 @@ void loop()
|
||||
EEPROM.write(adress+100,0xF0);
|
||||
}
|
||||
return id;
|
||||
}
|
||||
}
|
||||
|
||||
#else
|
||||
static uint32_t random_id(uint16_t adress, uint8_t create_new)
|
||||
{
|
||||
static uint32_t random_id(uint16_t adress, uint8_t create_new)
|
||||
{
|
||||
uint32_t id;
|
||||
uint8_t txid[4];
|
||||
|
||||
@ -1217,26 +1217,26 @@ void loop()
|
||||
eeprom_write_byte((uint8_t*)(adress+10),0xf0);//write bind flag in eeprom.
|
||||
}
|
||||
return id;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifndef XMEGA
|
||||
#ifndef STM32_board
|
||||
/************************************/
|
||||
/** Arduino replacement routines **/
|
||||
/************************************/
|
||||
// replacement millis() and micros()
|
||||
// These work polled, no interrupts
|
||||
// micros() MUST be called at least once every 32 milliseconds
|
||||
uint16_t MillisPrecount ;
|
||||
uint16_t lastTimerValue ;
|
||||
uint32_t TotalMicros ;
|
||||
uint32_t TotalMillis ;
|
||||
uint8_t Correction ;
|
||||
/************************************/
|
||||
/** Arduino replacement routines **/
|
||||
/************************************/
|
||||
// replacement millis() and micros()
|
||||
// These work polled, no interrupts
|
||||
// micros() MUST be called at least once every 32 milliseconds
|
||||
uint16_t MillisPrecount ;
|
||||
uint16_t lastTimerValue ;
|
||||
uint32_t TotalMicros ;
|
||||
uint32_t TotalMillis ;
|
||||
uint8_t Correction ;
|
||||
|
||||
uint32_t micros()
|
||||
{
|
||||
uint32_t micros()
|
||||
{
|
||||
uint16_t elapsed ;
|
||||
uint8_t millisToAdd ;
|
||||
uint8_t oldSREG = SREG ;
|
||||
@ -1287,16 +1287,16 @@ void loop()
|
||||
TotalMillis += millisToAdd ;
|
||||
MillisPrecount = elapsed ;
|
||||
return TotalMicros ;
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t millis()
|
||||
{
|
||||
uint32_t millis()
|
||||
{
|
||||
micros() ;
|
||||
return TotalMillis ;
|
||||
}
|
||||
}
|
||||
|
||||
void delayMilliseconds(unsigned long ms)
|
||||
{
|
||||
void delayMilliseconds(unsigned long ms)
|
||||
{
|
||||
uint16_t start = (uint16_t)micros();
|
||||
uint16_t lms = ms ;
|
||||
|
||||
@ -1306,13 +1306,13 @@ void loop()
|
||||
start += 1000;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Important notes:
|
||||
/* Important notes:
|
||||
- Max value is 16000µs
|
||||
- delay is not accurate due to interrupts happening */
|
||||
void delayMicroseconds(unsigned int us)
|
||||
{
|
||||
void delayMicroseconds(unsigned int us)
|
||||
{
|
||||
if (--us == 0)
|
||||
return;
|
||||
us <<= 2; // * 4
|
||||
@ -1321,36 +1321,36 @@ void loop()
|
||||
"1: sbiw %0,1" "\n\t" // 2 cycles
|
||||
"brne 1b" : "=w" (us) : "0" (us) // 2 cycles
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
void init()
|
||||
{
|
||||
void init()
|
||||
{
|
||||
// this needs to be called before setup() or some functions won't work there
|
||||
sei();
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
/**************************/
|
||||
/**************************/
|
||||
/** Interrupt routines **/
|
||||
/**************************/
|
||||
/**************************/
|
||||
/**************************/
|
||||
/**************************/
|
||||
/** Interrupt routines **/
|
||||
/**************************/
|
||||
/**************************/
|
||||
|
||||
//PPM
|
||||
//PPM
|
||||
#ifdef ENABLE_PPM
|
||||
#ifdef XMEGA
|
||||
ISR(PORTD_INT0_vect)
|
||||
ISR(PORTD_INT0_vect)
|
||||
#else
|
||||
#ifdef STM32_board
|
||||
void PPM_decode()
|
||||
void PPM_decode()
|
||||
#else
|
||||
ISR(INT1_vect)
|
||||
ISR(INT1_vect)
|
||||
#endif
|
||||
#endif
|
||||
{ // Interrupt on PPM pin
|
||||
{ // Interrupt on PPM pin
|
||||
static int8_t chan=-1;
|
||||
static uint16_t Prev_TCNT1=0;
|
||||
uint16_t Cur_TCNT1;
|
||||
@ -1381,20 +1381,19 @@ void loop()
|
||||
chan=-1; // don't accept any new channels
|
||||
}
|
||||
Prev_TCNT1+=Cur_TCNT1;
|
||||
}
|
||||
}
|
||||
#endif //ENABLE_PPM
|
||||
|
||||
|
||||
|
||||
#ifdef ENABLE_SERIAL
|
||||
//Serial RX
|
||||
//Serial RX
|
||||
#ifdef XMEGA
|
||||
ISR(USARTC0_RXC_vect)
|
||||
ISR(USARTC0_RXC_vect)
|
||||
#else
|
||||
#if defined STM32_board
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
extern "C" {
|
||||
#endif
|
||||
void __irq_usart2()
|
||||
#else
|
||||
@ -1407,6 +1406,9 @@ void loop()
|
||||
#ifdef XMEGA
|
||||
if((USARTC0.STATUS & 0x1C)==0) // Check frame error, data overrun and parity error
|
||||
#else
|
||||
#ifndef STM32_board
|
||||
UCSR0B &= ~_BV(RXCIE0) ; // RX interrupt disable
|
||||
#endif
|
||||
sei();
|
||||
#if defined STM32_board
|
||||
if(USART2_BASE->SR & USART_SR_RXNE) {
|
||||
@ -1461,7 +1463,6 @@ void loop()
|
||||
|
||||
rx_buff[(idx++)-1]=USART2_BASE->DR&0xff; // Store received byte
|
||||
#else
|
||||
|
||||
rx_buff[(idx++)-1]=UDR0; // Store received byte
|
||||
#endif
|
||||
#endif
|
||||
@ -1475,7 +1476,7 @@ void loop()
|
||||
}
|
||||
else
|
||||
RX_MISSED_BUFF_on; // notify that rx_buff is good
|
||||
idx=0; // start again
|
||||
discard_frame=1; // start again
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -1502,33 +1503,42 @@ void loop()
|
||||
detachInterrupt(2);//disable interrupt on ch2
|
||||
#else
|
||||
TIMSK1 &=~(1<<OCIE1B); // disable interrupt on compare B match
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifndef STM32_board
|
||||
#ifndef XMEGA
|
||||
TX_RX_PAUSE_off;
|
||||
tx_resume();
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#ifndef STM32_board)
|
||||
cli() ;
|
||||
UCSR0B |= _BV(RXCIE0) ; // RX interrupt enable
|
||||
|
||||
#endif
|
||||
#if defined STM32_board //If activated telemetry it doesn't work activated
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#if defined STM32_board
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
//Serial timer
|
||||
//Serial timer
|
||||
#ifdef XMEGA
|
||||
ISR(TCC1_CCB_vect)
|
||||
ISR(TCC1_CCB_vect)
|
||||
#else
|
||||
#if defined STM32_board
|
||||
void ISR_COMPB()
|
||||
void ISR_COMPB()
|
||||
#else
|
||||
ISR(TIMER1_COMPB_vect,ISR_NOBLOCK)
|
||||
ISR(TIMER1_COMPB_vect,ISR_NOBLOCK)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
{ // Timer1 compare B interrupt
|
||||
{ // Timer1 compare B interrupt
|
||||
discard_frame=1; // Error encountered discard full frame...
|
||||
#ifdef XMEGA
|
||||
TCC1.INTCTRLB &=0xF3; // Disable interrupt on compare B match
|
||||
@ -1539,7 +1549,10 @@ void loop()
|
||||
TIMSK1 &=~(1<<OCIE1B); // Disable interrupt on compare B match
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#ifndef STM32_board
|
||||
tx_resume();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
#endif //ENABLE_SERIAL
|
||||
|
Loading…
x
Reference in New Issue
Block a user