Browse Source

Partially rework input/eeprom + further cleanup part2

master
Schoenberger, Philipp 6 years ago
parent
commit
ea1741d7b7
No known key found for this signature in database GPG Key ID: 77E9DF7A0452BF64
  1. 1
      remote/include/FrSkyD_cc2500.h
  2. 4
      remote/include/Multiprotocol.h
  3. 10
      remote/include/Validate.h
  4. 79
      remote/include/config.h
  5. 10
      remote/include/crc.h
  6. 4
      remote/include/eeprom.h
  7. 7
      remote/include/input.h
  8. 1
      remote/include/state.h
  9. 361
      remote/include/telemetry.h
  10. 36
      remote/include/tx_def.h
  11. 55
      remote/src/FrSkyD_cc2500.cpp
  12. 222
      remote/src/Multiprotocol.cpp
  13. 4
      remote/src/cc2500_spi.cpp
  14. 28
      remote/src/crc.cpp
  15. 25
      remote/src/eeprom.cpp
  16. 14
      remote/src/input.cpp
  17. 296
      remote/src/state.cpp
  18. 77
      remote/src/state_bind.cpp
  19. 29
      remote/src/state_fly.cpp
  20. 31
      remote/src/state_init.cpp
  21. 115
      remote/src/state_joy_calib.cpp
  22. 84
      remote/src/state_menu.cpp

1
remote/include/FrSkyD_cc2500.h

@ -26,6 +26,7 @@ void frsky2way_data_frame(void);
uint16_t initFrSky_2way(void);
uint16_t ReadFrSky_2way(void);
uint16_t ReadFrSky_2way_bind(void);
uint16_t convert_channel_frsky(uint8_t num);
#endif

4
remote/include/Multiprotocol.h

@ -74,9 +74,7 @@ enum MultiPacketTypes
#define CHANGE_PROTOCOL_FLAG_off protocol_flags &= ~_BV(1)
#define IS_CHANGE_PROTOCOL_FLAG_on ( ( protocol_flags & _BV(1) ) !=0 )
//
#define POWER_FLAG_on protocol_flags |= _BV(2)
#define POWER_FLAG_off protocol_flags &= ~_BV(2)
#define IS_POWER_FLAG_on ( ( protocol_flags & _BV(2) ) !=0 )
#define IS_POWER_FLAG_on (true)
//
#define RANGE_FLAG_on protocol_flags |= _BV(3)
#define RANGE_FLAG_off protocol_flags &= ~_BV(3)

10
remote/include/Validate.h

@ -20,14 +20,4 @@
#endif
#endif
#if defined(ENABLE_BIND_CH)
#if BIND_CH<4
#error BIND_CH must be above 4.
#endif
#if BIND_CH>16
#error BIND_CH must be below or equal to 16.
#endif
#endif
#endif

79
remote/include/config.h

@ -16,17 +16,8 @@
#define _CONFIG_H_
#include <stdint.h>
/**********************************************/
/** Multiprotocol module configuration file ***/
/**********************************************/
/*******************/
/*** TX SETTINGS ***/
/*******************/
//Modify the channel order based on your TX: AETR, TAER, RETA...
//Examples: Flysky & DEVO is AETR, JR/Spektrum radio is TAER, Multiplex is AERT...
//Default is AETR.
#define AETR
#define DEFAULT_BIND_TIME 13 /*seconds*/
/*****************/
/*** AUTO BIND ***/ // Also referred as "Bind on powerup"
@ -171,37 +162,6 @@
/*************************/
/*** PPM MODE SETTINGS ***/
/*************************/
//In this section you can configure all details about PPM.
//If you do not plan to use the PPM mode comment this line using "//" to save Flash space, you don't need to configure anything below in this case
#define ENABLE_PPM
/** TX END POINTS **/
//It is important for the module to know the endpoints of your radio.
//Below are some standard transmitters already preconfigured.
//Uncomment only the one which matches your transmitter.
#define TX_ER9X //ER9X/ERSKY9X/OpenTX ( 988<->2012 microseconds)
//#define TX_DEVO7 //DEVO (1120<->1920 microseconds)
//#define TX_SPEKTRUM //Spektrum (1100<->1900 microseconds)
//#define TX_HISKY //HISKY (1120<->1920 microseconds)
//#define TX_MPX //Multiplex MC2020 (1250<->1950 microseconds)
//#define TX_WALKERA //Walkera PL0811-01H (1000<->1800 microseconds)
//#define TX_CUSTOM //Custom
// The lines below are used to set the end points in microseconds if you have selected TX_CUSTOM.
// A few things to consider:
// - If you put too big values compared to your TX you won't be able to reach the extremes which is bad for throttle as an example
// - If you put too low values you won't be able to use your full stick range, it will be maxed out before reaching the ends
// - Centered stick value is usually 1500. It should match the middle between MIN and MAX, ie Center=(MAX+MIN)/2. If your TX is not centered you can adjust the value MIN or MAX.
// - 100% is referred as the value when the TX is set to default with no trims
/** Number of PPM Channels **/
// 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
#define NBR_BANKS 1
extern uint8_t curr_bank;
@ -228,47 +188,12 @@ struct PPM_Parameters
enum PROTOCOLS
{
MODE_SERIAL = 0, // Serial commands
PROTO_FLYSKY = 1, // =>A7105
PROTO_HUBSAN = 2, // =>A7105
PROTO_FRSKYD = 3, // =>CC2500
PROTO_HISKY = 4, // =>NRF24L01
PROTO_V2X2 = 5, // =>NRF24L01
PROTO_DSM = 6, // =>CYRF6936
PROTO_DEVO = 7, // =>CYRF6936
PROTO_YD717 = 8, // =>NRF24L01
PROTO_KN = 9, // =>NRF24L01
PROTO_SYMAX = 10, // =>NRF24L01
PROTO_SLT = 11, // =>NRF24L01
PROTO_CX10 = 12, // =>NRF24L01
PROTO_CG023 = 13, // =>NRF24L01
PROTO_BAYANG = 14, // =>NRF24L01
PROTO_FRSKYX = 15, // =>CC2500
PROTO_ESKY = 16, // =>NRF24L01
PROTO_MT99XX = 17, // =>NRF24L01
PROTO_MJXQ = 18, // =>NRF24L01
PROTO_SHENQI = 19, // =>NRF24L01
PROTO_FY326 = 20, // =>NRF24L01
PROTO_SFHSS = 21, // =>CC2500
PROTO_J6PRO = 22, // =>CYRF6936
PROTO_FQ777 = 23, // =>NRF24L01
PROTO_ASSAN = 24, // =>NRF24L01
PROTO_FRSKYV = 25, // =>CC2500
PROTO_HONTAI = 26, // =>NRF24L01
PROTO_OPENLRS = 27, // =>OpenLRS hardware
PROTO_AFHDS2A = 28, // =>A7105
PROTO_Q2X2 = 29, // =>NRF24L01, extension of CX-10 protocol
PROTO_WK2x01 = 30, // =>CYRF6936
PROTO_Q303 = 31, // =>NRF24L01
PROTO_GW008 = 32, // =>NRF24L01
PROTO_DM002 = 33, // =>NRF24L01
PROTO_CABELL = 34, // =>NRF24L01
PROTO_ESKY150 = 35, // =>NRF24L01
PROTO_H8_3D = 36, // =>NRF24L01
PROTO_CORONA = 37, // =>CC2500
PROTO_CFLIE = 38, // =>NRF24L01
PROTO_HITEC = 39, // =>CC2500
PROTO_WFLY = 40, // =>CYRF6936
PROTO_BUGS = 41, // =>A7105
};
enum FRSKYX_SUP_PROTOCOL

10
remote/include/crc.h

@ -1,7 +1,5 @@
#ifndef __CRC_H_H__
#define __CRC_H_H__
#include <stdint.h>
uint32_t crc_update (uint32_t crc, uint8_t data);
#ifndef __CRC32_H_
#define __CRC32_H_
#include <Arduino.h>
uint32_t tiny_crc32(const void *data, unsigned int length);
#endif

4
remote/include/eeprom.h

@ -27,11 +27,11 @@ private:
uint32_t data_crc;
struct {
uint32_t master_id;
struct Input::ch_config[CH_COUNT];
struct Input::ch_config ch[Input::CH_COUNT];
} data;
} current_config;
bool sucessfull_read;
}
};
#endif

7
remote/include/input.h

@ -5,8 +5,6 @@
#define NUM_TX_CHN 16
extern Input input;
extern const char* ch_name[NUM_TX_CHN];
class Input {
public:
enum input_channels {
@ -60,6 +58,7 @@ class Input {
uint16_t *get_channel_data(void);
private:
// raw sticks input
uint16_t ch_raw[CH_COUNT];
@ -71,17 +70,19 @@ class Input {
// actual tx channel data
uint16_t channel_data[CH_COUNT];
uint16_t failsafe_data[CH_COUNT];
struct data input[2];
struct data* curr;
struct data* old;
// config of each channel
struct ch_config ch_config[CH_COUNT];
// pin setttings
uint32_t pins[CH_COUNT];
};
extern const char* ch_name[NUM_TX_CHN];
extern Input input;
#endif

1
remote/include/state.h

@ -6,6 +6,7 @@
#include <stdint.h>
extern LiquidCrystal_I2C lcd;
void init_state(void);
void update_state(void);

361
remote/include/telemetry.h

@ -0,0 +1,361 @@
/*
This project 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 3 of the License, or
(at your option) any later version.
Multiprotocol 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 General Public License for more details.
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
//**************************
// Telemetry serial code *
//**************************
#if defined TELEMETRY
uint8_t RetrySequence ;
#if ( defined(MULTI_TELEMETRY) || defined(MULTI_STATUS) )
#define MULTI_TIME 500 //in ms
#define INPUT_SYNC_TIME 100 //in ms
#define INPUT_ADDITIONAL_DELAY 100 // in 10µs, 100 => 1000 µs
uint32_t lastMulti = 0;
#endif // MULTI_TELEMETRY/MULTI_STATUS
#if defined SPORT_TELEMETRY
#define SPORT_TIME 12000 //12ms
#define FRSKY_SPORT_PACKET_SIZE 8
#define FX_BUFFERS 4
uint32_t last = 0;
uint8_t sport_counter=0;
uint8_t RxBt = 0;
uint8_t sport = 0;
uint8_t pktx1[FRSKY_SPORT_PACKET_SIZE*FX_BUFFERS];
// Store for out of sequence packet
uint8_t FrskyxRxTelemetryValidSequence ;
struct t_fx_rx_frame
{
uint8_t valid ;
uint8_t count ;
uint8_t payload[6] ;
} ;
// Store for FrskyX telemetry
struct t_fx_rx_frame FrskyxRxFrames[4] ;
uint8_t NextFxFrameToForward ;
#ifdef SPORT_POLLING
uint8_t sport_rx_index[28] ;
uint8_t ukindex ;
uint8_t kindex ;
uint8_t TxData[2];
uint8_t SportIndexPolling;
uint8_t RxData[16] ;
volatile uint8_t RxIndex=0 ;
uint8_t sport_bytes=0;
uint8_t skipped_id;
uint8_t rx_counter=0;
#endif
#endif // SPORT_TELEMETRY
#if defined HUB_TELEMETRY
#define USER_MAX_BYTES 6
uint8_t prev_index;
#endif // HUB_TELEMETRY
#define START_STOP 0x7e
#define BYTESTUFF 0x7d
#define STUFF_MASK 0x20
#define MAX_PKTX 10
uint8_t pktx[MAX_PKTX];
uint8_t indx;
uint8_t frame[18];
#if ( defined(MULTI_TELEMETRY) || defined(MULTI_STATUS) )
static void multi_send_header(uint8_t type, uint8_t len)
{
Serial_write('M');
#ifdef MULTI_TELEMETRY
Serial_write('P');
Serial_write(type);
#else
(void)type;
#endif
Serial_write(len);
}
#endif
#ifdef MULTI_TELEMETRY
static void multi_send_frskyhub()
{
multi_send_header(MULTI_TELEMETRY_HUB, 9);
for (uint8_t i = 0; i < 9; i++)
Serial_write(frame[i]);
}
#endif
void frskySendStuffed()
{
Serial_write(START_STOP);
for (uint8_t i = 0; i < 9; i++) {
if ((frame[i] == START_STOP) || (frame[i] == BYTESTUFF)) {
Serial_write(BYTESTUFF);
frame[i] ^= STUFF_MASK;
}
Serial_write(frame[i]);
}
Serial_write(START_STOP);
}
void frsky_check_telemetry(uint8_t *pkt,uint8_t len)
{
uint8_t clen = pkt[0] + 3 ;
if (len != clen) // wrong length
return;
if(pkt[1] == rx_tx_addr[3] &&
pkt[2] == rx_tx_addr[2] ) {
telemetry_link|=1; // Telemetry data is available
TX_RSSI = pkt[len-2];
if(TX_RSSI >=128)
TX_RSSI -= 128;
else
TX_RSSI += 128;
TX_LQI = pkt[len-1]&0x7F;
for (uint8_t i=3;i<len-2;i++)
pktt[i]=pkt[i]; // Buffer telemetry values to be sent
if(pktt[6]>0 && pktt[6]<=10) {
if (protocol==PROTO_FRSKYD) {
if ( ( pktt[7] & 0x1F ) == (telemetry_counter & 0x1F) ) {
uint8_t topBit = 0 ;
if ( telemetry_counter & 0x80 )
if ( ( telemetry_counter & 0x1F ) != RetrySequence )
topBit = 0x80 ;
telemetry_counter = ( (telemetry_counter+1)%32 ) | topBit ; // Request next telemetry frame
} else {
// incorrect sequence
RetrySequence = pktt[7] & 0x1F ;
telemetry_counter |= 0x80 ;
pktt[6]=0 ; // Discard current packet and wait for retransmit
}
}
} else
pktt[6]=0; // Discard packet
//
#if defined SPORT_TELEMETRY && defined FRSKYX_CC2500_INO
telemetry_lost=0;
if (protocol==PROTO_FRSKYX) {
uint16_t lcrc = frskyX_crc_x(&pkt[3], len-7 ) ;
if ( ( (lcrc >> 8) == pkt[len-4]) && ( (lcrc & 0x00FF ) == pkt[len-3]) ) {
// Check if in sequence
if ( (pkt[5] & 0x0F) == 0x08 ) {
FrX_receive_seq = 0x08 ;
NextFxFrameToForward = 0 ;
FrskyxRxFrames[0].valid = 0 ;
FrskyxRxFrames[1].valid = 0 ;
FrskyxRxFrames[2].valid = 0 ;
FrskyxRxFrames[3].valid = 0 ;
} else if ( (pkt[5] & 0x03) == (FrX_receive_seq & 0x03 ) ) {
// OK to process
struct t_fx_rx_frame *p ;
uint8_t count ;
p = &FrskyxRxFrames[FrX_receive_seq & 3] ;
count = pkt[6] ;
if ( count <= 6 ) {
p->count = count ;
for ( uint8_t i = 0 ; i < count ; i += 1 )
p->payload[i] = pkt[i+7] ;
}
else
p->count = 0 ;
p->valid = 1 ;
FrX_receive_seq = ( FrX_receive_seq + 1 ) & 0x03 ;
if ( FrskyxRxTelemetryValidSequence & 0x80 ) {
FrX_receive_seq = ( FrskyxRxTelemetryValidSequence + 1 ) & 3 ;
FrskyxRxTelemetryValidSequence &= 0x7F ;
}
} else {
// Save and request correct packet
struct t_fx_rx_frame *q ;
uint8_t count ;
// pkt[4] RSSI
// pkt[5] sequence control
// pkt[6] payload count
// pkt[7-12] payload
pktt[6] = 0 ; // Don't process
if ( (pkt[5] & 0x03) == ( ( FrX_receive_seq +1 ) & 3 ) ) {
q = &FrskyxRxFrames[(pkt[5] & 0x03)] ;
count = pkt[6] ;
if ( count <= 6 ) {
q->count = count ;
for ( uint8_t i = 0 ; i < count ; i += 1 ) {
q->payload[i] = pkt[i+7] ;
}
} else
q->count = 0 ;
q->valid = 1 ;
FrskyxRxTelemetryValidSequence = 0x80 | ( pkt[5] & 0x03 ) ;
}
FrX_receive_seq = ( FrX_receive_seq & 0x03 ) | 0x04 ; // Request re-transmission
}
if (((pktt[5] >> 4) & 0x0f) == 0x08)
FrX_send_seq = 0 ;
}
}
#endif
}
}
void init_frskyd_link_telemetry()
{
telemetry_link=0;
telemetry_counter=0;
v_lipo1=0;
v_lipo2=0;
RX_RSSI=0;
TX_RSSI=0;
RX_LQI=0;
TX_LQI=0;
}
#if defined SPORT_TELEMETRY
/* SPORT details serial
100K 8E2 normal-multiprotocol
-every 12ms-or multiple of 12; %36
1 2 3 4 5 6 7 8 9 CRC DESCR
7E 98 10 05 F1 20 23 0F 00 A6 SWR_ID
7E 98 10 01 F1 33 00 00 00 C9 RSSI_ID
7E 98 10 04 F1 58 00 00 00 A1 BATT_ID
7E BA 10 03 F1 E2 00 00 00 18 ADC2_ID
7E BA 10 03 F1 E2 00 00 00 18 ADC2_ID
7E BA 10 03 F1 E2 00 00 00 18 ADC2_ID
7E BA 10 03 F1 E2 00 00 00 18 ADC2_ID
7E BA 10 03 F1 E2 00 00 00 18 ADC2_ID
7E BA 10 03 F1 E2 00 00 00 18 ADC2_ID
Telemetry frames(RF) SPORT info
15 bytes payload
SPORT frame valid 6+3 bytes
[00] PKLEN 0E 0E 0E 0E
[01] TXID1 DD DD DD DD
[02] TXID2 6D 6D 6D 6D
[03] CONST 02 02 02 02
[04] RS/RB 2C D0 2C CE //D0;CE=2*RSSI;....2C = RX battery voltage(5V from Bec)
[05] HD-SK 03 10 21 32 //TX/RX telemetry hand-shake bytes
[06] NO.BT 00 00 06 03 //No.of valid SPORT frame bytes in the frame
[07] STRM1 00 00 7E 00
[08] STRM2 00 00 1A 00
[09] STRM3 00 00 10 00
[10] STRM4 03 03 03 03
[11] STRM5 F1 F1 F1 F1
[12] STRM6 D1 D1 D0 D0
[13] CHKSUM1 --|2 CRC bytes sent by RX (calculated on RX side crc16/table)
[14] CHKSUM2 --|
+2 appended bytes automatically RSSI and LQI/CRC bytes(len=0x0E+3);
0x06 0x06 0x06 0x06 0x06
0x7E 0x00 0x03 0x7E 0x00
0x1A 0x00 0xF1 0x1A 0x00
0x10 0x00 0xD7 0x10 0x00
0x03 0x7E 0x00 0x03 0x7E
0xF1 0x1A 0x00 0xF1 0x1A
0xD7 0x10 0x00 0xD7 0x10
0xE1 0x1C 0xD0 0xEE 0x33
0x34 0x0A 0xC3 0x56 0xF3
*/
#if defined SPORT_POLLING || defined MULTI_TELEMETRY
const uint8_t PROGMEM Indices[] = { 0x00, 0xA1, 0x22, 0x83, 0xE4, 0x45,
0xC6, 0x67, 0x48, 0xE9, 0x6A, 0xCB,
0xAC, 0x0D, 0x8E, 0x2F, 0xD0, 0x71,
0xF2, 0x53, 0x34, 0x95, 0x16, 0xB7,
0x98, 0x39, 0xBA, 0x1B } ;
#endif
#endif
/**************************/
/**************************/
/** Serial TX routines **/
/**************************/
/**************************/
// Routines for bit-bashed serial output
void Serial_write( uint8_t byte )
{
uint8_t temp ;
uint8_t temp1 ;
uint8_t byteLo ;
#ifdef INVERT_SERIAL
byte = ~byte ;
#endif
byteLo = byte ;
byteLo >>= 7 ; // Top bit
if ( SerialControl.speed == SPEED_100K )
{
#ifdef INVERT_SERIAL
byteLo |= 0x02 ; // Parity bit
#else
byteLo |= 0xFC ; // Stop bits
#endif
// calc parity
temp = byte ;
temp >>= 4 ;
temp = byte ^ temp ;
temp1 = temp ;
temp1 >>= 2 ;
temp = temp ^ temp1 ;
temp1 = temp ;
temp1 <<= 1 ;
temp ^= temp1 ;
temp &= 0x02 ;
#ifdef INVERT_SERIAL
byteLo ^= temp ;
#else
byteLo |= temp ;
#endif
}
else
{
byteLo |= 0xFE ; // Stop bit
}
byte <<= 1 ;
#ifdef INVERT_SERIAL
byte |= 1 ; // Start bit
#endif
uint8_t next = SerialControl.head + 2;
if(next>=TXBUFFER_SIZE)
next=0;
if ( next != SerialControl.tail )
{
SerialControl.data[SerialControl.head] = byte ;
SerialControl.data[SerialControl.head+1] = byteLo ;
SerialControl.head = next ;
}
if(!IS_TX_PAUSE_on)
tx_resume();
}
#endif // TELEMETRY

36
remote/include/tx_def.h

@ -1,42 +1,6 @@
#ifndef _TX_DEV_H_
#define _TX_DEV_H_
// Turnigy PPM and channels
#if defined(TX_ER9X)
#define PPM_MAX_100 2012 // 100%
#define PPM_MIN_100 988 // 100%
#endif
// Devo PPM and channels
#if defined(TX_DEVO7)
#define PPM_MAX_100 1920 // 100%
#define PPM_MIN_100 1120 // 100%
#endif
// SPEKTRUM PPM and channels
#if defined(TX_SPEKTRUM)
#define PPM_MAX_100 1900 // 100%
#define PPM_MIN_100 1100 // 100%
#endif
// HISKY
#if defined(TX_HISKY)
#define PPM_MAX_100 1920 // 100%
#define PPM_MIN_100 1120 // 100%
#endif
// Multiplex MC2020
#if defined(TX_MPX)
#define PPM_MAX_100 1950 // 100%
#define PPM_MIN_100 1250 // 100%
#endif
// Walkera PL0811-01H
#if defined(TX_WALKERA)
#define PPM_MAX_100 1800 // 100%
#define PPM_MIN_100 1000 // 100%
#endif
//Channel MIN MAX values
#define CHANNEL_MAX_100 1844 // 100%
#define CHANNEL_MIN_100 204 // 100%

55
remote/src/FrSkyD_cc2500.cpp

@ -16,6 +16,8 @@
#include "common.h"
#include "cc2500_spi.h"
#include "Multiprotocol.h"
#include "input.h"
#include "FrSkyD_cc2500.h"
uint8_t hopping_frequency[50];
uint16_t counter;
@ -45,7 +47,7 @@ void frsky2way_build_bind_packet()
packet[2] = 0x01;
packet[3] = rx_tx_addr[3];
packet[4] = rx_tx_addr[2];
uint16_t idx = ((state -FRSKY_BIND) % 10) * 5;
uint16_t idx = ((state - FRSKY_BIND) % 10) * 5;
packet[5] = idx;
packet[6] = hopping_frequency[idx++];
packet[7] = hopping_frequency[idx++];
@ -111,43 +113,44 @@ uint16_t initFrSky_2way()
}
return 10000;
}
uint16_t ReadFrSky_2way()
uint16_t ReadFrSky_2way_bind(void)
{
//debugln("%s",__func__);
frsky2way_build_bind_packet();
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR, 0x00);
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
CC2500_Strobe(CC2500_SFRX);//0x3A
CC2500_WriteData(packet, packet[0]+1);
if (state < FRSKY_BIND_DONE) {
frsky2way_build_bind_packet();
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR, 0x00);
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
CC2500_Strobe(CC2500_SFRX);//0x3A
CC2500_WriteData(packet, packet[0]+1);
if(IS_BIND_DONE) {
state = FRSKY_BIND;
debugln("%s bind done",__func__);
} else {
// menu tells us to stop so do not inc state
//state++;
}
if(IS_BIND_DONE) {
state = FRSKY_BIND;
debugln("%s bind done",__func__);
} else {
state++;
}
if(state == FRSKY_BIND_DONE) {
debugln("%s bind done fr",__func__);
}
return 9000;
if(state == FRSKY_BIND_DONE) {
/* reset state again */
state = 0;
debugln("%s bind done fr",__func__);
}
if (state == FRSKY_BIND_DONE) {
return 9000;
}
uint16_t ReadFrSky_2way()
{
if (state <= FRSKY_BIND_DONE) {
//debugln("%s bind done",__func__);
state = FRSKY_DATA2;
frsky2way_init(0);
counter = 0;
BIND_DONE;
} else if (state == FRSKY_DATA5) {
CC2500_Strobe(CC2500_SRX);//0x34 RX enable
state = FRSKY_DATA1;
return 9200;
}
}
counter = (counter + 1) % 188;
if (state == FRSKY_DATA4) { //telemetry receive
CC2500_SetTxRxMode(RX_EN);
@ -160,7 +163,7 @@ uint16_t ReadFrSky_2way()
if (state == FRSKY_DATA1) {
len = CC2500_ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
//debugln("%d len",len);
//debugln("%d len",len);
if (len && len<=(0x11+3)) { // 20bytes
CC2500_ReadData(pkt, len); //received telemetry packets
#if defined(TELEMETRY)

222
remote/src/Multiprotocol.cpp

@ -51,6 +51,7 @@ uint8_t protocol_flags=0,protocol_flags2=0;
uint8_t channel;
uint8_t packet[40];
static void protocol_init(void);
uint16_t seed;
@ -85,11 +86,6 @@ uint8_t len;
// Mode_select variables
uint8_t mode_select;
#ifdef ENABLE_PPM
// PPM variable
volatile uint8_t PPM_chan_max=0;
#endif
#if not defined (ORANGE_TX) && not defined (STM32_BOARD)
//Random variable
volatile uint32_t gWDT_entropy=0;
@ -120,8 +116,6 @@ void_function_t remote_callback = 0;
//forward declarations
void modules_reset();
uint32_t random_id(bool create_new);
static void protocol_init();
uint8_t Update_All();
// Init
void setup()
@ -213,7 +207,6 @@ void setup()
debugln("Module Id: %lx", MProtocol_id_master);
#ifdef ENABLE_PPM
//Protocol and interrupts initialization
{
uint8_t line=curr_bank*14+mode_select-1;
@ -222,39 +215,30 @@ void setup()
sub_protocol = PPM_prot[line].sub_proto;
RX_num = PPM_prot[line].rx_num;
debug("protocol: %d ", protocol);
switch(protocol) {
case PROTO_FRSKYD:
debugln("PROTO_FRSKYD");
break;
case PROTO_FRSKYX:
debugln("PROTO_FRSKYX");
break;
case PROTO_FRSKYV:
debugln("PROTO_FRSKYV");
break;
}
debug("sub_protocol: %d\n", sub_protocol);
option = PPM_prot[line].option; // Use radio-defined option value
debug("freq offset: %d\n", option);
if(PPM_prot[line].power)
POWER_FLAG_on;
if(PPM_prot[line].autobind) {
AUTOBIND_FLAG_on;
BIND_IN_PROGRESS; // Force a bind at protocol startup
debug("protocol: %d ", protocol);
switch(protocol) {
case PROTO_FRSKYD:
debugln("PROTO_FRSKYD");
break;
case PROTO_FRSKYX:
debugln("PROTO_FRSKYX");
break;
case PROTO_FRSKYV:
debugln("PROTO_FRSKYV");
break;
}
debug("sub_protocol: %d\n", sub_protocol);
option = PPM_prot[line].option; // Use radio-defined option value
debug("freq offset: %d\n", option);
line++;
protocol_init();
}
#endif //ENABLE_PPM
debug("Init complete\n");
input.init();
input.update();
init_state();
debug("Init complete\n");
input.init();
input.update();
init_state();
}
// Main
@ -272,12 +256,6 @@ void loop()
return;
uint32_t next_callback;
if(remote_callback==0 || IS_WAIT_BIND_on ) {
do {
Update_All();
} while(remote_callback==0 || IS_WAIT_BIND_on);
}
uint32_t end__ = micros();
uint32_t start = micros();
@ -310,170 +288,24 @@ void loop()
}
}
uint8_t Update_All() {
#ifdef ENABLE_BIND_CH
if(IS_AUTOBIND_FLAG_on &&
IS_BIND_CH_PREV_off &&
Channel_data[BIND_CH-1] > CHANNEL_MAX_COMMAND &&
Channel_data[Input::CH_THROTTLE] < (CHANNEL_MIN_100+50)
) { // Autobind is on and BIND_CH went up and Throttle is low
CHANGE_PROTOCOL_FLAG_on; //reload protocol
BIND_IN_PROGRESS; //enable bind
debugln("%s:%d set bind prog",__func__, __LINE__);
BIND_CH_PREV_on;
}
if(IS_AUTOBIND_FLAG_on && IS_BIND_CH_PREV_on && Channel_data[BIND_CH-1]<CHANNEL_MIN_COMMAND) {
// Autobind is on and BIND_CH went down
BIND_CH_PREV_off;
//Request protocol to terminate bind
#if defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO) || defined(FRSKYV_CC2500_INO)
if(protocol==PROTO_FRSKYD || protocol==PROTO_FRSKYX || protocol==PROTO_FRSKYV)
BIND_DONE;
else
#endif
if(bind_counter>2)
bind_counter=2;
}
#endif //ENABLE_BIND_CH
input.update();
if(IS_CHANGE_PROTOCOL_FLAG_on) {
debugln("%s:%d set bind prog",__func__, __LINE__);
// Protocol needs to be changed or relaunched for bind
protocol_init(); //init new protocol
return 1;
}
return 0;
}
// Protocol start
static void protocol_init() {
static uint16_t next_callback;
if(IS_WAIT_BIND_off) {
remote_callback = 0; // No protocol
next_callback=0; // Default is immediate call back
modules_reset(); // Reset all modules
//Set global ID and rx_tx_addr
MProtocol_id = RX_num + MProtocol_id_master;
set_rx_tx_addr(MProtocol_id);
modules_reset(); // Reset all modules
uint32_t next_callback = 0;
blink=millis();
//Set global ID and rx_tx_addr
MProtocol_id = RX_num + MProtocol_id_master;
set_rx_tx_addr(MProtocol_id);
debugln("Protocol selected: %d, sub proto %d, rxnum %d, option %d", protocol, sub_protocol, RX_num, option);
debugln("Protocol selected: %d, sub proto %d, rxnum %d, option %d", protocol, sub_protocol, RX_num, option);
switch(protocol) // Init the requested protocol
{
switch(protocol) // Init the requested protocol
{
case PROTO_FRSKYD:
next_callback = initFrSky_2way();
remote_callback = ReadFrSky_2way;
break;
}
}
#if defined(WAIT_FOR_BIND) && defined(ENABLE_BIND_CH)
if( IS_AUTOBIND_FLAG_on && IS_BIND_CH_PREV_off && (cur_protocol[1]&0x80)==0 && mode_select == MODE_SERIAL) {
// Autobind is active but no bind requested by either BIND_CH or BIND. But do not wait if in PPM mode...
WAIT_BIND_on;
return;
}
#endif
WAIT_BIND_off;
CHANGE_PROTOCOL_FLAG_off;
delayMicroseconds(next_callback);
debugln("%s BIND_BUTTON_FLAG_off",__func__);
}
void update_serial_data()
{
if(rx_ok_buff[1]&0x20) //check range
RANGE_FLAG_on;
else
RANGE_FLAG_off;
if(rx_ok_buff[1]&0x40) //check autobind
AUTOBIND_FLAG_on;
else
AUTOBIND_FLAG_off;
if(rx_ok_buff[2]&0x80) //if rx_ok_buff[2] ==1,power is low ,0-power high
POWER_FLAG_off; //power low
else
POWER_FLAG_on; //power high
//Forced frequency tuning values for CC2500 protocols
#if defined(FORCE_FRSKYD_TUNING)
if(protocol==PROTO_FRSKYD)
option=FORCE_FRSKYD_TUNING; // Use config-defined tuning value for FrSkyD
else
#endif
option=rx_ok_buff[3]; // Use radio-defined option value
#ifdef FAILSAFE_ENABLE
bool failsafe=false;
if(rx_ok_buff[0]&0x02) { // Packet contains failsafe instead of channels
failsafe=true;
rx_ok_buff[0]&=0xFD; //remove the failsafe flag
}
#endif
if( (rx_ok_buff[0] != cur_protocol[0]) || ((rx_ok_buff[1]&0x5F) != (cur_protocol[1]&0x5F)) || ( (rx_ok_buff[2]&0x7F) != (cur_protocol[2]&0x7F) ) )
{ // New model has been selected
CHANGE_PROTOCOL_FLAG_on; //change protocol
WAIT_BIND_off;
if((rx_ok_buff[1]&0x80)!=0 || IS_AUTOBIND_FLAG_on)
BIND_IN_PROGRESS; //launch bind right away if in autobind mode or bind is set
else
BIND_DONE;
protocol=(rx_ok_buff[0]==0x55?0:32) + (rx_ok_buff[1]&0x1F); //protocol no (0-63) bits 4-6 of buff[1] and bit 0 of buf[0]
sub_protocol=(rx_ok_buff[2]>>4)& 0x07; //subprotocol no (0-7) bits 4-6
RX_num=rx_ok_buff[2]& 0x0F; // rx_num bits 0---3
} else if( ((rx_ok_buff[1]&0x80)!=0) && ((cur_protocol[1]&0x80)==0) ) // Bind flag has been set
{ // Restart protocol with bind
CHANGE_PROTOCOL_FLAG_on;
BIND_IN_PROGRESS;
} else {
if( ((rx_ok_buff[1]&0x80)==0) && ((cur_protocol[1]&0x80)!=0) ) // Bind flag has been reset
{ // Request protocol to end bind
#if defined(FRSKYD_CC2500_INO) || defined(FRSKYX_CC2500_INO) || defined(FRSKYV_CC2500_INO)
if(protocol==PROTO_FRSKYD || protocol==PROTO_FRSKYX || protocol==PROTO_FRSKYV)
BIND_DONE;
else
#endif
if(bind_counter>2)
bind_counter=2;
}
}
//store current protocol values
for(uint8_t i=0;i<3;i++)
cur_protocol[i] = rx_ok_buff[i];
// decode channel/failsafe values
volatile uint8_t *p=rx_ok_buff+3;
uint8_t dec=-3;
for(uint8_t i=0;i<NUM_TX_CHN;i++) {
dec+=3;
if(dec>=8) {
dec-=8;
p++;
}
p++;
uint16_t temp=((*((uint32_t *)p))>>dec)&0x7FF;
if(failsafe)
Failsafe_data[i]=temp; //value range 0..2047, 0=no pulses, 2047=hold
else
Channel_data[i]=temp; //value range 0..2047, 0=-125%, 2047=+125%
}
cli();
if(IS_RX_MISSED_BUFF_on) // If the buffer is still valid
{ memcpy((void*)rx_ok_buff,(const void*)rx_buff,RXBUFFER_SIZE);// Duplicate the buffer
RX_MISSED_BUFF_off;
}
sei();
}
void modules_reset()

4
remote/src/cc2500_spi.cpp

@ -107,9 +107,9 @@ void CC2500_SetPower()
uint8_t power=CC2500_BIND_POWER;
if(IS_BIND_DONE) {
#ifdef CC2500_ENABLE_LOW_POWER
power=IS_POWER_FLAG_on?CC2500_HIGH_POWER:CC2500_LOW_POWER;
power = IS_POWER_FLAG_on ? CC2500_HIGH_POWER : CC2500_LOW_POWER;
#else
power=CC2500_HIGH_POWER;
power = CC2500_HIGH_POWER;
#endif
}
if(IS_RANGE_FLAG_on)

28
remote/src/crc.cpp

@ -1,22 +1,28 @@
#include "Arduino.h"
#include "crc.h"
static uint32_t crc_table[16] = {
static const unsigned int tiny_crc32tab[16] = {
0x00000000, 0x1db71064, 0x3b6e20c8, 0x26d930ac,
0x76dc4190, 0x6b6b51f4, 0x4db26158, 0x5005713c,
0xedb88320, 0xf00f9344, 0xd6d6a3e8, 0xcb61b38c,
0x9b64c2b0, 0x86d3d2d4, 0xa00ae278, 0xbdbdf21c
};
uint32_t crc_update (uint32_t crc, uint8_t data)
{
uint8_t tbl_idx;
uint8_t mask = 0x0f;
tbl_idx = crc ^ (data >> (0 * 4));
crc = (crc_table + (tbl_idx & mask)) ^ (crc >> 4);
uint32_t __tiny_crc32(const void *data, unsigned int length, uint32_t crc)
{
const unsigned char *buf = (const unsigned char *)data;
unsigned int i;
tbl_idx = crc ^ (data >> (1 * 4));
crc = (crc_table + (tbl_idx & mask)) ^ (crc >> 4);
for (i = 0; i < length; ++i) {
crc ^= buf[i];
crc = tiny_crc32tab[crc & 0x0f] ^ (crc >> 4);
crc = tiny_crc32tab[crc & 0x0f] ^ (crc >> 4);
}
return crc;
return crc;
}
uint32_t tiny_crc32(const void *data, unsigned int length)
{
// return value suitable for passing in next time, for final value invert it
return __tiny_crc32(data, length, 42) ^ 0xffffff;
}

25
remote/src/eeprom.cpp

@ -22,6 +22,8 @@ Eeprom_config::~Eeprom_config() {
}
int Eeprom_config::validate() {
uint32_t crc_calc = 0;
if (this->sucessfull_read == false) {
return -1;
}
@ -29,12 +31,8 @@ int Eeprom_config::validate() {
if (this->current_config.version != CURRENT_VERSION) {
return -1;
}
uint32_t crc_calc = 0;
uint8_t * data = &(this->current_config.data);
for (uint8_t i = 0; i < sizeof(struct eeprom_data_v1) ; i = 0) {
crc_calc = crc_update(crc_calc, data[i]);
}
crc_calc = tiny_crc32(&(this->current_config.data), sizeof(this->current_config.data));
if (crc_calc != this->current_config.data_crc) {
return -1;
@ -47,8 +45,7 @@ int Eeprom_config::read(void) {
data = (uint8_t *) &this->current_config;
for (uint8_t i = 0; i < sizeof(struct eeprom_data_v1) ; i = 0) {
EEPROM.read(0x10 + i , data);
data+=1;
data[i] = EEPROM.read(0x10 + i);
}
this->sucessfull_read = true;
@ -59,27 +56,29 @@ int Eeprom_config::write(void) {
uint8_t *data = NULL;
data = (uint8_t *) &this->current_config;
this->current_config.version = CURRENT_VERSION;
this->current_config.data_crc = tiny_crc32(&(this->current_config.data), sizeof(this->current_config.data));
for (uint8_t i = 0; i < sizeof(struct eeprom_data_v1) ; i = 0) {
EEPROM.write(0x10 + i , data);
data+=1;
EEPROM.write(0x10 + i , data[i]);
}
return 0;
}
int Eeprom_config::get_ch_config(struct ch_config* config) {
int Eeprom_config::get_ch_config(struct Input::ch_config* config) {
if (this->sucessfull_read == false && config != NULL) {
return -1;
}
memcpy(config, this->current_config.data.ch, sizeof(struct ch_config) * CH_COUNT);
memcpy(config, &this->current_config.data.ch, sizeof(struct Input::ch_config) * Input::CH_COUNT);
return 0;
}
int Eeprom_config::set_ch_config(struct ch_config* config) {
int Eeprom_config::set_ch_config(struct Input::ch_config* config) {
if (this->sucessfull_read == false && config != NULL) {
return -1;
}
memcpy(this->current_config.data.ch, config, sizeof(struct ch_config) * CH_COUNT);
memcpy(this->current_config.data.ch, config, sizeof(struct Input::ch_config) * Input::CH_COUNT);
return 0;
}

14
remote/src/input.cpp

@ -30,8 +30,8 @@ Input::Input(void) {
//InitFailsafe
for (uint8_t i = 0; i < NUM_TX_CHN; i++)
Failsafe_data[i] = (CHANNEL_MAX_100 - CHANNEL_MIN_100) / 2 + CHANNEL_MIN_100;
Failsafe_data[CH_THROTTLE] = CHANNEL_MIN_100; //1=-125%, 204=-100%
this->failsafe_data[i] = (CHANNEL_MAX_100 - CHANNEL_MIN_100) / 2 + CHANNEL_MIN_100;
this->failsafe_data[CH_THROTTLE] = CHANNEL_MIN_100; //1=-125%, 204=-100%
// init channel
@ -40,7 +40,7 @@ Input::Input(void) {
this->channel_data[CH_THROTTLE] = 204;
}
uint16_t *Input::get_channel_data(void) {
uint16_t* Input::get_channel_data(void) {
return this->channel_data;
}
void Input::mark_processed(void) {
@ -49,14 +49,6 @@ void Input::mark_processed(void) {
this->curr = temp;
}
struct Input::data* Input::get_curr_input(void) {
return this->curr;
}
struct Input::data* Input::get_old_input(void) {
return this->old;
}
void Input::init() {
this->pins[CH_THROTTLE] = Throttle_pin;
this->ch_config[CH_THROTTLE].is_analog = true;

296
remote/src/state.cpp

@ -96,299 +96,3 @@ void update_state(void) {
curr_state->enter();
}
}
//LCD_state_init
LCD_state_init::LCD_state_init(void) {
}
void LCD_state_init::enter(void) {
lcd.setCursor(0,0);
lcd.print(" wellcome ");
lcd.setCursor(0,1);
lcd.print(" phschoen ");
this->time_enter = millis();
}
void LCD_state_init::update(void)
{
uint32_t diff;
diff = millis() - this->time_enter;
if (diff > 5 * 1000) {
new_state = s_joy;
}
}
void LCD_state_init::leave(void)
{
lcd.clear();
}
//LCD_state_bind
LCD_state_bind::LCD_state_bind(void) {
this->bind_time = 20;
}
void LCD_state_bind::enter(void) {
lcd.setCursor(0,0);
lcd.print("bind mode ");
lcd.setCursor(0,1);
lcd.print(" ");
this->time_enter = millis();
}
void LCD_state_bind::update(void)
{
debugln("blubber\n");
char line[17];
unsigned long time_in_ms = millis() - this->time_enter;
unsigned long time_in_s = time_in_ms/1000; // to sec
unsigned long remain_s = this->bind_time - time_in_s;
snprintf(line,sizeof(line),"remaining sec %02lu",remain_s);
lcd.setCursor(0,1);
lcd.print(line);
uint32_t end__ = micros();
uint32_t start = micros();
uint32_t next_callback_time;
next_callback_time = initFrSky_2way();
while(1) {
start = end__;
next_callback_time = ReadFrSky_2way();
// update time
time_in_ms = millis() - this->time_enter;
time_in_s = time_in_ms/1000; // to sec
remain_s = this->bind_time - time_in_s;
// print on lcd
snprintf(line,sizeof(line),"%02lu",remain_s);
lcd.setCursor(14,1);
lcd.print(line);
uint32_t wait_until = start + next_callback_time;
end__ = micros();
if (end__ - start < next_callback_time) {
uint32_t wait = next_callback_time;
wait -= ((end__-start));
delayMicroseconds(wait);
end__ += wait;
}
end__ = micros();
if (remain_s == 0)
break;
}
// cange to menu when done
new_state = s_menu;
}
void LCD_state_bind::leave(void)
{
lcd.clear();
}
//
LCD_state_joy_calibration::LCD_state_joy_calibration(void) {
}
void LCD_state_joy_calibration::enter(void) {
lcd.setCursor(0,0);
lcd.print("calib. start ");
lcd.setCursor(0,1);
lcd.print("move all sticks ");
delay(500);
}
void show_dots(int row, int number) {
lcd.setCursor(0,row);
for(int c = 0; c < 16;++c) {
if (c < number)
lcd.print(".");
else
lcd.print(" ");
}
}
void LCD_state_joy_calibration::update(void) {
int8_t turns = 50;
int8_t i;
// init min/max
input.calibration_reset();
// min max calibration
lcd.setCursor(0,0);
lcd.print("min max Calib. ");
show_dots(1,16);
i = turns;
while(i > 0) {
input.update();
if (true == input.calibration_update()) {
i = turns;
}else {
i -= 1;
show_dots(1,(i *16)/turns);
}
delay(100);
}
// center
lcd.setCursor(0,0);
lcd.print("center sticks ");
i = turns;
while(i > 0) {
input.update();
if (false == input.is_centered()) {
i = turns;
}else {
i -= 1;
show_dots(1,(i *16)/turns);
}
delay(100);
}
for (uint8_t _ch = 0; _ch < 4 ; ++_ch) {
enum Input::input_channels ch = (enum Input::input_channels) _ch;
lcd.setCursor(0,0);
lcd.print("move to max: ");
lcd.setCursor(0,1);
lcd.print(" ");
lcd.setCursor(0,1);
lcd.print(ch_name[ch]);
i = turns;
while(i>0) {
delay(50);
input.update();
input.print_ch(ch);
if (input.is_high(ch)) {
i--;
continue;
}
if (input.is_low(ch)) {
input.invert_ch(ch);
debug("invert");
i = turns;
continue;
}
}
}
struct ch_config ch_config[CH_COUNT];
input.get_calibration(ch_config);
lcd.setCursor(0,0);
lcd.print("center again ");
lcd.setCursor(0,1);
lcd.print("all sticks ");
while (false == input.is_centered()) {
input.update();
}
new_state = s_menu;
}
void LCD_state_joy_calibration::leave(void) {
lcd.setCursor(0,0);
lcd.print("finished ");
lcd.setCursor(0,1);
lcd.print("calibration");
}
// #########################################################
// LCD_state_menu
LCD_state_menu::LCD_state_menu(void) {
}
void LCD_state_menu::enter(void) {
lcd.setCursor(0,0);
lcd.print("menu mode ");
lcd.setCursor(0,1);
lcd.print(" ");
this->curr_selected = 0;
}
void LCD_state_menu::update(void)
{
struct {
char name[15];
State * state;
} menus[] = {
{ "Flight ", s_fly },
{ "Bind ", s_bind },
{ "Joy calib ", s_joy },
{ "HF calib ", NULL },
{ " ", NULL },
};
bool wait = false;
char curr[2][16];
snprintf(curr[0], sizeof(curr[0]), "> %s", menus[this->curr_selected].name);
snprintf(curr[1], sizeof(curr[1]), " %s", menus[this->curr_selected+1].name);
lcd.setCursor(0,0);
lcd.print(curr[0]);
lcd.setCursor(0,1);
lcd.print(curr[1]);
if (false == input.is_centered(Input::MENU_UP_DOWN)) {
if (input.is_low(Input::MENU_UP_DOWN)){
this->curr_selected +=1;
if ( this->curr_selected > 3)
this->curr_selected = 3;
else
wait = true;
}
if (input.is_high(Input::MENU_UP_DOWN)){
this->curr_selected -=1;
if ( this->curr_selected < 0)
this->curr_selected = 0;
else
wait = true;
}
}
if (input.is_high(Input::MENU_LEFT_RIGHT)) {
lcd.setCursor(0,0);
lcd.print("entering ");
lcd.setCursor(0,1);
lcd.print(menus[this->curr_selected].name);
// do wait until its centered
while(false == input.is_centered(Input::MENU_LEFT_RIGHT)) {
input.update();
}
if (menus[this->curr_selected].state != NULL) {
new_state = menus[this->curr_selected].state;
}
wait = true;
}
if(wait)
delay(500);
}
void LCD_state_menu::leave(void)
{
lcd.clear();
}
// LCD_state_fly
LCD_state_fly::LCD_state_fly(void) {
}
void LCD_state_fly::enter(void) {
lcd.setCursor(0,0);
lcd.print("fly mode ");
lcd.setCursor(0,1);
lcd.print(" ");
this->time_enter = millis();
}
void LCD_state_fly::update(void)
{
}
void LCD_state_fly::leave(void)
{
lcd.clear();
}

77
remote/src/state_bind.cpp

@ -0,0 +1,77 @@
#include <LiquidCrystal_I2C.h>
#include <stdio.h>
#include "Arduino.h"
#include "FrSkyD_cc2500.h"
#include "state.h"
#include "input.h"
#include "eeprom.h"
#include "debug.h"
#include "tx_def.h"
#include "config.h"
LCD_state_bind::LCD_state_bind(void) {
this->bind_time = DEFAULT_BIND_TIME;
}
void LCD_state_bind::enter(void) {
lcd.setCursor(0,0);
lcd.print("bind mode ");
lcd.setCursor(0,1);
lcd.print(" ");
this->time_enter = millis();
}
void LCD_state_bind::update(void)
{
debugln("blubber\n");
char line[17];
unsigned long time_in_ms = millis() - this->time_enter;
unsigned long time_in_s = time_in_ms/1000; // to sec
unsigned long remain_s = this->bind_time - time_in_s;
snprintf(line,sizeof(line),"remaining sec %02lu",remain_s);
lcd.setCursor(0,1);
lcd.print(line);
uint32_t end__ = micros();
uint32_t start = micros();
uint32_t next_callback_time;
next_callback_time = initFrSky_2way();
while(1) {
start = end__;
next_callback_time = ReadFrSky_2way_bind();
// update time
time_in_ms = millis() - this->time_enter;
time_in_s = time_in_ms/1000; // to sec
remain_s = this->bind_time - time_in_s;
// print on lcd
snprintf(line,sizeof(line),"%02lu",remain_s);
lcd.setCursor(14,1);
lcd.print(line);
uint32_t wait_until = start + next_callback_time;
end__ = micros();
if (end__ - start < next_callback_time) {
uint32_t wait = next_callback_time;
wait -= ((end__-start));
delayMicroseconds(wait);
end__ += wait;
}
end__ = micros();
if (remain_s == 0)
break;
}
// cange to menu when done
new_state = s_menu;
}
void LCD_state_bind::leave(void)
{
lcd.clear();
}

29
remote/src/state_fly.cpp

@ -0,0 +1,29 @@
#include <LiquidCrystal_I2C.h>
#include <stdio.h>
#include "Arduino.h"
#include "FrSkyD_cc2500.h"
#include "state.h"
#include "input.h"
#include "eeprom.h"
#include "debug.h"
#include "tx_def.h"
LCD_state_fly::LCD_state_fly(void) {
}
void LCD_state_fly::enter(void) {
lcd.setCursor(0,0);
lcd.print("fly mode ");
lcd.setCursor(0,1);
lcd.print(" ");
this->time_enter = millis();
}
void LCD_state_fly::update(void)
{
}
void LCD_state_fly::leave(void)
{
lcd.clear();
}

31
remote/src/state_init.cpp

@ -0,0 +1,31 @@
#include <LiquidCrystal_I2C.h>
#include <stdio.h>
#include "Arduino.h"
#include "FrSkyD_cc2500.h"
#include "state.h"
#include "input.h"
#include "eeprom.h"
#include "debug.h"
#include "tx_def.h"
LCD_state_init::LCD_state_init(void) {
}
void LCD_state_init::enter(void) {
lcd.setCursor(0,0);
lcd.print(" wellcome ");
lcd.setCursor(0,1);
lcd.print(" phschoen ");
this->time_enter = millis();
}
void LCD_state_init::update(void)
{
uint32_t diff;
diff = millis() - this->time_enter;
if (diff > 5 * 1000) {
new_state = s_joy;
}
}
void LCD_state_init::leave(void)
{
lcd.clear();
}

115
remote/src/state_joy_calib.cpp

@ -0,0 +1,115 @@
#include <LiquidCrystal_I2C.h>
#include <stdio.h>
#include "Arduino.h"
#include "FrSkyD_cc2500.h"
#include "state.h"
#include "input.h"
#include "eeprom.h"
#include "debug.h"
#include "tx_def.h"
LCD_state_joy_calibration::LCD_state_joy_calibration(void) {
}
void LCD_state_joy_calibration::enter(void) {
lcd.setCursor(0,0);
lcd.print("calib. start ");
lcd.setCursor(0,1);
lcd.print("move all sticks ");
delay(500);
}
void show_dots(int row, int number) {
lcd.setCursor(0,row);
for(int c = 0; c < 16;++c) {
if (c < number)
lcd.print(".");
else
lcd.print(" ");
}
}
void LCD_state_joy_calibration::update(void) {
int8_t turns = 50;
int8_t i;
// init min/max
input.calibration_reset();
// min max calibration
lcd.setCursor(0,0);
lcd.print("min max Calib. ");
show_dots(1,16);
i = turns;
while(i > 0) {
input.update();
if (true == input.calibration_update()) {
i = turns;
}else {
i -= 1;
show_dots(1,(i *16)/turns);
}
delay(100);
}
// center
lcd.setCursor(0,0);
lcd.print("center sticks ");
i = turns;
while(i > 0) {
input.update();
if (false == input.is_centered()) {
i = turns;
}else {
i -= 1;
show_dots(1,(i *16)/turns);
}
delay(100);
}
for (uint8_t _ch = 0; _ch < 4 ; ++_ch) {
enum Input::input_channels ch = (enum Input::input_channels) _ch;
lcd.setCursor(0,0);
lcd.print("move to max: ");
lcd.setCursor(0,1);
lcd.print(" ");
lcd.setCursor(0,1);
lcd.print(ch_name[ch]);
i = turns;
while(i>0) {
delay(50);
input.update();
input.print_ch(ch);
if (input.is_high(ch)) {
i--;
continue;
}
if (input.is_low(ch)) {
input.invert_ch(ch);
debug("invert");
i = turns;
continue;
}
}
}
struct Input::ch_config ch_config[Input::CH_COUNT];
input.get_calibration(ch_config);
lcd.setCursor(0,0);
lcd.print("center again ");
lcd.setCursor(0,1);
lcd.print("all sticks ");
while (false == input.is_centered()) {
input.update();
}
new_state = s_menu;
}
void LCD_state_joy_calibration::leave(void) {
lcd.setCursor(0,0);
lcd.print("finished ");
lcd.setCursor(0,1);
lcd.print("calibration");
}

84
remote/src/state_menu.cpp

@ -0,0 +1,84 @@
#include <LiquidCrystal_I2C.h>
#include <stdio.h>
#include "Arduino.h"
#include "FrSkyD_cc2500.h"
#include "state.h"
#include "input.h"
#include "eeprom.h"
#include "debug.h"
#include "tx_def.h"
LCD_state_menu::LCD_state_menu(void) {
}
void LCD_state_menu::enter(void) {
lcd.setCursor(0,0);
lcd.print("menu mode ");
lcd.setCursor(0,1);
lcd.print(" ");
this->curr_selected = 0;
}
void LCD_state_menu::update(void)
{
struct {
char name[15];
State * state;
} menus[] = {
{ "Flight ", s_fly },
{ "Bind ", s_bind },
{ "Joy calib ", s_joy },
{ "HF calib ", NULL },
{ " ", NULL },
};
bool wait = false;
char curr[2][16];
snprintf(curr[0], sizeof(curr[0]), "> %s", menus[this->curr_selected].name);
snprintf(curr[1], sizeof(curr[1]), " %s", menus[this->curr_selected+1].name);
lcd.setCursor(0,0);
lcd.print(curr[0]);
lcd.setCursor(0,1);
lcd.print(curr[1]);
if (false == input.is_centered(Input::MENU_UP_DOWN)) {
if (input.is_low(Input::MENU_UP_DOWN)){
this->curr_selected +=1;
if ( this->curr_selected > 3)
this->curr_selected = 3;
else
wait = true;
}
if (input.is_high(Input::MENU_UP_DOWN)){
this->curr_selected -=1;
if ( this->curr_selected < 0)
this->curr_selected = 0;
else
wait = true;
}
}
if (input.is_high(Input::MENU_LEFT_RIGHT)) {
lcd.setCursor(0,0);
lcd.print("entering ");
lcd.setCursor(0,1);
lcd.print(menus[this->curr_selected].name);
// do wait until its centered
while(false == input.is_centered(Input::MENU_LEFT_RIGHT)) {
input.update();
}
if (menus[this->curr_selected].state != NULL) {
new_state = menus[this->curr_selected].state;
}
wait = true;
}
if(wait)
delay(500);
}
void LCD_state_menu::leave(void)
{
lcd.clear();
}
Loading…
Cancel
Save