Compare commits

...

196 Commits

Author SHA1 Message Date
pascallanger
d96ba9fa46 Flysky Flash space optimization 2016-09-04 16:49:00 +02:00
pascallanger
2261d655ea DEVO/J6pro Flash space optimization 2016-09-04 16:49:00 +02:00
pascallanger
8b67049863 Added NRF24L01_ReadPayloadLength 2016-09-04 16:49:00 +02:00
pascallanger
48258dd9dd Renamed FrSky protocols 2016-09-03 11:57:40 +02:00
pascallanger
e04c573726 Renamed FrSky protocols 2016-09-03 11:56:39 +02:00
pascallanger
4daec3794e Renamed FrSky protocols to match with receivers 2016-09-03 11:49:25 +02:00
pascallanger
f0646dde32 FrSky1 Fix 2016-09-03 10:12:30 +02:00
pascallanger
ec2086e0f7 Fixed invert serial compilation 2016-09-01 20:12:17 +02:00
pascallanger
2ac704178c FRSKY1 2016-09-01 18:12:35 +02:00
pascallanger
7c43c38e28 FRSKY1 2016-09-01 18:09:35 +02:00
pascallanger
043a8336e5 Code cleaning (XMEGA) 2016-09-01 17:41:38 +02:00
pascallanger
ee27535b82 Update README.md 2016-09-01 14:42:56 +02:00
pascallanger
89e6ae2475 Update Protocols_Details.md 2016-09-01 14:40:17 +02:00
pascallanger
e51615f520 DSM2 renamed to DSM 2016-09-01 14:00:49 +02:00
pascallanger
6e59897587 Update Protocols_Details.md 2016-09-01 13:53:48 +02:00
pascallanger
bd0644a261 Update Protocols_Details.md 2016-09-01 13:53:10 +02:00
pascallanger
d7825e1bf8 Update README.md 2016-09-01 13:47:42 +02:00
pascallanger
97956b6c5e FrSky1 CRC messed up... 2016-09-01 13:42:33 +02:00
pascallanger
8150504ea0 NRF CE 2016-09-01 13:05:56 +02:00
pascallanger
942dec81c7 Typo 2016-09-01 08:08:00 +02:00
pascallanger
dcbc377c62 FrSky1 optim 2016-08-31 15:54:24 +02:00
pascallanger
7b65233699 FrSky 1way protocol + cosmetic 2016-08-31 15:43:45 +02:00
pascallanger
eabfd8b5c4 Important changes of the scheduler and interrupts 2016-08-31 10:26:27 +02:00
pascallanger
b7b2799611 FrSky option applied live 2016-08-31 10:22:36 +02:00
pascallanger
ece59ac374 FrSky ppm option value default 40 2016-08-31 10:20:56 +02:00
pascallanger
83cc8b772c Merge branch 'master' of https://github.com/pascallanger/DIY-Multiprotocol-TX-Module 2016-08-31 10:19:59 +02:00
pascallanger
8b5bc18142 YD717 4-in-1 V2 compatibility 2016-08-31 10:19:55 +02:00
pascallanger
e1413baa9a Update Protocols_Details.md 2016-08-30 23:30:18 +02:00
pascallanger
03640e6d37 Changed update_serial_data 2016-08-29 17:32:21 +02:00
pascallanger
2588011524 Orange DSM module update 2016-08-29 09:51:34 +02:00
pascallanger
0c16a6804a E010 2016-08-29 08:29:57 +02:00
pascallanger
e2021fdf5d Update README.md 2016-08-29 08:24:52 +02:00
pascallanger
33b5694d35 MJXQ/E010 mod 2016-08-29 08:23:17 +02:00
pascallanger
af7d04fef6 Added E010 2016-08-28 14:05:21 +02:00
pascallanger
14e3419e4c Added MJXQ / E010 2016-08-28 14:03:22 +02:00
pascallanger
f6c5252376 DEVO PPM fixed id mode 2016-08-27 11:38:07 +02:00
pascallanger
78ee77444f Update README.md 2016-08-27 08:26:05 +02:00
pascallanger
fb022970b5 Update Protocols_Details.md 2016-08-26 21:02:50 +02:00
pascallanger
e5d378dc93 Update Protocols_Details.md 2016-08-26 18:46:03 +02:00
pascallanger
5969902263 MJXQ fix 2016-08-26 17:21:21 +02:00
pascallanger
d5894de142 Merge branch 'master' of https://github.com/pascallanger/DIY-Multiprotocol-TX-Module 2016-08-26 16:18:58 +02:00
pascallanger
059c6baa4e FrSkyX/SFHSS rfcal & second channel ASSAN 2016-08-26 16:18:50 +02:00
pascallanger
bbf9331baf Update README.md 2016-08-26 10:56:27 +02:00
pascallanger
a5b084f506 Update README.md 2016-08-26 10:55:13 +02:00
pascallanger
3b5471b97c Update Protocols_Details.md 2016-08-25 21:22:33 +02:00
pascallanger
fae37fe67d Update Protocols_Details.md 2016-08-25 19:39:08 +02:00
pascallanger
1f975efda1 Merge branch 'master' of https://github.com/pascallanger/DIY-Multiprotocol-TX-Module 2016-08-25 15:44:11 +02:00
pascallanger
3b3b61f52c DEVO channel order 2016-08-25 15:44:02 +02:00
pascallanger
1c1f6e21c5 Update Protocols_Details.md 2016-08-25 15:40:01 +02:00
pascallanger
8b60c7cc09 Update Protocols_Details.md 2016-08-25 15:30:57 +02:00
pascallanger
d4f9752cd4 Update Protocols_Details.md 2016-08-25 15:29:14 +02:00
pascallanger
6332a37f5b DEVO bind procedure 2016-08-25 15:28:57 +02:00
pascallanger
840a583a0b Devo fix 2016-08-25 14:48:48 +02:00
pascallanger
e7ed80d3e0 Devo fix 2016-08-25 13:42:21 +02:00
pascallanger
c2b9376313 Removed duplicate Telemetry defines 2016-08-25 11:40:38 +02:00
pascallanger
7a8b291189 Couples of fixes and improvements 2016-08-25 11:26:08 +02:00
pascallanger
e63f71d3a7 . 2016-08-24 15:05:31 +02:00
pascallanger
061c97caca New _Config.h file, MJXQ fix, 16 bit regs 2016-08-24 15:05:31 +02:00
pascallanger
988d28f2fd Update README.md 2016-08-23 13:39:10 +02:00
pascallanger
af8a0ea9c0 Update Protocols_Details.md 2016-08-23 13:07:37 +02:00
pascallanger
c78e8d8358 ASSAN protocol and FRSKY/FRSKYX/SFHSS option 2016-08-23 13:06:14 +02:00
pascallanger
392f7098bc ASSAN protocol addition 2016-08-23 12:56:04 +02:00
pascallanger
195f918543 DSM2 bind improvement? 2016-08-22 18:17:14 +02:00
pascallanger
b2579538fa Fix Cyrf reset... 2016-08-21 19:23:41 +02:00
pascallanger
35b97c4f45 Fixed disable telemetry compilation issue 2016-08-21 18:05:16 +02:00
pascallanger
adaa89a963 ASSAN protocol, FQ777 compilation fix on older Arduino 2016-08-21 17:54:12 +02:00
pascallanger
fc1429fae5 FQ777 fixed 2016-08-20 09:13:47 +02:00
pascallanger
4090f95098 Update Protocols_Details.md 2016-08-18 22:01:24 +02:00
pascallanger
3189d8d43e FQ777 2016-08-18 14:15:15 +02:00
pascallanger
cd6d10e428 SFHSS finally fixed 2016-08-17 15:50:59 +02:00
pascallanger
7d37236d78 SFHSS again 2016-08-17 14:28:25 +02:00
pascallanger
7c127acf17 Another SFHSS trial... 2016-08-17 13:44:20 +02:00
pascallanger
0a4ce2350a SFHSS fix? 2016-08-16 16:27:53 +02:00
pascallanger
181a70cb1f SFHSS fix? 2016-08-16 11:06:24 +02:00
pascallanger
7438545a16 Invert serial, optimization and SFHSS 2016-08-15 11:52:43 +02:00
pascallanger
9e902a5dd4 FQ777 Mod and FrSkyX optimization 2016-08-07 18:47:26 +02:00
pascallanger
91e395884f MT99xx->LS: more channels 2016-08-03 23:08:57 +02:00
pascallanger
7107c68a41 MT99xx->LS: more channels 2016-08-03 22:50:37 +02:00
pascallanger
86728b79e3 Fixed FQ777 2016-08-03 17:32:50 +02:00
pascallanger
e04f901590 LS protocol features 2016-08-03 10:12:08 +02:00
pascallanger
47ad2b5cfa MT99xx fix 2016-08-03 09:05:31 +02:00
pascallanger
cea0f1766f Update Protocols_Details.md 2016-08-03 09:05:10 +02:00
pascallanger
407e57d334 Update Protocols_Details.md 2016-08-02 20:55:29 +02:00
pascallanger
c4e66d0c9c Revert throttle on MT99xx... 2016-08-02 20:34:07 +02:00
pascallanger
c54f1ca9b0 Update README.md 2016-08-01 22:08:53 +02:00
pascallanger
f9fdc36d0d Arduino 1.6.10 and extra optimization 2016-08-01 22:06:29 +02:00
pascallanger
6d546094ef New protocols and optimizations
New protocols:
- FQ777 for FQ777-124
- MT99xx -> "LS" for 114/124
2016-08-01 21:57:27 +02:00
pascallanger
8dc5ae4f86 Add FQ777 2016-07-29 23:03:49 +02:00
pascallanger
fd7b81af10 Add FQ777 2016-07-29 22:54:30 +02:00
pascallanger
3abd859664 Update Protocols_Details.md 2016-07-29 11:33:48 +02:00
pascallanger
6134ce39d4 Update README.md 2016-07-29 11:31:12 +02:00
pascallanger
8ea42ea432 Couple of optimizations 2016-07-28 20:58:12 +02:00
pascallanger
fd4ff00ee2 J6Pro channel remapping 2016-07-28 15:01:32 +02:00
pascallanger
9d981b09ca Add J6Pro channels 2016-07-28 14:56:48 +02:00
pascallanger
ed807e0fe5 Add J6Pro in protocol list 2016-07-28 13:02:48 +02:00
pascallanger
32b962b036 J6Pro protocol addition 2016-07-27 22:24:58 +02:00
pascallanger
8ac476b6bd Update README.md 2016-07-27 22:06:13 +02:00
pascallanger
9ab8b84d81 Fixed Frsky telemetry 2016-07-27 20:55:53 +02:00
pascallanger
05cc4b4bd1 Update README.md 2016-07-27 20:22:24 +02:00
pascallanger
b28cf30f47 Update README.md 2016-07-27 20:21:17 +02:00
pascallanger
5bf8b0a2b6 Update README.md 2016-07-27 20:06:51 +02:00
pascallanger
d2891a49fc Update README.md 2016-07-27 20:03:39 +02:00
pascallanger
bec8ba6c2f BG board might need a resistor change to fix bind. 2016-07-27 19:58:50 +02:00
pascallanger
9e097be657 BG module needs to be flashed. 2016-07-27 19:51:19 +02:00
pascallanger
b008f55847 New BG board 2016-07-27 19:46:36 +02:00
pascallanger
487d90f260 Update README.md 2016-05-10 13:32:02 +02:00
pascallanger
671a745acc Update README.md 2016-05-09 15:43:50 +02:00
pascallanger
80880f4d2a Update README.md 2016-05-09 15:37:46 +02:00
pascallanger
109fba828b Update README.md 2016-04-20 19:44:34 +02:00
pascallanger
0a845fdfa6 Update README.md 2016-04-20 19:29:05 +02:00
pascallanger
5a5b8464fc 4in1 module addition 2016-04-20 19:27:56 +02:00
pascallanger
86d0b92a66 MultiOrange one more fix... 2016-04-20 17:53:59 +02:00
pascallanger
9f75234dac Fix xmega compile issue when devo is added 2016-04-20 17:34:28 +02:00
pascallanger
a58b129503 Orange module TAER order and Devo option 2016-04-19 14:29:47 +02:00
pascallanger
6d752acb28 Fixed xn297 scramble mode affecting cx-10a and probably other xn297 based protocols... 2016-04-18 19:43:12 +02:00
pascallanger
4486582006 LT8900 emulator address convention changed, updated Shenqi protocol accordingly. 2016-04-15 15:46:32 +02:00
pascallanger
ed027fd3ce SFHSS change 2016-04-12 15:00:06 +02:00
pascallanger
a92cb848c0 SFHSS change 2016-04-12 08:21:06 +02:00
pascallanger
e573e36aa6 SFHSS change 2016-04-11 21:17:46 +02:00
pascallanger
fc61753953 DSM2/X pncodes fix and FrSky RSSI&TSSI swap fix 2016-04-10 20:04:20 +02:00
pascallanger
9b74e19a99 Update README.md 2016-04-06 15:41:42 +02:00
pascallanger
e9e39cb985 Added all CC2500 power settings 2016-04-06 14:58:06 +02:00
pascallanger
d938f2ea50 Multi core fixes, DSM2/X fixes and telemetry, SFHSS addition, Flysky fixes, FrSkyX full telemetry and sub protocols
Many things since last commit...
2016-04-06 12:57:42 +02:00
pascallanger
6c3535951f Added SFHSS, DSM telemetry, FrSkyX telemetry and sub_protocols 2016-04-06 12:44:04 +02:00
pascallanger
cee78b4ae3 Update README.md 2016-04-06 12:33:43 +02:00
pascallanger
1ee646e1ce Update README.md 2016-04-06 12:32:14 +02:00
pascallanger
6199dec82f Update README.md 2016-03-18 17:20:15 +01:00
pascallanger
59f307bdb3 Update Protocols_Details.md 2016-03-18 17:16:39 +01:00
pascallanger
24747355ce Update README.md 2016-03-18 17:13:20 +01:00
pascallanger
3d287a2827 New FY326 protocol 2016-03-18 17:11:37 +01:00
pascallanger
def28df4dd Update README.md 2016-03-15 13:36:51 +01:00
pascallanger
d90e698a15 Update Protocols_Details.md 2016-03-13 09:39:34 +01:00
pascallanger
f4d6f88e5c Update Protocols_Details.md 2016-03-13 09:30:30 +01:00
pascallanger
799dce4b13 DSM2: Option enables the selection of the number of channels
- 0 : 4 channels @22ms
- 1 : 5 channels @22ms
- 2 : 6 channels @22ms
- 3 : 7 channels @22ms

- 4 : 4 channels @11ms
- 5 : 5 channels @11ms
- 6 : 6 channels @11ms
- 7 : 7 channels @11ms

- 8 : 8 channels @22ms
- 9 : 9 channels @22ms
- 10 : 10 channels @22ms
- 11 : 11 channels @22ms
- 12 : 12 channels @22ms
2016-03-13 09:29:25 +01:00
pascallanger
a025d028d4 Capital 'M' 2016-03-08 22:20:49 +01:00
pascallanger
8cfa9a891d Delete multiprotocol.h 2016-03-08 22:18:44 +01:00
pascallanger
5b44439dd2 Update README.md 2016-03-03 17:10:40 +01:00
pascallanger
44fb7dcdaa Add Arduino Mini has a supported platform. 2016-03-03 16:34:57 +01:00
pascallanger
4f5d1ba26b Correct serial init 2016-03-03 16:26:43 +01:00
pascallanger
0a08b09d70 Update Protocols_Details.md 2016-02-26 19:40:34 +01:00
pascallanger
35eedda352 Update README.md 2016-02-26 19:32:11 +01:00
pascallanger
05fb8bc742 Added Shenqi protocol and LT8910 emulation layer 2016-02-26 19:02:26 +01:00
pascallanger
795df2937e Space and ram optimization on FrSky & FrSkyX 2016-02-15 21:15:09 +01:00
pascallanger
5607740e77 Update Protocols_Details.md 2016-02-13 09:06:58 +01:00
pascallanger
d4287d3046 Update README.md 2016-02-11 23:01:39 +01:00
pascallanger
71ef72bae3 Update README.md 2016-02-11 22:56:26 +01:00
pascallanger
c310d698ca Short description on how to compile 2016-02-11 22:52:41 +01:00
pascallanger
13ce3d1c92 Separate MD files for readability 2016-02-11 22:35:38 +01:00
pascallanger
122ed79a98 Create Protocols_Details.md 2016-02-11 22:29:33 +01:00
pascallanger
6d655242a6 Update list of protocols 2016-02-11 22:11:08 +01:00
pascallanger
09cab9d825 Removed some pics 2016-02-10 16:33:12 +01:00
pascallanger
d8bd38c124 OSH Park link 2016-02-10 16:31:20 +01:00
pascallanger
abc8bf0e62 PCB v2.3d details 2016-02-10 11:39:41 +01:00
pascallanger
24106ac3d2 PCB v2.3d pictures 2016-02-10 11:26:57 +01:00
pascallanger
bf506d382f PCB v2.3d 2016-02-10 10:53:13 +01:00
pascallanger
84b1a9bbec PCB v2.3d 2016-02-10 10:45:35 +01:00
pascallanger
d67afd4396 Update README.md 2016-02-09 08:55:56 +01:00
pascallanger
9f2f7eff5b Update README.md 2016-02-08 09:20:35 +01:00
pascallanger
c863d5976b Fix MT99xx... 2016-02-06 11:33:50 +01:00
pascallanger
d6338e9daf Update README.md 2016-02-05 18:44:26 +01:00
pascallanger
b393d2666d Added FrSkyX protocol, Added MT99xx YZ sub protocol, Ram usage optimization 2016-02-05 17:28:09 +01:00
pascallanger
c5b1e73312 Update README.md 2016-02-04 22:08:07 +01:00
pascallanger
fa65222228 Added FrSkyX description and telemetry info 2016-02-04 21:59:49 +01:00
pascallanger
38e57ccd71 Update README.md 2016-02-04 14:19:48 +01:00
pascallanger
86d3d26273 New protocol MJXQ 2016-02-04 13:35:16 +01:00
pascallanger
db8e4a03a8 New protocol MJXQ and FTDI upload method 2016-02-04 13:24:16 +01:00
pascallanger
c90db8594a Update README.md 2016-02-03 18:32:08 +01:00
pascallanger
855ca77194 Update README.md 2016-02-03 18:24:56 +01:00
pascallanger
4f23af070e Update README.md 2016-02-03 17:49:42 +01:00
pascallanger
626613b545 Update README.md 2016-02-02 16:02:16 +01:00
pascallanger
c26de3bd67 Update README.md 2016-02-02 16:00:34 +01:00
pascallanger
c059915bd3 Update README.md 2016-02-01 15:22:58 +01:00
pascallanger
d2d70dcb38 Update README.md 2016-02-01 15:21:14 +01:00
pascallanger
846292442c CX10 sub protocol details 2016-02-01 15:19:12 +01:00
pascallanger
11283a2199 MT99xx protocol for MT99xx, Eachine H7, Yi Zhan i6S 2016-02-01 13:23:41 +01:00
pascallanger
4c8a0b9a63 MT99XX protocol 2016-02-01 12:18:09 +01:00
pascallanger
54accbf21f CG023 small change 2016-02-01 11:49:10 +01:00
pascallanger
08dc0db2e2 Preparation for new protocol MT99XX (includes H7) 2016-02-01 11:41:36 +01:00
pascallanger
38c6330a2a CX-10A bind improvement 2016-02-01 11:39:36 +01:00
pascallanger
2f983f42fe Update README.md 2016-01-31 22:03:43 +01:00
pascallanger
b9e45c4bb0 Fix: Hubsan telemetry packet check function 2016-01-28 19:31:03 +01:00
pascallanger
9d3b1d75d1 Revert "Fix: Hubsan telemetry packet check function & Change: Telemetry variables to static"
This reverts commit ac78ddcc82.
2016-01-28 19:27:56 +01:00
pascallanger
ac78ddcc82 Fix: Hubsan telemetry packet check function & Change: Telemetry variables to static 2016-01-28 18:43:59 +01:00
pascallanger
f912d84ab6 Telemetry display for Hubsan TX RSSI 2016-01-28 17:27:58 +01:00
pascallanger
85548d6e8e Add: Telemetry display for Hubsan TX RSSI 2016-01-28 17:25:15 +01:00
pascallanger
c74de12ceb Fix: small bug in telemetry for Hubsan 2016-01-28 11:42:56 +01:00
pascallanger
017a21c17f Added: Display error messages if wrong board type is selected at compilation time 2016-01-28 11:26:49 +01:00
pascallanger
9a63038a5f Arduino 1.6.7 support 2016-01-28 10:53:14 +01:00
pascallanger
304fc2536b Fix: Arduino 1.6.7 compilation issues 2016-01-28 10:51:11 +01:00
pascallanger
365169a9fb Update README.md 2016-01-28 09:52:44 +01:00
pascallanger
4b82ead18b Improved Toolchain section 2016-01-28 09:48:19 +01:00
pascallanger
141d7cc268 Update README.md 2016-01-28 09:45:00 +01:00
pascallanger
ee8e94cfb0 Telemetry additions 2016-01-27 18:09:20 +01:00
pascallanger
b50bedef39 Hub telemetry and fix compilation warnings/errors if protocols are commented 2016-01-27 17:57:33 +01:00
pascallanger
a689ce4de9 Fix: Update_aux_flags missplaced for PPM input 2016-01-26 22:33:17 +01:00
pascallanger
ae0478a7e9 Frsky telemetry update 2016-01-26 13:46:38 +01:00
53 changed files with 14174 additions and 2726 deletions

View File

@@ -23,12 +23,12 @@
void A7105_WriteData(uint8_t len, uint8_t channel)
{
uint8_t i;
CS_off;
A7105_Write(A7105_RST_WRPTR);
A7105_Write(0x05);
A7105_CS_off;
SPI_Write(A7105_RST_WRPTR);
SPI_Write(0x05);
for (i = 0; i < len; i++)
A7105_Write(packet[i]);
CS_on;
SPI_Write(packet[i]);
A7105_CS_on;
A7105_WriteReg(0x0F, channel);
A7105_Strobe(A7105_TX);
}
@@ -36,62 +36,42 @@ void A7105_WriteData(uint8_t len, uint8_t channel)
void A7105_ReadData() {
uint8_t i;
A7105_Strobe(0xF0); //A7105_RST_RDPTR
CS_off;
A7105_Write(0x45);
A7105_CS_off;
SPI_Write(0x45);
for (i=0;i<16;i++)
packet[i]=A7105_Read();
CS_on;
A7105_CS_on;
}
void A7105_WriteReg(uint8_t address, uint8_t data) {
CS_off;
A7105_Write(address);
A7105_CS_off;
SPI_Write(address);
NOP();
A7105_Write(data);
CS_on;
SPI_Write(data);
A7105_CS_on;
}
uint8_t A7105_ReadReg(uint8_t address) {
uint8_t result;
CS_off;
A7105_Write(address |=0x40); //bit 6 =1 for reading
A7105_CS_off;
SPI_Write(address |=0x40); //bit 6 =1 for reading
result = A7105_Read();
CS_on;
A7105_CS_on;
return(result);
}
void A7105_Write(uint8_t command) {
uint8_t n=8;
SCK_off;//SCK start low
SDI_off;
while(n--) {
if(command&0x80)
SDI_on;
else
SDI_off;
SCK_on;
NOP();
SCK_off;
command = command << 1;
}
SDI_on;
}
uint8_t A7105_Read(void) {
uint8_t A7105_Read(void)
{
uint8_t result=0;
uint8_t i;
SDI_SET_INPUT;
for(i=0;i<8;i++) {
for(uint8_t i=0;i<8;i++)
{
result=result<<1;
if(SDI_1) ///if SDIO =1
result=(result<<1)|0x01;
else
result=result<<1;
result |= 0x01;
SCK_on;
NOP();
SCK_off;
NOP();
}
SDI_SET_OUTPUT;
return result;
@@ -121,9 +101,8 @@ uint8_t A7105_Reset()
{
uint8_t result;
delay(10); //wait 10ms for A7105 wakeup
A7105_WriteReg(0x00, 0x00);
delay(1000);
delayMilliseconds(1);
A7105_SetTxRxMode(TXRX_OFF); //Set both GPIO as output and low
result=A7105_ReadReg(0x10) == 0x9E; //check if is reset.
A7105_Strobe(A7105_STANDBY);
@@ -131,13 +110,13 @@ uint8_t A7105_Reset()
}
void A7105_WriteID(uint32_t ida) {
CS_off;
A7105_Write(0x06);//ex id=0x5475c52a ;txid3txid2txid1txid0
A7105_Write((ida>>24)&0xff);//53
A7105_Write((ida>>16)&0xff);//75
A7105_Write((ida>>8)&0xff);//c5
A7105_Write((ida>>0)&0xff);//2a
CS_on;
A7105_CS_off;
SPI_Write(0x06);//ex id=0x5475c52a ;txid3txid2txid1txid0
SPI_Write((ida>>24)&0xff);//53
SPI_Write((ida>>16)&0xff);//75
SPI_Write((ida>>8)&0xff);//c5
SPI_Write((ida>>0)&0xff);//2a
A7105_CS_on;
}
/*
@@ -175,13 +154,17 @@ void A7105_SetPower()
power=IS_POWER_FLAG_on?A7105_HIGH_POWER:A7105_LOW_POWER;
if(IS_RANGE_FLAG_on)
power=A7105_RANGE_POWER;
A7105_WriteReg(0x28, power);
if(prev_power != power)
{
A7105_WriteReg(0x28, power);
prev_power=power;
}
}
void A7105_Strobe(uint8_t address) {
CS_off;
A7105_Write(address);
CS_on;
A7105_CS_off;
SPI_Write(address);
A7105_CS_on;
}
const uint8_t PROGMEM HUBSAN_A7105_regs[] = {

View File

@@ -0,0 +1,180 @@
/*
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/>.
*/
#if defined(ASSAN_NRF24L01_INO)
#include "iface_nrf24l01.h"
#define ASSAN_PACKET_SIZE 20
#define ASSAN_RF_BIND_CHANNEL 0x03
#define ASSAN_ADDRESS_LENGTH 4
enum {
ASSAN_BIND0=0,
ASSAN_BIND1,
ASSAN_BIND2,
ASSAN_DATA0,
ASSAN_DATA1,
ASSAN_DATA2,
ASSAN_DATA3,
ASSAN_DATA4,
ASSAN_DATA5
};
void ASSAN_init()
{
NRF24L01_Initialize();
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x02); // 4 bytes rx/tx address
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *)"\x80\x80\x80\xB8", ASSAN_ADDRESS_LENGTH); // Bind address
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, (uint8_t *)"\x80\x80\x80\xB8", ASSAN_ADDRESS_LENGTH); // Bind address
NRF24L01_FlushTx();
NRF24L01_FlushRx();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, ASSAN_PACKET_SIZE);
NRF24L01_SetPower();
}
void ASSAN_send_packet()
{
uint16_t temp;
for(uint8_t i=0;i<10;i++)
{
temp=Servo_data[i]<<3;
packet[2*i]=temp>>8;
packet[2*i+1]=temp;
}
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_FlushTx();
NRF24L01_WritePayload(packet, ASSAN_PACKET_SIZE);
}
uint16_t ASSAN_callback()
{
switch (phase)
{
// Bind
case ASSAN_BIND0:
//Config RX @1M
NRF24L01_WriteReg(NRF24L01_05_RF_CH, ASSAN_RF_BIND_CHANNEL);
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetTxRxMode(RX_EN);
phase++;
case ASSAN_BIND1:
//Wait for receiver to send the frames
if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR))
{ //Something has been received
NRF24L01_ReadPayload(packet, ASSAN_PACKET_SIZE);
if(packet[19]==0x13)
{ //Last frame received
phase++;
//Switch to TX
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_SetTxRxMode(TX_EN);
//Prepare bind packet
memset(packet,0x05,ASSAN_PACKET_SIZE-5);
packet[15]=0x99;
for(uint8_t i=0;i<4;i++)
packet[16+i]=packet[23-i];
packet_count=0;
delayMilliseconds(260);
return 10000; // Wait 270ms in total...
}
}
return 1000;
case ASSAN_BIND2:
// Send 20 packets
packet_count++;
if(packet_count==20)
packet[15]=0x13; // different value for last packet
NRF24L01_WritePayload(packet, ASSAN_PACKET_SIZE);
if(packet_count==20)
{
phase++;
delayMilliseconds(2165);
}
return 22520;
// Normal operation
case ASSAN_DATA0:
// Bind Done
BIND_DONE;
NRF24L01_SetBitrate(NRF24L01_BR_250K); // 250Kbps
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_SetTxRxMode(TX_EN);
case ASSAN_DATA1:
case ASSAN_DATA4:
// Change ID and RF channel
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR,packet+20+4*hopping_frequency_no, ASSAN_ADDRESS_LENGTH);
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no]);
hopping_frequency_no^=0x01;
NRF24L01_SetPower();
phase=ASSAN_DATA2;
return 2000;
case ASSAN_DATA2:
case ASSAN_DATA3:
ASSAN_send_packet();
phase++; // DATA 3 or 4
return 5000;
}
return 0;
}
static void __attribute__((unused)) ASSAN_initialize_txid()
{
/* //Renaud TXID with Freq=36 and alternate Freq 67 or 68 or 69 or 70 or 71 or 73 or 74 or 75 or 78 and may be more...
packet[23]=0x22;
packet[22]=0x37;
packet[21]=0xFA;
packet[20]=0x53; */
// Using packet[20..23] to store the ID1 and packet[24..27] to store the ID2
uint8_t freq=0,freq2;
for(uint8_t i=0;i<4;i++)
{
uint8_t temp=rx_tx_addr[0];
packet[i+20]=temp;
packet[i+24]=temp+1;
freq+=temp;
}
// Main frequency
freq=((freq%25)+2)<<1;
if(freq&0x02) freq|=0x01;
hopping_frequency[0]=freq;
// Alternate frequency has some random
do
{
randomSeed((uint32_t)analogRead(A6) << 10 | analogRead(A7));
freq2=random(0xfefefefe)%9;
freq2+=freq*2-5;
}
while( (freq2>118) || (freq2<freq+1) || (freq2==2*freq) );
hopping_frequency[1]=freq2; // Add some random to the second channel
}
uint16_t initASSAN()
{
ASSAN_initialize_txid();
ASSAN_init();
hopping_frequency_no = 0;
if(IS_AUTOBIND_FLAG_on)
phase=ASSAN_BIND0;
else
phase=ASSAN_DATA0;
return 1000;
}
#endif

View File

@@ -38,7 +38,7 @@ enum BAYANG_FLAGS {
BAYANG_FLAG_INVERTED = 0x80 // inverted flight on Floureon H101
};
static void BAYANG_send_packet(uint8_t bind)
static void __attribute__((unused)) BAYANG_send_packet(uint8_t bind)
{
uint8_t i;
if (bind)
@@ -112,7 +112,7 @@ static void BAYANG_send_packet(uint8_t bind)
NRF24L01_SetPower(); // Set tx_power
}
static void BAYANG_init()
static void __attribute__((unused)) BAYANG_init()
{
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
@@ -148,7 +148,7 @@ uint16_t BAYANG_callback()
return BAYANG_PACKET_PERIOD;
}
static void BAYANG_initialize_txid()
static void __attribute__((unused)) BAYANG_initialize_txid()
{
//Could be using txid[0..2] but using rx_tx_addr everywhere instead...
hopping_frequency[0]=0;

View File

@@ -19,125 +19,107 @@
//-------------------------------
#include "iface_cc2500.h"
void cc2500_readFifo(uint8_t *dpbuffer, uint8_t len)
{
ReadRegisterMulti(CC2500_3F_RXFIFO | CC2500_READ_BURST, dpbuffer, len);
}
//----------------------
static void ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t length)
//----------------------------
void CC2500_WriteReg(uint8_t address, uint8_t data)
{
CC25_CSN_off;
cc2500_spi_write(address);
SPI_Write(address);
NOP();
SPI_Write(data);
CC25_CSN_on;
}
//----------------------
static void CC2500_ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t length)
{
CC25_CSN_off;
SPI_Write(CC2500_READ_BURST | address);
for(uint8_t i = 0; i < length; i++)
data[i] = cc2500_spi_read();
data[i] = SPI_Read();
CC25_CSN_on;
}
//--------------------------------------------
static uint8_t CC2500_ReadReg(uint8_t address)
{
uint8_t result;
CC25_CSN_off;
SPI_Write(CC2500_READ_SINGLE | address);
result = SPI_Read();
CC25_CSN_on;
return(result);
}
//------------------------
void CC2500_ReadData(uint8_t *dpbuffer, uint8_t len)
{
CC2500_ReadRegisterMulti(CC2500_3F_RXFIFO, dpbuffer, len);
}
//*********************************************
void CC2500_Strobe(uint8_t state)
{
CC25_CSN_off;
SPI_Write(state);
CC25_CSN_on;
}
static void CC2500_WriteRegisterMulti(uint8_t address, const uint8_t data[], uint8_t length)
{
CC25_CSN_off;
cc2500_spi_write(CC2500_WRITE_BURST | address);
SPI_Write(CC2500_WRITE_BURST | address);
for(uint8_t i = 0; i < length; i++)
cc2500_spi_write(data[i]);
SPI_Write(data[i]);
CC25_CSN_on;
}
void cc2500_writeFifo(uint8_t *dpbuffer, uint8_t len)
void CC2500_WriteData(uint8_t *dpbuffer, uint8_t len)
{
cc2500_strobe(CC2500_SFTX);//0x3B
CC2500_Strobe(CC2500_SFTX);
CC2500_WriteRegisterMulti(CC2500_3F_TXFIFO, dpbuffer, len);
cc2500_strobe(CC2500_STX);//0x35
CC2500_Strobe(CC2500_STX);
}
//--------------------------------------
static void cc2500_spi_write(uint8_t command) {
uint8_t n=8;
SCK_off;//SCK start low
SDI_off;
while(n--)
{
if(command&0x80)
SDI_on;
else
SDI_off;
SCK_on;
NOP();
SCK_off;
command = command << 1;
}
SDI_on;
}
//----------------------------
void cc2500_writeReg(uint8_t address, uint8_t data) {//same as 7105
CC25_CSN_off;
cc2500_spi_write(address);
NOP();
cc2500_spi_write(data);
CC25_CSN_on;
}
static uint8_t cc2500_spi_read(void)
void CC2500_SetTxRxMode(uint8_t mode)
{
uint8_t result;
uint8_t i;
result=0;
for(i=0;i<8;i++)
{
if(SDO_1) ///
result=(result<<1)|0x01;
if(mode == TX_EN)
{//from deviation firmware
CC2500_WriteReg(CC2500_02_IOCFG0, 0x2F | 0x40);
CC2500_WriteReg(CC2500_00_IOCFG2, 0x2F);
}
else
if (mode == RX_EN)
{
CC2500_WriteReg(CC2500_02_IOCFG0, 0x2F);
CC2500_WriteReg(CC2500_00_IOCFG2, 0x2F | 0x40);
}
else
result=result<<1;
SCK_on;
NOP();
SCK_off;
NOP();
}
return result;
}
//--------------------------------------------
static uint8_t cc2500_readReg(uint8_t address)
{
uint8_t result;
CC25_CSN_off;
address |=0x80; //bit 7 =1 for reading
cc2500_spi_write(address);
result = cc2500_spi_read();
CC25_CSN_on;
return(result);
}
//------------------------
void cc2500_strobe(uint8_t address)
{
CC25_CSN_off;
cc2500_spi_write(address);
CC25_CSN_on;
{
CC2500_WriteReg(CC2500_02_IOCFG0, 0x2F);
CC2500_WriteReg(CC2500_00_IOCFG2, 0x2F);
}
}
//------------------------
/*static void cc2500_resetChip(void)
{
// Toggle chip select signal
CC25_CSN_on;
_delay_us(30);
delayMicroseconds(30);
CC25_CSN_off;
_delay_us(30);
delayMicroseconds(30);
CC25_CSN_on;
_delay_us(45);
cc2500_strobe(CC2500_SRES);
delayMicroseconds(45);
CC2500_Strobe(CC2500_SRES);
_delay_ms(100);
}
*/
uint8_t CC2500_Reset()
{
cc2500_strobe(CC2500_SRES);
_delay_us(1000);
CC2500_Strobe(CC2500_SRES);
delayMilliseconds(1);
CC2500_SetTxRxMode(TXRX_OFF);
return cc2500_readReg(CC2500_0E_FREQ1) == 0xC4;//check if reset
return CC2500_ReadReg(CC2500_0E_FREQ1) == 0xC4;//check if reset
}
/*
static void CC2500_SetPower_Value(uint8_t power)
@@ -154,7 +136,7 @@ static void CC2500_SetPower_Value(uint8_t power)
};
if (power > 7)
power = 7;
cc2500_writeReg(CC2500_3E_PATABLE, patable[power]);
CC2500_WriteReg(CC2500_3E_PATABLE, patable[power]);
}
*/
void CC2500_SetPower()
@@ -164,25 +146,10 @@ void CC2500_SetPower()
power=IS_POWER_FLAG_on?CC2500_HIGH_POWER:CC2500_LOW_POWER;
if(IS_RANGE_FLAG_on)
power=CC2500_RANGE_POWER;
cc2500_writeReg(CC2500_3E_PATABLE, power);
if(prev_power != power)
{
CC2500_WriteReg(CC2500_3E_PATABLE, power);
prev_power=power;
}
}
void CC2500_SetTxRxMode(uint8_t mode)
{
if(mode == TX_EN)
{//from deviation firmware
cc2500_writeReg(CC2500_02_IOCFG0, 0x2F | 0x40);
cc2500_writeReg(CC2500_00_IOCFG2, 0x2F);
}
else
if (mode == RX_EN)
{
cc2500_writeReg(CC2500_02_IOCFG0, 0x2F);
cc2500_writeReg(CC2500_00_IOCFG2, 0x2F | 0x40);
}
else
{
cc2500_writeReg(CC2500_02_IOCFG0, 0x2F);
cc2500_writeReg(CC2500_00_IOCFG2, 0x2F);
}
}

View File

@@ -25,7 +25,7 @@
#define CG023_INITIAL_WAIT 500
#define CG023_PACKET_SIZE 15 // packets have 15-byte payload
#define CG023_RF_BIND_CHANNEL 0x2D
#define CG023_BIND_COUNT 1000 // 8 seconds
#define CG023_BIND_COUNT 500 // 4 seconds
#define YD829_PACKET_PERIOD 4100 // Timeout for callback in uSec
#define H8_3D_PACKET_PERIOD 1800 // Timeout for callback in uSec
#define H8_3D_PACKET_SIZE 20
@@ -70,7 +70,7 @@ enum H8_3D_FLAGS_2 {
H8_3D_FLAG_CALIBRATE = 0x20, // accelerometer calibration
};
static void CG023_send_packet(uint8_t bind)
static void __attribute__((unused)) CG023_send_packet(uint8_t bind)
{
// throttle : 0x00 - 0xFF
throttle=convert_channel_8b(THROTTLE);
@@ -104,6 +104,8 @@ static void CG023_send_packet(uint8_t bind)
packet[6] = 0x08;
packet[7] = 0x03;
packet[9] = throttle;
if(rudder==0x01) rudder=0; // Small deadband
if(rudder==0x81) rudder=0; // Small deadband
packet[10] = rudder;
packet[11] = elevator;
packet[12] = aileron;
@@ -112,15 +114,11 @@ static void CG023_send_packet(uint8_t bind)
packet[14] = 0x20;
packet[15] = 0x20;
packet[16] = 0x20;
packet[17] = H8_3D_FLAG_RATE_HIGH;
if(Servo_AUX1)
packet[17] |= H8_3D_FLAG_FLIP;
if(Servo_AUX2)
packet[17] |= H8_3D_FLAG_LIGTH; //H22 light
if(Servo_AUX3)
packet[17] |= H8_3D_FLAG_HEADLESS;
if(Servo_AUX4)
packet[17] |= H8_3D_FLAG_RTH; // 180/360 flip mode on H8 3D
packet[17] = H8_3D_FLAG_RATE_HIGH
| GET_FLAG(Servo_AUX1,H8_3D_FLAG_FLIP)
| GET_FLAG(Servo_AUX2,H8_3D_FLAG_LIGTH) //H22 light
| GET_FLAG(Servo_AUX3,H8_3D_FLAG_HEADLESS)
| GET_FLAG(Servo_AUX4,H8_3D_FLAG_RTH); // 180/360 flip mode on H8 3D
if(Servo_AUX5)
packet[18] = H8_3D_FLAG_CALIBRATE;
}
@@ -152,32 +150,21 @@ static void CG023_send_packet(uint8_t bind)
if(sub_protocol==CG023)
{
// rate
packet[13] = CG023_FLAG_RATE_HIGH;
// flags
if(Servo_AUX1)
packet[13] |= CG023_FLAG_FLIP;
if(Servo_AUX2)
packet[13] |= CG023_FLAG_LED_OFF;
if(Servo_AUX3)
packet[13] |= CG023_FLAG_STILL;
if(Servo_AUX4)
packet[13] |= CG023_FLAG_VIDEO;
if(Servo_AUX5)
packet[13] |= CG023_FLAG_EASY;
packet[13] = CG023_FLAG_RATE_HIGH
| GET_FLAG(Servo_AUX1,CG023_FLAG_FLIP)
| GET_FLAG(Servo_AUX2,CG023_FLAG_LED_OFF)
| GET_FLAG(Servo_AUX3,CG023_FLAG_STILL)
| GET_FLAG(Servo_AUX4,CG023_FLAG_VIDEO)
| GET_FLAG(Servo_AUX5,CG023_FLAG_EASY);
}
else
{// YD829
// rate
packet[13] = YD829_FLAG_RATE_HIGH;
// flags
if(Servo_AUX1)
packet[13] |= YD829_FLAG_FLIP;
if(Servo_AUX3)
packet[13] |= YD829_FLAG_STILL;
if(Servo_AUX4)
packet[13] |= YD829_FLAG_VIDEO;
if(Servo_AUX5)
packet[13] |= YD829_FLAG_HEADLESS;
packet[13] = YD829_FLAG_RATE_HIGH
| GET_FLAG(Servo_AUX1,YD829_FLAG_FLIP)
| GET_FLAG(Servo_AUX3,YD829_FLAG_STILL)
| GET_FLAG(Servo_AUX4,YD829_FLAG_VIDEO)
| GET_FLAG(Servo_AUX5,YD829_FLAG_HEADLESS);
}
packet[14] = 0;
}
@@ -205,7 +192,7 @@ static void CG023_send_packet(uint8_t bind)
NRF24L01_SetPower(); // Set tx_power
}
static void CG023_init()
static void __attribute__((unused)) CG023_init()
{
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
@@ -237,16 +224,10 @@ uint16_t CG023_callback()
bind_counter--;
}
}
if(sub_protocol==CG023)
return CG023_PACKET_PERIOD;
else
if(sub_protocol==YD829)
return YD829_PACKET_PERIOD;
return H8_3D_PACKET_PERIOD;
return packet_period;
}
static void CG023_initialize_txid()
static void __attribute__((unused)) CG023_initialize_txid()
{
if(sub_protocol==H8_3D)
{
@@ -276,11 +257,13 @@ uint16_t initCG023(void)
CG023_initialize_txid();
CG023_init();
if(sub_protocol==CG023)
return CG023_INITIAL_WAIT+CG023_PACKET_PERIOD;
packet_period=CG023_PACKET_PERIOD;
else
if(sub_protocol==YD829)
return CG023_INITIAL_WAIT+YD829_PACKET_PERIOD;
return CG023_INITIAL_WAIT+H8_3D_PACKET_PERIOD;
packet_period=YD829_PACKET_PERIOD;
else
packet_period=H8_3D_PACKET_PERIOD;
return CG023_INITIAL_WAIT+YD829_PACKET_PERIOD;
}
#endif

View File

@@ -12,21 +12,21 @@
You should have received a copy of the GNU General Public License
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
// compatible with Cheerson CX-10 blue & newer red pcb, CX-10A, CX11, CX-10 green pcb, DM007, Floureon FX-10, CX-Stars
// compatible with Cheerson CX-10 blue & newer red pcb, CX-10A, CX11, CX-10 green pcb, DM007, Floureon FX-10, JXD 509 (Q282)
// Last sync with hexfet new_protocols/cx10_nrf24l01.c dated 2015-11-26
#if defined(CX10_NRF24L01_INO)
#include "iface_nrf24l01.h"
#define CX10_BIND_COUNT 4360 // 6 seconds
#define CX10_PACKET_SIZE 15
#define CX10A_PACKET_SIZE 19 // CX10 blue board packets have 19-byte payload
#define Q282_PACKET_SIZE 21
#define CX10_PACKET_PERIOD 1316 // Timeout for callback in uSec
#define CX10A_PACKET_PERIOD 6000
#define CX10_BIND_COUNT 4360 // 6 seconds
#define CX10_PACKET_SIZE 15
#define CX10A_PACKET_SIZE 19 // CX10 blue board packets have 19-byte payload
#define Q282_PACKET_SIZE 21
#define CX10_PACKET_PERIOD 1316 // Timeout for callback in uSec
#define CX10A_PACKET_PERIOD 6000
#define INITIAL_WAIT 500
#define CX10_INITIAL_WAIT 500
// flags
#define CX10_FLAG_FLIP 0x10 // goes to rudder channel
@@ -37,8 +37,8 @@
#define CX10_FLAG_SNAPSHOT 0x04
// frequency channel management
#define RF_BIND_CHANNEL 0x02
#define NUM_RF_CHANNELS 4
#define CX10_RF_BIND_CHANNEL 0x02
#define CX10_NUM_RF_CHANNELS 4
enum {
CX10_BIND1 = 0,
@@ -46,7 +46,7 @@ enum {
CX10_DATA
};
static void CX10_Write_Packet(uint8_t bind)
static void __attribute__((unused)) CX10_Write_Packet(uint8_t bind)
{
uint8_t offset = 0;
if(sub_protocol == CX10_BLUE)
@@ -86,63 +86,61 @@ static void CX10_Write_Packet(uint8_t bind)
switch(sub_protocol)
{
case CX10_BLUE:
if(Servo_AUX3) flags |= 0x10; // Channel 7 - picture
if(Servo_AUX4) flags |= 0x08; // Channel 8 - video
flags |= GET_FLAG(!Servo_AUX3, 0x10) // Channel 7 - picture
|GET_FLAG( Servo_AUX4, 0x08); // Channel 8 - video
break;
case Q282:
case Q242:
memcpy(&packet[15], "\x10\x10\xaa\xaa\x00\x00", 6);
//FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL
if(Servo_AUX1) flags2 =0x80; // Channel 5 - FLIP
if(Servo_AUX2) flags2|=0x40; // Channel 6 - LED
if(Servo_AUX5) flags2|=0x08; // Channel 9 - HEADLESS
flags2 = GET_FLAG(Servo_AUX1, 0x80) // Channel 5 - FLIP
|GET_FLAG(Servo_AUX2, 0x40) // Channel 6 - LED
|GET_FLAG(Servo_AUX5, 0x08) // Channel 9 - HEADLESS
|GET_FLAG(Servo_AUX7, 0x04) // Channel 11 - XCAL
|GET_FLAG(Servo_AUX8, 0x02); // Channel 12 - YCAL or Start/Stop motors on JXD 509
if(sub_protocol==Q282)
{
if(Servo_AUX3) flags2|=0x10; // Channel 7 - picture
if(Servo_AUX4) // Channel 8 - video
flags=3;
if(Servo_AUX4) // Channel 8 - video
{
if (!(video_state & 0x20)) video_state ^= 0x21;
}
else
if (video_state & 0x20) video_state &= 0x01;
flags2 |= video_state;
flags=3;
flags2 |= video_state
|GET_FLAG(Servo_AUX3,0x10); // Channel 7 - picture
}
else
{
if(Servo_AUX3) flags2|=0x01; // Channel 7 - picture
if(Servo_AUX4) flags2|=0x10; // Channel 8 - video
flags=2;
flags2|= GET_FLAG(Servo_AUX3,0x01) // Channel 7 - picture
|GET_FLAG(Servo_AUX4,0x10); // Channel 8 - video
packet[17]=0x00;
packet[18]=0x00;
}
if(Servo_AUX6) flags |=0x80; // Channel 10 - RTH
if(Servo_AUX7) flags2|=0x04; // Channel 11 - XCAL
if(Servo_AUX8) flags2|=0x02; // Channel 12 - YCAL
if(Servo_AUX6) flags |=0x80; // Channel 10 - RTH
break;
case DM007:
//FLIP|MODE|PICTURE|VIDEO|HEADLESS
if(Servo_AUX3) flags2 = CX10_FLAG_SNAPSHOT; // Channel 7 - picture
if(Servo_AUX4) flags2|= CX10_FLAG_VIDEO; // Channel 8 - video
if(Servo_AUX5) flags |= CX10_FLAG_HEADLESS; // Channel 9 - headless
break;
case JC3015_1:
//FLIP|MODE|PICTURE|VIDEO
if(Servo_AUX3) flags2 = _BV(3); // Channel 7 - picture
if(Servo_AUX4) flags2|= _BV(4); // Channel 8 - video
flags2= GET_FLAG(Servo_AUX3,CX10_FLAG_SNAPSHOT) // Channel 7 - picture
|GET_FLAG(Servo_AUX4,CX10_FLAG_VIDEO); // Channel 8 - video
if(Servo_AUX5) flags |= CX10_FLAG_HEADLESS; // Channel 9 - headless
break;
case JC3015_2:
//FLIP|MODE|LED|DFLIP
if(Servo_AUX3) flags2 = _BV(3); // Channel 7 - LED
if(Servo_AUX4) flags2|= _BV(4); // Channel 8 - DFLIP
if(Servo_AUX4) packet[12] &= ~CX10_FLAG_FLIP;
case JC3015_1:
//FLIP|MODE|PICTURE|VIDEO
flags2= GET_FLAG(Servo_AUX3,_BV(3)) // Channel 7
|GET_FLAG(Servo_AUX4,_BV(4)); // Channel 8
break;
case MK33041:
//FLIP|MODE|PICTURE|VIDEO|HEADLESS|RTH
if(Servo_AUX3) flags |= _BV(7); // Channel 7 - picture
if(Servo_AUX4) flags2 = _BV(0); // Channel 8 - video
if(Servo_AUX5) flags2|= _BV(5); // Channel 9 - headless
if(Servo_AUX6) flags |= _BV(2); // Channel 10 - rth
flags|=GET_FLAG(Servo_AUX3,_BV(7)) // Channel 7 - picture
|GET_FLAG(Servo_AUX6,_BV(2)); // Channel 10 - rth
flags2=GET_FLAG(Servo_AUX4,_BV(0)) // Channel 8 - video
|GET_FLAG(Servo_AUX5,_BV(5)); // Channel 9 - headless
break;
}
packet[13+offset]=flags;
@@ -152,11 +150,11 @@ static void CX10_Write_Packet(uint8_t bind)
// Why CRC0? xn297 does not interpret it - either 16-bit CRC or nothing
XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP));
if (bind)
NRF24L01_WriteReg(NRF24L01_05_RF_CH, RF_BIND_CHANNEL);
NRF24L01_WriteReg(NRF24L01_05_RF_CH, CX10_RF_BIND_CHANNEL);
else
{
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++]);
hopping_frequency_no %= NUM_RF_CHANNELS;
hopping_frequency_no %= CX10_NUM_RF_CHANNELS;
}
// clear packet status bits and TX FIFO
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
@@ -166,7 +164,7 @@ static void CX10_Write_Packet(uint8_t bind)
NRF24L01_SetPower();
}
static void CX10_init()
static void __attribute__((unused)) CX10_init()
{
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
@@ -178,12 +176,13 @@ static void CX10_init()
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgment on all data pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, packet_length); // rx pipe 0 (used only for blue board)
NRF24L01_WriteReg(NRF24L01_05_RF_CH, RF_BIND_CHANNEL);
NRF24L01_WriteReg(NRF24L01_05_RF_CH, CX10_RF_BIND_CHANNEL);
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower();
}
uint16_t CX10_callback() {
uint16_t CX10_callback()
{
switch (phase) {
case CX10_BIND1:
if (bind_counter == 0)
@@ -204,14 +203,19 @@ uint16_t CX10_callback() {
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_SetTxRxMode(TX_EN);
if(packet[9] == 1)
phase = CX10_BIND1;
{
BIND_DONE;
phase = CX10_DATA;
}
}
else
{
// switch to TX mode
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_FlushTx();
NRF24L01_SetTxRxMode(TX_EN);
CX10_Write_Packet(1);
delayMicroseconds(400); // 300µs in deviation but not working so using 400µs instead
delayMicroseconds(400);
// switch to RX mode
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_FlushRx();
@@ -226,7 +230,7 @@ uint16_t CX10_callback() {
return packet_period;
}
static void initialize_txid()
static void __attribute__((unused)) CX10_initialize_txid()
{
rx_tx_addr[1]%= 0x30;
if(sub_protocol==Q282)
@@ -259,8 +263,9 @@ uint16_t initCX10(void)
{
packet_length = CX10A_PACKET_SIZE;
packet_period = CX10A_PACKET_PERIOD;
phase = CX10_BIND2;
bind_counter=0;
for(uint8_t i=0; i<4; i++)
packet[5+i] = 0xff; // clear aircraft id
packet[9] = 0;
@@ -275,10 +280,10 @@ uint16_t initCX10(void)
phase = CX10_BIND1;
bind_counter = CX10_BIND_COUNT;
}
initialize_txid();
CX10_initialize_txid();
CX10_init();
BIND_IN_PROGRESS; // autobind protocol
return INITIAL_WAIT+packet_period;
return CX10_INITIAL_WAIT+packet_period;
}
#endif

View File

@@ -14,48 +14,12 @@
*/
#include "iface_cyrf6936.h"
static void cyrf_spi_write(uint8_t command)
{
uint8_t n=8;
SCK_off;//SCK start low
SDI_off;
while(n--) {
if(command&0x80)
SDI_on;
else
SDI_off;
SCK_on;
NOP();
SCK_off;
command = command << 1;
}
SDI_on;
}
static uint8_t cyrf_spi_read()
{
uint8_t result;
uint8_t i;
result=0;
for(i=0;i<8;i++)
{
if(SDO_1) ///
result=(result<<1)|0x01;
else
result=result<<1;
SCK_on;
NOP();
SCK_off;
NOP();
}
return result;
}
void CYRF_WriteRegister(uint8_t address, uint8_t data)
{
CYRF_CSN_off;
cyrf_spi_write(0x80 | address);
cyrf_spi_write(data);
SPI_Write(0x80 | address);
SPI_Write(data);
CYRF_CSN_on;
}
@@ -64,9 +28,9 @@ static void CYRF_WriteRegisterMulti(uint8_t address, const uint8_t data[], uint8
uint8_t i;
CYRF_CSN_off;
cyrf_spi_write(0x80 | address);
SPI_Write(0x80 | address);
for(i = 0; i < length; i++)
cyrf_spi_write(data[i]);
SPI_Write(data[i]);
CYRF_CSN_on;
}
@@ -75,9 +39,9 @@ static void CYRF_ReadRegisterMulti(uint8_t address, uint8_t data[], uint8_t leng
uint8_t i;
CYRF_CSN_off;
cyrf_spi_write(address);
SPI_Write(address);
for(i = 0; i < length; i++)
data[i] = cyrf_spi_read();
data[i] = SPI_Read();
CYRF_CSN_on;
}
@@ -85,8 +49,8 @@ uint8_t CYRF_ReadRegister(uint8_t address)
{
uint8_t data;
CYRF_CSN_off;
cyrf_spi_write(address);
data = cyrf_spi_read();
SPI_Write(address);
data = SPI_Read();
CYRF_CSN_on;
return data;
}
@@ -94,17 +58,19 @@ uint8_t CYRF_ReadRegister(uint8_t address)
uint8_t CYRF_Reset()
{
CYRF_WriteRegister(CYRF_1D_MODE_OVERRIDE, 0x01);//software reset
_delay_us(200);//
// RS_HI;
// _delay_us(100);
// RS_LO;
// _delay_us(100);
CYRF_WriteRegister(CYRF_0C_XTAL_CTRL, 0xC0); //Enable XOUT as GPIO
CYRF_WriteRegister(CYRF_0D_IO_CFG, 0x04); //Enable PACTL as GPIO
#ifdef CYRF_RST_HI
CYRF_RST_HI; //Hardware reset
delayMicroseconds(100);
CYRF_RST_LO;
delayMicroseconds(100);
#endif
CYRF_WriteRegister(CYRF_1D_MODE_OVERRIDE, 0x01); //Software reset
delayMicroseconds(200);
CYRF_WriteRegister(CYRF_0C_XTAL_CTRL, 0xC0); //Enable XOUT as GPIO
CYRF_WriteRegister(CYRF_0D_IO_CFG, 0x04); //Enable PACTL as GPIO
CYRF_SetTxRxMode(TXRX_OFF);
//Verify the CYRD chip is responding
return (CYRF_ReadRegister(CYRF_10_FRAMING_CFG) == 0xa5);//return if reset
//Verify the CYRF chip is responding
return (CYRF_ReadRegister(CYRF_10_FRAMING_CFG) == 0xa5);
}
/*
@@ -164,7 +130,12 @@ void CYRF_SetPower(uint8_t val)
power=IS_POWER_FLAG_on?CYRF_HIGH_POWER:CYRF_LOW_POWER;
if(IS_RANGE_FLAG_on)
power=CYRF_RANGE_POWER;
CYRF_WriteRegister(CYRF_03_TX_CFG, val | power);
power|=val;
if(prev_power != power)
{
CYRF_WriteRegister(CYRF_03_TX_CFG,power);
prev_power=power;
}
}
/*
@@ -196,10 +167,10 @@ void CYRF_ConfigDataCode(const uint8_t *datacodes, uint8_t len)
void CYRF_WritePreamble(uint32_t preamble)
{
CYRF_CSN_off;
cyrf_spi_write(0x80 | 0x24);
cyrf_spi_write(preamble & 0xff);
cyrf_spi_write((preamble >> 8) & 0xff);
cyrf_spi_write((preamble >> 16) & 0xff);
SPI_Write(0x80 | 0x24);
SPI_Write(preamble & 0xff);
SPI_Write((preamble >> 8) & 0xff);
SPI_Write((preamble >> 16) & 0xff);
CYRF_CSN_on;
}
/*
@@ -215,11 +186,11 @@ static void CYRF_StartReceive()
CYRF_ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, 0x10);
}
*/
/*static void CYRF_ReadDataPacketLen(uint8_t dpbuffer[], uint8_t length)
void CYRF_ReadDataPacketLen(uint8_t dpbuffer[], uint8_t length)
{
ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, length);
CYRF_ReadRegisterMulti(CYRF_21_RX_BUFFER, dpbuffer, length);
}
*/
static void CYRF_WriteDataPacketLen(const uint8_t dpbuffer[], uint8_t len)
{
CYRF_WriteRegister(CYRF_01_TX_LENGTH, len);
@@ -262,13 +233,13 @@ void CYRF_FindBestChannels(uint8_t *channels, uint8_t len, uint8_t minspace, uin
CYRF_ConfigCRCSeed(0x0000);
CYRF_SetTxRxMode(RX_EN);
//Wait for pre-amp to switch from send to receive
_delay_us(1000);
delayMilliseconds(1);
for(i = 0; i < NUM_FREQ; i++)
{
CYRF_ConfigRFChannel(i);
CYRF_ReadRegister(CYRF_13_RSSI);
CYRF_StartReceive();
_delay_us(10);
delayMicroseconds(10);
rssi[i] = CYRF_ReadRegister(CYRF_13_RSSI);
}
@@ -287,3 +258,37 @@ void CYRF_FindBestChannels(uint8_t *channels, uint8_t len, uint8_t minspace, uin
}
CYRF_SetTxRxMode(TX_EN);
}
#if defined(DEVO_CYRF6936_INO) || defined(J6PRO_CYRF6936_INO)
const uint8_t PROGMEM DEVO_j6pro_sopcodes[][8] = {
/* Note these are in order transmitted (LSB 1st) */
{0x3C, 0x37, 0xCC, 0x91, 0xE2, 0xF8, 0xCC, 0x91},
{0x9B, 0xC5, 0xA1, 0x0F, 0xAD, 0x39, 0xA2, 0x0F},
{0xEF, 0x64, 0xB0, 0x2A, 0xD2, 0x8F, 0xB1, 0x2A},
{0x66, 0xCD, 0x7C, 0x50, 0xDD, 0x26, 0x7C, 0x50},
{0x5C, 0xE1, 0xF6, 0x44, 0xAD, 0x16, 0xF6, 0x44},
{0x5A, 0xCC, 0xAE, 0x46, 0xB6, 0x31, 0xAE, 0x46},
{0xA1, 0x78, 0xDC, 0x3C, 0x9E, 0x82, 0xDC, 0x3C},
{0xB9, 0x8E, 0x19, 0x74, 0x6F, 0x65, 0x18, 0x74},
{0xDF, 0xB1, 0xC0, 0x49, 0x62, 0xDF, 0xC1, 0x49},
{0x97, 0xE5, 0x14, 0x72, 0x7F, 0x1A, 0x14, 0x72},
#if defined(J6PRO_CYRF6936_INO)
{0x82, 0xC7, 0x90, 0x36, 0x21, 0x03, 0xFF, 0x17},
{0xE2, 0xF8, 0xCC, 0x91, 0x3C, 0x37, 0xCC, 0x91}, //Note: the '03' was '9E' in the Cypress recommended table
{0xAD, 0x39, 0xA2, 0x0F, 0x9B, 0xC5, 0xA1, 0x0F}, //The following are the same as the 1st 8 above,
{0xD2, 0x8F, 0xB1, 0x2A, 0xEF, 0x64, 0xB0, 0x2A}, //but with the upper and lower word swapped
{0xDD, 0x26, 0x7C, 0x50, 0x66, 0xCD, 0x7C, 0x50},
{0xAD, 0x16, 0xF6, 0x44, 0x5C, 0xE1, 0xF6, 0x44},
{0xB6, 0x31, 0xAE, 0x46, 0x5A, 0xCC, 0xAE, 0x46},
{0x9E, 0x82, 0xDC, 0x3C, 0xA1, 0x78, 0xDC, 0x3C},
{0x6F, 0x65, 0x18, 0x74, 0xB9, 0x8E, 0x19, 0x74},
#endif
};
#endif
static void __attribute__((unused)) CYRF_PROGMEM_ConfigSOPCode(const uint8_t *data)
{
uint8_t code[8];
for(uint8_t i=0;i<8;i++)
code[i]=pgm_read_byte_near(&data[i]);
CYRF_ConfigSOPCode(code);
}

View File

@@ -13,15 +13,13 @@
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
#if defined(DSM2_CYRF6936_INO)
#if defined(DSM_CYRF6936_INO)
#include "iface_cyrf6936.h"
#define DSM2_NUM_CHANNELS 7
#define RANDOM_CHANNELS 0 // disabled
//#define RANDOM_CHANNELS 1 // enabled
#define BIND_CHANNEL 0x0d //13 This can be any odd channel
#define NUM_WAIT_LOOPS (100 / 5) //each loop is ~5us. Do not wait more than 100us
//During binding we will send BIND_COUNT/2 packets
//One packet each 10msec
@@ -42,8 +40,7 @@ enum {
DSM2_CH2_READ_B = BIND_COUNT1 + 10,
};
const uint8_t pncodes[5][9][8] = {
const uint8_t PROGMEM pncodes[5][9][8] = {
/* Note these are in order transmitted (LSB 1st) */
{ /* Row 0 */
/* Col 0 */ {0x03, 0xBC, 0x6E, 0x8A, 0xEF, 0xBD, 0xFE, 0xF8},
@@ -87,7 +84,7 @@ const uint8_t pncodes[5][9][8] = {
/* Col 5 */ {0x9B, 0x75, 0xF7, 0xE0, 0x14, 0x8D, 0xB5, 0x80},
/* Col 6 */ {0xBF, 0x54, 0x98, 0xB9, 0xB7, 0x30, 0x5A, 0x88},
/* Col 7 */ {0x35, 0xD1, 0xFC, 0x97, 0x23, 0xD4, 0xC9, 0x88},
/* Col 8 */ {0x88, 0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40}
/* Col 8 */ {0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40, 0x93}
},
{ /* Row 4 */
/* Col 0 */ {0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40, 0x93},
@@ -102,33 +99,25 @@ const uint8_t pncodes[5][9][8] = {
},
};
static void __attribute__((unused)) read_code(uint8_t *buf, uint8_t row, uint8_t col, uint8_t len)
{
for(uint8_t i=0;i<len;i++)
buf[i]=pgm_read_byte_near( &pncodes[row][col][i] );
}
//
uint8_t chidx;
uint8_t sop_col;
uint8_t data_col;
uint16_t cyrf_state;
uint8_t crcidx;
uint8_t binding;
uint16_t crc;
uint8_t model;
/*
#ifdef USE_FIXED_MFGID
const uint8_t cyrfmfg_id[6] = {0x5e, 0x28, 0xa3, 0x1b, 0x00, 0x00}; //dx8
const uint8_t cyrfmfg_id[6] = {0xd4, 0x62, 0xd6, 0xad, 0xd3, 0xff}; //dx6i
#else
//uint8_t cyrfmfg_id[6];
#endif
*/
static void build_bind_packet()
static void __attribute__((unused)) build_bind_packet()
{
uint8_t i;
uint16_t sum = 384 - 0x10;//
packet[0] = crc >> 8;
packet[1] = crc & 0xff;
packet[0] = 0xff ^ cyrfmfg_id[0];
packet[1] = 0xff ^ cyrfmfg_id[1];
packet[2] = 0xff ^ cyrfmfg_id[2];
packet[3] = (0xff ^ cyrfmfg_id[3]) + model;
packet[3] = 0xff ^ cyrfmfg_id[3];
packet[4] = packet[0];
packet[5] = packet[1];
packet[6] = packet[2];
@@ -138,15 +127,15 @@ static void build_bind_packet()
packet[8] = sum >> 8;
packet[9] = sum & 0xff;
packet[10] = 0x01; //???
packet[11] = DSM2_NUM_CHANNELS;
packet[11] = option>3?option:option+4;
if(sub_protocol==DSMX) //DSMX type
packet[12] = 0xb2; // Telemetry off: packet[12] = num_channels < 8 && Model.proto_opts[PROTOOPTS_TELEMETRY] == TELEM_OFF ? 0xa2 : 0xb2;
else
#if DSM2_NUM_CHANNELS < 8
packet[12] = 0x01;
#if defined DSM_TELEMETRY
packet[12] = 0xb2; // Telemetry on
#else
packet[12] = 0x02;
packet[12] = option<8? 0xa2 : 0xb2; // Telemetry off
#endif
else
packet[12] = option<8?0x01:0x02;
packet[13] = 0x00; //???
for(i = 8; i < 14; i++)
sum += packet[i];
@@ -154,46 +143,66 @@ static void build_bind_packet()
packet[15] = sum & 0xff;
}
static void build_data_packet(uint8_t upper)//
static uint8_t __attribute__((unused)) PROTOCOL_SticksMoved(uint8_t init)
{
#if DSM2_NUM_CHANNELS==4
const uint8_t ch_map[] = {0, 1, 2, 3, 0xff, 0xff, 0xff}; //Guess
#elif DSM2_NUM_CHANNELS==5
const uint8_t ch_map[] = {0, 1, 2, 3, 4, 0xff, 0xff}; //Guess
#elif DSM2_NUM_CHANNELS==6
const uint8_t ch_map[] = {1, 5, 2, 3, 0, 4, 0xff}; //HP6DSM
#elif DSM2_NUM_CHANNELS==7
const uint8_t ch_map[] = {1, 5, 2, 4, 3, 6, 0}; //DX6i
#elif DSM2_NUM_CHANNELS==8
const uint8_t ch_map[] = {1, 5, 2, 3, 6, 0xff, 0xff, 4, 0, 7, 0xff, 0xff, 0xff, 0xff}; //DX8
#elif DSM2_NUM_CHANNELS==9
const uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 0xff, 0xff, 0xff, 0xff, 0xff}; //DM9
#elif DSM2_NUM_CHANNELS==10
const uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 9, 0xff, 0xff, 0xff, 0xff};
#elif DSM2_NUM_CHANNELS==11
const uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 9, 10, 0xff, 0xff, 0xff};
#elif DSM2_NUM_CHANNELS==12
const uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 9, 10, 11, 0xff, 0xff};
#endif
#define STICK_MOVEMENT 15*(servo_max_125-servo_min_125)/100 // defines when the bind dialog should be interrupted (stick movement STICK_MOVEMENT %)
static uint16_t ele_start, ail_start;
uint16_t ele = Servo_data[ELEVATOR];//CHAN_ReadInput(MIXER_MapChannel(INP_ELEVATOR));
uint16_t ail = Servo_data[AILERON];//CHAN_ReadInput(MIXER_MapChannel(INP_AILERON));
if(init) {
ele_start = ele;
ail_start = ail;
return 0;
}
uint16_t ele_diff = ele_start - ele;//abs(ele_start - ele);
uint16_t ail_diff = ail_start - ail;//abs(ail_start - ail);
return ((ele_diff + ail_diff) > STICK_MOVEMENT);//
}
static void __attribute__((unused)) build_data_packet(uint8_t upper)//
{
uint8_t i;
uint8_t bits;
uint8_t ch_map[] = {3, 2, 1, 5, 0, 4, 6, 7, 8, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; //9 Channels - DM9 TX
switch(option>3?option:option+4) // Create channel map based on number of channels
{
case 12:
ch_map[11]=11; // 12 channels
case 11:
ch_map[10]=10; // 11 channels
case 10:
ch_map[9]=9; // 10 channels
break;
case 8:
memcpy(ch_map,"\x01\x05\x02\x03\x06\xFF\xFF\x04\x00\x07",10); // 8 channels - DX8 TX
break;
case 7:
memcpy(ch_map,"\x01\x05\x02\x04\x03\x06\x00",7); // 7 channels - DX6i TX
break;
case 6:
memcpy(ch_map,"\x01\x05\x02\x03\x00\x04\xFF",7); // 6 channels - HP6DSM TX
break;
case 4:
case 5:
memcpy(ch_map,"\x00\x01\x02\x03\xFF\xFF\xFF",7); // 4 channels - Guess
if(option&0x01)
ch_map[4]=4; // 5 channels - Guess
break;
}
//
if( binding && PROTOCOL_SticksMoved(0) )
{
//BIND_DONE;
binding = 0;
}
if (sub_protocol==DSMX)
{
packet[0] = cyrfmfg_id[2];
packet[1] = cyrfmfg_id[3] + model;
packet[1] = cyrfmfg_id[3];
bits=11;
}
else
{
packet[0] = (0xff ^ cyrfmfg_id[2]);
packet[1] = (0xff ^ cyrfmfg_id[3]) + model;
packet[1] = (0xff ^ cyrfmfg_id[3]);
bits=10;
}
//
@@ -203,10 +212,8 @@ static void build_data_packet(uint8_t upper)//
for (i = 0; i < 7; i++)
{
uint8_t idx = ch_map[upper * 7 + i];//1,5,2,3,0,4
uint16_t value;
if (idx == 0xff)
value = 0xffff;
else
uint16_t value = 0xffff;;
if (idx != 0xff)
{
if (binding)
{ // Failsafe position during binding
@@ -242,8 +249,20 @@ static void build_data_packet(uint8_t upper)//
case 7:
value=Servo_data[AUX4];
break;
case 8:
value=Servo_data[AUX5];
break;
case 9:
value=Servo_data[AUX6];
break;
case 10:
value=Servo_data[AUX7];
break;
case 11:
value=Servo_data[AUX8];
break;
}
value=map(value,PPM_MIN,PPM_MAX,0,max-1);
value=map(value,servo_min_125,servo_max_125,0,max-1);
}
value |= (upper && i == 0 ? 0x8000 : 0) | (idx << bits);
}
@@ -252,29 +271,13 @@ static void build_data_packet(uint8_t upper)//
}
}
static uint8_t PROTOCOL_SticksMoved(uint8_t init)
{
#define STICK_MOVEMENT 15*(PPM_MAX-PPM_MIN)/100 // defines when the bind dialog should be interrupted (stick movement STICK_MOVEMENT %)
static uint16_t ele_start, ail_start;
uint16_t ele = Servo_data[ELEVATOR];//CHAN_ReadInput(MIXER_MapChannel(INP_ELEVATOR));
uint16_t ail = Servo_data[AILERON];//CHAN_ReadInput(MIXER_MapChannel(INP_AILERON));
if(init) {
ele_start = ele;
ail_start = ail;
return 0;
}
uint16_t ele_diff = ele_start - ele;//abs(ele_start - ele);
uint16_t ail_diff = ail_start - ail;//abs(ail_start - ail);
return ((ele_diff + ail_diff) > STICK_MOVEMENT);//
}
static uint8_t get_pn_row(uint8_t channel)
static uint8_t __attribute__((unused)) get_pn_row(uint8_t channel)
{
return (sub_protocol == DSMX ? (channel - 2) % 5 : channel % 5);
}
const uint8_t init_vals[][2] = {
{CYRF_02_TX_CTRL, 0x00},
{CYRF_02_TX_CTRL, 0x02}, //0x00 in deviation but needed to know when transmit is over
{CYRF_05_RX_CTRL, 0x00},
{CYRF_28_CLK_EN, 0x02},
{CYRF_32_AUTO_CAL_TIME, 0x3c},
@@ -300,7 +303,7 @@ const uint8_t init_vals[][2] = {
{CYRF_01_TX_LENGTH, 0x10}, //16byte packet
};
static void cyrf_config()
static void __attribute__((unused)) cyrf_config()
{
for(uint8_t i = 0; i < sizeof(init_vals) / 2; i++)
CYRF_WriteRegister(init_vals[i][0], init_vals[i][1]);
@@ -308,19 +311,22 @@ static void cyrf_config()
CYRF_ConfigRFChannel(0x61);
}
static void initialize_bind_state()
static void __attribute__((unused)) initialize_bind_state()
{
const uint8_t pn_bind[] = { 0xc6,0x94,0x22,0xfe,0x48,0xe6,0x57,0x4e };
uint8_t data_code[32];
uint8_t code[32];
CYRF_ConfigRFChannel(BIND_CHANNEL); //This seems to be random?
uint8_t pn_row = get_pn_row(BIND_CHANNEL);
//printf("Ch: %d Row: %d SOP: %d Data: %d\n", BIND_CHANNEL, pn_row, sop_col, data_col);
CYRF_ConfigCRCSeed(crc);
CYRF_ConfigSOPCode(pncodes[pn_row][sop_col]);
memcpy(data_code, pncodes[pn_row][data_col], 16);
memcpy(data_code + 16, pncodes[0][8], 8);
memcpy(data_code + 24, pn_bind, 8);
CYRF_ConfigDataCode(data_code, 32);
read_code(code,pn_row,sop_col,8);
CYRF_ConfigSOPCode(code);
read_code(code,pn_row,data_col,16);
read_code(code+16,0,8,8);
memcpy(code + 24, (void *)"\xc6\x94\x22\xfe\x48\xe6\x57\x4e", 8);
CYRF_ConfigDataCode(code, 32);
build_bind_packet();
}
@@ -342,28 +348,33 @@ const uint8_t data_vals[][2] = {
{CYRF_10_FRAMING_CFG, 0xea},
};
static void cyrf_configdata()
static void __attribute__((unused)) cyrf_configdata()
{
for(uint8_t i = 0; i < sizeof(data_vals) / 2; i++)
CYRF_WriteRegister(data_vals[i][0], data_vals[i][1]);
}
static void set_sop_data_crc()
static void __attribute__((unused)) set_sop_data_crc()
{
uint8_t pn_row = get_pn_row(hopping_frequency[chidx]);
//printf("Ch: %d Row: %d SOP: %d Data: %d\n", ch[chidx], pn_row, sop_col, data_col);
CYRF_ConfigRFChannel(hopping_frequency[chidx]);
CYRF_ConfigCRCSeed(crcidx ? ~crc : crc);
CYRF_ConfigSOPCode(pncodes[pn_row][sop_col]);
CYRF_ConfigDataCode(pncodes[pn_row][data_col], 16);
uint8_t code[16];
uint8_t pn_row = get_pn_row(hopping_frequency[hopping_frequency_no]);
//printf("Ch: %d Row: %d SOP: %d Data: %d\n", ch[hopping_frequency_no], pn_row, sop_col, data_col);
CYRF_ConfigRFChannel(hopping_frequency[hopping_frequency_no]);
CYRF_ConfigCRCSeed(crc);
crc=~crc;
read_code(code,pn_row,sop_col,8);
CYRF_ConfigSOPCode(code);
read_code(code,pn_row,data_col,16);
CYRF_ConfigDataCode(code, 16);
if(sub_protocol == DSMX)
chidx = (chidx + 1) % 23;
hopping_frequency_no = (hopping_frequency_no + 1) % 23;
else
chidx = (chidx + 1) % 2;
crcidx = !crcidx;
hopping_frequency_no = (hopping_frequency_no + 1) % 2;
}
static void calc_dsmx_channel()
static void __attribute__((unused)) calc_dsmx_channel()
{
uint8_t idx = 0;
uint32_t id = ~(((uint32_t)cyrfmfg_id[0] << 24) | ((uint32_t)cyrfmfg_id[1] << 16) | ((uint32_t)cyrfmfg_id[2] << 8) | (cyrfmfg_id[3] << 0));
@@ -374,7 +385,7 @@ static void calc_dsmx_channel()
uint8_t count_3_27 = 0, count_28_51 = 0, count_52_76 = 0;
id_tmp = id_tmp * 0x0019660D + 0x3C6EF35F; // Randomization
uint8_t next_ch = ((id_tmp >> 8) % 0x49) + 3; // Use least-significant byte and must be larger than 3
if (((next_ch ^ id) & 0x01 )== 0)
if ( (next_ch ^ cyrfmfg_id[3]) & 0x01 )
continue;
for (i = 0; i < idx; i++)
{
@@ -397,23 +408,22 @@ static void calc_dsmx_channel()
}
}
uint16_t ReadDsm2()
uint16_t ReadDsm()
{
#define CH1_CH2_DELAY 4010 // Time between write of channel 1 and channel 2
#define WRITE_DELAY 1650 // 1550 original, Time after write to verify write complete
#define READ_DELAY 400 // Time before write to check read state, and switch channels
uint8_t i = 0;
#define DSM_CH1_CH2_DELAY 4010 // Time between write of channel 1 and channel 2
#define DSM_WRITE_DELAY 1550 // Time after write to verify write complete
#define DSM_READ_DELAY 600 // Time before write to check read state, and switch channels. Was 400 but 500 seems what the 328p needs to read a packet
uint16_t start;
switch(cyrf_state)
switch(state)
{
default:
//Binding
cyrf_state++;
if(cyrf_state & 1)
state++;
if(state & 1)
{
//Send packet on even states
//Note state has already incremented,
// so this is actually 'even' state
//Note state has already incremented, so this is actually 'even' state
CYRF_WriteDataPacket(packet);
return 8500;
}
@@ -429,60 +439,113 @@ uint16_t ReadDsm2()
//CYRF_FindBestChannels(ch, 2, 10, 1, 79);
cyrf_configdata();
CYRF_SetTxRxMode(TX_EN);
chidx = 0;
crcidx = 0;
cyrf_state = DSM2_CH1_WRITE_A; // in fact cyrf_state++
hopping_frequency_no = 0;
state = DSM2_CH1_WRITE_A; // in fact state++
set_sop_data_crc();
return 10000;
case DSM2_CH1_WRITE_A:
case DSM2_CH1_WRITE_B:
build_data_packet(cyrf_state == DSM2_CH1_WRITE_B);//compare state and DSM2_CH1_WRITE_B return 0 or 1
case DSM2_CH2_WRITE_A:
case DSM2_CH2_WRITE_B:
build_data_packet(state == DSM2_CH1_WRITE_B);// build lower or upper channels
CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS); // clear IRQ flags
CYRF_WriteDataPacket(packet);
cyrf_state++; // change from WRITE to CHECK mode
return WRITE_DELAY;
state++; // change from WRITE to CHECK mode
return DSM_WRITE_DELAY;
case DSM2_CH1_CHECK_A:
case DSM2_CH1_CHECK_B:
while (! (CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x02))
if(++i > NUM_WAIT_LOOPS)
start=micros();
while ((uint16_t)micros()-start < 500) // Wait max 500µs
if(CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x02)
break;
set_sop_data_crc();
cyrf_state++; // change from CH1_CHECK to CH2_WRITE
return CH1_CH2_DELAY - WRITE_DELAY;
state++; // change from CH1_CHECK to CH2_WRITE
return DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY;
case DSM2_CH2_CHECK_A:
case DSM2_CH2_CHECK_B:
while (! (CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x02))
if(++i > NUM_WAIT_LOOPS)
start=micros();
while ((uint16_t)micros()-start < 500) // Wait max 500µs
if(CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x02)
break;
if (cyrf_state == DSM2_CH2_CHECK_A)
CYRF_SetPower(0x28); //Keep transmit power in sync
// No telemetry...
set_sop_data_crc();
if (cyrf_state == DSM2_CH2_CHECK_A)
if (state == DSM2_CH2_CHECK_A)
CYRF_SetPower(0x28); //Keep transmit power in sync
#if defined DSM_TELEMETRY
state++; // change from CH2_CHECK to CH2_READ
if(option<=3 || option>7)
{ // disable telemetry for option between 4 and 7 ie 4,5,6,7 channels @11ms since it does not work...
CYRF_SetTxRxMode(RX_EN); //Receive mode
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x87); //0x80??? //Prepare to receive
}
return 11000 - DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY - DSM_READ_DELAY;
case DSM2_CH2_READ_A:
case DSM2_CH2_READ_B:
//Read telemetry
uint8_t rx_state = CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx_state & 0x03) == 0x02) // RXC=1, RXE=0 then 2nd check is required (debouncing)
rx_state |= CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx_state & 0x07) == 0x02)
{ // good data (complete with no errors)
CYRF_WriteRegister(CYRF_07_RX_IRQ_STATUS, 0x80); // need to set RXOW before data read
uint8_t len=CYRF_ReadRegister(CYRF_09_RX_COUNT);
if(len>MAX_PKT-2)
len=MAX_PKT-2;
CYRF_ReadDataPacketLen(pkt+1, len);
pkt[0]=CYRF_ReadRegister(CYRF_13_RSSI)&0x1F; // store RSSI of the received telemetry signal
telemetry_link=1;
}
if (state == DSM2_CH2_READ_A && option <= 3) // normal 22ms mode if option<=3 ie 4,5,6,7 channels @22ms
{
#if DSM2_NUM_CHANNELS < 8
cyrf_state = DSM2_CH1_WRITE_A; // change from CH2_CHECK_A to CH1_WRITE_A (ie no upper)
return 11000 - CH1_CH2_DELAY - WRITE_DELAY ; // Original is 22000 from deviation but it works better this way
#else
cyrf_state = DSM2_CH1_WRITE_B; // change from CH2_CHECK_A to CH1_WRITE_A (to transmit upper)
#endif
//Force end read state
CYRF_WriteRegister(CYRF_0F_XACT_CFG, (CYRF_ReadRegister(CYRF_0F_XACT_CFG) | 0x20)); // Force end state
start=micros();
while ((uint16_t)micros()-start < 100) // Wait max 100 µs
if((CYRF_ReadRegister(CYRF_0F_XACT_CFG) & 0x20) == 0)
break;
state = DSM2_CH2_READ_B;
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x87); //0x80??? //Prepare to receive
return 11000;
}
if (state == DSM2_CH2_READ_A && option>7)
state = DSM2_CH1_WRITE_B; //Transmit upper
else
state = DSM2_CH1_WRITE_A; //Force 11ms if option>3 ie 4,5,6,7 channels @11ms
CYRF_SetTxRxMode(TX_EN); //Write mode
set_sop_data_crc();
return DSM_READ_DELAY;
#else
// No telemetry
set_sop_data_crc();
if (state == DSM2_CH2_CHECK_A)
{
if(option < 8)
{
state = DSM2_CH1_WRITE_A; // change from CH2_CHECK_A to CH1_WRITE_A (ie no upper)
if(option>3)
return 11000 - DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY ; // force 11ms if option>3 ie 4,5,6,7 channels @11ms
else
return 22000 - DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY ; // normal 22ms mode if option<=3 ie 4,5,6,7 channels @22ms
}
else
state = DSM2_CH1_WRITE_B; // change from CH2_CHECK_A to CH1_WRITE_A (to transmit upper)
}
else
cyrf_state = DSM2_CH1_WRITE_A; // change from CH2_CHECK_B to CH1_WRITE_A (upper already transmitted so transmit lower)
return 11000 - CH1_CH2_DELAY - WRITE_DELAY;
state = DSM2_CH1_WRITE_A; // change from CH2_CHECK_B to CH1_WRITE_A (upper already transmitted so transmit lower)
return 11000 - DSM_CH1_CH2_DELAY - DSM_WRITE_DELAY;
#endif
}
return 0;
}
uint16_t initDsm2()
uint16_t initDsm()
{
CYRF_Reset();
CYRF_GetMfgData(cyrfmfg_id);//
//Model match
cyrfmfg_id[3]+=RX_num;
cyrf_config();
if (sub_protocol ==DSMX)
if (sub_protocol == DSMX)
calc_dsmx_channel();
else
{
@@ -506,27 +569,25 @@ uint16_t initDsm2()
#endif
}
///}
crc = ~((cyrfmfg_id[0] << 8) + cyrfmfg_id[1]); //The crc for channel 'a' is NOT(mfgid[1] << 8 + mfgid[0])
crcidx = 0;//The crc for channel 'b' is (mfgid[1] << 8 + mfgid[0])
//The crc for channel '1' is NOT(mfgid[0] << 8 + mfgid[1])
//The crc for channel '2' is (mfgid[0] << 8 + mfgid[1])
crc = ~((cyrfmfg_id[0] << 8) + cyrfmfg_id[1]);
//
sop_col = (cyrfmfg_id[0] + cyrfmfg_id[1] + cyrfmfg_id[2] + 2) & 0x07;//Ok
data_col = 7 - sop_col;//ok
sop_col = (cyrfmfg_id[0] + cyrfmfg_id[1] + cyrfmfg_id[2] + 2) & 0x07;
data_col = 7 - sop_col;
model=MProtocol_id-MProtocol_id_master; // RxNum for serial or 0 for ppm
CYRF_SetTxRxMode(TX_EN);
//
if(IS_AUTOBIND_FLAG_on)
{
cyrf_state = DSM2_BIND;
state = DSM2_BIND;
PROTOCOL_SticksMoved(1); //Initialize Stick position
initialize_bind_state();
binding = 1;
}
else
{
cyrf_state = DSM2_CHANSEL;//
state = DSM2_CHANSEL;//
binding = 0;
}
return 10000;

View File

@@ -21,16 +21,13 @@
//For Debug
//#define NO_SCRAMBLE
#define PKTS_PER_CHANNEL 4
#define DEVO_BIND_COUNT 0x1388
//#define TELEMETRY_ENABLE 0x30
#define NUM_WAIT_LOOPS (100 / 5) //each loop is ~5us. Do not wait more than 100us
//
//#define TELEM_ON 0
//#define TELEM_OFF 1
enum Devo_PhaseState
{
#define DEVO_PKTS_PER_CHANNEL 4
#define DEVO_BIND_COUNT 0x1388
#define DEVO_NUM_WAIT_LOOPS (100 / 5) //each loop is ~5us. Do not wait more than 100us
enum {
DEVO_BIND,
DEVO_BIND_SENDCH,
DEVO_BOUND,
@@ -46,77 +43,70 @@ enum Devo_PhaseState
DEVO_BOUND_10,
};
const uint8_t sopcodes[][8] = {
/* Note these are in order transmitted (LSB 1st) */
/* 0 */ {0x3C,0x37,0xCC,0x91,0xE2,0xF8,0xCC,0x91}, //0x91CCF8E291CC373C
/* 1 */ {0x9B,0xC5,0xA1,0x0F,0xAD,0x39,0xA2,0x0F}, //0x0FA239AD0FA1C59B
/* 2 */ {0xEF,0x64,0xB0,0x2A,0xD2,0x8F,0xB1,0x2A}, //0x2AB18FD22AB064EF
/* 3 */ {0x66,0xCD,0x7C,0x50,0xDD,0x26,0x7C,0x50}, //0x507C26DD507CCD66
/* 4 */ {0x5C,0xE1,0xF6,0x44,0xAD,0x16,0xF6,0x44}, //0x44F616AD44F6E15C
/* 5 */ {0x5A,0xCC,0xAE,0x46,0xB6,0x31,0xAE,0x46}, //0x46AE31B646AECC5A
/* 6 */ {0xA1,0x78,0xDC,0x3C,0x9E,0x82,0xDC,0x3C}, //0x3CDC829E3CDC78A1
/* 7 */ {0xB9,0x8E,0x19,0x74,0x6F,0x65,0x18,0x74}, //0x7418656F74198EB9
/* 8 */ {0xDF,0xB1,0xC0,0x49,0x62,0xDF,0xC1,0x49}, //0x49C1DF6249C0B1DF
/* 9 */ {0x97,0xE5,0x14,0x72,0x7F,0x1A,0x14,0x72}, //0x72141A7F7214E597
};
uint8_t txState;
uint8_t pkt_num;
uint8_t ch_idx;
uint8_t use_fixed_id;
uint8_t failsafe_pkt;
static void scramble_pkt()
static void __attribute__((unused)) DEVO_scramble_pkt()
{
#ifdef NO_SCRAMBLE
return;
#else
uint8_t i;
for(i = 0; i < 15; i++)
for(uint8_t i = 0; i < 15; i++)
packet[i + 1] ^= cyrfmfg_id[i % 4];
#endif
}
static void add_pkt_suffix()
static void __attribute__((unused)) DEVO_add_pkt_suffix()
{
uint8_t bind_state;
if (use_fixed_id)
uint8_t bind_state;
#ifdef ENABLE_PPM
if(mode_select && option==0 && IS_BIND_DONE_on) //PPM mode and option not already set and bind is finished
{
if (bind_counter > 0)
bind_state = 0xc0;
else
bind_state = 0x80;
BIND_SET_INPUT;
BIND_SET_PULLUP; // set pullup
if(IS_BIND_BUTTON_on)
{
eeprom_write_byte((uint8_t*)(30+mode_select),0x01); // Set fixed id mode for the current model
option=1;
}
BIND_SET_OUTPUT;
}
#endif //ENABLE_PPM
if(prev_option!=option && IS_BIND_DONE_on)
{
MProtocol_id = RX_num + MProtocol_id_master;
bind_counter=DEVO_BIND_COUNT;
}
if (option)
{
if (bind_counter > 0)
bind_state = 0xc0;
else
bind_state = 0x80;
}
else
bind_state = 0x00;
packet[10] = bind_state | (PKTS_PER_CHANNEL - pkt_num - 1);
bind_state = 0x00;
packet[10] = bind_state | (DEVO_PKTS_PER_CHANNEL - packet_count - 1);
packet[11] = *(hopping_frequency_ptr + 1);
packet[12] = *(hopping_frequency_ptr + 2);
packet[13] = fixed_id & 0xff;
packet[14] = (fixed_id >> 8) & 0xff;
packet[15] = (fixed_id >> 16) & 0xff;
packet[13] = MProtocol_id & 0xff;
packet[14] = (MProtocol_id >> 8) & 0xff;
packet[15] = (MProtocol_id >> 16) & 0xff;
}
static void build_beacon_pkt(uint8_t upper)
static void __attribute__((unused)) DEVO_build_beacon_pkt(uint8_t upper)
{
packet[0] = ((DEVO_NUM_CHANNELS << 4) | 0x07);
// uint8_t enable = 0;
packet[0] = (DEVO_NUM_CHANNELS << 4) | 0x07;
uint8_t max = 8;
// int offset = 0;
if (upper)
{
packet[0] += 1;
max = 4;
// offset = 8;
}
for(uint8_t i = 0; i < max; i++)
packet[i+1] = 0;
// packet[9] = enable;
packet[9] = 0;
add_pkt_suffix();
DEVO_add_pkt_suffix();
}
static void build_bind_pkt()
static void __attribute__((unused)) DEVO_build_bind_pkt()
{
packet[0] = (DEVO_NUM_CHANNELS << 4) | 0x0a;
packet[1] = bind_counter & 0xff;
@@ -128,7 +118,7 @@ static void build_bind_pkt()
packet[7] = cyrfmfg_id[1];
packet[8] = cyrfmfg_id[2];
packet[9] = cyrfmfg_id[3];
add_pkt_suffix();
DEVO_add_pkt_suffix();
//The fixed-id portion is scrambled in the bind packet
//I assume it is ignored
packet[13] ^= cyrfmfg_id[0];
@@ -136,16 +126,15 @@ static void build_bind_pkt()
packet[15] ^= cyrfmfg_id[2];
}
static void build_data_pkt()
static void __attribute__((unused)) DEVO_build_data_pkt()
{
uint8_t i;
static uint8_t ch_idx=0;
packet[0] = (DEVO_NUM_CHANNELS << 4) | (0x0b + ch_idx);
uint8_t sign = 0x0b;
for (i = 0; i < 4; i++)
for (uint8_t i = 0; i < 4; i++)
{
//
int16_t value= map(Servo_data[ch_idx * 4 + i],PPM_MIN,PPM_MAX,-1600,1600);//range -1600...+1600
//s32 value = (s32)Channels[ch_idx * 4 + i] * 0x640 / CHAN_MAX_VALUE;//10000
int16_t value=map(Servo_data[CH_EATR[ch_idx * 4 + i]],servo_min_125,servo_max_125,-1600,1600);//range -1600..+1600
if(value < 0)
{
value = -value;
@@ -155,13 +144,13 @@ static void build_data_pkt()
packet[2 * i + 2] = (value >> 8) & 0xff;
}
packet[9] = sign;
ch_idx = ch_idx + 1;
ch_idx++;
if (ch_idx * 4 >= DEVO_NUM_CHANNELS)
ch_idx = 0;
add_pkt_suffix();
DEVO_add_pkt_suffix();
}
static void cyrf_set_bound_sop_code()
static void __attribute__((unused)) DEVO_cyrf_set_bound_sop_code()
{
/* crc == 0 isn't allowed, so use 1 if the math results in 0 */
uint8_t crc = (cyrfmfg_id[0] + (cyrfmfg_id[1] >> 6) + cyrfmfg_id[2]);
@@ -170,68 +159,62 @@ static void cyrf_set_bound_sop_code()
uint8_t sopidx = (0xff &((cyrfmfg_id[0] << 2) + cyrfmfg_id[1] + cyrfmfg_id[2])) % 10;
CYRF_SetTxRxMode(TX_EN);
CYRF_ConfigCRCSeed((crc << 8) + crc);
CYRF_ConfigSOPCode(sopcodes[sopidx]);
CYRF_PROGMEM_ConfigSOPCode(DEVO_j6pro_sopcodes[sopidx]);
CYRF_SetPower(0x08);
}
static void cyrf_init()
const uint8_t PROGMEM DEVO_init_vals[][2] = {
{ CYRF_1D_MODE_OVERRIDE, 0x38 },
{ CYRF_03_TX_CFG, 0x08 },
{ CYRF_06_RX_CFG, 0x4A },
{ CYRF_0B_PWR_CTRL, 0x00 },
{ CYRF_10_FRAMING_CFG, 0xA4 },
{ CYRF_11_DATA32_THOLD, 0x05 },
{ CYRF_12_DATA64_THOLD, 0x0E },
{ CYRF_1B_TX_OFFSET_LSB, 0x55 },
{ CYRF_1C_TX_OFFSET_MSB, 0x05 },
{ CYRF_32_AUTO_CAL_TIME, 0x3C },
{ CYRF_35_AUTOCAL_OFFSET, 0x14 },
{ CYRF_39_ANALOG_CTRL, 0x01 },
{ CYRF_1E_RX_OVERRIDE, 0x10 },
{ CYRF_1F_TX_OVERRIDE, 0x00 },
{ CYRF_01_TX_LENGTH, 0x10 },
{ CYRF_0F_XACT_CFG, 0x10 },
{ CYRF_27_CLK_OVERRIDE, 0x02 },
{ CYRF_28_CLK_EN, 0x02 },
{ CYRF_0F_XACT_CFG, 0x28 }
};
static void __attribute__((unused)) DEVO_cyrf_init()
{
/* Initialise CYRF chip */
CYRF_WriteRegister(CYRF_1D_MODE_OVERRIDE, 0x39);
CYRF_SetPower(0x08);
CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4A);
CYRF_WriteRegister(CYRF_0B_PWR_CTRL, 0x00);
CYRF_WriteRegister(CYRF_0D_IO_CFG, 0x04);
CYRF_WriteRegister(CYRF_0E_GPIO_CTRL, 0x20);
CYRF_WriteRegister(CYRF_10_FRAMING_CFG, 0xA4);
CYRF_WriteRegister(CYRF_11_DATA32_THOLD, 0x05);
CYRF_WriteRegister(CYRF_12_DATA64_THOLD, 0x0E);
CYRF_WriteRegister(CYRF_1B_TX_OFFSET_LSB, 0x55);
CYRF_WriteRegister(CYRF_1C_TX_OFFSET_MSB, 0x05);
CYRF_WriteRegister(CYRF_32_AUTO_CAL_TIME, 0x3C);
CYRF_WriteRegister(CYRF_35_AUTOCAL_OFFSET, 0x14);
CYRF_WriteRegister(CYRF_39_ANALOG_CTRL, 0x01);
CYRF_WriteRegister(CYRF_1E_RX_OVERRIDE, 0x10);
CYRF_WriteRegister(CYRF_1F_TX_OVERRIDE, 0x00);
CYRF_WriteRegister(CYRF_01_TX_LENGTH, 0x10);
CYRF_WriteRegister(CYRF_0C_XTAL_CTRL, 0xC0);
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x10);
CYRF_WriteRegister(CYRF_27_CLK_OVERRIDE, 0x02);
CYRF_WriteRegister(CYRF_28_CLK_EN, 0x02);
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x28);
for(uint8_t i = 0; i < sizeof(DEVO_init_vals) / 2; i++)
CYRF_WriteRegister(pgm_read_byte( &DEVO_init_vals[i][0]), pgm_read_byte( &DEVO_init_vals[i][1]) );
}
static void set_radio_channels()
static void __attribute__((unused)) DEVO_set_radio_channels()
{
//int i;
CYRF_FindBestChannels(hopping_frequency, 3, 4, 4, 80);
//printf("Radio Channels:");
// for (i = 0; i < 3; i++) {
// printf(" %02x", radio_ch[i]);
//Serial.print(radio_ch[i]);
// }
// printf("\n");
//Makes code a little easier to duplicate these here
hopping_frequency[3] = hopping_frequency[0];
hopping_frequency[4] = hopping_frequency[1];
}
static void DEVO_BuildPacket()
static void __attribute__((unused)) DEVO_BuildPacket()
{
static uint8_t failsafe_pkt=0;
switch(phase)
{
case DEVO_BIND:
if(bind_counter>0)
if(bind_counter)
bind_counter--;
build_bind_pkt();
DEVO_build_bind_pkt();
phase = DEVO_BIND_SENDCH;
break;
case DEVO_BIND_SENDCH:
if(bind_counter>0)
if(bind_counter)
bind_counter--;
build_data_pkt();
scramble_pkt();
DEVO_build_data_pkt();
DEVO_scramble_pkt();
if (bind_counter == 0)
{
phase = DEVO_BOUND;
@@ -250,10 +233,10 @@ static void DEVO_BuildPacket()
case DEVO_BOUND_7:
case DEVO_BOUND_8:
case DEVO_BOUND_9:
build_data_pkt();
scramble_pkt();
DEVO_build_data_pkt();
DEVO_scramble_pkt();
phase++;
if (bind_counter > 0)
if (bind_counter)
{
bind_counter--;
if (bind_counter == 0)
@@ -261,19 +244,20 @@ static void DEVO_BuildPacket()
}
break;
case DEVO_BOUND_10:
build_beacon_pkt(DEVO_NUM_CHANNELS > 8 ? failsafe_pkt : 0);
DEVO_build_beacon_pkt(DEVO_NUM_CHANNELS > 8 ? failsafe_pkt : 0);
failsafe_pkt = failsafe_pkt ? 0 : 1;
scramble_pkt();
DEVO_scramble_pkt();
phase = DEVO_BOUND_1;
break;
}
pkt_num++;
if(pkt_num == PKTS_PER_CHANNEL)
pkt_num = 0;
packet_count++;
if(packet_count == DEVO_PKTS_PER_CHANNEL)
packet_count = 0;
}
uint16_t devo_callback()
{
static uint8_t txState=0;
if (txState == 0)
{
txState = 1;
@@ -284,107 +268,54 @@ uint16_t devo_callback()
txState = 0;
uint8_t i = 0;
while (! (CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x02))
if(++i > NUM_WAIT_LOOPS)
if(++i > DEVO_NUM_WAIT_LOOPS)
return 1200;
if (phase == DEVO_BOUND)
{
/* exit binding state */
phase = DEVO_BOUND_3;
cyrf_set_bound_sop_code();
DEVO_cyrf_set_bound_sop_code();
}
if(pkt_num == 0)
if(packet_count == 0)
{
//Keep tx power updated
CYRF_SetPower(0x08);
CYRF_SetPower(0x08); //Keep tx power updated
hopping_frequency_ptr = hopping_frequency_ptr == &hopping_frequency[2] ? hopping_frequency : hopping_frequency_ptr + 1;
CYRF_ConfigRFChannel(*hopping_frequency_ptr);
}
return 1200;
}
/*static void devo_bind()
{
fixed_id = Model_fixed_id;
bind_counter = DEVO_BIND_COUNT;
use_fixed_id = 1;
//PROTOCOL_SetBindState(0x1388 * 2400 / 1000); //msecs 12000ms
}
static void generate_fixed_id_bind(){
if(BIND_0){
//randomSeed((uint32_t)analogRead(A6)<<10|analogRead(A7));//seed
uint8_t txid[4];
//Model_fixed_id = random(0xfefefefe) + ((uint32_t)random(0xfefefefe) << 16);
Model_fixed_id=0x332211;
txid[0]= (id &0xFF);
txid[1] = ((id >> 8) & 0xFF);
txid[2] = ((id >> 16) & 0xFF);
//txid[3] = ((id >> 24) & 0xFF);
eeprom_write_block((const void*)txid,(void*)40,3);
devo_bind();
}
}
*/
uint16_t DevoInit()
{
CYRF_Reset();
cyrf_init();
DEVO_cyrf_init();
CYRF_GetMfgData(cyrfmfg_id);
CYRF_SetTxRxMode(TX_EN);
CYRF_ConfigCRCSeed(0x0000);
CYRF_ConfigSOPCode(sopcodes[0]);
set_radio_channels();
use_fixed_id = 0;
failsafe_pkt = 0;
CYRF_PROGMEM_ConfigSOPCode(DEVO_j6pro_sopcodes[0]);
DEVO_set_radio_channels();
hopping_frequency_ptr = hopping_frequency;
//
CYRF_ConfigRFChannel(*hopping_frequency_ptr);
//FIXME: Properly setnumber of channels;
pkt_num = 0;
ch_idx = 0;
txState = 0;
//uint8_t txid[4];
//
/*
if(BIND_0){
Model_fixed_id=0;
eeprom_write_block((const void*)0,(void*)40,4);
while(1){
LED_ON;
delay(100);
LED_OFF;
delay(100);
}
}
else{
eeprom_read_block((void*)txid,(const void*)40,3);
Model_fixed_id=(txid[0] | ((uint32_t)txid[1]<<8) | ((uint32_t)txid[2]<<16));
}
*/
if(! Model_fixed_id)
{//model fixed ID =0
fixed_id = ((uint32_t)(hopping_frequency[0] ^ cyrfmfg_id[0] ^ cyrfmfg_id[3]) << 16)
| ((uint32_t)(hopping_frequency[1] ^ cyrfmfg_id[1] ^ cyrfmfg_id[4]) << 8)
| ((uint32_t)(hopping_frequency[2] ^ cyrfmfg_id[2] ^ cyrfmfg_id[5]) << 0);
fixed_id = fixed_id % 1000000;
packet_count = 0;
prev_option=option;
if(option==0)
{
MProtocol_id = ((uint32_t)(hopping_frequency[0] ^ cyrfmfg_id[0] ^ cyrfmfg_id[3]) << 16)
| ((uint32_t)(hopping_frequency[1] ^ cyrfmfg_id[1] ^ cyrfmfg_id[4]) << 8)
| ((uint32_t)(hopping_frequency[2] ^ cyrfmfg_id[2] ^ cyrfmfg_id[5]) << 0);
MProtocol_id %= 1000000;
bind_counter = DEVO_BIND_COUNT;
phase = DEVO_BIND;
//PROTOCOL_SetBindState(0x1388 * 2400 / 1000); //msecs
BIND_IN_PROGRESS;
}
else
{
fixed_id = Model_fixed_id;
use_fixed_id = 1;
phase = DEVO_BOUND_1;
bind_counter = 0;
cyrf_set_bound_sop_code();
DEVO_cyrf_set_bound_sop_code();
}
return 2400;
}

View File

@@ -23,14 +23,14 @@
#define ESKY_PAYLOAD_SIZE 13
#define ESKY_PACKET_CHKTIME 100 // Time to wait for packet to be sent (no ACK, so very short)
static void ESKY_set_data_address()
static void __attribute__((unused)) ESKY_set_data_address()
{
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x02); // 4-byte RX/TX address for regular packets
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 4);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 4);
}
static void ESKY_init(uint8_t bind)
static void __attribute__((unused)) ESKY_init(uint8_t bind)
{
NRF24L01_Initialize();
@@ -60,7 +60,7 @@ static void ESKY_init(uint8_t bind)
NRF24L01_WriteReg(NRF24L01_17_FIFO_STATUS, 0x00); // Just in case, no real bits to write here
}
static void ESKY_init2()
static void __attribute__((unused)) ESKY_init2()
{
NRF24L01_FlushTx();
packet_sent = 0;
@@ -90,7 +90,7 @@ static void ESKY_init2()
NRF24L01_SetTxRxMode(TX_EN);
}
static void ESKY_send_packet(uint8_t bind)
static void __attribute__((unused)) ESKY_send_packet(uint8_t bind)
{
uint8_t rf_ch = 50; // bind channel
if (bind)
@@ -117,11 +117,10 @@ static void ESKY_send_packet(uint8_t bind)
// For arithmetic simplicity, channels are repeated in rf_channels array
if (hopping_frequency_no == 0)
{
const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2};
for (uint8_t i = 0; i < 6; i++)
{
packet[i*2] = Servo_data[ch[i]]>>8; //high byte of servo timing(1000-2000us)
packet[i*2+1] = Servo_data[ch[i]]&0xFF; //low byte of servo timing(1000-2000us)
packet[i*2] = Servo_data[CH_AETR[i]]>>8; //high byte of servo timing(1000-2000us)
packet[i*2+1] = Servo_data[CH_AETR[i]]&0xFF; //low byte of servo timing(1000-2000us)
}
}
rf_ch = hopping_frequency[hopping_frequency_no];

View File

@@ -0,0 +1,212 @@
/*
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/>.
*/
// Last sync with bikemike FQ777-124.ino
#if defined(FQ777_NRF24L01_INO)
#include "iface_nrf24l01.h"
#define FQ777_INITIAL_WAIT 500
#define FQ777_PACKET_PERIOD 2000
#define FQ777_PACKET_SIZE 8
#define FQ777_BIND_COUNT 1000
#define FQ777_NUM_RF_CHANNELS 4
enum {
FQ777_FLAG_RETURN = 0x40, // 0x40 when not off, !0x40 when one key return
FQ777_FLAG_HEADLESS = 0x04,
FQ777_FLAG_EXPERT = 0x01,
FQ777_FLAG_FLIP = 0x80,
};
const uint8_t ssv_xor[] = {0x80,0x44,0x64,0x75,0x6C,0x71,0x2A,0x36,0x7C,0xF1,0x6E,0x52,0x9,0x9D,0x1F,0x78,0x3F,0xE1,0xEE,0x16,0x6D,0xE8,0x73,0x9,0x15,0xD7,0x92,0xE7,0x3,0xBA};
uint8_t FQ777_bind_addr [] = {0xe7,0xe7,0xe7,0xe7,0x67};
static void __attribute__((unused)) ssv_pack_dpl(uint8_t addr[], uint8_t pid, uint8_t* len, uint8_t* payload, uint8_t* packed_payload)
{
uint8_t i = 0;
uint16_t pcf = (*len & 0x3f) << 3;
pcf |= (pid & 0x3) << 1;
pcf |= 0x00; // noack field
uint8_t header[7] = {0};
header[6] = pcf;
header[5] = (pcf >> 7) | (addr[0] << 1);
header[4] = (addr[0] >> 7) | (addr[1] << 1);
header[3] = (addr[1] >> 7) | (addr[2] << 1);
header[2] = (addr[2] >> 7) | (addr[3] << 1);
header[1] = (addr[3] >> 7) | (addr[4] << 1);
header[0] = (addr[4] >> 7);
// calculate the crc
union
{
uint8_t bytes[2];
uint16_t val;
} crc;
crc.val=0x3c18;
for (i = 0; i < 7; ++i)
crc.val=crc16_update(crc.val,header[i]);
for (i = 0; i < *len; ++i)
crc.val=crc16_update(crc.val,payload[i]);
// encode payload and crc
// xor with this:
for (i = 0; i < *len; ++i)
payload[i] ^= ssv_xor[i];
crc.bytes[1] ^= ssv_xor[i++];
crc.bytes[0] ^= ssv_xor[i++];
// pack the pcf, payload, and crc into packed_payload
packed_payload[0] = pcf >> 1;
packed_payload[1] = (pcf << 7) | (payload[0] >> 1);
for (i = 0; i < *len - 1; ++i)
packed_payload[i+2] = (payload[i] << 7) | (payload[i+1] >> 1);
packed_payload[i+2] = (payload[i] << 7) | (crc.val >> 9);
++i;
packed_payload[i+2] = (crc.val >> 1 & 0x80 ) | (crc.val >> 1 & 0x7F);
++i;
packed_payload[i+2] = (crc.val << 7);
*len += 4;
}
static void __attribute__((unused)) FQ777_send_packet(uint8_t bind)
{
uint8_t packet_len = FQ777_PACKET_SIZE;
uint8_t packet_ori[8];
if (bind)
{
// 4,5,6 = address fields
// last field is checksum of address fields
packet_ori[0] = 0x20;
packet_ori[1] = 0x15;
packet_ori[2] = 0x05;
packet_ori[3] = 0x06;
packet_ori[4] = rx_tx_addr[0];
packet_ori[5] = rx_tx_addr[1];
packet_ori[6] = rx_tx_addr[2];
packet_ori[7] = packet_ori[4] + packet_ori[5] + packet_ori[6];
}
else
{
// throt, yaw, pitch, roll, trims, flags/left button,00,right button
//0-3 0x00-0x64
//4 roll/pitch/yaw trims. cycles through one trim at a time - 0-40 trim1, 40-80 trim2, 80-C0 trim3 (center: A0 20 60)
//5 flags for throttle button, two buttons above throttle - def: 0x40
//6 00 ??
//7 checksum - add values in other fields
// Trims are usually done through the radio configuration but leaving the code here just in case...
uint8_t trim_mod = packet_count % 144;
uint8_t trim_val = 0;
if (36 <= trim_mod && trim_mod < 72) // yaw
trim_val = 0x20; // don't modify yaw trim
else
if (108 < trim_mod && trim_mod) // pitch
trim_val = 0xA0;
else // roll
trim_val = 0x60;
packet_ori[0] = convert_channel_8b_scale(THROTTLE,0,0x64);
packet_ori[1] = convert_channel_8b_scale(RUDDER,0,0x64);
packet_ori[2] = convert_channel_8b_scale(ELEVATOR,0,0x64);
packet_ori[3] = convert_channel_8b_scale(AILERON,0,0x64);
packet_ori[4] = trim_val; // calculated above
packet_ori[5] = GET_FLAG(Servo_AUX1, FQ777_FLAG_FLIP)
| GET_FLAG(Servo_AUX3, FQ777_FLAG_HEADLESS)
| GET_FLAG(!Servo_AUX2, FQ777_FLAG_RETURN)
| GET_FLAG(Servo_AUX4,FQ777_FLAG_EXPERT);
packet_ori[6] = 0x00;
// calculate checksum
uint8_t checksum = 0;
for (int i = 0; i < 7; ++i)
checksum += packet_ori[i];
packet_ori[7] = checksum;
packet_count++;
}
ssv_pack_dpl( (0 == bind) ? rx_tx_addr : FQ777_bind_addr, hopping_frequency_no, &packet_len, packet_ori, packet);
NRF24L01_WriteReg(NRF24L01_00_CONFIG,_BV(NRF24L01_00_PWR_UP));
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++]);
hopping_frequency_no %= FQ777_NUM_RF_CHANNELS;
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
NRF24L01_FlushTx();
NRF24L01_WritePayload(packet, packet_len);
NRF24L01_WritePayload(packet, packet_len);
NRF24L01_WritePayload(packet, packet_len);
}
static void __attribute__((unused)) FQ777_init()
{
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, FQ777_bind_addr, 5);
NRF24L01_FlushTx();
NRF24L01_FlushRx();
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgement on all data pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x00);
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03);
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // no retransmits
NRF24L01_SetBitrate(NRF24L01_BR_250K);
NRF24L01_SetPower();
NRF24L01_Activate(0x73); // Activate feature register
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x00); // Disable dynamic payload length on all pipes
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x01);
NRF24L01_Activate(0x73);
}
uint16_t FQ777_callback()
{
if(bind_counter!=0)
{
FQ777_send_packet(1);
bind_counter--;
if (bind_counter == 0)
{
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5);
BIND_DONE;
}
}
else
FQ777_send_packet(0);
return FQ777_PACKET_PERIOD;
}
uint16_t initFQ777(void)
{
BIND_IN_PROGRESS; // autobind protocol
bind_counter = FQ777_BIND_COUNT;
packet_count=0;
hopping_frequency[0] = 0x4D;
hopping_frequency[1] = 0x43;
hopping_frequency[2] = 0x27;
hopping_frequency[3] = 0x07;
hopping_frequency_no=0;
rx_tx_addr[2] = 0x00;
rx_tx_addr[3] = 0xe7;
rx_tx_addr[4] = 0x67;
FQ777_init();
return FQ777_INITIAL_WAIT;
}
#endif

View File

@@ -0,0 +1,167 @@
/*
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/>.
*/
// Last sync with hexfet new_protocols/fy326_nrf24l01.c dated 2015-07-29
#if defined(FY326_NRF24L01_INO)
#include "iface_nrf24l01.h"
#define FY326_INITIAL_WAIT 500
#define FY326_PACKET_PERIOD 1500
#define FY326_PACKET_CHKTIME 300
#define FY326_PACKET_SIZE 15
#define FY326_BIND_COUNT 16
#define FY326_RF_BIND_CHANNEL 0x17
#define FY326_NUM_RF_CHANNELS 5
enum {
FY326_BIND1=0,
FY326_BIND2,
FY326_DATA
};
#define rxid channel
#define CHAN_TO_TRIM(chanval) ((chanval/10)-10)
static void __attribute__((unused)) FY326_send_packet(uint8_t bind)
{
packet[0] = rx_tx_addr[3];
if(bind)
packet[1] = 0x55;
else
packet[1] = GET_FLAG(Servo_AUX3, 0x80) // Headless
| GET_FLAG(Servo_AUX2, 0x40) // RTH
| GET_FLAG(Servo_AUX1, 0x02) // Flip
| GET_FLAG(Servo_AUX5, 0x01) // Calibrate
| GET_FLAG(Servo_AUX4, 0x04); // Expert
packet[2] = 200 - convert_channel_8b_scale(AILERON, 0, 200); // aileron
packet[3] = convert_channel_8b_scale(ELEVATOR, 0, 200); // elevator
packet[4] = 200 - convert_channel_8b_scale(RUDDER, 0, 200); // rudder
packet[5] = convert_channel_8b_scale(THROTTLE, 0, 200); // throttle
packet[6] = rx_tx_addr[0];
packet[7] = rx_tx_addr[1];
packet[8] = rx_tx_addr[2];
packet[9] = CHAN_TO_TRIM(packet[2]); // aileron_trim;
packet[10] = CHAN_TO_TRIM(packet[3]); // elevator_trim;
packet[11] = CHAN_TO_TRIM(packet[4]); // rudder_trim;
packet[12] = 0; // throttle_trim;
packet[13] = rxid;
packet[14] = rx_tx_addr[4];
if (bind)
NRF24L01_WriteReg(NRF24L01_05_RF_CH, FY326_RF_BIND_CHANNEL);
else
{
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++]);
hopping_frequency_no %= FY326_NUM_RF_CHANNELS;
}
// clear packet status bits and TX FIFO
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
NRF24L01_FlushTx();
NRF24L01_WritePayload(packet, FY326_PACKET_SIZE);
NRF24L01_SetPower(); // Set tx_power
}
static void __attribute__((unused)) FY326_init()
{
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // Three-byte rx/tx address
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *)"\x15\x59\x23\xc6\x29", 5);
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, (uint8_t *)"\x15\x59\x23\xc6\x29", 5);
NRF24L01_FlushTx();
NRF24L01_FlushRx();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgement on all data pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, FY326_PACKET_SIZE);
NRF24L01_WriteReg(NRF24L01_05_RF_CH, FY326_RF_BIND_CHANNEL);
NRF24L01_SetBitrate(NRF24L01_BR_250K);
NRF24L01_SetPower();
NRF24L01_Activate(0x73);
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3f);
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07);
NRF24L01_Activate(0x73);
}
uint16_t FY326_callback()
{
switch (phase)
{
case FY326_BIND1:
if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR))
{ // RX fifo data ready
NRF24L01_ReadPayload(packet, FY326_PACKET_SIZE);
rxid = packet[13];
rx_tx_addr[0] = 0xAA;
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_SetTxRxMode(TX_EN);
BIND_DONE;
phase = FY326_DATA;
}
else
if (bind_counter-- == 0)
{
bind_counter = FY326_BIND_COUNT;
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_SetTxRxMode(TX_EN);
FY326_send_packet(1);
phase = FY326_BIND2;
return FY326_PACKET_CHKTIME;
}
break;
case FY326_BIND2:
if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_TX_DS))
{ // TX data sent -> switch to RX mode
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_FlushRx();
NRF24L01_SetTxRxMode(RX_EN);
phase = FY326_BIND1;
}
else
return FY326_PACKET_CHKTIME;
break;
case FY326_DATA:
FY326_send_packet(0);
break;
}
return FY326_PACKET_PERIOD;
}
static void __attribute__((unused)) FY326_initialize_txid()
{
hopping_frequency[0] = (rx_tx_addr[0]&0x0f);
hopping_frequency[1] = 0x10 + (rx_tx_addr[0] >> 4);
hopping_frequency[2] = 0x20 + (rx_tx_addr[1]&0x0f);
hopping_frequency[3] = 0x30 + (rx_tx_addr[1] >> 4);
hopping_frequency[4] = 0x40 + (rx_tx_addr[2] >> 4);
}
uint16_t initFY326(void)
{
BIND_IN_PROGRESS; // autobind protocol
rxid = 0xAA;
bind_counter = 0;
FY326_initialize_txid();
FY326_init();
phase=FY326_BIND1;
return FY326_INITIAL_WAIT;
}
#endif

View File

@@ -21,31 +21,12 @@
//FlySky constants & variables
#define FLYSKY_BIND_COUNT 2500
const uint8_t PROGMEM tx_channels[] = {
0x0a, 0x5a, 0x14, 0x64, 0x1e, 0x6e, 0x28, 0x78, 0x32, 0x82, 0x3c, 0x8c, 0x46, 0x96, 0x50, 0xa0,
0xa0, 0x50, 0x96, 0x46, 0x8c, 0x3c, 0x82, 0x32, 0x78, 0x28, 0x6e, 0x1e, 0x64, 0x14, 0x5a, 0x0a,
0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x46, 0x96, 0x1e, 0x6e, 0x3c, 0x8c, 0x28, 0x78, 0x32, 0x82,
0x82, 0x32, 0x78, 0x28, 0x8c, 0x3c, 0x6e, 0x1e, 0x96, 0x46, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a,
0x28, 0x78, 0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96,
0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a, 0x78, 0x28,
0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96, 0x14, 0x64,
0x64, 0x14, 0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50,
0x50, 0xa0, 0x46, 0x96, 0x3c, 0x8c, 0x28, 0x78, 0x0a, 0x5a, 0x32, 0x82, 0x1e, 0x6e, 0x14, 0x64,
0x64, 0x14, 0x6e, 0x1e, 0x82, 0x32, 0x5a, 0x0a, 0x78, 0x28, 0x8c, 0x3c, 0x96, 0x46, 0xa0, 0x50,
0x46, 0x96, 0x3c, 0x8c, 0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64,
0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50, 0x8c, 0x3c, 0x96, 0x46,
0x46, 0x96, 0x0a, 0x5a, 0x3c, 0x8c, 0x14, 0x64, 0x50, 0xa0, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82,
0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0xa0, 0x50, 0x64, 0x14, 0x8c, 0x3c, 0x5a, 0x0a, 0x96, 0x46,
0x46, 0x96, 0x0a, 0x5a, 0x50, 0xa0, 0x3c, 0x8c, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64,
0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0x8c, 0x3c, 0xa0, 0x50, 0x5a, 0x0a, 0x96, 0x46
};
enum {
// flags going to byte 10
FLAG_V9X9_VIDEO = 0x40,
FLAG_V9X9_CAMERA= 0x80,
// flags going to byte 12
FLAG_V9X9_UNK = 0x10, // undocumented ?
FLAG_V9X9_FLIP = 0x10,
FLAG_V9X9_LED = 0x20,
};
@@ -69,20 +50,17 @@ enum {
FLAG_V912_BTMBTN= 0x80,
};
uint8_t chanrow;
uint8_t chancol;
uint8_t chanoffset;
static void flysky_apply_extension_flags()
{
const uint8_t V912_X17_SEQ[10] = { 0x14, 0x31, 0x40, 0x49, 0x49, // sometime first byte is 0x15 ?
const uint8_t PROGMEM V912_X17_SEQ[10] = { 0x14, 0x31, 0x40, 0x49, 0x49, // sometime first byte is 0x15 ?
0x49, 0x49, 0x49, 0x49, 0x49, };
static void __attribute__((unused)) flysky_apply_extension_flags()
{
static uint8_t seq_counter;
switch(sub_protocol)
{
case V9X9:
if(Servo_AUX1)
packet[12] |= FLAG_V9X9_UNK;
packet[12] |= FLAG_V9X9_FLIP;
if(Servo_AUX2)
packet[12] |= FLAG_V9X9_LED;
if(Servo_AUX3)
@@ -134,7 +112,7 @@ static void flysky_apply_extension_flags()
packet[14] |= FLAG_V912_TOPBTN;
packet[15] = 0x27; // [15] and [16] apparently hold an analog channel with a value lower than 1000
packet[16] = 0x03; // maybe it's there for a pitch channel for a CP copter ?
packet[17] = V912_X17_SEQ[seq_counter]; // not sure what [17] & [18] are for
packet[17] = pgm_read_byte( &V912_X17_SEQ[seq_counter] ) ; // not sure what [17] & [18] are for
if(seq_counter == 0) // V912 Rx does not even read those bytes... [17-20]
packet[18] = 0x02;
else
@@ -148,7 +126,7 @@ static void flysky_apply_extension_flags()
}
}
static void flysky_build_packet(uint8_t init)
static void __attribute__((unused)) flysky_build_packet(uint8_t init)
{
uint8_t i;
//servodata timing range for flysky.
@@ -161,11 +139,10 @@ static void flysky_build_packet(uint8_t init)
packet[2] = rx_tx_addr[2];
packet[3] = rx_tx_addr[1];
packet[4] = rx_tx_addr[0];
const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4};
for(i = 0; i < 8; i++)
{
packet[5+2*i]=lowByte(Servo_data[ch[i]]); //low byte of servo timing(1000-2000us)
packet[6+2*i]=highByte(Servo_data[ch[i]]); //high byte of servo timing(1000-2000us)
packet[5 + i*2]=Servo_data[CH_AETR[i]]&0xFF; //low byte of servo timing(1000-2000us)
packet[6 + i*2]=(Servo_data[CH_AETR[i]]>>8)&0xFF; //high byte of servo timing(1000-2000us)
}
flysky_apply_extension_flags();
}
@@ -182,31 +159,57 @@ uint16_t ReadFlySky()
}
else
{
flysky_build_packet(0);
A7105_WriteData(21, pgm_read_byte_near(&tx_channels[chanrow*16+chancol])-chanoffset);
chancol = (chancol + 1) % 16;
if (! chancol) //Keep transmit power updated
A7105_SetPower();
flysky_build_packet(0);
A7105_WriteData(21, hopping_frequency[hopping_frequency_no]);
hopping_frequency_no = (hopping_frequency_no + 1) & 0x0F;
A7105_SetPower();
}
return 1460;
return 1510; //1460 on deviation but not working with the latest V911 bricks... Turnigy 9X v2 is 1533, Flysky TX for 9XR/9XR Pro is 1510, V911 TX is 1490.
}
uint16_t initFlySky() {
//A7105_Reset();
const uint8_t PROGMEM tx_channels[8][4] = {
{ 0x12, 0x34, 0x56, 0x78},
{ 0x18, 0x27, 0x36, 0x45},
{ 0x41, 0x82, 0x36, 0x57},
{ 0x84, 0x13, 0x65, 0x72},
{ 0x87, 0x64, 0x15, 0x32},
{ 0x76, 0x84, 0x13, 0x52},
{ 0x71, 0x62, 0x84, 0x35},
{ 0x71, 0x86, 0x43, 0x52}
};
uint16_t initFlySky()
{
uint8_t chanrow;
uint8_t chanoffset;
uint8_t temp;
A7105_Init(INIT_FLYSKY); //flysky_init();
if (rx_tx_addr[3] > 0x90) // limit offset to 9 as higher values don't work with some RX (ie V912)
rx_tx_addr[3] = rx_tx_addr[3] - 0x70;
chanrow=rx_tx_addr[3] % 16;
chancol=0;
chanoffset=rx_tx_addr[3] / 16;
if ((rx_tx_addr[3]&0xF0) > 0x90) // limit offset to 9 as higher values don't work with some RX (ie V912)
rx_tx_addr[3]=rx_tx_addr[3]-0x70;
chanrow=rx_tx_addr[3] & 0x0F;
chanoffset=rx_tx_addr[3]/16;
// Build frequency hop table
for(uint8_t i=0;i<16;i++)
{
temp=pgm_read_byte_near(&tx_channels[chanrow>>1][i>>2]);
if(i&0x01)
temp&=0x0F;
else
temp>>=4;
temp*=0x0A;
if(i&0x02)
temp+=0x50;
hopping_frequency[((chanrow&1)?15-i:i)]=temp-chanoffset;
}
hopping_frequency_no=0;
if(IS_AUTOBIND_FLAG_on)
bind_counter = FLYSKY_BIND_COUNT;
else
bind_counter = 0;
return 2400;
}
#endif

View File

@@ -0,0 +1,208 @@
/*
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/>.
*/
#if defined(FRSKYD_CC2500_INO)
#include "iface_cc2500.h"
static void __attribute__((unused)) frsky2way_init(uint8_t bind)
{
// Configure cc2500 for tx mode
//
for(uint8_t i=0;i<36;i++)
{
uint8_t reg=pgm_read_byte_near(&cc2500_conf[i][0]);
uint8_t val=pgm_read_byte_near(&cc2500_conf[i][1]);
if(reg==CC2500_0C_FSCTRL0)
val=option;
else
if(reg==CC2500_1B_AGCCTRL2)
val=bind ? 0x43 : 0x03;
CC2500_WriteReg(reg,val);
}
prev_option = option ;
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_09_ADDR, bind ? 0x03 : rx_tx_addr[3]);
CC2500_WriteReg(CC2500_07_PKTCTRL1, 0x05);
CC2500_Strobe(CC2500_SIDLE); // Go to idle...
//
CC2500_WriteReg(CC2500_0A_CHANNR, 0x00);
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
CC2500_Strobe(CC2500_SFRX);
//#######END INIT########
}
static uint8_t __attribute__((unused)) get_chan_num(uint16_t idx)
{
uint8_t ret = (idx * 0x1e) % 0xeb;
if(idx == 3 || idx == 23 || idx == 47)
ret++;
if(idx > 47)
return 0;
return ret;
}
static void __attribute__((unused)) frsky2way_build_bind_packet()
{
//11 03 01 d7 2d 00 00 1e 3c 5b 78 00 00 00 00 00 00 01
//11 03 01 19 3e 00 02 8e 2f bb 5c 00 00 00 00 00 00 01
packet[0] = 0x11;
packet[1] = 0x03;
packet[2] = 0x01;
packet[3] = rx_tx_addr[3];
packet[4] = rx_tx_addr[2];
uint16_t idx = ((state -FRSKY_BIND) % 10) * 5;
packet[5] = idx;
packet[6] = get_chan_num(idx++);
packet[7] = get_chan_num(idx++);
packet[8] = get_chan_num(idx++);
packet[9] = get_chan_num(idx++);
packet[10] = get_chan_num(idx++);
packet[11] = 0x00;
packet[12] = 0x00;
packet[13] = 0x00;
packet[14] = 0x00;
packet[15] = 0x00;
packet[16] = 0x00;
packet[17] = 0x01;
}
static void __attribute__((unused)) frsky2way_data_frame()
{//pachet[4] is telemetry user frame counter(hub)
//11 d7 2d 22 00 01 c9 c9 ca ca 88 88 ca ca c9 ca 88 88
//11 57 12 00 00 01 f2 f2 f2 f2 06 06 ca ca ca ca 18 18
packet[0] = 0x11; //Length
packet[1] = rx_tx_addr[3];
packet[2] = rx_tx_addr[2];
packet[3] = counter;//
#if defined TELEMETRY
packet[4] = telemetry_counter;
#else
packet[4] = 0x00;
#endif
packet[5] = 0x01;
//
packet[10] = 0;
packet[11] = 0;
packet[16] = 0;
packet[17] = 0;
for(uint8_t i = 0; i < 8; i++)
{
uint16_t value;
value = convert_channel_frsky(i);
if(i < 4)
{
packet[6+i] = value & 0xff;
packet[10+(i>>1)] |= ((value >> 8) & 0x0f) << (4 *(i & 0x01));
}
else
{
packet[8+i] = value & 0xff;
packet[16+((i-4)>>1)] |= ((value >> 8) & 0x0f) << (4 * ((i-4) & 0x01));
}
}
}
uint16_t initFrSky_2way()
{
if(IS_AUTOBIND_FLAG_on)
{
frsky2way_init(1);
state = FRSKY_BIND;
}
else
{
frsky2way_init(0);
state = FRSKY_DATA2;
}
return 10000;
}
uint16_t ReadFrSky_2way()
{
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);
state++;
return 9000;
}
if (state == FRSKY_BIND_DONE)
{
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);
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR, get_chan_num(counter % 47));
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
state++;
return 1300;
}
else
{
if (state == FRSKY_DATA1)
{
len = CC2500_ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (len && len<=MAX_PKT)//27 bytes
{
CC2500_ReadData(pkt, len); //received telemetry packets
#if defined(TELEMETRY)
//parse telemetry packet here
frsky_check_telemetry(pkt,len); //check if valid telemetry packets and buffer them.
#endif
}
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower(); // Set tx_power
}
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR, get_chan_num(counter % 47));
if ( prev_option != option )
{
CC2500_WriteReg(CC2500_0C_FSCTRL0,option); // Frequency offset hack
prev_option = option ;
}
CC2500_WriteReg(CC2500_23_FSCAL3, 0x89);
CC2500_Strobe(CC2500_SFRX);
frsky2way_data_frame();
CC2500_WriteData(packet, packet[0]+1);
state++;
}
return state == FRSKY_DATA4 ? 7500 : 9000;
}
#endif

View File

@@ -0,0 +1,209 @@
/*
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/>.
*/
#if defined(FRSKYV_CC2500_INO)
#define FRSKYV_BIND_COUNT 200
enum {
FRSKYV_DATA1=0,
FRSKYV_DATA2,
FRSKYV_DATA3,
FRSKYV_DATA4,
FRSKYV_DATA5
};
#include "iface_cc2500.h"
const PROGMEM uint8_t FRSKYV_cc2500_conf[][2]={
{ CC2500_17_MCSM1, 0x0c },
{ CC2500_18_MCSM0, 0x18 },
{ CC2500_06_PKTLEN, 0xff },
{ CC2500_07_PKTCTRL1, 0x04 },
{ CC2500_08_PKTCTRL0, 0x05 },
{ CC2500_3E_PATABLE, 0xfe },
{ CC2500_0B_FSCTRL1, 0x08 },
{ CC2500_0C_FSCTRL0, 0x00 },
{ CC2500_0D_FREQ2, 0x5c },
{ CC2500_0E_FREQ1, 0x58 },
{ CC2500_0F_FREQ0, 0x9d },
{ CC2500_10_MDMCFG4, 0xaa },
{ CC2500_11_MDMCFG3, 0x10 },
{ CC2500_12_MDMCFG2, 0x93 },
{ CC2500_13_MDMCFG1, 0x23 },
{ CC2500_14_MDMCFG0, 0x7a },
{ CC2500_15_DEVIATN, 0x41 }
};
static void __attribute__((unused)) FRSKYV_init()
{
for(uint8_t i=0;i<17;i++)
{
uint8_t reg=pgm_read_byte_near(&FRSKYV_cc2500_conf[i][0]);
uint8_t val=pgm_read_byte_near(&FRSKYV_cc2500_conf[i][1]);
if(reg==CC2500_0C_FSCTRL0)
val=option;
CC2500_WriteReg(reg,val);
}
prev_option = option ;
for(uint8_t i=19;i<36;i++)
{
uint8_t reg=pgm_read_byte_near(&cc2500_conf[i][0]);
uint8_t val=pgm_read_byte_near(&cc2500_conf[i][1]);
CC2500_WriteReg(reg,val);
}
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
CC2500_Strobe(CC2500_SIDLE); // Go to idle...
}
static uint8_t __attribute__((unused)) FRSKYV_crc8(uint8_t result, uint8_t *data, uint8_t len)
{
for(uint8_t i = 0; i < len; i++)
{
result = result ^ data[i];
for(uint8_t j = 0; j < 8; j++)
if(result & 0x80)
result = (result << 1) ^ 0x07;
else
result = result << 1;
}
return result;
}
static uint8_t __attribute__((unused)) FRSKYV_crc8_le(uint8_t *data, uint8_t len)
{
uint8_t result = 0xD6;
for(uint8_t i = 0; i < len; i++)
{
result = result ^ data[i];
for(uint8_t j = 0; j < 8; j++)
if(result & 0x01)
result = (result >> 1) ^ 0x83;
else
result = result >> 1;
}
return result;
}
static void __attribute__((unused)) FRSKYV_build_bind_packet()
{
//0e 03 01 57 12 00 06 0b 10 15 1a 00 00 00 61
packet[0] = 0x0e; //Length
packet[1] = 0x03; //Packet type
packet[2] = 0x01; //Packet type
packet[3] = rx_tx_addr[3];
packet[4] = rx_tx_addr[2];
packet[5] = (binding_idx % 10) * 5;
packet[6] = packet[5] * 5 + 6;
packet[7] = packet[5] * 5 + 11;
packet[8] = packet[5] * 5 + 16;
packet[9] = packet[5] * 5 + 21;
packet[10] = packet[5] * 5 + 26;
packet[11] = 0x00;
packet[12] = 0x00;
packet[13] = 0x00;
packet[14] = FRSKYV_crc8(0x93, packet, 14);
}
static uint8_t __attribute__((unused)) FRSKYV_calc_channel()
{
uint32_t temp=seed;
temp = (temp * 0xaa) % 0x7673;
seed = temp;
return (seed & 0xff) % 0x32;
}
static void __attribute__((unused)) FRSKYV_build_data_packet()
{
uint8_t idx = 0; // transmit lower channels
packet[0] = 0x0e;
packet[1] = rx_tx_addr[3];
packet[2] = rx_tx_addr[2];
packet[3] = seed & 0xff;
packet[4] = seed >> 8;
if (phase == FRSKYV_DATA1 || phase == FRSKYV_DATA3)
packet[5] = 0x0f;
else
if(phase == FRSKYV_DATA2 || phase == FRSKYV_DATA4)
{
packet[5] = 0xf0;
idx=4; // transmit upper channels
}
else
packet[5] = 0x00;
for(uint8_t i = 0; i < 4; i++)
{
uint16_t value = convert_channel_frsky(i+idx);
packet[2*i + 6] = value & 0xff;
packet[2*i + 7] = value >> 8;
}
packet[14] = FRSKYV_crc8(crc8, packet, 14);
}
uint16_t ReadFRSKYV()
{
if(IS_BIND_DONE_on)
{ // Normal operation
uint8_t chan = FRSKYV_calc_channel();
CC2500_Strobe(CC2500_SIDLE);
if (option != prev_option)
{
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
prev_option=option;
}
CC2500_WriteReg(CC2500_0A_CHANNR, chan * 5 + 6);
FRSKYV_build_data_packet();
if (phase == FRSKYV_DATA5)
{
CC2500_SetPower();
phase = FRSKYV_DATA1;
}
else
phase++;
CC2500_WriteData(packet, packet[0]+1);
return 9006;
}
// Bind mode
FRSKYV_build_bind_packet();
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR, 0x00);
CC2500_WriteData(packet, packet[0]+1);
binding_idx++;
if(binding_idx>=FRSKYV_BIND_COUNT)
BIND_DONE;
return 53460;
}
uint16_t initFRSKYV()
{
//ID is 15 bits. Using rx_tx_addr[2] and rx_tx_addr[3] since we want to use RX_Num for model match
rx_tx_addr[2]&=0x7F;
crc8 = FRSKYV_crc8_le(rx_tx_addr+2, 2);
FRSKYV_init();
seed = 1;
binding_idx=0;
phase = FRSKYV_DATA1;
return 10000;
}
#endif

View File

@@ -1,21 +1,335 @@
/*
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/>.
*/
/* **************************
* By Midelic on RCGroups *
**************************
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/>.
*/
#if defined(FRSKYX_CC2500_INO)
#include "iface_cc2500.h"
uint8_t chanskip;
uint8_t counter_rst;
uint8_t ctr;
uint8_t seq_last_sent;
uint8_t seq_last_rcvd;
#endif
const PROGMEM uint8_t hop_data[]={
0x02, 0xD4, 0xBB, 0xA2, 0x89,
0x70, 0x57, 0x3E, 0x25, 0x0C,
0xDE, 0xC5, 0xAC, 0x93, 0x7A,
0x61, 0x48, 0x2F, 0x16, 0xE8,
0xCF, 0xB6, 0x9D, 0x84, 0x6B,
0x52, 0x39, 0x20, 0x07, 0xD9,
0xC0, 0xA7, 0x8E, 0x75, 0x5C,
0x43, 0x2A, 0x11, 0xE3, 0xCA,
0xB1, 0x98, 0x7F, 0x66, 0x4D,
0x34, 0x1B, 0x00, 0x1D, 0x03
};
static uint8_t __attribute__((unused)) hop(uint8_t byte)
{
return pgm_read_byte_near(&hop_data[byte]);
}
static void __attribute__((unused)) set_start(uint8_t ch )
{
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_25_FSCAL1, calData[ch]);
CC2500_WriteReg(CC2500_0A_CHANNR, ch==47? 0:hop(ch));
}
static void __attribute__((unused)) frskyX_init()
{
for(uint8_t i=0;i<36;i++)
{
uint8_t reg=pgm_read_byte_near(&cc2500_conf[i][0]);
uint8_t val=pgm_read_byte_near(&cc2500_conf[i][1]);
if(reg==CC2500_06_PKTLEN)
val=0x1E;
else
if(reg==CC2500_08_PKTCTRL0)
val=0x01;
else
if(reg==CC2500_0B_FSCTRL1)
val=0x0A;
else
if(reg==CC2500_10_MDMCFG4)
val=0x7B;
else
if(reg==CC2500_11_MDMCFG3)
val=0x61;
else
if(reg==CC2500_12_MDMCFG2)
val=0x13;
else
if(reg==CC2500_15_DEVIATN)
val=0x51;
CC2500_WriteReg(reg,val);
}
CC2500_WriteReg(CC2500_07_PKTCTRL1, 0x04);
prev_option = option ;
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
CC2500_Strobe(CC2500_SIDLE);
//
for(uint8_t c=0;c < 47;c++)
{//calibrate hop channels
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR,hop(c));
CC2500_Strobe(CC2500_SCAL);
delayMicroseconds(900);//
calData[c] = CC2500_ReadReg(CC2500_25_FSCAL1);
}
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR,0x00);
CC2500_Strobe(CC2500_SCAL);
delayMicroseconds(900);
calData[47] = CC2500_ReadReg(CC2500_25_FSCAL1);
//#######END INIT########
}
static void __attribute__((unused)) initialize_data(uint8_t adr)
{
CC2500_WriteReg(CC2500_0C_FSCTRL0,option); // Frequency offset hack
CC2500_WriteReg(CC2500_18_MCSM0, 0x8);
CC2500_WriteReg(CC2500_09_ADDR, adr ? 0x03 : rx_tx_addr[3]);
CC2500_WriteReg(CC2500_07_PKTCTRL1,0x05);
}
//**CRC**
const uint16_t PROGMEM CRC_Short[]={
0x0000, 0x1189, 0x2312, 0x329B, 0x4624, 0x57AD, 0x6536, 0x74BF,
0x8C48, 0x9DC1, 0xAF5A, 0xBED3, 0xCA6C, 0xDBE5, 0xE97E, 0xF8F7 };
static uint16_t CRCTable(uint8_t val)
{
uint16_t word ;
word = pgm_read_word(&CRC_Short[val&0x0F]) ;
val /= 16 ;
return word ^ (0x1081 * val) ;
}
static uint16_t __attribute__((unused)) crc_x(uint8_t *data, uint8_t len)
{
uint16_t crc = 0;
for(uint8_t i=0; i < len; i++)
crc = (crc<<8) ^ CRCTable((uint8_t)(crc>>8) ^ *data++);
return crc;
}
// 0-2047, 0 = 817, 1024 = 1500, 2047 = 2182
//64=860,1024=1500,1984=2140//Taranis 125%
static uint16_t __attribute__((unused)) scaleForPXX( uint8_t i )
{ //mapped 860,2140(125%) range to 64,1984(PXX values);
return (uint16_t)(((Servo_data[i]-servo_min_125)*3)>>1)+64;
}
static void __attribute__((unused)) frskyX_build_bind_packet()
{
packet[0] = 0x1D;
packet[1] = 0x03;
packet[2] = 0x01;
//
packet[3] = rx_tx_addr[3];
packet[4] = rx_tx_addr[2];
int idx = ((state -FRSKY_BIND) % 10) * 5;
packet[5] = idx;
packet[6] = hop(idx++);
packet[7] = hop(idx++);
packet[8] = hop(idx++);
packet[9] = hop(idx++);
packet[10] = hop(idx++);
packet[11] = 0x02;
packet[12] = RX_num;
//
memset(&packet[13], 0, 15);
uint16_t lcrc = crc_x(&packet[3], 25);
//
packet[28] = lcrc >> 8;
packet[29] = lcrc;
//
}
static void __attribute__((unused)) frskyX_data_frame()
{
//0x1D 0xB3 0xFD 0x02 0x56 0x07 0x15 0x00 0x00 0x00 0x04 0x40 0x00 0x04 0x40 0x00 0x04 0x40 0x00 0x04 0x40 0x08 0x00 0x00 0x00 0x00 0x00 0x00 0x96 0x12
//
static uint8_t lpass;
uint16_t chan_0 ;
uint16_t chan_1 ;
uint8_t startChan = 0;
//
packet[0] = 0x1D;
packet[1] = rx_tx_addr[3];
packet[2] = rx_tx_addr[2];
packet[3] = 0x02;
//
packet[4] = (ctr<<6)+hopping_frequency_no;
packet[5] = counter_rst;
packet[6] = RX_num;
//packet[7] = FLAGS 00 - standard packet
//10, 12, 14, 16, 18, 1A, 1C, 1E - failsafe packet
//20 - range check packet
packet[7] = 0;
packet[8] = 0;
//
if ( lpass & 1 )
startChan += 8 ;
for(uint8_t i = 0; i <12 ; i+=3)
{//12 bytes
chan_0 = scaleForPXX(startChan);
if(lpass & 1 )
chan_0+=2048;
startChan+=1;
//
chan_1 = scaleForPXX(startChan);
if(lpass & 1 )
chan_1+= 2048;
startChan+=1;
//
packet[9+i] = lowByte(chan_0);//3 bytes*4
packet[9+i+1]=(((chan_0>>8) & 0x0F)|(chan_1 << 4));
packet[9+i+2]=chan_1>>4;
}
packet[21] = seq_last_sent << 4 | seq_last_rcvd;//8 at start
if (seq_last_sent < 0x08 && seq_last_rcvd < 8)
seq_last_sent = (seq_last_sent + 1) % 4;
else if (seq_last_rcvd == 0x00)
seq_last_sent = 1;
if(sub_protocol== CH_8 )// in X8 mode send only 8ch every 9ms
lpass = 0 ;
else
lpass += 1 ;
for (uint8_t i=22;i<28;i++)
packet[i]=0;
uint16_t lcrc = crc_x(&packet[3], 25);
packet[28]=lcrc>>8;//high byte
packet[29]=lcrc;//low byte
}
uint16_t ReadFrSkyX()
{
switch(state)
{
default:
set_start(47);
CC2500_SetPower();
CC2500_Strobe(CC2500_SFRX);
//
frskyX_build_bind_packet();
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteData(packet, packet[0]+1);
state++;
return 9000;
case FRSKY_BIND_DONE:
initialize_data(0);
hopping_frequency_no=0;
BIND_DONE;
state++;
break;
case FRSKY_DATA1:
if ( prev_option != option )
{
CC2500_WriteReg(CC2500_0C_FSCTRL0,option); // Frequency offset hack
prev_option = option ;
}
CC2500_SetTxRxMode(TX_EN);
set_start(hopping_frequency_no);
CC2500_SetPower();
CC2500_Strobe(CC2500_SFRX);
hopping_frequency_no = (hopping_frequency_no+chanskip)%47;
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteData(packet, packet[0]+1);
//
frskyX_data_frame();
state++;
return 5500;
case FRSKY_DATA2:
CC2500_SetTxRxMode(RX_EN);
CC2500_Strobe(CC2500_SIDLE);
state++;
return 200;
case FRSKY_DATA3:
CC2500_Strobe(CC2500_SRX);
state++;
return 3000;
case FRSKY_DATA4:
len = CC2500_ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (len && (len<MAX_PKT))
{
CC2500_ReadData(pkt, len);
#if defined TELEMETRY
frsky_check_telemetry(pkt,len); //check if valid telemetry packets
//parse telemetry packets here
//The same telemetry function used by FrSky(D8).
#endif
}
else
{
counter++;
// restart sequence on missed packet - might need count or timeout instead of one missed
if(counter>100)
{//~1sec
seq_last_sent = 0;
seq_last_rcvd = 8;
counter=0;
}
}
state = FRSKY_DATA1;
return 300;
}
return 1;
}
uint16_t initFrSkyX()
{
while(!chanskip)
{
randomSeed((uint32_t)analogRead(A6) << 10 | analogRead(A7));
chanskip=random(0xfefefefe)%47;
}
while((chanskip-ctr)%4)
ctr=(ctr+1)%4;
counter_rst=(chanskip-ctr)>>2;
//for test***************
//rx_tx_addr[3]=0xB3;
//rx_tx_addr[2]=0xFD;
//************************
frskyX_init();
CC2500_SetTxRxMode(TX_EN);
//
if(IS_AUTOBIND_FLAG_on)
{
state = FRSKY_BIND;
initialize_data(1);
}
else
{
state = FRSKY_DATA1;
initialize_data(0);
}
seq_last_sent = 0;
seq_last_rcvd = 8;
return 10000;
}
#endif

View File

@@ -1,268 +0,0 @@
/*
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/>.
*/
#if defined(FRSKY_CC2500_INO)
#include "iface_cc2500.h"
//##########Variables########
uint32_t state;
uint8_t len;
enum {
FRSKY_BIND = 0,
FRSKY_BIND_DONE = 1000,
FRSKY_DATA1,
FRSKY_DATA2,
FRSKY_DATA3,
FRSKY_DATA4,
FRSKY_DATA5
};
uint16_t initFrSky_2way()
{
if(IS_AUTOBIND_FLAG_on)
{
frsky2way_init(1);
state = FRSKY_BIND;//
}
else
{
frsky2way_init(0);
state = FRSKY_DATA2;
}
return 10000;
}
uint16_t ReadFrSky_2way()
{
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_writeFifo(packet, packet[0]+1);
state++;
return 9000;
}
if (state == FRSKY_BIND_DONE)
{
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);
cc2500_strobe(CC2500_SIDLE);
cc2500_writeReg(CC2500_0A_CHANNR, get_chan_num(counter % 47));
cc2500_writeReg(CC2500_23_FSCAL3, 0x89);
state++;
return 1300;
}
else
{
if (state == FRSKY_DATA1)
{
len = cc2500_readReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (len)//20 bytes
{
cc2500_readFifo(pkt, len); //received telemetry packets
#if defined(TELEMETRY)
//parse telemetry packet here
check_telemetry(pkt,len); //check if valid telemetry packets and buffer them.
#endif
}
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower(); // Set tx_power
}
cc2500_strobe(CC2500_SIDLE);
cc2500_writeReg(CC2500_0A_CHANNR, get_chan_num(counter % 47));
cc2500_writeReg(CC2500_23_FSCAL3, 0x89);
cc2500_strobe(CC2500_SFRX);
frsky2way_data_frame();
cc2500_writeFifo(packet, packet[0]+1);
state++;
}
return state == FRSKY_DATA4 ? 7500 : 9000;
}
#if defined(TELEMETRY)
static void check_telemetry(uint8_t *pkt,uint8_t len)
{
if(pkt[1] != rx_tx_addr[3] || pkt[2] != rx_tx_addr[2] || len != pkt[0] + 3)
{//only packets with the required id and packet length
for(uint8_t i=3;i<6;i++)
pktt[i]=0;
return;
}
else
{
for (uint8_t i=3;i<len;i++)
pktt[i]=pkt[i];
telemetry_link=1;
}
}
void compute_RSSIdbm(){
RSSI_dBm = (((uint16_t)(pktt[len-2])*18)>>5);
if(pktt[len-2] >=128)
RSSI_dBm -= 82;
else
RSSI_dBm += 65;
}
#endif
static void frsky2way_init(uint8_t bind)
{
// Configure cc2500 for tx mode
CC2500_Reset();
//
cc2500_writeReg(CC2500_02_IOCFG0, 0x06);
cc2500_writeReg(CC2500_00_IOCFG2, 0x06);
cc2500_writeReg(CC2500_17_MCSM1, 0x0c);
cc2500_writeReg(CC2500_18_MCSM0, 0x18);
cc2500_writeReg(CC2500_06_PKTLEN, 0x19);
cc2500_writeReg(CC2500_07_PKTCTRL1, 0x04);
cc2500_writeReg(CC2500_08_PKTCTRL0, 0x05);
cc2500_writeReg(CC2500_3E_PATABLE, 0xff);
cc2500_writeReg(CC2500_0B_FSCTRL1, 0x08);
cc2500_writeReg(CC2500_0C_FSCTRL0, option);
//base freq FREQ = 0x5C7627 (F = 2404MHz)
cc2500_writeReg(CC2500_0D_FREQ2, 0x5c);
cc2500_writeReg(CC2500_0E_FREQ1, 0x76);
cc2500_writeReg(CC2500_0F_FREQ0, 0x27);
//
cc2500_writeReg(CC2500_10_MDMCFG4, 0xAA);
cc2500_writeReg(CC2500_11_MDMCFG3, 0x39);
cc2500_writeReg(CC2500_12_MDMCFG2, 0x11);
cc2500_writeReg(CC2500_13_MDMCFG1, 0x23);
cc2500_writeReg(CC2500_14_MDMCFG0, 0x7a);
cc2500_writeReg(CC2500_15_DEVIATN, 0x42);
cc2500_writeReg(CC2500_19_FOCCFG, 0x16);
cc2500_writeReg(CC2500_1A_BSCFG, 0x6c);
cc2500_writeReg(CC2500_1B_AGCCTRL2, bind ? 0x43 : 0x03);
cc2500_writeReg(CC2500_1C_AGCCTRL1,0x40);
cc2500_writeReg(CC2500_1D_AGCCTRL0,0x91);
cc2500_writeReg(CC2500_21_FREND1, 0x56);
cc2500_writeReg(CC2500_22_FREND0, 0x10);
cc2500_writeReg(CC2500_23_FSCAL3, 0xa9);
cc2500_writeReg(CC2500_24_FSCAL2, 0x0A);
cc2500_writeReg(CC2500_25_FSCAL1, 0x00);
cc2500_writeReg(CC2500_26_FSCAL0, 0x11);
cc2500_writeReg(CC2500_29_FSTEST, 0x59);
cc2500_writeReg(CC2500_2C_TEST2, 0x88);
cc2500_writeReg(CC2500_2D_TEST1, 0x31);
cc2500_writeReg(CC2500_2E_TEST0, 0x0B);
cc2500_writeReg(CC2500_03_FIFOTHR, 0x07);
cc2500_writeReg(CC2500_09_ADDR, 0x00);
//
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
cc2500_strobe(CC2500_SIDLE);
cc2500_writeReg(CC2500_09_ADDR, bind ? 0x03 : rx_tx_addr[3]);
cc2500_writeReg(CC2500_07_PKTCTRL1, 0x05);
cc2500_strobe(CC2500_SIDLE); // Go to idle...
//
cc2500_writeReg(CC2500_0A_CHANNR, 0x00);
cc2500_writeReg(CC2500_23_FSCAL3, 0x89);
cc2500_strobe(CC2500_SFRX);
//#######END INIT########
}
static uint8_t get_chan_num(uint16_t idx)
{
uint8_t ret = (idx * 0x1e) % 0xeb;
if(idx == 3 || idx == 23 || idx == 47)
ret++;
if(idx > 47)
return 0;
return ret;
}
static void frsky2way_build_bind_packet()
{
//11 03 01 d7 2d 00 00 1e 3c 5b 78 00 00 00 00 00 00 01
//11 03 01 19 3e 00 02 8e 2f bb 5c 00 00 00 00 00 00 01
packet[0] = 0x11;
packet[1] = 0x03;
packet[2] = 0x01;
packet[3] = rx_tx_addr[3];
packet[4] = rx_tx_addr[2];
uint16_t idx = ((state -FRSKY_BIND) % 10) * 5;
packet[5] = idx;
packet[6] = get_chan_num(idx++);
packet[7] = get_chan_num(idx++);
packet[8] = get_chan_num(idx++);
packet[9] = get_chan_num(idx++);
packet[10] = get_chan_num(idx++);
packet[11] = 0x00;
packet[12] = 0x00;
packet[13] = 0x00;
packet[14] = 0x00;
packet[15] = 0x00;
packet[16] = 0x00;
packet[17] = 0x01;
}
uint8_t telemetry_counter=0;
static void frsky2way_data_frame()
{//pachet[4] is telemetry user frame counter(hub)
//11 d7 2d 22 00 01 c9 c9 ca ca 88 88 ca ca c9 ca 88 88
//11 57 12 00 00 01 f2 f2 f2 f2 06 06 ca ca ca ca 18 18
packet[0] = 0x11; //Length
packet[1] = rx_tx_addr[3];
packet[2] = rx_tx_addr[2];
packet[3] = counter;//
packet[4] = pkt[6]?(telemetry_counter++)%32:0;
packet[5] = 0x01;
//
packet[10] = 0;
packet[11] = 0;
packet[16] = 0;
packet[17] = 0;
for(uint8_t i = 0; i < 8; i++)
{
uint16_t value;
value = convert_channel_frsky(i);
if(i < 4)
{
packet[6+i] = value & 0xff;
packet[10+(i>>1)] |= ((value >> 8) & 0x0f) << (4 *(i & 0x01));
}
else
{
packet[8+i] = value & 0xff;
packet[16+((i-4)>>1)] |= ((value >> 8) & 0x0f) << (4 * ((i-4) & 0x01));
}
}
}
#endif

View File

@@ -27,7 +27,7 @@ uint8_t bind_buf_arry[4][10];
// HiSky protocol uses TX id as an address for nRF24L01, and uses frequency hopping sequence
// which does not depend on this id and is passed explicitly in binding sequence. So we are free
// to generate this sequence as we wish. It should be in the range [02..77]
static void calc_fh_channels()
static void __attribute__((unused)) calc_fh_channels()
{
uint8_t idx = 0;
uint32_t rnd = MProtocol_id;
@@ -61,7 +61,7 @@ static void calc_fh_channels()
}
}
static void build_binding_packet(void)
static void __attribute__((unused)) build_binding_packet(void)
{
uint8_t i;
uint16_t sum=0;
@@ -95,7 +95,7 @@ static void build_binding_packet(void)
}
}
static void hisky_init()
static void __attribute__((unused)) hisky_init()
{
NRF24L01_Initialize();
@@ -116,14 +116,13 @@ static void hisky_init()
// HiSky channel sequence: AILE ELEV THRO RUDD GEAR PITCH, channel data value is from 0 to 1000
// Channel 7 - Gyro mode, 0 - 6 axis, 3 - 3 axis
static void build_ch_data()
static void __attribute__((unused)) build_ch_data()
{
uint16_t temp;
uint8_t i,j;
const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER, AUX1, AUX2, AUX3, AUX4};
for (i = 0; i< 8; i++) {
j=ch[i];
temp=map(limit_channel_100(j),PPM_MIN_100,PPM_MAX_100,0,1000);
j=CH_AETR[i];
temp=map(limit_channel_100(j),servo_min_100,servo_max_100,0,1000);
if (j == THROTTLE) // It is clear that hisky's throttle stick is made reversely, so I adjust it here on purpose
temp = 1000 -temp;
if (j == AUX3)
@@ -217,7 +216,7 @@ uint16_t hisky_cb()
return 1000; // send 1 binding packet and 1 data packet per 9ms
}
static void initialize_tx_id()
static void __attribute__((unused)) initialize_tx_id()
{
//Generate frequency hopping table
if(sub_protocol==HK310)

View File

@@ -56,7 +56,7 @@ enum {
};
#define WAIT_WRITE 0x80
static void update_crc()
static void __attribute__((unused)) hubsan_update_crc()
{
uint8_t sum = 0;
for(uint8_t i = 0; i < 15; i++)
@@ -64,7 +64,7 @@ static void update_crc()
packet[15] = (256 - (sum % 256)) & 0xFF;
}
static void hubsan_build_bind_packet(uint8_t bind_state)
static void __attribute__((unused)) hubsan_build_bind_packet(uint8_t bind_state)
{
static uint8_t handshake_counter;
if(phase < BIND_7)
@@ -99,14 +99,14 @@ static void hubsan_build_bind_packet(uint8_t bind_state)
if(phase == BIND_7)
packet[2] = handshake_counter++;
}
update_crc();
hubsan_update_crc();
}
//cc : throttle observed range: 0x00 - 0xFF (smaller is down)
//ee : rudder observed range: 0x34 - 0xcc (smaller is right)52-204-60%
//gg : elevator observed range: 0x3e - 0xbc (smaller is up)62-188 -50%
//ii : aileron observed range: 0x45 - 0xc3 (smaller is right)69-195-50%
static void hubsan_build_packet()
static void __attribute__((unused)) hubsan_build_packet()
{
static uint8_t vtx_freq = 0;
memset(packet, 0, 16);
@@ -177,24 +177,27 @@ static void hubsan_build_packet()
packet_count++;
}
}
update_crc();
hubsan_update_crc();
}
#if defined(TELEMETRY)
/*static uint8_t hubsan_check_integrity()
static uint8_t __attribute__((unused)) hubsan_check_integrity()
{
int sum = 0;
if( (packet[0]&0xFE) != 0xE0 )
return 0;
uint8_t sum = 0;
for(uint8_t i = 0; i < 15; i++)
sum += packet[i];
return packet[15] == ((256 - (sum % 256)) & 0xFF);
return ( packet[15] == (uint8_t)(-sum) );
}
*/
#endif
uint16_t ReadHubsan()
{
static uint8_t txState=0;
#if defined(TELEMETRY)
static uint8_t rfMode=0;
#endif
static uint8_t txState=0;
static uint8_t bind_count=0;
uint16_t delay;
uint8_t i;
@@ -232,9 +235,9 @@ uint16_t ReadHubsan()
phase &= ~WAIT_WRITE;
if(id_data == ID_PLUS)
{
if(state == BIND_7 && packet[2] == 9)
if(phase == BIND_7 && packet[2] == 9)
{
state = DATA_1;
phase = DATA_1;
A7105_WriteReg(A7105_1F_CODE_I, 0x0F);
BIND_DONE;
return 4500;
@@ -277,7 +280,9 @@ uint16_t ReadHubsan()
case DATA_4:
case DATA_5:
if( txState == 0) { // send packet
#if defined(TELEMETRY)
rfMode = A7105_TX;
#endif
if( phase == DATA_1)
A7105_SetPower(); //Keep transmit power in sync
hubsan_build_packet();
@@ -291,7 +296,8 @@ uint16_t ReadHubsan()
}
else {
#if defined(TELEMETRY)
if( rfMode == A7105_TX) {// switch to rx mode 3ms after packet sent
if( rfMode == A7105_TX)
{// switch to rx mode 3ms after packet sent
for( i=0; i<10; i++)
{
if( !(A7105_ReadReg(A7105_00_MODE) & 0x01)) {// wait for tx completion
@@ -302,15 +308,23 @@ uint16_t ReadHubsan()
}
}
}
if( rfMode == A7105_RX) { // check for telemetry frame
for( i=0; i<10; i++) {
if( !(A7105_ReadReg(A7105_00_MODE) & 0x01)) { // data received
if( rfMode == A7105_RX)
{ // check for telemetry frame
for( i=0; i<10; i++)
{
if( !(A7105_ReadReg(A7105_00_MODE) & 0x01))
{ // data received
A7105_ReadData();
if( !(A7105_ReadReg(A7105_00_MODE) & 0x01)){ // data received
v_lipo=packet[13];// hubsan lipo voltage 8bits the real value is h_lipo/10(0x2A=42-4.2V)
if( hubsan_check_integrity() )
{
v_lipo=packet[13];// hubsan lipo voltage 8bits the real value is h_lipo/10(0x2A=42 -> 4.2V)
telemetry_link=1;
}
A7105_Strobe(A7105_RX);
// Read TX RSSI
RSSI_dBm=256-(A7105_ReadReg(A7105_1D_RSSI_THOLD)*8)/5; // value from A7105 is between 8 for maximum signal strength to 160 or less
if(RSSI_dBm<0) RSSI_dBm=0;
else if(RSSI_dBm>255) RSSI_dBm=255;
break;
}
}
@@ -340,7 +354,6 @@ uint16_t initHubsan() {
packet_count=0;
id_data=ID_NORMAL;
#if defined(TELEMETRY)
v_lipo=0;
telemetry_link=0;
#endif
return 10000;

View File

@@ -0,0 +1,250 @@
/*
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/>.
*/
#if defined(J6PRO_CYRF6936_INO)
#include "iface_cyrf6936.h"
enum PktState {
J6PRO_BIND,
J6PRO_BIND_01,
J6PRO_BIND_03_START,
J6PRO_BIND_03_CHECK,
J6PRO_BIND_05_1,
J6PRO_BIND_05_2,
J6PRO_BIND_05_3,
J6PRO_BIND_05_4,
J6PRO_BIND_05_5,
J6PRO_BIND_05_6,
J6PRO_CHANSEL,
J6PRO_CHAN_1,
J6PRO_CHAN_2,
J6PRO_CHAN_3,
J6PRO_CHAN_4,
};
const uint8_t PROGMEM j6pro_bind_sop_code[] = {0x62, 0xdf, 0xc1, 0x49, 0xdf, 0xb1, 0xc0, 0x49};
const uint8_t j6pro_data_code[] = {0x02, 0xf9, 0x93, 0x97, 0x02, 0xfa, 0x5c, 0xe3, 0x01, 0x2b, 0xf1, 0xdb, 0x01, 0x32, 0xbe, 0x6f};
static void __attribute__((unused)) j6pro_build_bind_packet()
{
packet[0] = 0x01; //Packet type
packet[1] = 0x01; //FIXME: What is this? Model number maybe?
packet[2] = 0x56; //FIXME: What is this?
packet[3] = cyrfmfg_id[0];
packet[4] = cyrfmfg_id[1];
packet[5] = cyrfmfg_id[2];
packet[6] = cyrfmfg_id[3];
packet[7] = cyrfmfg_id[4];
packet[8] = cyrfmfg_id[5];
}
static void __attribute__((unused)) j6pro_build_data_packet()
{
uint8_t i;
uint32_t upperbits = 0;
uint16_t value;
packet[0] = 0xaa; //FIXME what is this?
for (i = 0; i < 12; i++)
{
value = convert_channel_10b(CH_AETR[i]);
packet[i+1] = value & 0xff;
upperbits |= (value >> 8) << (i * 2);
}
packet[13] = upperbits & 0xff;
packet[14] = (upperbits >> 8) & 0xff;
packet[15] = (upperbits >> 16) & 0xff;
}
static void __attribute__((unused)) j6pro_cyrf_init()
{
/* Initialise CYRF chip */
CYRF_WriteRegister(CYRF_28_CLK_EN, 0x02);
CYRF_WriteRegister(CYRF_32_AUTO_CAL_TIME, 0x3c);
CYRF_WriteRegister(CYRF_35_AUTOCAL_OFFSET, 0x14);
CYRF_WriteRegister(CYRF_1C_TX_OFFSET_MSB, 0x05);
CYRF_WriteRegister(CYRF_1B_TX_OFFSET_LSB, 0x55);
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25);
CYRF_SetPower(0x05);
CYRF_WriteRegister(CYRF_06_RX_CFG, 0x8a);
CYRF_SetPower(0x28);
CYRF_WriteRegister(CYRF_12_DATA64_THOLD, 0x0e);
CYRF_WriteRegister(CYRF_10_FRAMING_CFG, 0xee);
CYRF_WriteRegister(CYRF_1F_TX_OVERRIDE, 0x00);
CYRF_WriteRegister(CYRF_1E_RX_OVERRIDE, 0x00);
CYRF_ConfigDataCode(j6pro_data_code, 16);
CYRF_WritePreamble(0x023333);
CYRF_GetMfgData(cyrfmfg_id);
//Model match
cyrfmfg_id[3]+=RX_num;
}
static void __attribute__((unused)) cyrf_bindinit()
{
/* Use when binding */
//0.060470# 03 2f
CYRF_SetPower(0x28); //Deviation using max power, replaced by bind power...
CYRF_ConfigRFChannel(0x52);
CYRF_PROGMEM_ConfigSOPCode(j6pro_bind_sop_code);
CYRF_ConfigCRCSeed(0x0000);
CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4a);
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83);
//0.061511# 13 20
CYRF_ConfigRFChannel(0x52);
//0.062684# 0f 05
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25);
//0.062792# 0f 05
CYRF_WriteRegister(CYRF_02_TX_CTRL, 0x40);
j6pro_build_bind_packet(); //01 01 e9 49 ec a9 c4 c1 ff
//CYRF_WriteDataPacketLen(packet, 0x09);
}
static void __attribute__((unused)) cyrf_datainit()
{
/* Use when already bound */
//0.094007# 0f 05
uint8_t sop_idx = (0xff & (cyrfmfg_id[0] + cyrfmfg_id[1] + cyrfmfg_id[2] + cyrfmfg_id[3] - cyrfmfg_id[5])) % 19;
uint16_t crc = (0xff & (cyrfmfg_id[1] - cyrfmfg_id[4] + cyrfmfg_id[5])) |
((0xff & (cyrfmfg_id[2] + cyrfmfg_id[3] - cyrfmfg_id[4] + cyrfmfg_id[5])) << 8);
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25);
CYRF_PROGMEM_ConfigSOPCode(DEVO_j6pro_sopcodes[sop_idx]);
CYRF_ConfigCRCSeed(crc);
}
static void __attribute__((unused)) j6pro_set_radio_channels()
{
//FIXME: Query free channels
//lowest channel is 0x08, upper channel is 0x4d?
CYRF_FindBestChannels(hopping_frequency, 3, 5, 8, 77);
hopping_frequency[3] = hopping_frequency[0];
}
uint16_t ReadJ6Pro()
{
uint32_t start;
switch(phase)
{
case J6PRO_BIND:
cyrf_bindinit();
phase = J6PRO_BIND_01;
//no break because we want to send the 1st bind packet now
case J6PRO_BIND_01:
CYRF_ConfigRFChannel(0x52);
CYRF_SetTxRxMode(TX_EN);
//0.062684# 0f 05
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25);
//0.062684# 0f 05
CYRF_WriteDataPacketLen(packet, 0x09);
phase = J6PRO_BIND_03_START;
return 3000; //3msec
case J6PRO_BIND_03_START:
start=micros();
while (micros()-start < 500) // Wait max 500µs
if(CYRF_ReadRegister(CYRF_04_TX_IRQ_STATUS) & 0x06)
break;
CYRF_ConfigRFChannel(0x53);
CYRF_SetTxRxMode(RX_EN);
CYRF_WriteRegister(CYRF_06_RX_CFG, 0x4a);
CYRF_WriteRegister(CYRF_05_RX_CTRL, 0x83);
phase = J6PRO_BIND_03_CHECK;
return 30000; //30msec
case J6PRO_BIND_03_CHECK:
{
uint8_t rx = CYRF_ReadRegister(CYRF_07_RX_IRQ_STATUS);
if((rx & 0x1a) == 0x1a) {
rx = CYRF_ReadRegister(CYRF_0A_RX_LENGTH);
if(rx == 0x0f) {
rx = CYRF_ReadRegister(CYRF_09_RX_COUNT);
if(rx == 0x0f) {
//Expected and actual length are both 15
CYRF_ReadDataPacketLen(packet, rx);
if (packet[0] == 0x03 &&
packet[3] == cyrfmfg_id[0] &&
packet[4] == cyrfmfg_id[1] &&
packet[5] == cyrfmfg_id[2] &&
packet[6] == cyrfmfg_id[3] &&
packet[7] == cyrfmfg_id[4] &&
packet[8] == cyrfmfg_id[5])
{
//Send back Ack
packet[0] = 0x05;
CYRF_ConfigRFChannel(0x54);
CYRF_SetTxRxMode(TX_EN);
phase = J6PRO_BIND_05_1;
return 2000; //2msec
}
}
}
}
phase = J6PRO_BIND_01;
return 500;
}
case J6PRO_BIND_05_1:
case J6PRO_BIND_05_2:
case J6PRO_BIND_05_3:
case J6PRO_BIND_05_4:
case J6PRO_BIND_05_5:
case J6PRO_BIND_05_6:
CYRF_WriteRegister(CYRF_0F_XACT_CFG, 0x25);
CYRF_WriteDataPacketLen(packet, 0x0f);
phase = phase + 1;
return 4600; //4.6msec
case J6PRO_CHANSEL:
BIND_DONE;
j6pro_set_radio_channels();
cyrf_datainit();
phase = J6PRO_CHAN_1;
case J6PRO_CHAN_1:
//Keep transmit power updated
CYRF_SetPower(0);
j6pro_build_data_packet();
//return 3400;
case J6PRO_CHAN_2:
//return 3500;
case J6PRO_CHAN_3:
//return 3750
case J6PRO_CHAN_4:
CYRF_ConfigRFChannel(hopping_frequency[phase - J6PRO_CHAN_1]);
CYRF_SetTxRxMode(TX_EN);
CYRF_WriteDataPacket(packet);
if (phase == J6PRO_CHAN_4) {
phase = J6PRO_CHAN_1;
return 13900;
}
phase = phase + 1;
return 3550;
}
return 0;
}
uint16_t initJ6Pro()
{
CYRF_Reset();
j6pro_cyrf_init();
if(IS_AUTOBIND_FLAG_on) {
phase = J6PRO_BIND;
}
else {
phase = J6PRO_CHANSEL;
}
return 2400;
}
#endif

View File

@@ -70,6 +70,205 @@ enum {
KN_FLAG_GYROR = 0x80 // Always 0 so far
};
//-------------------------------------------------------------------------------------------------
// This function init 24L01 regs and packet data for binding
// Send tx address, hopping table (for Wl Toys), and data rate to the KN receiver during binding.
// It seems that KN can remember these parameters, no binding needed after power up.
// Bind uses fixed TX address "KNDZK", 1 Mbps data rate and channel 83
//-------------------------------------------------------------------------------------------------
static void __attribute__((unused)) kn_bind_init()
{
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t*)"KNDZK", 5);
packet[0] = 'K';
packet[1] = 'N';
packet[2] = 'D';
packet[3] = 'Z';
//Use first four bytes of tx_addr
packet[4] = rx_tx_addr[0];
packet[5] = rx_tx_addr[1];
packet[6] = rx_tx_addr[2];
packet[7] = rx_tx_addr[3];
if(sub_protocol==WLTOYS)
{
packet[8] = hopping_frequency[0];
packet[9] = hopping_frequency[1];
packet[10] = hopping_frequency[2];
packet[11] = hopping_frequency[3];
}
else
{
packet[8] = 0x00;
packet[9] = 0x00;
packet[10] = 0x00;
packet[11] = 0x00;
}
packet[12] = 0x00;
packet[13] = 0x00;
packet[14] = 0x00;
packet[15] = 0x01; //(USE1MBPS_YES) ? 0x01 : 0x00;
//Set RF channel
NRF24L01_WriteReg(NRF24L01_05_RF_CH, 83);
}
//-------------------------------------------------------------------------------------------------
// Update control data to be sent
// Do it once per frequency, so the same values will be sent 4 times
// KN uses 4 10-bit data channels plus a 8-bit switch channel
//
// The packet[0] is used for pitch/throttle, the relation is hard coded, not changeable.
// We can change the throttle/pitch range though.
//
// How to use trim? V977 stock controller can trim 6-axis mode to eliminate the drift.
//-------------------------------------------------------------------------------------------------
static void __attribute__((unused)) kn_update_packet_control_data()
{
uint16_t value;
value = convert_channel_10b(THROTTLE);
packet[0] = (value >> 8) & 0xFF;
packet[1] = value & 0xFF;
value = convert_channel_10b(AILERON);
packet[2] = (value >> 8) & 0xFF;
packet[3] = value & 0xFF;
value = convert_channel_10b(ELEVATOR);
packet[4] = (value >> 8) & 0xFF;
packet[5] = value & 0xFF;
value = convert_channel_10b(RUDDER);
packet[6] = (value >> 8) & 0xFF;
packet[7] = value & 0xFF;
// Trims, middle is 0x64 (100) range 0-200
packet[8] = convert_channel_8b_scale(AUX5,0,200); // 0x64; // T
packet[9] = convert_channel_8b_scale(AUX6,0,200); // 0x64; // A
packet[10] = convert_channel_8b_scale(AUX7,0,200); // 0x64; // E
packet[11] = 0x64; // R
flags=0;
if (Servo_AUX1)
flags = KN_FLAG_DR;
if (Servo_AUX2)
flags |= KN_FLAG_TH;
if (Servo_AUX3)
flags |= KN_FLAG_IDLEUP;
if (Servo_AUX4)
flags |= KN_FLAG_GYRO3;
packet[12] = flags;
packet[13] = 0x00;
if(sub_protocol==WLTOYS)
packet[13] = (packet_sent << 5) | (hopping_frequency_no << 2);
packet[14] = 0x00;
packet[15] = 0x00;
NRF24L01_SetPower();
}
//-------------------------------------------------------------------------------------------------
// This function generate RF TX packet address
// V977 can remember the binding parameters; we do not need rebind when power up.
// This requires the address must be repeatable for a specific RF ID at power up.
//-------------------------------------------------------------------------------------------------
static void __attribute__((unused)) kn_calculate_tx_addr()
{
if(sub_protocol==FEILUN)
{
uint8_t addr2;
// Generate TXID with sum of minimum 256 and maximum 256+MAX_RF_CHANNEL-32
rx_tx_addr[1] = 1 + rx_tx_addr[0] % (KN_MAX_RF_CHANNEL-33);
addr2 = 1 + rx_tx_addr[2] % (KN_MAX_RF_CHANNEL-33);
if ((uint16_t)(rx_tx_addr[0] + rx_tx_addr[1]) < 256)
rx_tx_addr[2] = addr2;
else
rx_tx_addr[2] = 0x00;
rx_tx_addr[3] = 0x00;
while((uint16_t)(rx_tx_addr[0] + rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3]) < 257)
rx_tx_addr[3] += addr2;
}
//The 5th byte is a constant, must be 'K'
rx_tx_addr[4] = 'K';
}
//-------------------------------------------------------------------------------------------------
// This function generates "random" RF hopping frequency channel numbers.
// These numbers must be repeatable for a specific seed
// The generated number range is from 0 to MAX_RF_CHANNEL. No repeat or adjacent numbers
//
// For Feilun variant, the channels are calculated from TXID, and since only 2 channels are used
// we copy them to fill up to MAX_RF_CHANNEL
//-------------------------------------------------------------------------------------------------
static void __attribute__((unused)) kn_calculate_freqency_hopping_channels()
{
if(sub_protocol==WLTOYS)
{
uint8_t idx = 0;
uint32_t rnd = MProtocol_id;
while (idx < KN_RF_CH_COUNT)
{
uint8_t i;
rnd = rnd * 0x0019660D + 0x3C6EF35F; // Randomization
// Use least-significant byte. 73 is prime, so channels 76..77 are unused
uint8_t next_ch = ((rnd >> 8) % KN_MAX_RF_CHANNEL) + 2;
// Keep the distance 2 between the channels - either odd or even
if (((next_ch ^ MProtocol_id) & 0x01 )== 0)
continue;
// Check that it's not duplicate and spread uniformly
for (i = 0; i < idx; i++)
if(hopping_frequency[i] == next_ch)
break;
if (i != idx)
continue;
hopping_frequency[idx++] = next_ch;
}
}
else
{//FEILUN
hopping_frequency[0] = rx_tx_addr[0] + rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3]; // - 256; ???
hopping_frequency[1] = hopping_frequency[0] + 32;
hopping_frequency[2] = hopping_frequency[0];
hopping_frequency[3] = hopping_frequency[1];
}
}
//-------------------------------------------------------------------------------------------------
// This function setup 24L01
// V977 uses one way communication, receiving only. 24L01 RX is never enabled.
// V977 needs payload length in the packet. We should configure 24L01 to enable Packet Control Field(PCF)
// Some RX reg settings are actually for enable PCF
//-------------------------------------------------------------------------------------------------
static void __attribute__((unused)) kn_init()
{
kn_calculate_tx_addr();
kn_calculate_freqency_hopping_channels();
NRF24L01_Initialize();
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO));
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0); // Disable retransmit
NRF24L01_SetPower();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, 0x20); // bytes of data payload for pipe 0
NRF24L01_Activate(0x73);
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 1); // Dynamic payload for data pipe 0
// Enable: Dynamic Payload Length to enable PCF
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF2401_1D_EN_DPL));
NRF24L01_SetPower();
NRF24L01_FlushTx();
// Turn radio power on
NRF24L01_SetTxRxMode(TX_EN);
NRF24L01_SetBitrate(NRF24L01_BR_1M); //USE1MBPS_YES ? NRF24L01_BR_1M : NRF24L01_BR_250K;
}
//================================================================================================
// Private Functions
//================================================================================================
@@ -145,202 +344,4 @@ uint16_t kn_callback()
return packet_period;
}
//-------------------------------------------------------------------------------------------------
// This function init 24L01 regs and packet data for binding
// Send tx address, hopping table (for Wl Toys), and data rate to the KN receiver during binding.
// It seems that KN can remember these parameters, no binding needed after power up.
// Bind uses fixed TX address "KNDZK", 1 Mbps data rate and channel 83
//-------------------------------------------------------------------------------------------------
static void kn_bind_init()
{
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t*)"KNDZK", 5);
packet[0] = 'K';
packet[1] = 'N';
packet[2] = 'D';
packet[3] = 'Z';
//Use first four bytes of tx_addr
packet[4] = rx_tx_addr[0];
packet[5] = rx_tx_addr[1];
packet[6] = rx_tx_addr[2];
packet[7] = rx_tx_addr[3];
if(sub_protocol==WLTOYS)
{
packet[8] = hopping_frequency[0];
packet[9] = hopping_frequency[1];
packet[10] = hopping_frequency[2];
packet[11] = hopping_frequency[3];
}
else
{
packet[8] = 0x00;
packet[9] = 0x00;
packet[10] = 0x00;
packet[11] = 0x00;
}
packet[12] = 0x00;
packet[13] = 0x00;
packet[14] = 0x00;
packet[15] = 0x01; //(USE1MBPS_YES) ? 0x01 : 0x00;
//Set RF channel
NRF24L01_WriteReg(NRF24L01_05_RF_CH, 83);
}
//-------------------------------------------------------------------------------------------------
// Update control data to be sent
// Do it once per frequency, so the same values will be sent 4 times
// KN uses 4 10-bit data channels plus a 8-bit switch channel
//
// The packet[0] is used for pitch/throttle, the relation is hard coded, not changeable.
// We can change the throttle/pitch range though.
//
// How to use trim? V977 stock controller can trim 6-axis mode to eliminate the drift.
//-------------------------------------------------------------------------------------------------
static void kn_update_packet_control_data()
{
uint16_t value;
value = convert_channel_10b(THROTTLE);
packet[0] = (value >> 8) & 0xFF;
packet[1] = value & 0xFF;
value = convert_channel_10b(AILERON);
packet[2] = (value >> 8) & 0xFF;
packet[3] = value & 0xFF;
value = convert_channel_10b(ELEVATOR);
packet[4] = (value >> 8) & 0xFF;
packet[5] = value & 0xFF;
value = convert_channel_10b(RUDDER);
packet[6] = (value >> 8) & 0xFF;
packet[7] = value & 0xFF;
// Trims, middle is 0x64 (100) range 0-200
packet[8] = convert_channel_8b_scale(AUX5,0,200); // 0x64; // T
packet[9] = convert_channel_8b_scale(AUX6,0,200); // 0x64; // A
packet[10] = convert_channel_8b_scale(AUX7,0,200); // 0x64; // E
packet[11] = 0x64; // R
flags=0;
if (Servo_data[AUX1] > PPM_SWITCH)
flags = KN_FLAG_DR;
if (Servo_data[AUX2] > PPM_SWITCH)
flags |= KN_FLAG_TH;
if (Servo_data[AUX3] > PPM_SWITCH)
flags |= KN_FLAG_IDLEUP;
if (Servo_data[AUX4] > PPM_SWITCH)
flags |= KN_FLAG_GYRO3;
packet[12] = flags;
packet[13] = 0x00;
if(sub_protocol==WLTOYS)
packet[13] = (packet_sent << 5) | (hopping_frequency_no << 2);
packet[14] = 0x00;
packet[15] = 0x00;
NRF24L01_SetPower();
}
//-------------------------------------------------------------------------------------------------
// This function setup 24L01
// V977 uses one way communication, receiving only. 24L01 RX is never enabled.
// V977 needs payload length in the packet. We should configure 24L01 to enable Packet Control Field(PCF)
// Some RX reg settings are actually for enable PCF
//-------------------------------------------------------------------------------------------------
static void kn_init()
{
kn_calculate_tx_addr();
kn_calculate_freqency_hopping_channels();
NRF24L01_Initialize();
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO));
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0); // Disable retransmit
NRF24L01_SetPower();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, 0x20); // bytes of data payload for pipe 0
NRF24L01_Activate(0x73);
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 1); // Dynamic payload for data pipe 0
// Enable: Dynamic Payload Length to enable PCF
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF2401_1D_EN_DPL));
NRF24L01_SetPower();
NRF24L01_FlushTx();
// Turn radio power on
NRF24L01_SetTxRxMode(TX_EN);
NRF24L01_SetBitrate(NRF24L01_BR_1M); //USE1MBPS_YES ? NRF24L01_BR_1M : NRF24L01_BR_250K;
}
//-------------------------------------------------------------------------------------------------
// This function generate RF TX packet address
// V977 can remember the binding parameters; we do not need rebind when power up.
// This requires the address must be repeatable for a specific RF ID at power up.
//-------------------------------------------------------------------------------------------------
static void kn_calculate_tx_addr()
{
if(sub_protocol==FEILUN)
{
uint8_t addr2;
// Generate TXID with sum of minimum 256 and maximum 256+MAX_RF_CHANNEL-32
rx_tx_addr[1] = 1 + rx_tx_addr[0] % (KN_MAX_RF_CHANNEL-33);
addr2 = 1 + rx_tx_addr[2] % (KN_MAX_RF_CHANNEL-33);
if ((uint16_t)(rx_tx_addr[0] + rx_tx_addr[1]) < 256)
rx_tx_addr[2] = addr2;
else
rx_tx_addr[2] = 0x00;
rx_tx_addr[3] = 0x00;
while((uint16_t)(rx_tx_addr[0] + rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3]) < 257)
rx_tx_addr[3] += addr2;
}
//The 5th byte is a constant, must be 'K'
rx_tx_addr[4] = 'K';
}
//-------------------------------------------------------------------------------------------------
// This function generates "random" RF hopping frequency channel numbers.
// These numbers must be repeatable for a specific seed
// The generated number range is from 0 to MAX_RF_CHANNEL. No repeat or adjacent numbers
//
// For Feilun variant, the channels are calculated from TXID, and since only 2 channels are used
// we copy them to fill up to MAX_RF_CHANNEL
//-------------------------------------------------------------------------------------------------
static void kn_calculate_freqency_hopping_channels()
{
if(sub_protocol==WLTOYS)
{
uint8_t idx = 0;
uint32_t rnd = MProtocol_id;
while (idx < KN_RF_CH_COUNT)
{
uint8_t i;
rnd = rnd * 0x0019660D + 0x3C6EF35F; // Randomization
// Use least-significant byte. 73 is prime, so channels 76..77 are unused
uint8_t next_ch = ((rnd >> 8) % KN_MAX_RF_CHANNEL) + 2;
// Keep the distance 2 between the channels - either odd or even
if (((next_ch ^ MProtocol_id) & 0x01 )== 0)
continue;
// Check that it's not duplicate and spread uniformly
for (i = 0; i < idx; i++)
if(hopping_frequency[i] == next_ch)
break;
if (i != idx)
continue;
hopping_frequency[idx++] = next_ch;
}
}
else
{//FEILUN
hopping_frequency[0] = rx_tx_addr[0] + rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3]; // - 256; ???
hopping_frequency[1] = hopping_frequency[0] + 32;
hopping_frequency[2] = hopping_frequency[0];
hopping_frequency[3] = hopping_frequency[1];
}
}
#endif

View File

@@ -0,0 +1,261 @@
/*
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/>.
*/
// compatible with MJX WLH08, X600, X800, H26D, Eachine E010
// Last sync with hexfet new_protocols/mjxq_nrf24l01.c dated 2016-01-17
#if defined(MJXQ_NRF24L01_INO)
#include "iface_nrf24l01.h"
#define MJXQ_BIND_COUNT 150
#define MJXQ_PACKET_PERIOD 4000 // Timeout for callback in uSec
#define MJXQ_INITIAL_WAIT 500
#define MJXQ_PACKET_SIZE 16
#define MJXQ_RF_NUM_CHANNELS 4
#define MJXQ_ADDRESS_LENGTH 5
// haven't figured out txid<-->rf channel mapping for MJX models
const uint8_t PROGMEM MJXQ_map_rfchan[][4] = {
{0x0A, 0x46, 0x3A, 0x42},
{0x0A, 0x3C, 0x36, 0x3F},
{0x0A, 0x43, 0x36, 0x3F} };
const uint8_t PROGMEM MJXQ_map_txid[][3] = {
{0xF8, 0x4F, 0x1C},
{0xC8, 0x6E, 0x02},
{0x48, 0x6A, 0x40} };
#define MJXQ_PAN_TILT_COUNT 16 // for H26D - match stock tx timing
#define MJXQ_PAN_DOWN 0x08
#define MJXQ_PAN_UP 0x04
#define MJXQ_TILT_DOWN 0x20
#define MJXQ_TILT_UP 0x10
static uint8_t __attribute__((unused)) MJXQ_pan_tilt_value()
{
// Servo_AUX8 PAN // H26D
// Servo_AUX9 TILT
uint8_t pan = 0;
packet_count++;
if(packet_count & MJXQ_PAN_TILT_COUNT)
{
if(Servo_data[AUX8]>PPM_MAX_COMMAND)
pan=MJXQ_PAN_UP;
if(Servo_data[AUX8]<PPM_MIN_COMMAND)
pan=MJXQ_PAN_DOWN;
if(Servo_data[AUX9]>PPM_MAX_COMMAND)
pan+=MJXQ_TILT_UP;
if(Servo_data[AUX9]<PPM_MIN_COMMAND)
pan+=MJXQ_TILT_DOWN;
}
return pan;
}
#define MJXQ_CHAN2TRIM(X) (((X) & 0x80 ? (X) : 0x7f - (X)) >> 1)
static void __attribute__((unused)) MJXQ_send_packet(uint8_t bind)
{
packet[0] = convert_channel_8b(THROTTLE);
packet[1] = convert_channel_s8b(RUDDER);
packet[4] = 0x40; // rudder does not work well with dyntrim
packet[2] = convert_channel_s8b(ELEVATOR);
packet[5] = MJXQ_CHAN2TRIM(packet[2]); // trim elevator
packet[3] = convert_channel_s8b(AILERON);
packet[6] = MJXQ_CHAN2TRIM(packet[3]); // trim aileron
packet[7] = rx_tx_addr[0];
packet[8] = rx_tx_addr[1];
packet[9] = rx_tx_addr[2];
packet[10] = 0x00; // overwritten below for feature bits
packet[11] = 0x00; // overwritten below for X600
packet[12] = 0x00;
packet[13] = 0x00;
packet[14] = 0xC0; // bind value
// Servo_AUX1 FLIP
// Servo_AUX2 LED
// Servo_AUX3 PICTURE
// Servo_AUX4 VIDEO
// Servo_AUX5 HEADLESS
// Servo_AUX6 RTH
// Servo_AUX7 AUTOFLIP // X800, X600
switch(sub_protocol)
{
case H26D:
packet[10]=MJXQ_pan_tilt_value();
// fall through on purpose - no break
case WLH08:
case E010:
packet[10] += GET_FLAG(Servo_AUX6, 0x02) //RTH
| GET_FLAG(Servo_AUX5, 0x01); //HEADLESS
if (!bind)
{
packet[14] = 0x04
| GET_FLAG(Servo_AUX1, 0x01) //FLIP
| GET_FLAG(Servo_AUX3, 0x08) //PICTURE
| GET_FLAG(Servo_AUX4, 0x10) //VIDEO
| GET_FLAG(!Servo_AUX2, 0x20); // air/ground mode
}
break;
case X600:
if(Servo_AUX5) //HEADLESS
{ // driven trims cause issues when headless is enabled
packet[5] = 0x40;
packet[6] = 0x40;
}
packet[10] = GET_FLAG(!Servo_AUX2, 0x02); //LED
packet[11] = GET_FLAG(Servo_AUX6, 0x01); //RTH
if (!bind)
{
packet[14] = 0x02 // always high rates by bit2 = 1
| GET_FLAG(Servo_AUX1, 0x04) //FLIP
| GET_FLAG(Servo_AUX7, 0x10) //AUTOFLIP
| GET_FLAG(Servo_AUX5, 0x20); //HEADLESS
}
break;
case X800:
default:
packet[10] = 0x10
| GET_FLAG(!Servo_AUX2, 0x02) //LED
| GET_FLAG(Servo_AUX7, 0x01); //AUTOFLIP
if (!bind)
{
packet[14] = 0x02 // always high rates by bit2 = 1
| GET_FLAG(Servo_AUX1, 0x04) //FLIP
| GET_FLAG(Servo_AUX3, 0x08) //PICTURE
| GET_FLAG(Servo_AUX4, 0x10); //VIDEO
}
break;
}
uint8_t sum = packet[0];
for (uint8_t i=1; i < MJXQ_PACKET_SIZE-1; i++) sum += packet[i];
packet[15] = sum;
// Power on, TX mode, 2byte CRC
if (sub_protocol == H26D)
NRF24L01_SetTxRxMode(TX_EN);
else
XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP));
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no++ / 2]);
hopping_frequency_no %= 2 * MJXQ_RF_NUM_CHANNELS; // channels repeated
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
NRF24L01_FlushTx();
if (sub_protocol == H26D)
NRF24L01_WritePayload(packet, MJXQ_PACKET_SIZE);
else
XN297_WritePayload(packet, MJXQ_PACKET_SIZE);
NRF24L01_SetPower();
}
static void __attribute__((unused)) MJXQ_init()
{
uint8_t addr[MJXQ_ADDRESS_LENGTH];
memcpy(addr, "\x6d\x6a\x77\x77\x77", MJXQ_ADDRESS_LENGTH);
if (sub_protocol == WLH08)
memcpy(hopping_frequency, "\x12\x22\x32\x42", MJXQ_RF_NUM_CHANNELS);
else
if (sub_protocol == H26D || sub_protocol == E010)
memcpy(hopping_frequency, "\x36\x3e\x46\x2e", MJXQ_RF_NUM_CHANNELS);
else
{
memcpy(hopping_frequency, "\x0a\x35\x42\x3d", MJXQ_RF_NUM_CHANNELS);
memcpy(addr, "\x6d\x6a\x73\x73\x73", MJXQ_ADDRESS_LENGTH);
}
NRF24L01_Initialize();
NRF24L01_SetTxRxMode(TX_EN);
if (sub_protocol == H26D)
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, addr, MJXQ_ADDRESS_LENGTH);
else
XN297_SetTXAddr(addr, MJXQ_ADDRESS_LENGTH);
NRF24L01_FlushTx();
NRF24L01_FlushRx();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgment on all data pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // no retransmits
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, MJXQ_PACKET_SIZE); // rx pipe 0 (used only for blue board)
if (sub_protocol == E010)
NRF24L01_SetBitrate(NRF24L01_BR_250K); // 250K
else
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower();
}
static void __attribute__((unused)) MJXQ_init2()
{
if (sub_protocol == H26D)
memcpy(hopping_frequency, "\x32\x3e\x42\x4e", MJXQ_RF_NUM_CHANNELS);
else
if (sub_protocol != WLH08 && sub_protocol != E010)
for(uint8_t i=0;i<MJXQ_RF_NUM_CHANNELS;i++)
hopping_frequency[i]=pgm_read_byte_near( &MJXQ_map_rfchan[rx_tx_addr[4]%3][i] );
}
static void __attribute__((unused)) MJXQ_initialize_txid()
{
if (sub_protocol == E010)
{
rx_tx_addr[0]=0x90;
rx_tx_addr[1]=0x1C;
rx_tx_addr[2]=0x00;
}
else
if (sub_protocol == WLH08)
rx_tx_addr[0]&=0xF8; // txid must be multiple of 8
else
for(uint8_t i=0;i<3;i++)
rx_tx_addr[i]=pgm_read_byte_near( &MJXQ_map_txid[rx_tx_addr[4]%3][i] );
}
uint16_t MJXQ_callback()
{
if(IS_BIND_DONE_on)
MJXQ_send_packet(0);
else
{
if (bind_counter == 0)
{
MJXQ_init2();
BIND_DONE;
}
else
{
bind_counter--;
MJXQ_send_packet(1);
}
}
return MJXQ_PACKET_PERIOD;
}
uint16_t initMJXQ(void)
{
BIND_IN_PROGRESS; // autobind protocol
bind_counter = MJXQ_BIND_COUNT;
MJXQ_initialize_txid();
MJXQ_init();
packet_count=0;
return MJXQ_INITIAL_WAIT+MJXQ_PACKET_PERIOD;
}
#endif

View File

@@ -0,0 +1,268 @@
/*
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/>.
*/
// compatible with MT99xx, Eachine H7, Yi Zhan i6S and LS114/124
// Last sync with Goebish mt99xx_nrf24l01.c dated 2016-01-29
#if defined(MT99XX_NRF24L01_INO)
#include "iface_nrf24l01.h"
#define MT99XX_BIND_COUNT 928
#define MT99XX_PACKET_PERIOD_MT 2625
#define MT99XX_PACKET_PERIOD_YZ 3125
#define MT99XX_INITIAL_WAIT 500
#define MT99XX_PACKET_SIZE 9
#define checksum_offset rf_ch_num
#define channel_offset phase
enum{
// flags going to packet[6] (MT99xx, H7)
FLAG_MT_RATE1 = 0x01, // (H7 high rate)
FLAG_MT_RATE2 = 0x02, // (MT9916 only)
FLAG_MT_VIDEO = 0x10,
FLAG_MT_SNAPSHOT= 0x20,
FLAG_MT_FLIP = 0x80,
};
enum{
// flags going to packet[6] (LS)
FLAG_LS_INVERT = 0x01,
FLAG_LS_RATE = 0x02,
FLAG_LS_HEADLESS= 0x10,
FLAG_LS_SNAPSHOT= 0x20,
FLAG_LS_VIDEO = 0x40,
FLAG_LS_FLIP = 0x80,
};
enum {
MT99XX_INIT = 0,
MT99XX_BIND,
MT99XX_DATA
};
const uint8_t h7_mys_byte[] = {
0x01, 0x11, 0x02, 0x12, 0x03, 0x13, 0x04, 0x14,
0x05, 0x15, 0x06, 0x16, 0x07, 0x17, 0x00, 0x10
};
static const u8 ls_mys_byte[] = {
0x05, 0x15, 0x25, 0x06, 0x16, 0x26,
0x07, 0x17, 0x27, 0x00, 0x10, 0x20,
0x01, 0x11, 0x21, 0x02, 0x12, 0x22,
0x03, 0x13, 0x23, 0x04, 0x14, 0x24
};
static void __attribute__((unused)) MT99XX_send_packet()
{
const uint8_t yz_p4_seq[] = {0xa0, 0x20, 0x60};
static uint8_t yz_seq_num=0;
static uint8_t ls_counter=0;
if(sub_protocol != YZ)
{ // MT99XX & H7 & LS
packet[0] = convert_channel_8b_scale(THROTTLE,0xE1,0x00); // throttle
packet[1] = convert_channel_8b_scale(RUDDER ,0x00,0xE1); // rudder
packet[2] = convert_channel_8b_scale(AILERON ,0xE1,0x00); // aileron
packet[3] = convert_channel_8b_scale(ELEVATOR,0x00,0xE1); // elevator
packet[4] = 0x20; // pitch trim (0x3f-0x20-0x00)
packet[5] = 0x20; // roll trim (0x00-0x20-0x3f)
packet[6] = GET_FLAG( Servo_AUX1, FLAG_MT_FLIP );
packet[7] = h7_mys_byte[hopping_frequency_no]; // next rf channel index ?
if(sub_protocol==H7)
packet[6]|=FLAG_MT_RATE1; // max rate on H7
else
if(sub_protocol==MT99)
packet[6] |= 0x40 | FLAG_MT_RATE2
| GET_FLAG( Servo_AUX3, FLAG_MT_SNAPSHOT )
| GET_FLAG( Servo_AUX4, FLAG_MT_VIDEO ); // max rate on MT99xx
else //LS
{
packet[6] |= FLAG_LS_RATE // max rate
| GET_FLAG( Servo_AUX2, FLAG_LS_INVERT ) //INVERT
| GET_FLAG( Servo_AUX3, FLAG_LS_SNAPSHOT ) //SNAPSHOT
| GET_FLAG( Servo_AUX4, FLAG_LS_VIDEO ) //VIDEO
| GET_FLAG( Servo_AUX5, FLAG_LS_HEADLESS ); //HEADLESS
packet[7] = ls_mys_byte[ls_counter++];
if(ls_counter >= sizeof(ls_mys_byte))
ls_counter=0;
}
uint8_t result=checksum_offset;
for(uint8_t i=0; i<8; i++)
result += packet[i];
packet[8] = result;
}
else
{ // YZ
packet[0] = convert_channel_8b_scale(THROTTLE,0x00,0x64); // throttle
packet[1] = convert_channel_8b_scale(RUDDER ,0x64,0x00); // rudder
packet[2] = convert_channel_8b_scale(ELEVATOR,0x00,0x64); // elevator
packet[3] = convert_channel_8b_scale(AILERON ,0x64,0x00); // aileron
if(packet_count++ >= 23)
{
yz_seq_num ++;
if(yz_seq_num > 2)
yz_seq_num = 0;
packet_count=0;
}
packet[4] = yz_p4_seq[yz_seq_num];
packet[5] = 0x02 // expert ? (0=unarmed, 1=normal)
| GET_FLAG(Servo_AUX4, 0x10) //VIDEO
| GET_FLAG(Servo_AUX1, 0x80) //FLIP
| GET_FLAG(Servo_AUX5, 0x04) //HEADLESS
| GET_FLAG(Servo_AUX3, 0x20); //SNAPSHOT
packet[6] = GET_FLAG(Servo_AUX2, 0x80); //LED
packet[7] = packet[0];
for(uint8_t idx = 1; idx < MT99XX_PACKET_SIZE-2; idx++)
packet[7] += packet[idx];
packet[8] = 0xff;
}
if(sub_protocol == LS)
NRF24L01_WriteReg(NRF24L01_05_RF_CH, 0x2D); // LS always transmits on the same channel
else
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no] + channel_offset);
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
NRF24L01_FlushTx();
XN297_WritePayload(packet, MT99XX_PACKET_SIZE);
hopping_frequency_no++;
if(sub_protocol == YZ)
hopping_frequency_no++; // skip every other channel
if(hopping_frequency_no > 15)
hopping_frequency_no = 0;
NRF24L01_SetPower();
}
static void __attribute__((unused)) MT99XX_init()
{
NRF24L01_Initialize();
if(sub_protocol == YZ)
XN297_SetScrambledMode(XN297_UNSCRAMBLED);
NRF24L01_SetTxRxMode(TX_EN);
NRF24L01_FlushTx();
XN297_SetTXAddr((uint8_t *)"\xCC\xCC\xCC\xCC\xCC", 5);
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5 bytes address
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // no auto retransmit
if(sub_protocol == YZ)
NRF24L01_SetBitrate(NRF24L01_BR_250K); // 250Kbps (nRF24L01+ only)
else
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower();
XN297_Configure(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP) );
}
static void __attribute__((unused)) MT99XX_initialize_txid()
{
rx_tx_addr[3] = 0xCC;
rx_tx_addr[4] = 0xCC;
if(sub_protocol == YZ)
{
rx_tx_addr[0] = 0x53; // test (SB id)
rx_tx_addr[1] = 0x00;
rx_tx_addr[2] = 0x00;
}
else
if(sub_protocol == LS)
rx_tx_addr[0] = 0xCC;
else //MT99 & H7
rx_tx_addr[2] = 0x00;
checksum_offset = rx_tx_addr[0] + rx_tx_addr[1] + rx_tx_addr[2];
channel_offset = (((checksum_offset & 0xf0)>>4) + (checksum_offset & 0x0f)) % 8;
}
uint16_t MT99XX_callback()
{
if(IS_BIND_DONE_on)
MT99XX_send_packet();
else
{
if (bind_counter == 0)
{
// set tx address for data packets
XN297_SetTXAddr(rx_tx_addr, 5);
BIND_DONE;
}
else
{
if(sub_protocol == LS)
NRF24L01_WriteReg(NRF24L01_05_RF_CH, 0x2D); // LS always transmits on the same channel
else
NRF24L01_WriteReg(NRF24L01_05_RF_CH, hopping_frequency[hopping_frequency_no]);
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70);
NRF24L01_FlushTx();
XN297_WritePayload(packet, MT99XX_PACKET_SIZE); // bind packet
hopping_frequency_no++;
if(sub_protocol == YZ)
hopping_frequency_no++; // skip every other channel
if(hopping_frequency_no > 15)
hopping_frequency_no = 0;
bind_counter--;
}
}
return packet_period;
}
uint16_t initMT99XX(void)
{
BIND_IN_PROGRESS; // autobind protocol
bind_counter = MT99XX_BIND_COUNT;
memcpy(hopping_frequency,"\x02\x48\x0C\x3e\x16\x34\x20\x2A\x2A\x20\x34\x16\x3e\x0c\x48\x02",16);
MT99XX_initialize_txid();
MT99XX_init();
packet[0] = 0x20;
packet_period = MT99XX_PACKET_PERIOD_MT;
switch(sub_protocol)
{ // MT99 & H7
case MT99:
case H7:
packet[1] = 0x14;
packet[2] = 0x03;
packet[3] = 0x25;
break;
case YZ:
packet_period = MT99XX_PACKET_PERIOD_YZ;
packet[1] = 0x15;
packet[2] = 0x05;
packet[3] = 0x06;
break;
case LS:
packet[1] = 0x14;
packet[2] = 0x05;
packet[3] = 0x11;
break;
}
packet[4] = rx_tx_addr[0];
packet[5] = rx_tx_addr[1];
packet[6] = rx_tx_addr[2];
packet[7] = checksum_offset; // checksum offset
packet[8] = 0xAA; // fixed
packet_count=0;
return MT99XX_INITIAL_WAIT+MT99XX_PACKET_PERIOD_MT;
}
#endif

View File

@@ -0,0 +1,624 @@
# Hey Emacs, this is a -*- makefile -*-
#----------------------------------------------------------------------------
# WinAVR Makefile
#
# On command line:
#
# make all = Make software.
#
# make clean = Clean out built project files.
#
# make coff = Convert ELF to AVR COFF.
#
# make extcoff = Convert ELF to AVR Extended COFF.
#
# make program = Download the hex file to the device, using avrdude.
# Please customize the avrdude settings below first!
#
# make debug = Start either simulavr or avarice as specified for debugging,
# with avr-gdb or avr-insight as the front end for debugging.
#
# make filename.s = Just compile filename.c into the assembler code only.
#
# make filename.i = Create a preprocessed source file for use in submitting
# bug reports to the GCC project.
#
# To rebuild project do "make clean" then "make all".
#----------------------------------------------------------------------------
# MCU name
MCU = atxmega32d4
# Processor frequency.
# This will define a symbol, F_CPU, in all source code files equal to the
# processor frequency. You can then use this symbol in your source code to
# calculate timings. Do NOT tack on a 'UL' at the end, this will be done
# automatically to create a 32-bit value in your source code.
# Typical values are:
# F_CPU = 1000000
# F_CPU = 1843200
# F_CPU = 2000000
# F_CPU = 3686400
# F_CPU = 4000000
# F_CPU = 7372800
# F_CPU = 8000000
# F_CPU = 11059200
# F_CPU = 14745600
# F_CPU = 16000000
# F_CPU = 18432000
# F_CPU = 20000000
F_CPU = 32000000
# Output format. (can be srec, ihex, binary)
FORMAT = ihex
# Target file name (without extension).
TARGET = MultiOrange
# Object files directory
# To put object files in current directory, use a dot (.), do NOT make
# this an empty or blank macro!
OBJDIR = .
# List C source files here. (C dependencies are automatically generated.)
SRC =
# List C++ source files here. (C dependencies are automatically generated.)
CPPSRC = $(TARGET).cpp
CPPSRC += Wmath.cpp
#CPPSRC += DSM2_cyrf6936.cpp
# List Assembler source files here.
# Make them always end in a capital .S. Files ending in a lowercase .s
# will not be considered source files but generated files (assembler
# output from the compiler), and will be deleted upon "make clean"!
# Even though the DOS/Win* filesystem matches both .s and .S the same,
# it will preserve the spelling of the filenames, and gcc itself does
# care about how the name is spelled on its command-line.
ASRC =
# Optimization level, can be [0, 1, 2, 3, s].
# 0 = turn off optimization. s = optimize for size.
# (Note: 3 is not always the best optimization level. See avr-libc FAQ.)
OPT = s
# Debugging format.
# Native formats for AVR-GCC's -g are dwarf-2 [default] or stabs.
# AVR Studio 4.10 requires dwarf-2.
# AVR [Extended] COFF format requires stabs, plus an avr-objcopy run.
#DEBUG = stabs
DEBUG = dwarf-2
# List any extra directories to look for include files here.
# Each directory must be seperated by a space.
# Use forward slashes for directory separators.
# For a directory that has spaces, enclose it in quotes.
EXTRAINCDIRS =
# Compiler flag to set the C Standard level.
# c89 = "ANSI" C
# gnu89 = c89 plus GCC extensions
# c99 = ISO C99 standard (not yet fully implemented)
# gnu99 = c99 plus GCC extensions
CSTANDARD = -std=gnu99
# Place -D or -U options here for C sources
CDEFS = -DF_CPU=$(F_CPU)UL
# Place -D or -U options here for ASM sources
ADEFS = -DF_CPU=$(F_CPU)
# Place -D or -U options here for C++ sources
CPPDEFS = -DF_CPU=$(F_CPU)UL
#CPPDEFS += -D__STDC_LIMIT_MACROS
#CPPDEFS += -D__STDC_CONSTANT_MACROS
#---------------- Compiler Options C ----------------
# -g*: generate debugging information
# -O*: optimization level
# -f...: tuning, see GCC manual and avr-libc documentation
# -Wall...: warning level
# -Wa,...: tell GCC to pass this to the assembler.
# -adhlns...: create assembler listing
CFLAGS = -g$(DEBUG)
CFLAGS += $(CDEFS)
CFLAGS += -O$(OPT)
CFLAGS += -funsigned-char
CFLAGS += -funsigned-bitfields
CFLAGS += -fpack-struct
CFLAGS += -fshort-enums
CFLAGS += -Wall
CFLAGS += -Wno-main
CFLAGS += -Wstrict-prototypes
#CFLAGS += -mshort-calls
#CFLAGS += -fno-unit-at-a-time
#CFLAGS += -Wundef
#CFLAGS += -Wunreachable-code
#CFLAGS += -Wsign-compare
CFLAGS += -Wa,-adlns=$(<:%.c=$(OBJDIR)/%.lst)
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
CFLAGS += $(CSTANDARD)
# Next line dumps rtl file
#CFLAGS += -dr
#CFLAGS += -Wa,-adhlns=$(<:%.c=$(OBJDIR)/%.lst)
#---------------- Compiler Options C++ ----------------
# -g*: generate debugging information
# -O*: optimization level
# -f...: tuning, see GCC manual and avr-libc documentation
# -Wall...: warning level
# -Wa,...: tell GCC to pass this to the assembler.
# -adhlns...: create assembler listing
CPPFLAGS = -g$(DEBUG)
CPPFLAGS += $(CPPDEFS)
CPPFLAGS += -O$(OPT)
CPPFLAGS += -funsigned-char
CPPFLAGS += -funsigned-bitfields
CPPFLAGS += -fpack-struct
CPPFLAGS += -fshort-enums
CPPFLAGS += -fno-exceptions
CPPFLAGS += -Wall
CFLAGS += -Wundef
#CPPFLAGS += -mshort-calls
#CPPFLAGS += -fno-unit-at-a-time
#CPPFLAGS += -Wstrict-prototypes
#CPPFLAGS += -Wunreachable-code
#CPPFLAGS += -Wsign-compare
CPPFLAGS += -Wa,-adlns=$(<:%.cpp=$(OBJDIR)/%.lst)
CPPFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
#CPPFLAGS += $(CSTANDARD)
#CPPFLAGS += -Wa,-adhlns=$(<:%.cpp=$(OBJDIR)/%.lst)
#---------------- Assembler Options ----------------
# -Wa,...: tell GCC to pass this to the assembler.
# -adhlns: create listing
# -gstabs: have the assembler create line number information; note that
# for use in COFF files, additional information about filenames
# and function names needs to be present in the assembler source
# files -- see avr-libc docs [FIXME: not yet described there]
# -listing-cont-lines: Sets the maximum number of continuation lines of hex
# dump that will be displayed for a given single line of source input.
ASFLAGS = $(ADEFS) -Wa,-adhlns=$(<:%.S=$(OBJDIR)/%.lst),-gstabs,--listing-cont-lines=100
#---------------- Library Options ----------------
# Minimalistic printf version
PRINTF_LIB_MIN = -Wl,-u,vfprintf -lprintf_min
# Floating point printf version (requires MATH_LIB = -lm below)
PRINTF_LIB_FLOAT = -Wl,-u,vfprintf -lprintf_flt
# If this is left blank, then it will use the Standard printf version.
PRINTF_LIB =
#PRINTF_LIB = $(PRINTF_LIB_MIN)
#PRINTF_LIB = $(PRINTF_LIB_FLOAT)
# Minimalistic scanf version
SCANF_LIB_MIN = -Wl,-u,vfscanf -lscanf_min
# Floating point + %[ scanf version (requires MATH_LIB = -lm below)
SCANF_LIB_FLOAT = -Wl,-u,vfscanf -lscanf_flt
# If this is left blank, then it will use the Standard scanf version.
SCANF_LIB =
#SCANF_LIB = $(SCANF_LIB_MIN)
#SCANF_LIB = $(SCANF_LIB_FLOAT)
MATH_LIB = -lm
# List any extra directories to look for libraries here.
# Each directory must be seperated by a space.
# Use forward slashes for directory separators.
# For a directory that has spaces, enclose it in quotes.
EXTRALIBDIRS =
#---------------- External Memory Options ----------------
# 64 KB of external RAM, starting after internal RAM (ATmega128!),
# used for variables (.data/.bss) and heap (malloc()).
#EXTMEMOPTS = -Wl,-Tdata=0x801100,--defsym=__heap_end=0x80ffff
# 64 KB of external RAM, starting after internal RAM (ATmega128!),
# only used for heap (malloc()).
#EXTMEMOPTS = -Wl,--section-start,.data=0x801100,--defsym=__heap_end=0x80ffff
EXTMEMOPTS =
#---------------- Linker Options ----------------
# -Wl,...: tell GCC to pass this to linker.
# -Map: create map file
# --cref: add cross reference to map file
LDFLAGS = -Wl,-Map=$(TARGET).map,--cref
LDFLAGS += $(EXTMEMOPTS)
LDFLAGS += $(patsubst %,-L%,$(EXTRALIBDIRS))
LDFLAGS += $(PRINTF_LIB) $(SCANF_LIB) $(MATH_LIB)
#LDFLAGS += -Wl,--section-start=.text=0x00D0
#LDFLAGS += -Wl,--section-start=.vectors=0x0080
#LDFLAGS += -T avr3-167.ld
LDFLAGS += -N
#---------------- Programming Options (avrdude) ----------------
# Programming hardware: alf avr910 avrisp bascom bsd
# dt006 pavr picoweb pony-stk200 sp12 stk200 stk500
#
# Type: avrdude -c ?
# to get a full listing.
#
AVRDUDE_PROGRAMMER = stk500
# com1 = serial port. Use lpt1 to connect to parallel port.
AVRDUDE_PORT = com3
AVRDUDE_WRITE_FLASH = -U flash:w:$(TARGET).hex
#AVRDUDE_WRITE_EEPROM = -U eeprom:w:$(TARGET).eep
# Uncomment the following if you want avrdude's erase cycle counter.
# Note that this counter needs to be initialized first using -Yn,
# see avrdude manual.
#AVRDUDE_ERASE_COUNTER = -y
# Uncomment the following if you do /not/ wish a verification to be
# performed after programming the device.
#AVRDUDE_NO_VERIFY = -V
# Increase verbosity level. Please use this when submitting bug
# reports about avrdude. See <http://savannah.nongnu.org/projects/avrdude>
# to submit bug reports.
#AVRDUDE_VERBOSE = -v -v
AVRDUDE_FLAGS = -p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER)
AVRDUDE_FLAGS += $(AVRDUDE_NO_VERIFY)
AVRDUDE_FLAGS += $(AVRDUDE_VERBOSE)
AVRDUDE_FLAGS += $(AVRDUDE_ERASE_COUNTER)
#---------------- Debugging Options ----------------
# For simulavr only - target MCU frequency.
DEBUG_MFREQ = $(F_CPU)
# Set the DEBUG_UI to either gdb or insight.
# DEBUG_UI = gdb
DEBUG_UI = insight
# Set the debugging back-end to either avarice, simulavr.
DEBUG_BACKEND = avarice
#DEBUG_BACKEND = simulavr
# GDB Init Filename.
GDBINIT_FILE = __avr_gdbinit
# When using avarice settings for the JTAG
JTAG_DEV = /dev/com1
# Debugging port used to communicate between GDB / avarice / simulavr.
DEBUG_PORT = 4242
# Debugging host used to communicate between GDB / avarice / simulavr, normally
# just set to localhost unless doing some sort of crazy debugging when
# avarice is running on a different computer.
DEBUG_HOST = localhost
#============================================================================
# Define programs and commands.
SHELL = sh
CC = avr-gcc
OBJCOPY = avr-objcopy
OBJDUMP = avr-objdump
SIZE = avr-size
AR = avr-ar rcs
NM = avr-nm
AVRDUDE = avrdude
REMOVE = rm -f
REMOVEDIR = rm -rf
COPY = cp
WINSHELL = cmd
# Define Messages
# English
MSG_ERRORS_NONE = Errors: none
MSG_BEGIN = -------- begin --------
MSG_END = -------- end --------
MSG_SIZE_BEFORE = Size before:
MSG_SIZE_AFTER = Size after:
MSG_COFF = Converting to AVR COFF:
MSG_EXTENDED_COFF = Converting to AVR Extended COFF:
MSG_FLASH = Creating load file for Flash:
MSG_EEPROM = Creating load file for EEPROM:
MSG_EXTENDED_LISTING = Creating Extended Listing:
MSG_SYMBOL_TABLE = Creating Symbol Table:
MSG_LINKING = Linking:
MSG_COMPILING = Compiling C:
MSG_COMPILING_CPP = Compiling C++:
MSG_ASSEMBLING = Assembling:
MSG_CLEANING = Cleaning project:
MSG_CREATING_LIBRARY = Creating library:
# Define all object files.
OBJ = $(SRC:%.c=$(OBJDIR)/%.o) $(CPPSRC:%.cpp=$(OBJDIR)/%.o) $(ASRC:%.S=$(OBJDIR)/%.o)
# Define all listing files.
LST = $(SRC:%.c=$(OBJDIR)/%.lst) $(CPPSRC:%.cpp=$(OBJDIR)/%.lst) $(ASRC:%.S=$(OBJDIR)/%.lst)
# Compiler flags to generate dependency files.
GENDEPFLAGS = -MMD -MP -MF .dep/$(@F).d
# Combine all necessary flags and optional flags.
# Add target processor to flags.
ALL_CFLAGS = -mmcu=$(MCU) -I. $(CFLAGS) $(GENDEPFLAGS)
ALL_CPPFLAGS = -mmcu=$(MCU) -I. -x c++ $(CPPFLAGS) $(GENDEPFLAGS)
ALL_ASFLAGS = -mmcu=$(MCU) -I. -x assembler-with-cpp $(ASFLAGS)
# Default target.
all: begin gccversion sizebefore build sizeafter end
# Change the build target to build a HEX file or a library.
build: elf hex eep lss sym bin
#build: lib
elf: $(TARGET).elf
hex: $(TARGET).hex
bin: $(TARGET).bin
eep: $(TARGET).eep
lss: $(TARGET).lss
sym: $(TARGET).sym
LIBNAME=lib$(TARGET).a
lib: $(LIBNAME)
# Eye candy.
# AVR Studio 3.x does not check make's exit code but relies on
# the following magic strings to be generated by the compile job.
begin:
@echo
@echo $(MSG_BEGIN)
end:
@echo $(MSG_END)
@echo
# Display size of file.
HEXSIZE = $(SIZE) --target=$(FORMAT) $(TARGET).hex
ELFSIZE = $(SIZE) --mcu=$(MCU) --format=avr $(TARGET).elf
sizebefore:
@if test -f $(TARGET).elf; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); \
2>/dev/null; echo; fi
sizeafter:
@if test -f $(TARGET).elf; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); \
2>/dev/null; echo; fi
# Display compiler version information.
gccversion :
@$(CC) --version
# Program the device.
program: $(TARGET).hex $(TARGET).eep
$(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH) $(AVRDUDE_WRITE_EEPROM)
# Generate avr-gdb config/init file which does the following:
# define the reset signal, load the target file, connect to target, and set
# a breakpoint at main().
gdb-config:
@$(REMOVE) $(GDBINIT_FILE)
@echo define reset >> $(GDBINIT_FILE)
@echo SIGNAL SIGHUP >> $(GDBINIT_FILE)
@echo end >> $(GDBINIT_FILE)
@echo file $(TARGET).elf >> $(GDBINIT_FILE)
@echo target remote $(DEBUG_HOST):$(DEBUG_PORT) >> $(GDBINIT_FILE)
ifeq ($(DEBUG_BACKEND),simulavr)
@echo load >> $(GDBINIT_FILE)
endif
@echo break main >> $(GDBINIT_FILE)
debug: gdb-config $(TARGET).elf
ifeq ($(DEBUG_BACKEND), avarice)
@echo Starting AVaRICE - Press enter when "waiting to connect" message displays.
@$(WINSHELL) /c start avarice --jtag $(JTAG_DEV) --erase --program --file \
$(TARGET).elf $(DEBUG_HOST):$(DEBUG_PORT)
@$(WINSHELL) /c pause
else
@$(WINSHELL) /c start simulavr --gdbserver --device $(MCU) --clock-freq \
$(DEBUG_MFREQ) --port $(DEBUG_PORT)
endif
@$(WINSHELL) /c start avr-$(DEBUG_UI) --command=$(GDBINIT_FILE)
# Convert ELF to COFF for use in debugging / simulating in AVR Studio or VMLAB.
COFFCONVERT = $(OBJCOPY) --debugging
COFFCONVERT += --change-section-address .data-0x800000
COFFCONVERT += --change-section-address .bss-0x800000
COFFCONVERT += --change-section-address .noinit-0x800000
COFFCONVERT += --change-section-address .eeprom-0x810000
coff: $(TARGET).elf
@echo
@echo $(MSG_COFF) $(TARGET).cof
$(COFFCONVERT) -O coff-avr $< $(TARGET).cof
extcoff: $(TARGET).elf
@echo
@echo $(MSG_EXTENDED_COFF) $(TARGET).cof
$(COFFCONVERT) -O coff-ext-avr $< $(TARGET).cof
# Create final output files (.hex, .eep) from ELF output file.
%.hex: %.elf
@echo
@echo $(MSG_FLASH) $@
$(OBJCOPY) -O $(FORMAT) -R .eeprom $< $@
%.bin: %.elf
$(OBJCOPY) -O binary $< $@
%.eep: %.elf
@echo
@echo $(MSG_EEPROM) $@
-$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \
--change-section-lma .eeprom=0 --no-change-warnings -O $(FORMAT) $< $@ || exit 0
# Create extended listing file from ELF output file.
%.lss: %.elf
@echo
@echo $(MSG_EXTENDED_LISTING) $@
$(OBJDUMP) -h -S $< > $@
# Create a symbol table from ELF output file.
%.sym: %.elf
@echo
@echo $(MSG_SYMBOL_TABLE) $@
$(NM) -n $< > $@
# Create library from object files.
.SECONDARY : $(TARGET).a
.PRECIOUS : $(OBJ)
%.a: $(OBJ)
@echo
@echo $(MSG_CREATING_LIBRARY) $@
$(AR) $@ $(OBJ)
# Link: create ELF output file from object files.
.SECONDARY : $(TARGET).elf
.PRECIOUS : $(OBJ)
%.elf: $(OBJ)
@echo
@echo $(MSG_LINKING) $@
$(CC) $(ALL_CFLAGS) $^ --output $@ $(LDFLAGS)
# Compile: create object files from C source files.
$(OBJDIR)/%.o : %.c
@echo
@echo $(MSG_COMPILING) $<
$(CC) -c $(ALL_CFLAGS) $< -o $@
# Compile: create object files from C++ source files.
$(OBJDIR)/%.o : %.cpp
@echo
@echo $(MSG_COMPILING_CPP) $<
$(CC) -c $(ALL_CPPFLAGS) $< -o $@
# Compile: create assembler files from C source files.
%.s : %.c
$(CC) -S $(ALL_CFLAGS) $< -o $@
# Compile: create assembler files from C++ source files.
%.s : %.cpp
$(CC) -S $(ALL_CPPFLAGS) $< -o $@
# Assemble: create object files from assembler source files.
$(OBJDIR)/%.o : %.S
@echo
@echo $(MSG_ASSEMBLING) $<
$(CC) -c $(ALL_ASFLAGS) $< -o $@
# Create preprocessed source for use in sending a bug report.
%.i : %.c
$(CC) -E -mmcu=$(MCU) -I. $(CFLAGS) $< -o $@
# Target: clean project.
clean: begin clean_list end
clean_list :
@echo
@echo $(MSG_CLEANING)
$(REMOVE) $(TARGET).hex
$(REMOVE) $(TARGET).eep
$(REMOVE) $(TARGET).cof
$(REMOVE) $(TARGET).elf
$(REMOVE) $(TARGET).map
$(REMOVE) $(TARGET).sym
$(REMOVE) $(TARGET).lss
$(REMOVE) $(SRC:%.c=$(OBJDIR)/%.o)
$(REMOVE) $(SRC:%.c=$(OBJDIR)/%.lst)
$(REMOVE) $(SRC:.c=.s)
$(REMOVE) $(SRC:.c=.d)
$(REMOVE) $(SRC:.c=.i)
$(REMOVEDIR) .dep
# Create object files directory
$(shell mkdir $(OBJDIR) 2>/dev/null)
# Include the dependency files.
-include $(shell mkdir .dep 2>/dev/null) $(wildcard .dep/*)
# Listing of phony targets.
.PHONY : all begin finish end sizebefore sizeafter gccversion \
build elf hex eep lss sym coff extcoff \
clean clean_list program debug gdb-config

View File

@@ -0,0 +1,480 @@
#define ARDUINO_AVR_PRO 1
//#define __AVR_ATmega328P__ 1
#define XMEGA 1
#include <stdlib.h>
#include <string.h>
#include <avr/interrupt.h>
static void protocol_init(void) ;
static void update_aux_flags(void) ;
static void PPM_Telemetry_serial_init(void) ;
static uint32_t random_id(uint16_t adress, uint8_t create_new) ;
static void update_serial_data(void) ;
static void Mprotocol_serial_init(void) ;
static void module_reset(void) ;
static void update_led_status(void) ;
static void set_rx_tx_addr(uint32_t id) ;
uint16_t limit_channel_100(uint8_t ch) ;
void initTXSerial( uint8_t speed);
void Serial_write(uint8_t data);
extern void NRF24L01_Reset(void ) ;
extern void A7105_Reset(void ) ;
extern void CC2500_Reset(void ) ;
extern uint8_t CYRF_Reset(void ) ;
extern void CYRF_SetTxRxMode(uint8_t mode) ;
extern void frskyUpdate(void) ;
extern uint16_t initDsm2(void) ;
extern uint16_t ReadDsm2(void) ;
extern uint16_t DevoInit(void) ;
extern uint16_t devo_callback(void) ;
extern void randomSeed(unsigned int seed) ;
extern long random(long howbig) ;
extern long map(long x, long in_min, long in_max, long out_min, long out_max) ;
extern uint32_t millis(void) ;
extern uint32_t micros(void) ;
extern void delayMicroseconds(uint16_t x) ;
extern void init(void) ;
extern int analogRead(uint8_t pin) ;
#define A6 20
#define A7 21
#define yield()
//void _delay_us( uint16_t x )
//{
// delayMicroseconds( x ) ;
//}
#define clockCyclesPerMicrosecond() ( F_CPU / 1000000L )
#define clockCyclesToMicroseconds(a) ( (a) / clockCyclesPerMicrosecond() )
// the prescaler is set so that timer0 ticks every 64 clock cycles, and the
// the overflow handler is called every 256 ticks.
#define MICROSECONDS_PER_TIMER0_OVERFLOW (clockCyclesToMicroseconds(64 * 256))
// the whole number of milliseconds per timer0 overflow
#define MILLIS_INC (MICROSECONDS_PER_TIMER0_OVERFLOW / 1000)
// the fractional number of milliseconds per timer0 overflow. we shift right
// by three to fit these numbers into a byte. (for the clock speeds we care
// about - 8 and 16 MHz - this doesn't lose precision.)
#define FRACT_INC ((MICROSECONDS_PER_TIMER0_OVERFLOW % 1000) >> 3)
#define FRACT_MAX (1000 >> 3)
volatile unsigned long timer0_overflow_count = 0;
volatile unsigned long timer0_millis = 0;
static unsigned char timer0_fract = 0;
//void chipInit()
//{
// PR.PRGEN = 0 ; // RTC and event system active
// PR.PRPC = 0 ; // No power reduction port C
// PR.PRPD = 0 ; // No power reduction port D
// PMIC.CTRL = 7 ;
// OSC.CTRL = 0xC3 ; // unclear
// OSC.CTRL |= 0x08 ; // Enable external oscillator
// while( ( OSC.STATUS & 0x08 ) == 0 ) ; // Wait for ext osc to be ready
// OSC.PLLCTRL = 0xC2 ; // Ext. Osc times 2
// OSC.CTRL |= 0x10 ; // Enable PLL
// while( ( OSC.STATUS & 0x10 ) == 0 ) ; // Wait PLL ready
// CPU_CCP = 0xD8 ; // 0x34
// CLK.CTRL = 0 ; // Select 2MHz internal clock
// CPU_CCP = 0xD8 ; // 0x34
// CLK.CTRL = 0x04 ; // Select PLL as clock (32MHz)
// PORTD.OUTSET = 0x17 ;
// PORTD.DIRSET = 0xB2 ;
// PORTD.DIRCLR = 0x4D ;
// PORTD.PIN0CTRL = 0x18 ;
// PORTD.PIN2CTRL = 0x18 ;
// PORTE.DIRSET = 0x01 ;
// PORTE.DIRCLR = 0x02 ;
// PORTE.OUTSET = 0x01 ;
// PORTA.DIRCLR = 0xFF ;
// PORTA.PIN0CTRL = 0x18 ;
// PORTA.PIN1CTRL = 0x18 ;
// PORTA.PIN2CTRL = 0x18 ;
// PORTA.PIN3CTRL = 0x18 ;
// PORTA.PIN4CTRL = 0x18 ;
// PORTA.PIN5CTRL = 0x18 ;
// PORTA.PIN6CTRL = 0x18 ;
// PORTA.PIN7CTRL = 0x18 ;
// PORTC.DIRSET = 0x20 ;
// PORTC.OUTCLR = 0x20 ;
// SPID.CTRL = 0x51 ;
// PORTC.OUTSET = 0x08 ;
// PORTC.DIRSET = 0x08 ;
// PORTC.PIN3CTRL = 0x18 ;
// PORTC.PIN2CTRL = 0x18 ;
// USARTC0.BAUDCTRLA = 19 ;
// USARTC0.BAUDCTRLB = 0 ;
// USARTC0.CTRLB = 0x18 ;
// USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ;
// USARTC0.CTRLC = 0x03 ;
// TCC0.CTRLB = 0 ;
// TCC0.CTRLC = 0 ;
// TCC0.CTRLD = 0 ;
// TCC0.CTRLE = 0 ;
// TCC0.INTCTRLA = 0x01 ;
// TCC0.INTCTRLB = 0 ;
// TCC0.PER = 0x00FF ;
// TCC0.CTRLA = 4 ;
// TCC1.CTRLB = 0 ;
// TCC1.CTRLC = 0 ;
// TCC1.CTRLD = 0 ;
// TCC1.CTRLE = 0 ;
// TCC1.INTCTRLA = 0x03 ;
// TCC1.INTCTRLB = 0 ;
// TCC1.PER = 0xFFFF ;
// TCC1.CNT = 0 ;
// TCC1.CTRLA = 4 ;
// TCD0.CTRLA = 4 ;
// TCD0.INTCTRLA = 0x03 ;
// TCD0.PER = 0x02ED ;
//// L0EDB() ;
// NVM.CTRLB &= 0xF7 ; // No EEPROM mapping
//}
ISR(TCC0_OVF_vect)
{
// copy these to local variables so they can be stored in registers
// (volatile variables must be read from memory on every access)
unsigned long m = timer0_millis;
unsigned char f = timer0_fract;
m += MILLIS_INC;
f += FRACT_INC;
if (f >= FRACT_MAX) {
f -= FRACT_MAX;
m += 1;
}
timer0_fract = f;
timer0_millis = m;
timer0_overflow_count++;
}
unsigned long millis()
{
unsigned long m;
uint8_t oldSREG = SREG;
// disable interrupts while we read timer0_millis or we might get an
// inconsistent value (e.g. in the middle of a write to timer0_millis)
cli();
m = timer0_millis;
SREG = oldSREG;
return m;
}
unsigned long micros()
{
unsigned long m;
uint8_t oldSREG = SREG, t;
cli();
m = timer0_overflow_count;
t = TCC0.CNT ;
if ((TCC0.INTFLAGS & TC0_OVFIF_bm) && (t < 255))
m++;
SREG = oldSREG;
return ((m << 8) + t) * (64 / clockCyclesPerMicrosecond());
}
void delayMilliseconds(unsigned long ms)
{
uint16_t start = (uint16_t)micros();
while (ms > 0) {
yield();
if (((uint16_t)micros() - start) >= 1000) {
ms--;
start += 1000;
}
}
}
/* Delay for the given number of microseconds. Assumes a 8 or 16 MHz clock. */
void delayMicroseconds(unsigned int us)
{
// calling avrlib's delay_us() function with low values (e.g. 1 or
// 2 microseconds) gives delays longer than desired.
//delay_us(us);
#if F_CPU >= 20000000L
// for the 20 MHz clock on rare Arduino boards
// for a one-microsecond delay, simply wait 2 cycle and return. The overhead
// of the function call yields a delay of exactly a one microsecond.
__asm__ __volatile__ (
"nop" "\n\t"
"nop"); //just waiting 2 cycle
if (--us == 0)
return;
// the following loop takes a 1/5 of a microsecond (4 cycles)
// per iteration, so execute it five times for each microsecond of
// delay requested.
us = (us<<2) + us; // x5 us
// account for the time taken in the preceeding commands.
us -= 2;
#elif F_CPU >= 16000000L
// for the 16 MHz clock on most Arduino boards
// for a one-microsecond delay, simply return. the overhead
// of the function call yields a delay of approximately 1 1/8 us.
if (--us == 0)
return;
// the following loop takes a quarter of a microsecond (4 cycles)
// per iteration, so execute it four times for each microsecond of
// delay requested.
us <<= 2;
// account for the time taken in the preceeding commands.
us -= 2;
#else
// for the 8 MHz internal clock on the ATmega168
// for a one- or two-microsecond delay, simply return. the overhead of
// the function calls takes more than two microseconds. can't just
// subtract two, since us is unsigned; we'd overflow.
if (--us == 0)
return;
if (--us == 0)
return;
// the following loop takes half of a microsecond (4 cycles)
// per iteration, so execute it twice for each microsecond of
// delay requested.
us <<= 1;
// partially compensate for the time taken by the preceeding commands.
// we can't subtract any more than this or we'd overflow w/ small delays.
us--;
#endif
// busy wait
__asm__ __volatile__ (
"1: sbiw %0,1" "\n\t" // 2 cycles
"brne 1b" : "=w" (us) : "0" (us) // 2 cycles
);
}
#ifndef cbi
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
#endif
#ifndef sbi
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
#endif
void init()
{
// this needs to be called before setup() or some functions won't
// work there
// Enable external oscillator (16MHz)
OSC.XOSCCTRL = OSC_FRQRANGE_12TO16_gc | OSC_XOSCSEL_XTAL_256CLK_gc ;
OSC.CTRL |= OSC_XOSCEN_bm ;
while( ( OSC.STATUS & OSC_XOSCRDY_bm ) == 0 )
/* wait */ ;
// Enable PLL (*2 = 32MHz)
OSC.PLLCTRL = OSC_PLLSRC_XOSC_gc | 2 ;
OSC.CTRL |= OSC_PLLEN_bm ;
while( ( OSC.STATUS & OSC_PLLRDY_bm ) == 0 )
/* wait */ ;
// Switch to PLL clock
CPU_CCP = 0xD8 ;
CLK.CTRL = CLK_SCLKSEL_RC2M_gc ;
CPU_CCP = 0xD8 ;
CLK.CTRL = CLK_SCLKSEL_PLL_gc ;
PMIC.CTRL = 7 ; // Enable all interrupt levels
sei();
// on the ATmega168, timer 0 is also used for fast hardware pwm
// (using phase-correct PWM would mean that timer 0 overflowed half as often
// resulting in different millis() behavior on the ATmega8 and ATmega168)
//#if defined(TCCR0A) && defined(WGM01)
// sbi(TCCR0A, WGM01);
// sbi(TCCR0A, WGM00);
//#endif
// TCC0 counts 0-255 at 4uS clock rate
EVSYS.CH2MUX = 0x80 + 0x07 ; // Prescaler of 128
TCC0.CTRLB = 0 ;
TCC0.CTRLC = 0 ;
TCC0.CTRLD = 0 ;
TCC0.CTRLE = 0 ;
TCC0.INTCTRLA = 0x01 ;
TCC0.INTCTRLB = 0 ;
TCC0.PER = 0x00FF ;
TCC0.CTRLA = 0x0A ;
#if defined(ADCSRA)
// set a2d prescale factor to 128
// 16 MHz / 128 = 125 KHz, inside the desired 50-200 KHz range.
// XXX: this will not work properly for other clock speeds, and
// this code should use F_CPU to determine the prescale factor.
sbi(ADCSRA, ADPS2);
sbi(ADCSRA, ADPS1);
sbi(ADCSRA, ADPS0);
// enable a2d conversions
sbi(ADCSRA, ADEN);
#endif
// the bootloader connects pins 0 and 1 to the USART; disconnect them
// here so they can be used as normal digital i/o; they will be
// reconnected in Serial.begin()
#if defined(UCSRB)
UCSRB = 0;
#elif defined(UCSR0B)
UCSR0B = 0;
#endif
// PPM interrupt
PORTD.DIRCLR = 0x08 ; // D3 is input
PORTD.PIN3CTRL = 0x01 ; // Rising edge
PORTD.INT0MASK = 0x08 ;
PORTD.INTCTRL = 0x02 ; // Medium level interrupt
// Dip Switch inputs
PORTA.DIRCLR = 0xFF ;
PORTA.PIN0CTRL = 0x18 ;
PORTA.PIN1CTRL = 0x18 ;
PORTA.PIN2CTRL = 0x18 ;
PORTA.PIN3CTRL = 0x18 ;
PORTA.PIN4CTRL = 0x18 ;
PORTA.PIN5CTRL = 0x18 ;
PORTA.PIN6CTRL = 0x18 ;
PORTA.PIN7CTRL = 0x18 ;
}
#define DEFAULT 1
uint8_t analog_reference = DEFAULT;
void analogReference(uint8_t mode)
{
// can't actually set the register here because the default setting
// will connect AVCC and the AREF pin, which would cause a short if
// there's something connected to AREF.
analog_reference = mode;
}
int analogRead(uint8_t pin)
{
uint8_t low, high;
#if defined(analogPinToChannel)
#if defined(__AVR_ATmega32U4__)
if (pin >= 18) pin -= 18; // allow for channel or pin numbers
#endif
pin = analogPinToChannel(pin);
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
if (pin >= 54) pin -= 54; // allow for channel or pin numbers
#elif defined(__AVR_ATmega32U4__)
if (pin >= 18) pin -= 18; // allow for channel or pin numbers
#elif defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega644__) || defined(__AVR_ATmega644A__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__)
if (pin >= 24) pin -= 24; // allow for channel or pin numbers
#else
if (pin >= 14) pin -= 14; // allow for channel or pin numbers
#endif
#if defined(ADCSRB) && defined(MUX5)
// the MUX5 bit of ADCSRB selects whether we're reading from channels
// 0 to 7 (MUX5 low) or 8 to 15 (MUX5 high).
ADCSRB = (ADCSRB & ~(1 << MUX5)) | (((pin >> 3) & 0x01) << MUX5);
#endif
// set the analog reference (high two bits of ADMUX) and select the
// channel (low 4 bits). this also sets ADLAR (left-adjust result)
// to 0 (the default).
#if defined(ADMUX)
ADMUX = (analog_reference << 6) | (pin & 0x07);
#endif
// without a delay, we seem to read from the wrong channel
//delayMilliseconds(1);
#if defined(ADCSRA) && defined(ADCL)
// start the conversion
sbi(ADCSRA, ADSC);
// ADSC is cleared when the conversion finishes
while (bit_is_set(ADCSRA, ADSC));
// we have to read ADCL first; doing so locks both ADCL
// and ADCH until ADCH is read. reading ADCL second would
// cause the results of each conversion to be discarded,
// as ADCL and ADCH would be locked when it completed.
low = ADCL;
high = ADCH;
#else
// we dont have an ADC, return 0
low = 0;
high = 0;
#endif
// combine the two bytes
return (high << 8) | low;
}
void A7105_Reset()
{
}
void CC2500_Reset()
{
}
void NRF24L01_Reset()
{
}
#include "Multiprotocol.ino"
#include "cyrf6936_SPI.ino"
#include "DSM2_cyrf6936.ino"
#include "Devo_cyrf6936.ino"
#include "Telemetry.ino"
int main(void)
{
init() ;
setup() ;
for(;;)
{
loop() ;
}
}

View File

@@ -0,0 +1,610 @@
/*
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/>.
*/
// Check selected board type
#ifndef XMEGA
#if not defined(ARDUINO_AVR_PRO) && not defined(ARDUINO_AVR_MINI)
#error You must select the board type "Arduino Pro or Pro Mini" or "Arduino Mini"
#endif
#if F_CPU != 16000000L || not defined(__AVR_ATmega328P__)
#error You must select the processor type "ATmega328(5V, 16MHz)"
#endif
#endif
//******************
// Protocols
//******************
enum PROTOCOLS
{
MODE_SERIAL = 0, // Serial commands
MODE_FLYSKY = 1, // =>A7105
MODE_HUBSAN = 2, // =>A7105
MODE_FRSKYD = 3, // =>CC2500
MODE_HISKY = 4, // =>NRF24L01
MODE_V2X2 = 5, // =>NRF24L01
MODE_DSM = 6, // =>CYRF6936
MODE_DEVO = 7, // =>CYRF6936
MODE_YD717 = 8, // =>NRF24L01
MODE_KN = 9, // =>NRF24L01
MODE_SYMAX = 10, // =>NRF24L01
MODE_SLT = 11, // =>NRF24L01
MODE_CX10 = 12, // =>NRF24L01
MODE_CG023 = 13, // =>NRF24L01
MODE_BAYANG = 14, // =>NRF24L01
MODE_FRSKYX = 15, // =>CC2500
MODE_ESKY = 16, // =>NRF24L01
MODE_MT99XX = 17, // =>NRF24L01
MODE_MJXQ = 18, // =>NRF24L01
MODE_SHENQI = 19, // =>NRF24L01
MODE_FY326 = 20, // =>NRF24L01
MODE_SFHSS = 21, // =>CC2500
MODE_J6PRO = 22, // =>CYRF6936
MODE_FQ777 = 23, // =>NRF24L01
MODE_ASSAN = 24, // =>NRF24L01
MODE_FRSKYV = 25 // =>CC2500
};
enum Flysky
{
Flysky = 0,
V9X9 = 1,
V6X6 = 2,
V912 = 3
};
enum Hisky
{
Hisky = 0,
HK310 = 1
};
enum DSM
{
DSM2 = 0,
DSMX = 1
};
enum YD717
{
YD717 = 0,
SKYWLKR = 1,
SYMAX4 = 2,
XINXUN = 3,
NIHUI = 4
};
enum KN
{
WLTOYS = 0,
FEILUN = 1
};
enum SYMAX
{
SYMAX = 0,
SYMAX5C = 1
};
enum CX10
{
CX10_GREEN = 0,
CX10_BLUE = 1, // also compatible with CX10-A, CX12
DM007 = 2,
Q282 = 3,
JC3015_1 = 4,
JC3015_2 = 5,
MK33041 = 6,
Q242 = 7
};
enum CG023
{
CG023 = 0,
YD829 = 1,
H8_3D = 2
};
enum MT99XX
{
MT99 = 0,
H7 = 1,
YZ = 2,
LS = 3
};
enum MJXQ
{
WLH08 = 0,
X600 = 1,
X800 = 2,
H26D = 3,
E010 = 4
};
enum FRSKYX
{
CH_16 = 0,
CH_8 = 1,
};
#define NONE 0
#define P_HIGH 1
#define P_LOW 0
#define AUTOBIND 1
#define NO_AUTOBIND 0
struct PPM_Parameters
{
uint8_t protocol : 5;
uint8_t sub_proto : 3;
uint8_t rx_num : 4;
uint8_t power : 1;
uint8_t autobind : 1;
uint8_t option;
};
//*******************
//*** Timer ***
//*******************
#ifdef XMEGA
#define TIFR1 TCC1.INTFLAGS
#define OCF1A_bm TC1_CCAIF_bm
#define OCR1A TCC1.CCA
#define TCNT1 TCC1.CNT
#define USARTC0.DATA UDR0
#define OCF1B_bm TC1_CCBIF_bm
#define OCR1B TCC1.CCB
#define TCC1.INTCTRLB TIMSK1
#define SET_TIMSK1_OCIE1B TIMSK1 = (TIMSK1 & 0xF3) | 0x04
#define CLR_TIMSK1_OCIE1B TIMSK1 &= 0xF3
#else
#define OCF1A_bm _BV(OCF1A)
#define OCF1B_bm _BV(OCF1B)
#define SET_TIMSK1_OCIE1B TIMSK1 |= _BV(OCIE1B)
#define CLR_TIMSK1_OCIE1B TIMSK1 &=~_BV(OCIE1B)
#endif
//*******************
//*** Pinouts ***
//*******************
#define LED_pin 5 //D13 = PB5
#define BIND_pin 5 //D13 = PB5
#define PPM_pin 3 //D3 = PD3
#ifdef XMEGA
#define SDI_pin 6 //SDIO-D6
#else
#define SDI_pin 5 //D5 = PD5
#endif
#define SCLK_pin 4 //D4 = PD4
#define A7105_CS_pin 2 //D2 = PD2
#define SDO_pin 6 //D6 = PD6
#define CC25_CSN_pin 7 //D7 = PD7
#define NRF_CSN_pin 0 //D8 = PB0
#define CYRF_CSN_pin 1 //D9 = PB1
#define CTRL1_pin 1 //A1 = PC1
#define CTRL2_pin 2 //A2 = PC2
//
#ifdef XMEGA
#define CTRL1_on
#define CTRL1_off
#define CTRL2_on
#define CTRL2_off
#else
#define CTRL1_on PORTC |= _BV(1)
#define CTRL1_off PORTC &= ~_BV(1)
#define CTRL2_on PORTC |= _BV(2)
#define CTRL2_off PORTC &= ~_BV(2)
#endif
//
#ifdef XMEGA
#define A7105_CS_on PORTD.OUTSET = _BV(4) //D4
#define A7105_CS_off PORTD.OUTCLR = _BV(4) //D4
#else
#define A7105_CS_on PORTD |= _BV(2) //D2
#define A7105_CS_off PORTD &= ~_BV(2) //D2
#endif
//
#ifdef XMEGA
#define SCK_on PORTD.OUTSET = _BV(7) //D7
#define SCK_off PORTD.OUTCLR = _BV(7) //D7
#else
#define SCK_on PORTD |= _BV(4) //D4
#define SCK_off PORTD &= ~_BV(4) //D4
#endif
//
#ifdef XMEGA
#define SDI_on PORTD.OUTSET = _BV(5) //D5
#define SDI_off PORTD.OUTCLR = _BV(5) //D5
#else
#define SDI_on PORTD |= _BV(5) //D5
#define SDI_off PORTD &= ~_BV(5) //D5
#endif
//
#ifdef XMEGA
#define SDI_1 (PORTD.IN & _BV(SDI_pin)) == _BV(SDI_pin) //D5
#define SDI_0 (PORTD.IN & _BV(SDI_pin)) == 0x00 //D5
#else
#define SDI_1 (PIND & _BV(SDI_pin)) == _BV(SDI_pin) //D5
#define SDI_0 (PIND & _BV(SDI_pin)) == 0x00 //D5
#endif
//
#define SDI_SET_INPUT DDRD &= ~_BV(5) //D5
#define SDI_SET_OUTPUT DDRD |= _BV(5) //D5
//
#ifdef XMEGA
#define CC25_CSN_on PORTD.OUTSET = _BV(7) //D7
#define CC25_CSN_off PORTD.OUTCLR = _BV(7) //D7
#else
#define CC25_CSN_on PORTD |= _BV(7) //D7
#define CC25_CSN_off PORTD &= ~_BV(7) //D7
#endif
//
#ifdef XMEGA
#define NRF_CSN_on
#define NRF_CSN_off
#define NRF_CE_on
#define NRF_CE_off
#else
#define NRF_CSN_on PORTB |= _BV(0) //D8
#define NRF_CSN_off PORTB &= ~_BV(0) //D8
#define NRF_CE_on
#define NRF_CE_off
#endif
//
#ifdef XMEGA
#define CYRF_CSN_on PORTD.OUTSET = _BV(4)
#define CYRF_CSN_off PORTD.OUTCLR = _BV(4)
#else
#define CYRF_CSN_on PORTB |= _BV(1) //D9
#define CYRF_CSN_off PORTB &= ~_BV(1) //D9
#define CYRF_RST_HI PORTC |= _BV(5) //A5
#define CYRF_RST_LO PORTC &= ~_BV(5) //A5
#define CYRF_RST_pin 5
#endif
//
#ifdef XMEGA
#define SDO_1 (PORTD.IN & _BV(SDO_pin)) == _BV(SDO_pin) //D6
#define SDO_0 (PORTD.IN & _BV(SDO_pin)) == 0x00 //D6
#else
#define SDO_1 (PIND & _BV(SDO_pin)) == _BV(SDO_pin) //D6
#define SDO_0 (PIND & _BV(SDO_pin)) == 0x00 //D6
#endif
//
//
// LED
#ifdef XMEGA
#define LED_ON PORTD.OUTCLR = _BV(1)
#define LED_OFF PORTD.OUTSET = _BV(1)
#define LED_TOGGLE PORTD.OUTTGL = _BV(1)
#define LED_SET_OUTPUT PORTD.DIRSET = _BV(1)
#define IS_LED_on ( (PORTD.OUT & _BV(1)) != 0x00 )
#else
#define LED_ON PORTB |= _BV(5)
#define LED_OFF PORTB &= ~_BV(5)
#define LED_TOGGLE PORTB ^= _BV(5)
#define LED_SET_OUTPUT DDRB |= _BV(5)
#define IS_LED_on ( (PORTB & _BV(5)) != 0x00 )
#endif
//BIND
#ifdef XMEGA
#define IS_BIND_BUTTON_on ( (PORTD.IN & _BV(2)) == 0x00 )
#else
#define BIND_SET_INPUT DDRB &= ~_BV(5)
#define BIND_SET_PULLUP PORTB |= _BV(5)
#define IS_BIND_BUTTON_on ( (PINB & _BV(5)) == 0x00 )
#define BIND_SET_OUTPUT DDRB |= _BV(5)
#endif
// TX
#ifdef DEBUG_TX
#define TX_ON PORTD |= _BV(1)
#define TX_OFF PORTD &= ~_BV(1)
#define TX_TOGGLE PORTD ^= _BV(1)
#define TX_SET_OUTPUT DDRD |= _BV(1)
#else
#define TX_ON
#define TX_OFF
#define TX_TOGGLE
#define TX_SET_OUTPUT
#endif
// Macros
#define NOP() __asm__ __volatile__("nop")
#define BV(bit) (1 << bit)
//Serial flags definition
#define RX_FLAG_on protocol_flags |= _BV(0)
#define RX_FLAG_off protocol_flags &= ~_BV(0)
#define IS_RX_FLAG_on ( ( protocol_flags & _BV(0) ) !=0 )
//
#define CHANGE_PROTOCOL_FLAG_on protocol_flags |= _BV(1)
#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 RANGE_FLAG_on protocol_flags |= _BV(3)
#define RANGE_FLAG_off protocol_flags &= ~_BV(3)
#define IS_RANGE_FLAG_on ( ( protocol_flags & _BV(3) ) !=0 )
//
#define AUTOBIND_FLAG_on protocol_flags |= _BV(4)
#define AUTOBIND_FLAG_off protocol_flags &= ~_BV(4)
#define IS_AUTOBIND_FLAG_on ( ( protocol_flags & _BV(4) ) !=0 )
//
#define BIND_BUTTON_FLAG_on protocol_flags |= _BV(5)
#define BIND_BUTTON_FLAG_off protocol_flags &= ~_BV(5)
#define IS_BIND_BUTTON_FLAG_on ( ( protocol_flags & _BV(5) ) !=0 )
//PPM RX OK
#define PPM_FLAG_off protocol_flags &= ~_BV(6)
#define PPM_FLAG_on protocol_flags |= _BV(6)
#define IS_PPM_FLAG_on ( ( protocol_flags & _BV(6) ) !=0 )
//Bind flag for blinking
#define BIND_IN_PROGRESS protocol_flags &= ~_BV(7)
#define BIND_DONE protocol_flags |= _BV(7)
#define IS_BIND_DONE_on ( ( protocol_flags & _BV(7) ) !=0 )
#define BAD_PROTO_off protocol_flags2 &= ~_BV(0)
#define BAD_PROTO_on protocol_flags2 |= _BV(0)
#define IS_BAD_PROTO_on ( ( protocol_flags2 & _BV(0) ) !=0 )
#define RX_DONOTUPDTAE_off protocol_flags2 &= ~_BV(1)
#define RX_DONOTUPDTAE_on protocol_flags2 |= _BV(1)
#define IS_RX_DONOTUPDTAE_on ( ( protocol_flags2 & _BV(1) ) !=0 )
#define RX_MISSED_BUFF_off protocol_flags2 &= ~_BV(2)
#define RX_MISSED_BUFF_on protocol_flags2 |= _BV(2)
#define IS_RX_MISSED_BUFF_on ( ( protocol_flags2 & _BV(2) ) !=0 )
#define TX_MAIN_PAUSE_off protocol_flags2 &= ~_BV(3)
#define TX_MAIN_PAUSE_on protocol_flags2 |= _BV(3)
#define IS_TX_MAIN_PAUSE_on ( ( protocol_flags2 & _BV(3) ) !=0 )
#define TX_RX_PAUSE_off protocol_flags2 &= ~_BV(4)
#define TX_RX_PAUSE_on protocol_flags2 |= _BV(4)
#define IS_TX_RX_PAUSE_on ( ( protocol_flags2 & _BV(4) ) !=0 )
#define IS_TX_PAUSE_on ( ( protocol_flags2 & (_BV(4)|_BV(3)) ) !=0 )
#define BLINK_BIND_TIME 100
#define BLINK_SERIAL_TIME 500
#define BLINK_BAD_PROTO_TIME_LOW 1000
#define BLINK_BAD_PROTO_TIME_HIGH 50
//AUX flags definition
#define Servo_AUX1 Servo_AUX & _BV(0)
#define Servo_AUX2 Servo_AUX & _BV(1)
#define Servo_AUX3 Servo_AUX & _BV(2)
#define Servo_AUX4 Servo_AUX & _BV(3)
#define Servo_AUX5 Servo_AUX & _BV(4)
#define Servo_AUX6 Servo_AUX & _BV(5)
#define Servo_AUX7 Servo_AUX & _BV(6)
#define Servo_AUX8 Servo_AUX & _BV(7)
#define GET_FLAG(ch, mask) ( ch ? mask : 0)
//************************
//*** Power settings ***
//************************
enum {
TXPOWER_100uW,
TXPOWER_300uW,
TXPOWER_1mW,
TXPOWER_3mW,
TXPOWER_10mW,
TXPOWER_30mW,
TXPOWER_100mW,
TXPOWER_150mW
};
// A7105 power
// Power amp is ~+16dBm so:
enum A7105_POWER
{
A7105_POWER_0 = 0x00<<3 | 0x00, // TXPOWER_100uW = -23dBm == PAC=0 TBG=0
A7105_POWER_1 = 0x00<<3 | 0x01, // TXPOWER_300uW = -20dBm == PAC=0 TBG=1
A7105_POWER_2 = 0x00<<3 | 0x02, // TXPOWER_1mW = -16dBm == PAC=0 TBG=2
A7105_POWER_3 = 0x00<<3 | 0x04, // TXPOWER_3mW = -11dBm == PAC=0 TBG=4
A7105_POWER_4 = 0x01<<3 | 0x05, // TXPOWER_10mW = -6dBm == PAC=1 TBG=5
A7105_POWER_5 = 0x02<<3 | 0x07, // TXPOWER_30mW = 0dBm == PAC=2 TBG=7
A7105_POWER_6 = 0x03<<3 | 0x07, // TXPOWER_100mW = 1dBm == PAC=3 TBG=7
A7105_POWER_7 = 0x03<<3 | 0x07 // TXPOWER_150mW = 1dBm == PAC=3 TBG=7
};
#define A7105_HIGH_POWER A7105_POWER_7
#define A7105_LOW_POWER A7105_POWER_3
#define A7105_RANGE_POWER A7105_POWER_0
#define A7105_BIND_POWER A7105_POWER_0
// NRF Power
// Power setting is 0..3 for nRF24L01
// Claimed power amp for nRF24L01 from eBay is 20dBm.
enum NRF_POWER
{ // Raw w 20dBm PA
NRF_POWER_0 = 0x00, // 0 : -18dBm (16uW) 2dBm (1.6mW)
NRF_POWER_1 = 0x01, // 1 : -12dBm (60uW) 8dBm (6mW)
NRF_POWER_2 = 0x02, // 2 : -6dBm (250uW) 14dBm (25mW)
NRF_POWER_3 = 0x03 // 3 : 0dBm (1mW) 20dBm (100mW)
};
#define NRF_HIGH_POWER NRF_POWER_2
#define NRF_LOW_POWER NRF_POWER_1
#define NRF_RANGE_POWER NRF_POWER_0
#define NRF_BIND_POWER NRF_POWER_0
// CC2500 power output from the chip itself
// The numbers do not take into account any outside amplifier
enum CC2500_POWER
{
CC2500_POWER_0 = 0x00, // 55dbm or less
CC2500_POWER_1 = 0x50, // -30dbm
CC2500_POWER_2 = 0x44, // 28dbm
CC2500_POWER_3 = 0xC0, // 26dbm
CC2500_POWER_4 = 0x84, // 24dbm
CC2500_POWER_5 = 0x81, // 22dbm
CC2500_POWER_6 = 0x46, // 20dbm
CC2500_POWER_7 = 0x93, // 18dbm
CC2500_POWER_8 = 0x55, // 16dbm
CC2500_POWER_9 = 0x8D, // 14dbm
CC2500_POWER_10 = 0xC6, // -12dbm
CC2500_POWER_11 = 0x97, // -10dbm
CC2500_POWER_12 = 0x6E, // -8dbm
CC2500_POWER_13 = 0x7F, // -6dbm
CC2500_POWER_14 = 0xA9, // -4dbm
CC2500_POWER_15 = 0xBB, // -2dbm
CC2500_POWER_16 = 0xFE, // 0dbm
CC2500_POWER_17 = 0xFF // +1dbm
};
#define CC2500_HIGH_POWER CC2500_POWER_16
#define CC2500_LOW_POWER CC2500_POWER_13
#define CC2500_RANGE_POWER CC2500_POWER_1
#define CC2500_BIND_POWER CC2500_POWER_1
// CYRF power
enum CYRF_POWER
{
CYRF_POWER_0 = 0x00, // -35dbm
CYRF_POWER_1 = 0x01, // -30dbm
CYRF_POWER_2 = 0x02, // -24dbm
CYRF_POWER_3 = 0x03, // -18dbm
CYRF_POWER_4 = 0x04, // -13dbm
CYRF_POWER_5 = 0x05, // -5dbm
CYRF_POWER_6 = 0x06, // 0dbm
CYRF_POWER_7 = 0x07 // +4dbm
};
#define CYRF_HIGH_POWER CYRF_POWER_7
#define CYRF_LOW_POWER CYRF_POWER_3
#define CYRF_RANGE_POWER CYRF_POWER_1 // 1/30 of the full power distance
#define CYRF_BIND_POWER CYRF_POWER_0
enum TXRX_State {
TXRX_OFF,
TX_EN,
RX_EN
};
// Packet ack status values
enum {
PKT_PENDING = 0,
PKT_ACKED,
PKT_TIMEOUT
};
// baudrate defines for serial
#define SPEED_100K 0
#define SPEED_9600 1
//****************************************
//*** MULTI protocol serial definition ***
//****************************************
/*
**************************
16 channels serial protocol
**************************
Serial: 100000 Baud 8e2 _ xxxx xxxx p --
Total of 26 bytes
Stream[0] = 0x55
header
Stream[1] = sub_protocol|BindBit|RangeCheckBit|AutoBindBit;
sub_protocol is 0..31 (bits 0..4)
=> Reserved 0
Flysky 1
Hubsan 2
FrskyD 3
Hisky 4
V2x2 5
DSM 6
Devo 7
YD717 8
KN 9
SymaX 10
SLT 11
CX10 12
CG023 13
Bayang 14
FrskyX 15
ESky 16
MT99XX 17
MJXQ 18
SHENQI 19
FY326 20
SFHSS 21
J6PRO 22
FQ777 23
ASSAN 24
FrskyV 25
BindBit=> 0x80 1=Bind/0=No
AutoBindBit=> 0x40 1=Yes /0=No
RangeCheck=> 0x20 1=Yes /0=No
Stream[2] = RxNum | Power | Type;
RxNum value is 0..15 (bits 0..3)
Type is 0..7 <<4 (bit 4..6)
sub_protocol==Flysky
Flysky 0
V9x9 1
V6x6 2
V912 3
sub_protocol==Hisky
Hisky 0
HK310 1
sub_protocol==DSM
DSM2 0
DSMX 1
sub_protocol==YD717
YD717 0
SKYWLKR 1
SYMAX4 2
XINXUN 3
NIHUI 4
sub_protocol==KN
WLTOYS 0
FEILUN 1
sub_protocol==SYMAX
SYMAX 0
SYMAX5C 1
sub_protocol==CX10
CX10_GREEN 0
CX10_BLUE 1 // also compatible with CX10-A, CX12
DM007 2
Q282 3
JC3015_1 4
JC3015_2 5
MK33041 6
Q242 7
sub_protocol==CG023
CG023 0
YD829 1
H8_3D 2
sub_protocol==MT99XX
MT99 0
H7 1
YZ 2
LS 3
sub_protocol==MJXQ
WLH08 0
X600 1
X800 2
H26D 3
E010 4
sub_protocol==FRSKYX
CH_16 0
CH_8 1
Power value => 0x80 0=High/1=Low
Stream[3] = option_protocol;
option_protocol value is -127..127
Stream[4] to [25] = Channels
16 Channels on 11 bits (0..2047)
0 -125%
204 -100%
1024 0%
1843 +100%
2047 +125%
Channels bits are concatenated to fit in 22 bytes like in SBUS protocol
*/

File diff suppressed because it is too large Load Diff

View File

@@ -19,45 +19,6 @@
//---------------------------
#include "iface_nrf24l01.h"
static void nrf_spi_write(uint8_t command)
{
uint8_t n=8;
SCK_off;//SCK start low
SDI_off;
while(n--) {
if(command&0x80)
SDI_on;
else
SDI_off;
SCK_on;
NOP();
SCK_off;
command = command << 1;
}
SDI_on;
}
//VARIANT 2
static uint8_t nrf_spi_read(void)
{
uint8_t result;
uint8_t i;
result=0;
for(i=0;i<8;i++) {
result<<=1;
if(SDO_1) ///
result|=0x01;
SCK_on;
NOP();
SCK_off;
NOP();
}
return result;
}
//--------------------------------------------
//---------------------------
// NRF24L01+ SPI Specific Functions
@@ -73,8 +34,8 @@ void NRF24L01_Initialize()
void NRF24L01_WriteReg(uint8_t reg, uint8_t data)
{
NRF_CSN_off;
nrf_spi_write(W_REGISTER | (REGISTER_MASK & reg));
nrf_spi_write(data);
SPI_Write(W_REGISTER | (REGISTER_MASK & reg));
SPI_Write(data);
NRF_CSN_on;
}
@@ -82,26 +43,26 @@ void NRF24L01_WriteRegisterMulti(uint8_t reg, uint8_t * data, uint8_t length)
{
NRF_CSN_off;
nrf_spi_write(W_REGISTER | ( REGISTER_MASK & reg));
SPI_Write(W_REGISTER | ( REGISTER_MASK & reg));
for (uint8_t i = 0; i < length; i++)
nrf_spi_write(data[i]);
SPI_Write(data[i]);
NRF_CSN_on;
}
void NRF24L01_WritePayload(uint8_t * data, uint8_t length)
{
NRF_CSN_off;
nrf_spi_write(W_TX_PAYLOAD);
SPI_Write(W_TX_PAYLOAD);
for (uint8_t i = 0; i < length; i++)
nrf_spi_write(data[i]);
SPI_Write(data[i]);
NRF_CSN_on;
}
uint8_t NRF24L01_ReadReg(uint8_t reg)
{
NRF_CSN_off;
nrf_spi_write(R_REGISTER | (REGISTER_MASK & reg));
uint8_t data = nrf_spi_read();
SPI_Write(R_REGISTER | (REGISTER_MASK & reg));
uint8_t data = SPI_Read();
NRF_CSN_on;
return data;
}
@@ -109,25 +70,35 @@ uint8_t NRF24L01_ReadReg(uint8_t reg)
/*static void NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t * data, uint8_t length)
{
NRF_CSN_off;
nrf_spi_write(R_REGISTER | (REGISTER_MASK & reg));
SPI_Write(R_REGISTER | (REGISTER_MASK & reg));
for(uint8_t i = 0; i < length; i++)
data[i] = nrf_spi_read();
data[i] = SPI_Read();
NRF_CSN_on;
}
*/
static uint8_t __attribute__((unused)) NRF24L01_ReadPayloadLength()
{
NRF_CSN_off;
SPI_Write(R_RX_PL_WID);
uint8_t len = SPI_Read();
NRF_CSN_on;
return len;
}
static void NRF24L01_ReadPayload(uint8_t * data, uint8_t length)
{
NRF_CSN_off;
nrf_spi_write(R_RX_PAYLOAD);
SPI_Write(R_RX_PAYLOAD);
for(uint8_t i = 0; i < length; i++)
data[i] = nrf_spi_read();
data[i] = SPI_Read();
NRF_CSN_on;
}
static void NRF24L01_Strobe(uint8_t state)
{
NRF_CSN_off;
nrf_spi_write(state);
SPI_Write(state);
NRF_CSN_on;
}
@@ -144,8 +115,8 @@ void NRF24L01_FlushRx()
void NRF24L01_Activate(uint8_t code)
{
NRF_CSN_off;
nrf_spi_write(ACTIVATE);
nrf_spi_write(code);
SPI_Write(ACTIVATE);
SPI_Write(code);
NRF_CSN_on;
}
@@ -154,7 +125,7 @@ void NRF24L01_SetBitrate(uint8_t bitrate)
// Note that bitrate 250kbps (and bit RF_DR_LOW) is valid only
// for nRF24L01+. There is no way to programmatically tell it from
// older version, nRF24L01, but the older is practically phased out
// by Nordic, so we assume that we deal with with modern version.
// by Nordic, so we assume that we deal with modern version.
// Bit 0 goes to RF_DR_HIGH, bit 1 - to RF_DR_LOW
rf_setup = (rf_setup & 0xD7) | ((bitrate & 0x02) << 4) | ((bitrate & 0x01) << 3);
@@ -189,25 +160,29 @@ void NRF24L01_SetPower()
if(IS_RANGE_FLAG_on)
power=NRF_POWER_0;
rf_setup = (rf_setup & 0xF9) | (power << 1);
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, rf_setup);
if(prev_power != power)
{
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, rf_setup);
prev_power=power;
}
}
void NRF24L01_SetTxRxMode(enum TXRX_State mode)
{
if(mode == TX_EN) {
NRF_CSN_off;
NRF_CE_off;
NRF24L01_WriteReg(NRF24L01_07_STATUS, (1 << NRF24L01_07_RX_DR) //reset the flag(s)
| (1 << NRF24L01_07_TX_DS)
| (1 << NRF24L01_07_MAX_RT));
NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_EN_CRC) // switch to TX mode
| (1 << NRF24L01_00_CRCO)
| (1 << NRF24L01_00_PWR_UP));
_delay_us(130);
NRF_CSN_on;
delayMicroseconds(130);
NRF_CE_on;
}
else
if (mode == RX_EN) {
NRF_CSN_off;
NRF_CE_off;
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // reset the flag(s)
NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0F); // switch to RX mode
NRF24L01_WriteReg(NRF24L01_07_STATUS, (1 << NRF24L01_07_RX_DR) //reset the flag(s)
@@ -217,13 +192,13 @@ void NRF24L01_SetTxRxMode(enum TXRX_State mode)
| (1 << NRF24L01_00_CRCO)
| (1 << NRF24L01_00_PWR_UP)
| (1 << NRF24L01_00_PRIM_RX));
_delay_us(130);
NRF_CSN_on;
delayMicroseconds(130);
NRF_CE_on;
}
else
{
NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_EN_CRC)); //PowerDown
NRF_CSN_off;
NRF_CE_off;
}
}
@@ -239,14 +214,15 @@ void NRF24L01_Reset()
NRF24L01_FlushTx();
NRF24L01_FlushRx();
NRF24L01_Strobe(0xff); // NOP
NRF24L01_ReadReg(0x07);
NRF24L01_ReadReg(NRF24L01_07_STATUS);
NRF24L01_SetTxRxMode(TXRX_OFF);
_delay_us(100);
delayMicroseconds(100);
}
uint8_t NRF24L01_packet_ack()
{
switch (NRF24L01_ReadReg(NRF24L01_07_STATUS) & (BV(NRF24L01_07_TX_DS) | BV(NRF24L01_07_MAX_RT))) {
switch (NRF24L01_ReadReg(NRF24L01_07_STATUS) & (BV(NRF24L01_07_TX_DS) | BV(NRF24L01_07_MAX_RT)))
{
case BV(NRF24L01_07_TX_DS):
return PKT_ACKED;
case BV(NRF24L01_07_MAX_RT):
@@ -255,8 +231,10 @@ uint8_t NRF24L01_packet_ack()
return PKT_PENDING;
}
///////////////
// XN297 emulation layer
uint8_t xn297_scramble_enabled=XN297_SCRAMBLED; //enabled by default
uint8_t xn297_addr_len;
uint8_t xn297_tx_addr[5];
uint8_t xn297_rx_addr[5];
@@ -269,13 +247,20 @@ static const uint8_t xn297_scramble[] = {
0x1b, 0x5d, 0x19, 0x10, 0x24, 0xd3, 0xdc, 0x3f,
0x8e, 0xc5, 0x2f};
static const uint16_t xn297_crc_xorout[] = {
0x0000, 0x3448, 0x9BA7, 0x8BBB, 0x85E1, 0x3E8C, // 1st entry is missing, probably never needed
0x451E, 0x18E6, 0x6B24, 0xE7AB, 0x3828, 0x814B, // it's used for 3-byte address w/ 0 byte payload only
const uint16_t PROGMEM xn297_crc_xorout_scrambled[] = {
0x0000, 0x3448, 0x9BA7, 0x8BBB, 0x85E1, 0x3E8C,
0x451E, 0x18E6, 0x6B24, 0xE7AB, 0x3828, 0x814B,
0xD461, 0xF494, 0x2503, 0x691D, 0xFE8B, 0x9BA7,
0x8B17, 0x2920, 0x8B5F, 0x61B1, 0xD391, 0x7401,
0x2138, 0x129F, 0xB3A0, 0x2988};
const uint16_t PROGMEM xn297_crc_xorout[] = {
0x0000, 0x3d5f, 0xa6f1, 0x3a23, 0xaa16, 0x1caf,
0x62b2, 0xe0eb, 0x0821, 0xbe07, 0x5f1a, 0xaf15,
0x4f0a, 0xad24, 0x5e48, 0xed34, 0x068c, 0xf2c9,
0x1852, 0xdf36, 0x129d, 0xb17c, 0xd5f5, 0x70d7,
0xb798, 0x5133, 0x67db, 0xd94e};
static uint8_t bit_reverse(uint8_t b_in)
{
uint8_t b_out = 0;
@@ -287,10 +272,9 @@ static uint8_t bit_reverse(uint8_t b_in)
return b_out;
}
static const uint16_t polynomial = 0x1021;
static uint16_t crc16_update(uint16_t crc, uint8_t a)
{
static const uint16_t polynomial = 0x1021;
crc ^= a << 8;
for (uint8_t i = 0; i < 8; ++i)
if (crc & 0x8000)
@@ -327,7 +311,11 @@ void XN297_SetRXAddr(const uint8_t* addr, uint8_t len)
memcpy(buf, addr, len);
memcpy(xn297_rx_addr, addr, len);
for (uint8_t i = 0; i < xn297_addr_len; ++i)
buf[i] = xn297_rx_addr[i] ^ xn297_scramble[xn297_addr_len-i-1];
{
buf[i] = xn297_rx_addr[i];
if(xn297_scramble_enabled)
buf[i] ^= xn297_scramble[xn297_addr_len-i-1];
}
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, len-2);
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, buf, 5);
}
@@ -336,7 +324,12 @@ void XN297_Configure(uint8_t flags)
{
xn297_crc = !!(flags & BV(NRF24L01_00_EN_CRC));
flags &= ~(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO));
NRF24L01_WriteReg(NRF24L01_00_CONFIG, flags);
NRF24L01_WriteReg(NRF24L01_00_CONFIG, flags & 0xFF);
}
void XN297_SetScrambledMode(const u8 mode)
{
xn297_scramble_enabled = mode;
}
void XN297_WritePayload(uint8_t* msg, uint8_t len)
@@ -352,12 +345,20 @@ void XN297_WritePayload(uint8_t* msg, uint8_t len)
buf[last++] = 0x55;
}
for (uint8_t i = 0; i < xn297_addr_len; ++i)
buf[last++] = xn297_tx_addr[xn297_addr_len-i-1] ^ xn297_scramble[i];
for (uint8_t i = 0; i < len; ++i) {
{
buf[last] = xn297_tx_addr[xn297_addr_len-i-1];
if(xn297_scramble_enabled)
buf[last] ^= xn297_scramble[i];
last++;
}
for (uint8_t i = 0; i < len; ++i)
{
// bit-reverse bytes in packet
uint8_t b_out = bit_reverse(msg[i]);
buf[last++] = b_out ^ xn297_scramble[xn297_addr_len+i];
buf[last] = b_out;
if(xn297_scramble_enabled)
buf[last] ^= xn297_scramble[xn297_addr_len+i];
last++;
}
if (xn297_crc)
{
@@ -365,7 +366,10 @@ void XN297_WritePayload(uint8_t* msg, uint8_t len)
uint16_t crc = 0xb5d2;
for (uint8_t i = offset; i < last; ++i)
crc = crc16_update(crc, buf[i]);
crc ^= xn297_crc_xorout[xn297_addr_len - 3 + len];
if(xn297_scramble_enabled)
crc ^= pgm_read_word(&xn297_crc_xorout_scrambled[xn297_addr_len - 3 + len]);
else
crc ^= pgm_read_word(&xn297_crc_xorout[xn297_addr_len - 3 + len]);
buf[last++] = crc >> 8;
buf[last++] = crc & 0xff;
}
@@ -374,9 +378,208 @@ void XN297_WritePayload(uint8_t* msg, uint8_t len)
void XN297_ReadPayload(uint8_t* msg, uint8_t len)
{
// TODO: if xn297_crc==1, check CRC before filling *msg
NRF24L01_ReadPayload(msg, len);
for(uint8_t i=0; i<len; i++)
msg[i] = bit_reverse(msg[i]) ^ bit_reverse(xn297_scramble[i+xn297_addr_len]);
{
msg[i] = bit_reverse(msg[i]);
if(xn297_scramble_enabled)
msg[i] ^= bit_reverse(xn297_scramble[i+xn297_addr_len]);
}
}
// End of XN297 emulation
///////////////
// LT8900 emulation layer
uint8_t LT8900_buffer[64];
uint8_t LT8900_buffer_start;
uint16_t LT8900_buffer_overhead_bits;
uint8_t LT8900_addr[8];
uint8_t LT8900_addr_size;
uint8_t LT8900_Preamble_Len;
uint8_t LT8900_Tailer_Len;
uint8_t LT8900_CRC_Initial_Data;
uint8_t LT8900_Flags;
#define LT8900_CRC_ON 6
#define LT8900_SCRAMBLE_ON 5
#define LT8900_PACKET_LENGTH_EN 4
#define LT8900_DATA_PACKET_TYPE_1 3
#define LT8900_DATA_PACKET_TYPE_0 2
#define LT8900_FEC_TYPE_1 1
#define LT8900_FEC_TYPE_0 0
void LT8900_Config(uint8_t preamble_len, uint8_t trailer_len, uint8_t flags, uint8_t crc_init)
{
//Preamble 1 to 8 bytes
LT8900_Preamble_Len=preamble_len;
//Trailer 4 to 18 bits
LT8900_Tailer_Len=trailer_len;
//Flags
// CRC_ON: 1 on, 0 off
// SCRAMBLE_ON: 1 on, 0 off
// PACKET_LENGTH_EN: 1 1st byte of payload is payload size
// DATA_PACKET_TYPE: 00 NRZ, 01 Manchester, 10 8bit/10bit line code, 11 interleave data type
// FEC_TYPE: 00 No FEC, 01 FEC13, 10 FEC23, 11 reserved
LT8900_Flags=flags;
//CRC init constant
LT8900_CRC_Initial_Data=crc_init;
}
void LT8900_SetChannel(uint8_t channel)
{
NRF24L01_WriteReg(NRF24L01_05_RF_CH, channel +2); //NRF24L01 is 2400+channel but LT8900 is 2402+channel
}
void LT8900_SetTxRxMode(enum TXRX_State mode)
{
if(mode == TX_EN)
{
//Switch to TX
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_SetTxRxMode(TX_EN);
//Disable CRC
NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_PWR_UP));
}
else
if (mode == RX_EN)
{
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, 32);
//Switch to RX
NRF24L01_SetTxRxMode(TXRX_OFF);
NRF24L01_FlushRx();
NRF24L01_SetTxRxMode(RX_EN);
// Disable CRC
NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_PWR_UP) | (1 << NRF24L01_00_PRIM_RX) );
}
else
NRF24L01_SetTxRxMode(TXRX_OFF);
}
void LT8900_BuildOverhead()
{
uint8_t pos;
//Build overhead
//preamble
memset(LT8900_buffer,LT8900_addr[0]&0x01?0xAA:0x55,LT8900_Preamble_Len-1);
pos=LT8900_Preamble_Len-1;
//address
for(uint8_t i=0;i<LT8900_addr_size;i++)
{
LT8900_buffer[pos]=bit_reverse(LT8900_addr[i]);
pos++;
}
//trailer
memset(LT8900_buffer+pos,(LT8900_buffer[pos-1]&0x01)==0?0xAA:0x55,3);
LT8900_buffer_overhead_bits=pos*8+LT8900_Tailer_Len;
//nrf address length max is 5
pos+=LT8900_Tailer_Len/8;
LT8900_buffer_start=pos>5?5:pos;
}
void LT8900_SetAddress(uint8_t *address,uint8_t addr_size)
{
uint8_t addr[5];
//Address size (SyncWord) 2 to 8 bytes, 16/32/48/64 bits
LT8900_addr_size=addr_size;
for (uint8_t i = 0; i < addr_size; i++)
LT8900_addr[i] = address[addr_size-1-i];
//Build overhead
LT8900_BuildOverhead();
//Set NRF RX&TX address based on overhead content
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, LT8900_buffer_start-2);
for(uint8_t i=0;i<LT8900_buffer_start;i++) // reverse bytes order
addr[i]=LT8900_buffer[LT8900_buffer_start-i-1];
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, addr,LT8900_buffer_start);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, addr,LT8900_buffer_start);
}
uint8_t LT8900_ReadPayload(uint8_t* msg, uint8_t len)
{
uint8_t i,pos=0,shift,end,buffer[32];
unsigned int crc=LT8900_CRC_Initial_Data,a;
pos=LT8900_buffer_overhead_bits/8-LT8900_buffer_start;
end=pos+len+(LT8900_Flags&_BV(LT8900_PACKET_LENGTH_EN)?1:0)+(LT8900_Flags&_BV(LT8900_CRC_ON)?2:0);
//Read payload
NRF24L01_ReadPayload(buffer,end+1);
//Check address + trail
for(i=0;i<pos;i++)
if(LT8900_buffer[LT8900_buffer_start+i]!=buffer[i])
return 0; // wrong address...
//Shift buffer to remove trail bits
shift=LT8900_buffer_overhead_bits&0x7;
for(i=pos;i<end;i++)
{
a=(buffer[i]<<8)+buffer[i+1];
a<<=shift;
buffer[i]=(a>>8)&0xFF;
}
//Check len
if(LT8900_Flags&_BV(LT8900_PACKET_LENGTH_EN))
{
crc=crc16_update(crc,buffer[pos]);
if(bit_reverse(len)!=buffer[pos++])
return 0; // wrong len...
}
//Decode message
for(i=0;i<len;i++)
{
crc=crc16_update(crc,buffer[pos]);
msg[i]=bit_reverse(buffer[pos++]);
}
//Check CRC
if(LT8900_Flags&_BV(LT8900_CRC_ON))
{
if(buffer[pos++]!=((crc>>8)&0xFF)) return 0; // wrong CRC...
if(buffer[pos]!=(crc&0xFF)) return 0; // wrong CRC...
}
//Everything ok
return 1;
}
void LT8900_WritePayload(uint8_t* msg, uint8_t len)
{
unsigned int crc=LT8900_CRC_Initial_Data,a,mask;
uint8_t i, pos=0,tmp, buffer[64], pos_final,shift;
//Add packet len
if(LT8900_Flags&_BV(LT8900_PACKET_LENGTH_EN))
{
tmp=bit_reverse(len);
buffer[pos++]=tmp;
crc=crc16_update(crc,tmp);
}
//Add payload
for(i=0;i<len;i++)
{
tmp=bit_reverse(msg[i]);
buffer[pos++]=tmp;
crc=crc16_update(crc,tmp);
}
//Add CRC
if(LT8900_Flags&_BV(LT8900_CRC_ON))
{
buffer[pos++]=crc>>8;
buffer[pos++]=crc;
}
//Shift everything to fit behind the trailer (4 to 18 bits)
shift=LT8900_buffer_overhead_bits&0x7;
pos_final=LT8900_buffer_overhead_bits/8;
mask=~(0xFF<<(8-shift));
LT8900_buffer[pos_final+pos]=0xFF;
for(i=pos-1;i!=0xFF;i--)
{
a=buffer[i]<<(8-shift);
LT8900_buffer[pos_final+i]=(LT8900_buffer[pos_final+i]&mask>>8)|a>>8;
LT8900_buffer[pos_final+i+1]=(LT8900_buffer[pos_final+i+1]&mask)|a;
}
if(shift)
pos++;
//Send everything
NRF24L01_WritePayload(LT8900_buffer+LT8900_buffer_start,pos_final+pos-LT8900_buffer_start);
}
// End of LT8900 emulation

View File

@@ -0,0 +1,248 @@
/*
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/>.
*/
// Last sync with main deviation/sfhss_cc2500.c dated 2016-03-23
#if defined(SFHSS_CC2500_INO)
#include "iface_cc2500.h"
#define SFHSS_COARSE 0
#define SFHSS_PACKET_LEN 13
#define SFHSS_TX_ID_LEN 2
uint8_t fhss_code; // 0-27
enum {
SFHSS_START = 0x00,
SFHSS_CAL = 0x01,
SFHSS_DATA1 = 0x02, // do not change this value
SFHSS_DATA2 = 0x0B, // do not change this value
SFHSS_TUNE = 0x0F
};
#define SFHSS_FREQ0_VAL 0xC4
// Some important initialization parameters, all others are either default,
// or not important in the context of transmitter
// IOCFG2 2F - GDO2_INV=0 GDO2_CFG=2F - HW0
// IOCFG1 2E - GDO1_INV=0 GDO1_CFG=2E - High Impedance
// IOCFG0 2F - GDO0 same as GDO2, TEMP_SENSOR_ENABLE=off
// FIFOTHR 07 - 33 decimal TX threshold
// SYNC1 D3
// SYNC0 91
// PKTLEN 0D - Packet length, 0D bytes
// PKTCTRL1 04 - APPEND_STATUS on, all other are receive parameters - irrelevant
// PKTCTRL0 0C - No whitening, use FIFO, CC2400 compatibility on, use CRC, fixed packet length
// ADDR 29
// CHANNR 10
// FSCTRL1 06 - IF 152343.75Hz, see page 65
// FSCTRL0 00 - zero freq offset
// FREQ2 5C - synthesizer frequency 2399999633Hz for 26MHz crystal, ibid
// FREQ1 4E
// FREQ0 C4
// MDMCFG4 7C - CHANBW_E - 01, CHANBW_M - 03, DRATE_E - 0C. Filter bandwidth = 232142Hz
// MDMCFG3 43 - DRATE_M - 43. Data rate = 128143bps
// MDMCFG2 83 - disable DC blocking, 2-FSK, no Manchester code, 15/16 sync bits detected (irrelevant for TX)
// MDMCFG1 23 - no FEC, 4 preamble bytes, CHANSPC_E - 03
// MDMCFG0 3B - CHANSPC_M - 3B. Channel spacing = 249938Hz (each 6th channel used, resulting in spacing of 1499628Hz)
// DEVIATN 44 - DEVIATION_E - 04, DEVIATION_M - 04. Deviation = 38085.9Hz
// MCSM2 07 - receive parameters, default, irrelevant
// MCSM1 0C - no CCA (transmit always), when packet received stay in RX, when sent go to IDLE
// MCSM0 08 - no autocalibration, PO_TIMEOUT - 64, no pin radio control, no forcing XTAL to stay in SLEEP
// FOCCFG 1D - not interesting, Frequency Offset Compensation
// FREND0 10 - PA_POWER = 0
const PROGMEM uint8_t SFHSS_init_values[] = {
/* 00 */ 0x2F, 0x2E, 0x2F, 0x07, 0xD3, 0x91, 0x0D, 0x04,
/* 08 */ 0x0C, 0x29, 0x10, 0x06, 0x00, 0x5C, 0x4E, SFHSS_FREQ0_VAL + SFHSS_COARSE,
/* 10 */ 0x7C, 0x43, 0x83, 0x23, 0x3B, 0x44, 0x07, 0x0C,
/* 18 */ 0x08, 0x1D, 0x1C, 0x43, 0x40, 0x91, 0x57, 0x6B,
/* 20 */ 0xF8, 0xB6, 0x10, 0xEA, 0x0A, 0x11, 0x11
};
static void __attribute__((unused)) SFHSS_rf_init()
{
CC2500_Reset();
CC2500_Strobe(CC2500_SIDLE);
for (uint8_t i = 0; i < 39; ++i)
CC2500_WriteReg(i, pgm_read_byte_near(&SFHSS_init_values[i]));
prev_option = option;
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
CC2500_SetTxRxMode(TX_EN);
CC2500_SetPower();
}
static void __attribute__((unused)) SFHSS_tune_chan()
{
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR, rf_ch_num*6+16);
CC2500_Strobe(CC2500_SCAL);
}
static void __attribute__((unused)) SFHSS_tune_chan_fast()
{
CC2500_Strobe(CC2500_SIDLE);
CC2500_WriteReg(CC2500_0A_CHANNR, rf_ch_num*6+16);
CC2500_WriteReg(CC2500_25_FSCAL1, calData[rf_ch_num]);
}
static void __attribute__((unused)) SFHSS_tune_freq()
{
if ( prev_option != option )
{
CC2500_WriteReg(CC2500_0C_FSCTRL0, option);
CC2500_WriteReg(CC2500_0F_FREQ0, SFHSS_FREQ0_VAL + SFHSS_COARSE);
prev_option = option ;
phase = SFHSS_START; // Restart the tune process if option is changed to get good tuned values
}
}
static void __attribute__((unused)) SFHSS_calc_next_chan()
{
rf_ch_num += fhss_code + 2;
if (rf_ch_num > 29)
{
if (rf_ch_num < 31)
rf_ch_num += fhss_code + 2;
rf_ch_num -= 31;
}
}
// Channel values are 10-bit values between 86 and 906, 496 is the middle.
// Values grow down and to the right, so we just revert every channel.
static uint16_t __attribute__((unused)) SFHSS_convert_channel(uint8_t num)
{
return (uint16_t) (map(limit_channel_100(num),servo_min_100,servo_max_100,906,86));
}
static void __attribute__((unused)) SFHSS_build_data_packet()
{
#define spacer1 0x02 //0b10
#define spacer2 (spacer1 << 4)
uint8_t ch_offset = phase == SFHSS_DATA1 ? 0 : 4;
uint16_t ch1 = SFHSS_convert_channel(CH_AETR[ch_offset+0]);
uint16_t ch2 = SFHSS_convert_channel(CH_AETR[ch_offset+1]);
uint16_t ch3 = SFHSS_convert_channel(CH_AETR[ch_offset+2]);
uint16_t ch4 = SFHSS_convert_channel(CH_AETR[ch_offset+3]);
packet[0] = 0x81; // can be 80 or 81 for Orange, only 81 for XK
packet[1] = rx_tx_addr[0];
packet[2] = rx_tx_addr[1];
packet[3] = 0;
packet[4] = 0;
packet[5] = (rf_ch_num << 3) | spacer1 | ((ch1 >> 9) & 0x01);
packet[6] = (ch1 >> 1);
packet[7] = (ch1 << 7) | spacer2 | ((ch2 >> 5) & 0x1F /*0b11111*/);
packet[8] = (ch2 << 3) | spacer1 | ((ch3 >> 9) & 0x01);
packet[9] = (ch3 >> 1);
packet[10] = (ch3 << 7) | spacer2 | ((ch4 >> 5) & 0x1F /*0b11111*/);
packet[11] = (ch4 << 3) | ((fhss_code >> 2) & 0x07 /*0b111 */);
packet[12] = (fhss_code << 6) | phase;
}
static void __attribute__((unused)) SFHSS_send_packet()
{
CC2500_WriteData(packet, SFHSS_PACKET_LEN);
}
uint16_t ReadSFHSS()
{
switch(phase)
{
case SFHSS_START:
rf_ch_num = 0;
SFHSS_tune_chan();
phase = SFHSS_CAL;
return 2000;
case SFHSS_CAL:
calData[rf_ch_num]=CC2500_ReadReg(CC2500_25_FSCAL1);
if (++rf_ch_num < 30)
SFHSS_tune_chan();
else
{
rf_ch_num = 0;
phase = SFHSS_DATA1;
}
return 2000;
/* Work cycle, 6.8ms, second packet 1.65ms after first */
case SFHSS_DATA1:
SFHSS_build_data_packet();
SFHSS_send_packet();
phase = SFHSS_DATA2;
return 1650;
case SFHSS_DATA2:
SFHSS_build_data_packet();
SFHSS_send_packet();
SFHSS_calc_next_chan();
phase = SFHSS_TUNE;
return 2000;
case SFHSS_TUNE:
phase = SFHSS_DATA1;
SFHSS_tune_freq();
SFHSS_tune_chan_fast();
CC2500_SetPower();
return 3150;
}
return 0;
}
// Generate internal id
static void __attribute__((unused)) SFHSS_get_tx_id()
{
uint32_t fixed_id;
// Some receivers (Orange) behaves better if they tuned to id that has
// no more than 6 consecutive zeros and ones
uint8_t run_count = 0;
// add guard for bit count
fixed_id = 1 ^ (MProtocol_id & 1);
for (uint8_t i = 0; i < 16; ++i)
{
fixed_id = (fixed_id << 1) | (MProtocol_id & 1);
MProtocol_id >>= 1;
// If two LS bits are the same
if ((fixed_id & 3) == 0 || (fixed_id & 3) == 3)
{
if (++run_count > 6)
{
fixed_id ^= 1;
run_count = 0;
}
}
else
run_count = 0;
}
// fixed_id = 0xBC11;
rx_tx_addr[0] = fixed_id >> 8;
rx_tx_addr[1] = fixed_id;
}
uint16_t initSFHSS()
{
BIND_DONE; // Not a TX bind protocol
SFHSS_get_tx_id();
fhss_code=rx_tx_addr[2]%28; // Initialize it to random 0-27 inclusive
SFHSS_rf_init();
phase = SFHSS_START;
return 10000;
}
#endif

View File

@@ -0,0 +1,123 @@
/*
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/>.
*/
#if defined(SHENQI_NRF24L01_INO)
#include "iface_nrf24l01.h"
const uint8_t PROGMEM SHENQI_Freq[] = {
50,50,20,60,30,40,
10,30,40,20,60,10,
50,20,50,40,10,60,
30,30,60,10,40,50,
20,10,60,20,50,30,
40,40,30,50,20,60,
10,10,20,30,40,50,
60,60,50,40,30,20,
10,60,10,50,30,40,
20,10,40,30,60,20 };
void SHENQI_init()
{
NRF24L01_Initialize();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower();
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5 bytes rx/tx address
LT8900_Config(4, 8, _BV(LT8900_CRC_ON)|_BV(LT8900_PACKET_LENGTH_EN), 0xAA);
LT8900_SetChannel(2);
LT8900_SetAddress((uint8_t *)"\x9A\x9A\x9A\x9A",4);
LT8900_SetTxRxMode(RX_EN);
}
void SHENQI_send_packet()
{
packet[0]=0x00;
if(packet_count==0)
{
uint8_t bind_addr[4];
bind_addr[0]=rx_tx_addr[0];
bind_addr[1]=rx_tx_addr[1];
bind_addr[2]=0x9A;
bind_addr[3]=0x9A;
LT8900_SetAddress(bind_addr,4);
LT8900_SetChannel(2);
packet[1]=rx_tx_addr[2];
packet[2]=rx_tx_addr[3];
packet_period=2508;
}
else
{
LT8900_SetAddress(rx_tx_addr,4);
packet[1]=255-convert_channel_8b(RUDDER);
packet[2]=255-convert_channel_8b_scale(THROTTLE,0x60,0xA0);
uint8_t freq=pgm_read_byte_near(&SHENQI_Freq[hopping_frequency_no])+(rx_tx_addr[2]&0x0F);
LT8900_SetChannel(freq);
hopping_frequency_no++;
if(hopping_frequency_no==60)
hopping_frequency_no=0;
packet_period=1750;
}
// Send packet + 1 retransmit - not sure why but needed (not present on original TX...)
LT8900_WritePayload(packet,3);
while(NRF24L01_packet_ack()!=PKT_ACKED);
LT8900_WritePayload(packet,3);
packet_count++;
if(packet_count==7)
{
packet_count=0;
packet_period=3000;
}
// Set power
NRF24L01_SetPower();
}
uint16_t SHENQI_callback()
{
if(IS_BIND_DONE_on)
SHENQI_send_packet();
else
{
if( NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_RX_DR))
{
if(LT8900_ReadPayload(packet, 3))
{
BIND_DONE;
rx_tx_addr[0]=packet[1];
rx_tx_addr[1]=packet[2];
LT8900_SetTxRxMode(TX_EN);
packet_period=14000;
}
NRF24L01_FlushRx();
}
}
return packet_period;
}
uint16_t initSHENQI()
{
BIND_IN_PROGRESS; // autobind protocol
SHENQI_init();
hopping_frequency_no = 0;
packet_count=0;
packet_period=100;
return 1000;
}
#endif

View File

@@ -31,7 +31,7 @@ enum {
SLT_DATA3
};
static void SLT_init()
static void __attribute__((unused)) SLT_init()
{
NRF24L01_Initialize();
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO)); // 2-bytes CRC, radio off
@@ -47,7 +47,7 @@ static void SLT_init()
NRF24L01_FlushRx();
}
static void SLT_init2()
static void __attribute__((unused)) SLT_init2()
{
NRF24L01_FlushTx();
packet_sent = 0;
@@ -57,7 +57,7 @@ static void SLT_init2()
NRF24L01_SetTxRxMode(TX_EN);
}
static void SLT_set_tx_id(void)
static void __attribute__((unused)) SLT_set_tx_id(void)
{
// Frequency hopping sequence generation
for (uint8_t i = 0; i < 4; ++i)
@@ -90,14 +90,14 @@ static void SLT_set_tx_id(void)
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 4);
}
static void SLT_wait_radio()
static void __attribute__((unused)) SLT_wait_radio()
{
if (packet_sent)
while (!(NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_TX_DS))) ;
packet_sent = 0;
}
static void SLT_send_data(uint8_t *data, uint8_t len)
static void __attribute__((unused)) SLT_send_data(uint8_t *data, uint8_t len)
{
SLT_wait_radio();
NRF24L01_FlushTx();
@@ -107,13 +107,12 @@ static void SLT_send_data(uint8_t *data, uint8_t len)
packet_sent = 1;
}
static void SLT_build_packet()
static void __attribute__((unused)) SLT_build_packet()
{
// aileron, elevator, throttle, rudder, gear, pitch
uint8_t e = 0; // byte where extension 2 bits for every 10-bit channel are packed
const uint8_t ch[]={AILERON, ELEVATOR, THROTTLE, RUDDER};
for (uint8_t i = 0; i < 4; ++i) {
uint16_t v = convert_channel_10b(ch[i]);
uint16_t v = convert_channel_10b(CH_AETR[i]);
packet[i] = v;
e = (e >> 2) | (uint8_t) ((v >> 2) & 0xC0);
}
@@ -129,7 +128,7 @@ static void SLT_build_packet()
hopping_frequency_no = 0;
}
static void SLT_send_bind_packet()
static void __attribute__((unused)) SLT_send_bind_packet()
{
SLT_wait_radio();
BIND_IN_PROGRESS; // autobind protocol

View File

@@ -41,7 +41,7 @@ enum {
SYMAX_DATA
};
static uint8_t SYMAX_checksum(uint8_t *data)
static uint8_t __attribute__((unused)) SYMAX_checksum(uint8_t *data)
{
uint8_t sum = data[0];
@@ -54,7 +54,7 @@ static uint8_t SYMAX_checksum(uint8_t *data)
return sum + ( sub_protocol==SYMAX5C ? 0 : 0x55 );
}
static void SYMAX_read_controls()
static void __attribute__((unused)) SYMAX_read_controls()
{
// Protocol is registered AETRF, that is
// Aileron is channel 1, Elevator - 2, Throttle - 3, Rudder - 4, Flip control - 5
@@ -80,7 +80,7 @@ static void SYMAX_read_controls()
#define X5C_CHAN2TRIM(X) ((((X) & 0x80 ? 0xff - (X) : 0x80 + (X)) >> 2) + 0x20)
static void SYMAX_build_packet_x5c(uint8_t bind)
static void __attribute__((unused)) SYMAX_build_packet_x5c(uint8_t bind)
{
if (bind)
{
@@ -116,7 +116,7 @@ static void SYMAX_build_packet_x5c(uint8_t bind)
}
}
static void SYMAX_build_packet(uint8_t bind)
static void __attribute__((unused)) SYMAX_build_packet(uint8_t bind)
{
if (bind)
{
@@ -146,7 +146,7 @@ static void SYMAX_build_packet(uint8_t bind)
packet[9] = SYMAX_checksum(packet);
}
static void SYMAX_send_packet(uint8_t bind)
static void __attribute__((unused)) SYMAX_send_packet(uint8_t bind)
{
if (sub_protocol==SYMAX5C)
SYMAX_build_packet_x5c(bind);
@@ -161,13 +161,13 @@ static void SYMAX_send_packet(uint8_t bind)
NRF24L01_WritePayload(packet, packet_length);
if (packet_counter++ % 2) // use each channel twice
if (packet_count++ % 2) // use each channel twice
hopping_frequency_no = (hopping_frequency_no + 1) % rf_ch_num;
NRF24L01_SetPower(); // Set tx_power
}
static void symax_init()
static void __attribute__((unused)) symax_init()
{
NRF24L01_Initialize();
//
@@ -219,7 +219,7 @@ static void symax_init()
NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0e); // power on
}
static void symax_init1()
static void __attribute__((unused)) symax_init1()
{
// duplicate stock tx sending strange packet (effect unknown)
uint8_t first_packet[] = {0xf9, 0x96, 0x82, 0x1b, 0x20, 0x08, 0x08, 0xf2, 0x7d, 0xef, 0xff, 0x00, 0x00, 0x00, 0x00};
@@ -243,11 +243,11 @@ static void symax_init1()
memcpy(hopping_frequency, chans_bind, rf_ch_num);
}
hopping_frequency_no = 0;
packet_counter = 0;
packet_count = 0;
}
// channels determined by last byte of tx address
static void symax_set_channels(uint8_t address)
static void __attribute__((unused)) symax_set_channels(uint8_t address)
{
static const uint8_t start_chans_1[] = {0x0a, 0x1a, 0x2a, 0x3a};
static const uint8_t start_chans_2[] = {0x2a, 0x0a, 0x42, 0x22};
@@ -290,9 +290,9 @@ static void symax_set_channels(uint8_t address)
*pchans = 0x39194121;
}
static void symax_init2()
static void __attribute__((unused)) symax_init2()
{
uint8_t chans_data_x5c[] = {0x1d, 0x2f, 0x26, 0x3d, 0x15, 0x2b, 0x25, 0x24,
static uint8_t chans_data_x5c[] = {0x1d, 0x2f, 0x26, 0x3d, 0x15, 0x2b, 0x25, 0x24,
0x27, 0x2c, 0x1c, 0x3e, 0x39, 0x2d, 0x22};
if (sub_protocol==SYMAX5C)
@@ -306,7 +306,7 @@ static void symax_init2()
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5);
}
hopping_frequency_no = 0;
packet_counter = 0;
packet_count = 0;
}
uint16_t symax_callback()
@@ -345,7 +345,7 @@ uint16_t symax_callback()
uint16_t initSymax()
{
packet_counter = 0;
packet_count = 0;
flags = 0;
BIND_IN_PROGRESS; // autobind protocol
symax_init();

255
Multiprotocol/TX_Def.h Normal file
View File

@@ -0,0 +1,255 @@
// Turnigy PPM and channels
#if defined(TX_ER9X)
#define PPM_MAX_100 2012 // 100%
#define PPM_MIN_100 988 // 100%
#define PPM_MAX_125 2140 // 125%
#define PPM_MIN_125 860 // 125%
#endif
// Devo PPM and channels
#if defined(TX_DEVO7)
#define PPM_MAX_100 1920 // 100%
#define PPM_MIN_100 1120 // 100%
#define PPM_MAX_125 2100 // 125%
#define PPM_MIN_125 900 // 125%
#endif
// SPEKTRUM PPM and channels
#if defined(TX_SPEKTRUM)
#define PPM_MAX_100 1900 // 100%
#define PPM_MIN_100 1100 // 100%
#define PPM_MAX_125 2000 // 125%
#define PPM_MIN_125 1000 // 125%
#endif
// HISKY
#if defined(TX_HISKY)
#define PPM_MAX_125 2000 // 125%
#define PPM_MIN_125 1000 // 125%
#define PPM_MAX_100 1900 // 100%
#define PPM_MIN_100 1100 // 100%
#define PPM_MAX_125 2000 // 125%
#define PPM_MIN_125 1000 // 125%
#endif
//Serial MIN MAX values
#define SERIAL_MAX_100 2012 // 100%
#define SERIAL_MIN_100 988 // 100%
#define SERIAL_MAX_125 2140 // 125%
#define SERIAL_MIN_125 860 // 125%
//PPM values used to compare
#define PPM_MIN_COMMAND 1250
#define PPM_SWITCH 1550
#define PPM_MAX_COMMAND 1750
//Channel definitions
#ifdef AETR
enum {
AILERON =0,
ELEVATOR,
THROTTLE,
RUDDER,
};
#endif
#ifdef AERT
enum {
AILERON =0,
ELEVATOR,
RUDDER,
THROTTLE,
};
#endif
#ifdef ARET
enum {
AILERON =0,
RUDDER,
ELEVATOR,
THROTTLE,
};
#endif
#ifdef ARTE
enum {
AILERON =0,
RUDDER,
THROTTLE,
ELEVATOR,
};
#endif
#ifdef ATRE
enum {
AILERON =0,
THROTTLE,
RUDDER,
ELEVATOR,
};
#endif
#ifdef ATER
enum {
AILERON =0,
THROTTLE,
ELEVATOR,
RUDDER,
};
#endif
#ifdef EATR
enum {
ELEVATOR =0,
AILERON,
THROTTLE,
RUDDER,
};
#endif
#ifdef EART
enum {
ELEVATOR =0,
AILERON,
RUDDER,
THROTTLE,
};
#endif
#ifdef ERAT
enum {
ELEVATOR =0,
RUDDER,
AILERON,
THROTTLE,
};
#endif
#ifdef ERTA
enum {
ELEVATOR =0,
RUDDER,
THROTTLE,
AILERON,
};
#endif
#ifdef ETRA
enum {
ELEVATOR =0,
THROTTLE,
RUDDER,
AILERON,
};
#endif
#ifdef ETAR
enum {
ELEVATOR =0,
THROTTLE,
AILERON,
RUDDER,
};
#endif
#ifdef TEAR
enum {
THROTTLE =0,
ELEVATOR,
AILERON,
RUDDER,
};
#endif
#ifdef TERA
enum {
THROTTLE =0,
ELEVATOR,
RUDDER,
AILERON,
};
#endif
#ifdef TREA
enum {
THROTTLE =0,
RUDDER,
ELEVATOR,
AILERON,
};
#endif
#ifdef TRAE
enum {
THROTTLE =0,
RUDDER,
AILERON,
ELEVATOR,
};
#endif
#ifdef TARE
enum {
THROTTLE =0,
AILERON,
RUDDER,
ELEVATOR,
};
#endif
#ifdef TAER
enum {
THROTTLE =0,
AILERON,
ELEVATOR,
RUDDER,
};
#endif
#ifdef RETA
enum {
RUDDER =0,
ELEVATOR,
THROTTLE,
AILERON,
};
#endif
#ifdef REAT
enum {
RUDDER =0,
ELEVATOR,
AILERON,
THROTTLE,
};
#endif
#ifdef RAET
enum {
RUDDER =0,
AILERON,
ELEVATOR,
THROTTLE,
};
#endif
#ifdef RATE
enum {
RUDDER =0,
AILERON,
THROTTLE,
ELEVATOR,
};
#endif
#ifdef RTAE
enum {
RUDDER =0,
THROTTLE,
AILERON,
ELEVATOR,
};
#endif
#ifdef RTEA
enum {
RUDDER =0,
THROTTLE,
ELEVATOR,
AILERON,
};
#endif
#define AUX1 4
#define AUX2 5
#define AUX3 6
#define AUX4 7
#define AUX5 8
#define AUX6 9
#define AUX7 10
#define AUX8 11
#define AUX9 12
#define AUX10 13
#define AUX11 14
#define AUX12 15
#define AUX13 16

779
Multiprotocol/Telemetry.ino Normal file
View File

@@ -0,0 +1,779 @@
//**************************
// Telemetry serial code *
// By Midelic on RCGroups *
//**************************
#if defined TELEMETRY
#if defined SPORT_TELEMETRY
#define SPORT_TIME 12000
#define FRSKY_SPORT_PACKET_SIZE 8
uint32_t last = 0;
uint8_t sport_counter=0;
uint8_t RxBt = 0;
uint8_t rssi;
uint8_t sport = 0;
#endif
#if defined HUB_TELEMETRY
#define USER_MAX_BYTES 6
uint8_t prev_index;
#endif
#define START_STOP 0x7e
#define BYTESTUFF 0x7d
#define STUFF_MASK 0x20
#define MAX_PKTX 10
uint8_t pktx[MAX_PKTX];
uint8_t pktx1[MAX_PKTX];
uint8_t index;
uint8_t frame[18];
#ifdef BASH_SERIAL
// For bit-bashed serial output
struct t_serial_bash
{
uint8_t head ;
uint8_t tail ;
uint8_t data[64] ;
uint8_t busy ;
uint8_t speed ;
} SerialControl ;
#endif
#if defined DSM_TELEMETRY
void DSM_frame()
{
Serial_write(0xAA); // Start
for (uint8_t i = 0; i < 17; i++) // RSSI value followed by 16 bytes of telemetry data
Serial_write(pkt[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 compute_RSSIdbm()
{
RSSI_dBm = (((uint16_t)(pktt[len-2])*18)>>4);
if(pktt[len-2] >=128)
RSSI_dBm -= 164;
else
RSSI_dBm += 130;
}
void frsky_check_telemetry(uint8_t *pkt,uint8_t len)
{
if(pkt[1] == rx_tx_addr[3] && pkt[2] == rx_tx_addr[2] && len ==(pkt[0] + 3))
{
for (uint8_t i=3;i<len;i++)
pktt[i]=pkt[i];
telemetry_link=1;
if(pktt[6])
telemetry_counter=(telemetry_counter+1)%32;
//
#if defined FRSKYX_CC2500_INO
if ((cur_protocol[0]&0x1F)==MODE_FRSKYX)
{
if ((pktt[5] >> 4 & 0x0f) == 0x08)
{
seq_last_sent = 8;
seq_last_rcvd = 0;
pass=0;
}
else
{
if ((pktt[5] >> 4 & 0x03) == (seq_last_rcvd + 1) % 4)
seq_last_rcvd = (seq_last_rcvd + 1) % 4;
else
pass=0;//reset if sequence wrong
}
}
#endif
}
}
void frsky_link_frame()
{
frame[0] = 0xFE;
if ((cur_protocol[0]&0x1F)==MODE_FRSKYD)
{
compute_RSSIdbm();
frame[1] = pktt[3];
frame[2] = pktt[4];
frame[3] = pktt[5];
frame[4] = (uint8_t)RSSI_dBm;
}
else
if ((cur_protocol[0]&0x1F)==MODE_HUBSAN)
{
frame[1] = v_lipo*2; //v_lipo; common 0x2A=42/10=4.2V
frame[2] = frame[1];
frame[3] = 0x00;
frame[4] = (uint8_t)RSSI_dBm;
}
frame[5] = frame[6] = frame[7] = frame[8] = 0;
frskySendStuffed();
}
#if defined HUB_TELEMETRY
void frsky_user_frame()
{
uint8_t indexx = 0, j=8, i;
//uint8_t c=0, n=0;
if(pktt[6]>0 && pktt[6]<=10)
{//only valid hub frames
frame[0] = 0xFD;
frame[2] = pktt[7];
switch(pass)
{
case 0:
indexx=pktt[6];
for(i=0;i<indexx;i++)
{
// if(pktt[j]==0x5E)
// {
// if(c++)
// {
// c=0;
// n++;
// j++;
// }
// }
pktx[i]=pktt[j++];
}
// indexx = indexx-n;
pass=1;
case 1:
index=indexx;
prev_index = indexx;
if(index<USER_MAX_BYTES)
{
for(i=0;i<index;i++)
frame[i+3]=pktx[i];
pktt[6]=0;
pass=0;
}
else
{
index = USER_MAX_BYTES;
for(i=0;i<index;i++)
frame[i+3]=pktx[i];
pass=2;
}
break;
case 2:
index = prev_index - index;
prev_index=0;
if(index<=(MAX_PKTX-USER_MAX_BYTES)) //10-6=4
for(i=0;i<index;i++)
frame[i+3]=pktx[USER_MAX_BYTES+i];
pass=0;
pktt[6]=0;
break;
default:
break;
}
if(!index)
return;
frame[1] = index;
frskySendStuffed();
}
else
pass=0;
}
#endif
/*
HuB RX packets.
pkt[6]|(counter++)|00 01 02 03 04 05 06 07 08 09
%32
01 08 5E 28 12 00 5E 5E 3A 06 00 5E
0A 09 28 12 00 5E 5E 3A 06 00 5E 5E
09 0A 3B 09 00 5E 5E 06 36 7D 5E 5E
03 0B 5E 28 11 00 5E 5E 06 06 6C 5E
0A 0C 00 5E 5E 3A 06 00 5E 5E 3B 09
07 0D 00 5E 5E 06 06 6C 5E 16 72 5E
05 0E 5E 28 11 00 5E 5E 3A 06 00 5E
0A 0F 5E 3A 06 00 5E 5E 3B 09 00 5E
05 10 5E 06 16 72 5E 5E 3A 06 00 5E
*/
#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
*/
void sportSend(uint8_t *p)
{
uint16_t crc_s = 0;
Serial_write(START_STOP);//+9
Serial_write(p[0]) ;
for (uint8_t i = 1; i < 9; i++)
{
if (i == 8)
p[i] = 0xff - crc_s;
if ((p[i] == START_STOP) || (p[i] == BYTESTUFF))
{
Serial_write(BYTESTUFF);//stuff again
Serial_write(STUFF_MASK ^ p[i]);
}
else
Serial_write(p[i]);
if (i>0)
{
crc_s += p[i]; //0-1FF
crc_s += crc_s >> 8; //0-100
crc_s &= 0x00ff;
}
}
}
void sportIdle()
{
Serial_write(START_STOP);
}
void sportSendFrame()
{
uint8_t i;
sport_counter = (sport_counter + 1) %36;
if(sport_counter<6)
{
frame[0] = 0x98;
frame[1] = 0x10;
for (i=5;i<8;i++)
frame[i]=0;
}
switch (sport_counter)
{
case 0:
frame[2] = 0x05;
frame[3] = 0xf1;
frame[4] = 0x02 ;//dummy values if swr 20230f00
frame[5] = 0x23;
frame[6] = 0x0F;
break;
case 2: // RSSI
frame[2] = 0x01;
frame[3] = 0xf1;
frame[4] = rssi;
break;
case 4: //BATT
frame[2] = 0x04;
frame[3] = 0xf1;
frame[4] = RxBt;//a1;
break;
default:
if(sport)
{
for (i=0;i<FRSKY_SPORT_PACKET_SIZE;i++)
frame[i]=pktx1[i];
sport=0;
break;
}
else
{
sportIdle();
return;
}
}
sportSend(frame);
}
void proces_sport_data(uint8_t data)
{
switch (pass)
{
case 0:
if (data == START_STOP)
{//waiting for 0x7e
index = 0;
pass = 1;
}
break;
case 1:
if (data == START_STOP) // Happens if missed packet
{//waiting for 0x7e
index = 0;
pass = 1;
break;
}
if(data == BYTESTUFF)//if they are stuffed
pass=2;
else
if (index < MAX_PKTX)
pktx[index++] = data;
break;
case 2:
if (index < MAX_PKTX)
pktx[index++] = data ^ STUFF_MASK; //unstuff bytes
pass=1;
break;
} // end switch
if (index >= FRSKY_SPORT_PACKET_SIZE)
{//8 bytes no crc
if ( sport )
{
// overrun!
}
else
{
uint8_t i ;
for ( i = 0 ; i < FRSKY_SPORT_PACKET_SIZE ; i += 1 )
{
pktx1[i] = pktx[i] ; // Double buffer
}
sport = 1;//ok to send
}
pass = 0;//reset
}
}
#endif
void TelemetryUpdate()
{
#if defined SPORT_TELEMETRY
if ((cur_protocol[0]&0x1F)==MODE_FRSKYX)
{ // FrSkyX
if(telemetry_link)
{
if(pktt[4] & 0x80)
rssi=pktt[4] & 0x7F ;
else
RxBt = (pktt[4]<<1) + 1 ;
for (uint8_t i=0; i < pktt[6]; i++)
proces_sport_data(pktt[7+i]);
telemetry_link=0;
}
}
#endif
// check for space in tx buffer
#ifdef BASH_SERIAL
uint8_t h ;
uint8_t t ;
h = SerialControl.head ;
t = SerialControl.tail ;
if ( h >= t )
{
t += 64 - h ;
}
else
{
t -= h ;
}
if ( t < 32 )
{
return ;
}
#else
uint8_t h ;
uint8_t t ;
h = tx_head ;
t = tx_tail ;
if ( h >= t )
{
t += TXBUFFER_SIZE - h ;
}
else
{
t -= h ;
}
if ( t < 16 )
{
return ;
}
#endif
#if defined DSM_TELEMETRY
if(telemetry_link && (cur_protocol[0]&0x1F) == MODE_DSM )
{ // DSM
DSM_frame();
telemetry_link=0;
return;
}
#endif
if(telemetry_link && (cur_protocol[0]&0x1F) != MODE_FRSKYX )
{ // FrSky + Hubsan
frsky_link_frame();
telemetry_link=0;
return;
}
#if defined HUB_TELEMETRY
if(!telemetry_link && (cur_protocol[0]&0x1F) == MODE_FRSKYD)
{ // FrSky
frsky_user_frame();
return;
}
#endif
#if defined SPORT_TELEMETRY
if ((cur_protocol[0]&0x1F)==MODE_FRSKYX)
{ // FrSkyX
uint32_t now = micros();
if ((now - last) > SPORT_TIME)
{
sportSendFrame();
last += SPORT_TIME ;
}
}
#endif
}
/**************************/
/**************************/
/** Serial TX routines **/
/**************************/
/**************************/
#ifndef BASH_SERIAL
// Routines for normal serial output
void Serial_write(uint8_t data)
{
uint8_t nextHead ;
nextHead = tx_head + 1 ;
if ( nextHead >= TXBUFFER_SIZE )
nextHead = 0 ;
tx_buff[nextHead]=data;
tx_head = nextHead ;
tx_resume();
}
// Speed is 0 for 100K and 1 for 9600
void initTXSerial( uint8_t speed)
{
if(speed==SPEED_9600)
{ // 9600
#ifdef XMEGA
USARTC0.BAUDCTRLA = 207 ;
USARTC0.BAUDCTRLB = 0 ;
USARTC0.CTRLB = 0x18 ;
USARTC0.CTRLA = (USARTC0.CTRLA & 0xCF) | 0x10 ;
USARTC0.CTRLC = 0x03 ;
}
#else
//9600 bauds
UBRR0H = 0x00;
UBRR0L = 0x67;
UCSR0A = 0 ; // Clear X2 bit
//Set frame format to 8 data bits, none, 1 stop bit
UCSR0C = (1<<UCSZ01)|(1<<UCSZ00);
}
UCSR0B |= (1<<TXEN0);//tx enable
#endif
}
#ifdef XMEGA
ISR(USARTC0_DRE_vect)
#else
ISR(USART_UDRE_vect)
#endif
{ // Transmit interrupt
if(tx_head!=tx_tail)
{
if(++tx_tail>=TXBUFFER_SIZE)//head
tx_tail=0;
UDR0=tx_buff[tx_tail];
}
if (tx_tail == tx_head)
tx_pause(); // Check if all data is transmitted . if yes disable transmitter UDRE interrupt
}
#else //BASH_SERIAL
// Routines for bit-bashed serial output
// Speed is 0 for 100K and 1 for 9600
void initTXSerial( uint8_t speed)
{
TIMSK0 = 0 ; // Stop all timer 0 interrupts
#ifdef INVERT_SERIAL
PORTD &= ~2 ;
#else
PORTD |= 2 ;
#endif
DDRD |= 2 ; // TxD pin is an output
UCSR0B &= ~(1<<TXEN0) ;
SerialControl.speed = speed ;
if ( speed == SPEED_9600 )
{
OCR0A = 207 ; // 104uS period
TCCR0A = 3 ;
TCCR0B = 0x0A ; // Fast PMM, 2MHz
}
else // 100K
{
TCCR0A = 0 ;
TCCR0B = 2 ; // Clock/8 (0.5uS)
}
}
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) & 0x3f ;
if ( next != SerialControl.tail )
{
SerialControl.data[SerialControl.head] = byte ;
SerialControl.data[SerialControl.head+1] = byteLo ;
SerialControl.head = next ;
}
cli() ;
if ( SerialControl.busy == 0 )
{
sei() ;
// Start the transmission here
#ifdef INVERT_SERIAL
GPIOR2 = 0 ;
#else
GPIOR2 = 0x01 ;
#endif
if ( SerialControl.speed == SPEED_100K )
{
GPIOR1 = 1 ;
OCR0B = TCNT0 + 40 ;
OCR0A = OCR0B + 210 ;
TIFR0 = (1<<OCF0A) | (1<<OCF0B) ;
TIMSK0 |= (1<<OCIE0B) ;
SerialControl.busy = 1 ;
}
else
{
GPIOR1 = 1 ;
TIFR0 = (1<<TOV0) ;
TIMSK0 |= (1<<TOIE0) ;
SerialControl.busy = 1 ;
}
}
else
{
sei() ;
}
}
// Assume timer0 at 0.5uS clock
ISR(TIMER0_COMPA_vect)
{
uint8_t byte ;
byte = GPIOR0 ;
if ( byte & 0x01 )
{
PORTD |= 0x02 ;
}
else
{
PORTD &= ~0x02 ;
}
byte /= 2 ; // Generates shorter code than byte >>= 1
GPIOR0 = byte ;
if ( --GPIOR1 == 0 )
{
TIMSK0 &= ~(1<<OCIE0A) ;
GPIOR1 = 3 ;
}
else
{
OCR0A += 20 ;
}
}
ISR(TIMER0_COMPB_vect)
{
uint8_t byte ;
byte = GPIOR2 ;
if ( byte & 0x01 )
{
PORTD |= 0x02 ;
}
else
{
PORTD &= ~0x02 ;
}
byte /= 2 ; // Generates shorter code than byte >>= 1
GPIOR2 = byte ;
if ( --GPIOR1 == 0 )
{
// prepare next byte and allow for 2 stop bits
struct t_serial_bash *ptr = &SerialControl ;
if ( ptr->head != ptr->tail )
{
GPIOR0 = ptr->data[ptr->tail] ;
GPIOR2 = ptr->data[ptr->tail+1] ;
ptr->tail = ( ptr->tail + 2 ) & 0x3F ;
GPIOR1 = 8 ;
OCR0A = OCR0B + 40 ;
OCR0B = OCR0A + 8 * 20 ;
TIMSK0 |= (1<<OCIE0A) ;
}
else
{
SerialControl.busy = 0 ;
TIMSK0 &= ~(1<<OCIE0B) ;
}
}
else
{
OCR0B += 20 ;
}
}
ISR(TIMER0_OVF_vect)
{
uint8_t byte ;
if ( GPIOR1 > 2 )
{
byte = GPIOR0 ;
}
else
{
byte = GPIOR2 ;
}
if ( byte & 0x01 )
{
PORTD |= 0x02 ;
}
else
{
PORTD &= ~0x02 ;
}
byte /= 2 ; // Generates shorter code than byte >>= 1
if ( GPIOR1 > 2 )
{
GPIOR0 = byte ;
}
else
{
GPIOR2 = byte ;
}
if ( --GPIOR1 == 0 )
{
// prepare next byte
struct t_serial_bash *ptr = &SerialControl ;
if ( ptr->head != ptr->tail )
{
GPIOR0 = ptr->data[ptr->tail] ;
GPIOR2 = ptr->data[ptr->tail+1] ;
ptr->tail = ( ptr->tail + 2 ) & 0x3F ;
GPIOR1 = 10 ;
}
else
{
SerialControl.busy = 0 ;
TIMSK0 &= ~(1<<TOIE0) ;
}
}
}
#endif // BASH_SERIAL
#endif // TELEMETRY

View File

@@ -75,7 +75,7 @@ static const uint8_t freq_hopping[][16] = {
0x18, 0x2A, 0x21, 0x38, 0x10, 0x26, 0x20, 0x1F } // 03
};
static void v202_init()
static void __attribute__((unused)) v202_init()
{
NRF24L01_Initialize();
@@ -108,7 +108,7 @@ static void v202_init()
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (uint8_t *)"\x66\x88\x68\x68\x68", 5);
}
static void V202_init2()
static void __attribute__((unused)) V202_init2()
{
NRF24L01_FlushTx();
packet_sent = 0;
@@ -119,7 +119,7 @@ static void V202_init2()
//Done by TX_EN??? => NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP));
}
static void V2X2_set_tx_id(void)
static void __attribute__((unused)) V2X2_set_tx_id(void)
{
uint8_t sum;
sum = rx_tx_addr[1] + rx_tx_addr[2] + rx_tx_addr[3];
@@ -134,7 +134,7 @@ static void V2X2_set_tx_id(void)
}
}
static void V2X2_add_pkt_checksum()
static void __attribute__((unused)) V2X2_add_pkt_checksum()
{
uint8_t sum = 0;
for (uint8_t i = 0; i < 15; ++i)
@@ -142,7 +142,7 @@ static void V2X2_add_pkt_checksum()
packet[15] = sum;
}
static void V2X2_send_packet(uint8_t bind)
static void __attribute__((unused)) V2X2_send_packet(uint8_t bind)
{
uint8_t flags2=0;
if (bind)
@@ -180,13 +180,13 @@ static void V2X2_send_packet(uint8_t bind)
//Flags2
// Channel 9
if (Servo_data[AUX5] > PPM_SWITCH)
if (Servo_AUX5)
flags2 = V2X2_FLAG_HEADLESS;
// Channel 10
if (Servo_data[AUX6] > PPM_SWITCH)
if (Servo_AUX6)
flags2 |= V2X2_FLAG_MAG_CAL_X;
// Channel 11
if (Servo_data[AUX7] > PPM_SWITCH)
if (Servo_AUX7)
flags2 |= V2X2_FLAG_MAG_CAL_Y;
}
// TX id

View File

@@ -0,0 +1,60 @@
/* -*- mode: jde; c-basic-offset: 2; indent-tabs-mode: nil -*- */
/*
Part of the Wiring project - http://wiring.org.co
Copyright (c) 2004-06 Hernando Barragan
Modified 13 August 2006, David A. Mellis for Arduino - http://www.arduino.cc/
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General
Public License along with this library; if not, write to the
Free Software Foundation, Inc., 59 Temple Place, Suite 330,
Boston, MA 02111-1307 USA
$Id$
*/
extern "C" {
#include "stdlib.h"
}
void randomSeed(unsigned int seed)
{
if (seed != 0) {
srandom(seed);
}
}
long random(long howbig)
{
if (howbig == 0) {
return 0;
}
return random() % howbig;
}
//long random(long howsmall, long howbig)
//{
// if (howsmall >= howbig) {
// return howsmall;
// }
// long diff = howbig - howsmall;
// return random(diff) + howsmall;
//}
long map(long x, long in_min, long in_max, long out_min, long out_max)
{
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
unsigned int makeWord(unsigned int w) { return w; }
unsigned int makeWord(unsigned char h, unsigned char l) { return (h << 8) | l; }

View File

@@ -34,14 +34,7 @@
#define YD717_PAYLOADSIZE 8 // receive data pipes set to this size, but unused
enum {
YD717_INIT1 = 0,
YD717_BIND2,
YD717_BIND3,
YD717_DATA
};
static void yd717_send_packet(uint8_t bind)
static void __attribute__((unused)) yd717_send_packet(uint8_t bind)
{
uint8_t rudder_trim, elevator_trim, aileron_trim;
if (bind)
@@ -125,126 +118,71 @@ static void yd717_send_packet(uint8_t bind)
NRF24L01_SetPower(); // Set tx_power
}
static void yd717_init()
static void __attribute__((unused)) yd717_init()
{
NRF24L01_Initialize();
// CRC, radio on
NRF24L01_SetTxRxMode(TX_EN);
NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_PWR_UP));
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x3F); // Auto Acknoledgement on all data pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x3F); // Enable all data pipes
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x1A); // 500uS retransmit t/o, 10 tries
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // Disable Acknoledgement on all data pipes
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x00); // Disable all data pipes
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00); // No retransmit
NRF24L01_WriteReg(NRF24L01_05_RF_CH, YD717_RF_CHANNEL); // Channel 3C
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps
NRF24L01_SetPower();
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_WriteReg(NRF24L01_0C_RX_ADDR_P2, 0xC3); // LSB byte of pipe 2 receive address
NRF24L01_WriteReg(NRF24L01_0D_RX_ADDR_P3, 0xC4);
NRF24L01_WriteReg(NRF24L01_0E_RX_ADDR_P4, 0xC5);
NRF24L01_WriteReg(NRF24L01_0F_RX_ADDR_P5, 0xC6);
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, YD717_PAYLOADSIZE); // bytes of data payload for pipe 1
NRF24L01_WriteReg(NRF24L01_12_RX_PW_P1, YD717_PAYLOADSIZE);
NRF24L01_WriteReg(NRF24L01_13_RX_PW_P2, YD717_PAYLOADSIZE);
NRF24L01_WriteReg(NRF24L01_14_RX_PW_P3, YD717_PAYLOADSIZE);
NRF24L01_WriteReg(NRF24L01_15_RX_PW_P4, YD717_PAYLOADSIZE);
NRF24L01_WriteReg(NRF24L01_16_RX_PW_P5, YD717_PAYLOADSIZE);
NRF24L01_WriteReg(NRF24L01_17_FIFO_STATUS, 0x00); // Just in case, no real bits to write here
NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit
NRF24L01_Activate(0x73); // Activate feature register
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3F); // Enable dynamic payload length on all pipes
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07); // Set feature bits on
NRF24L01_Activate(0x73); // Activate feature register
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x3F); // Enable dynamic payload length on all pipes
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x07); // Set feature bits on
NRF24L01_Activate(0x73);
// set tx id
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5);
}
static void YD717_init1()
{
// for bind packets set address to prearranged value known to receiver
uint8_t bind_rx_tx_addr[] = {0x65, 0x65, 0x65, 0x65, 0x65};
uint8_t i;
if( sub_protocol==SYMAX4 )
for(i=0; i < 5; i++)
for(uint8_t i=0; i < 5; i++)
bind_rx_tx_addr[i] = 0x60;
else
if( sub_protocol==NIHUI )
for(i=0; i < 5; i++)
for(uint8_t i=0; i < 5; i++)
bind_rx_tx_addr[i] = 0x64;
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, bind_rx_tx_addr, 5);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, bind_rx_tx_addr, 5);
}
static void YD717_init2()
{
// set rx/tx address for data phase
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5);
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5);
}
uint16_t yd717_callback()
{
switch (phase)
if(IS_BIND_DONE_on)
yd717_send_packet(0);
else
{
case YD717_INIT1:
yd717_send_packet(0); // receiver doesn't re-enter bind mode if connection lost...check if already bound
phase = YD717_BIND3;
break;
case YD717_BIND2:
if (counter == 0)
{
if (NRF24L01_packet_ack() == PKT_PENDING)
return YD717_PACKET_CHKTIME; // packet send not yet complete
YD717_init2(); // change to data phase rx/tx address
yd717_send_packet(0);
phase = YD717_BIND3;
}
else
{
if (NRF24L01_packet_ack() == PKT_PENDING)
return YD717_PACKET_CHKTIME; // packet send not yet complete;
yd717_send_packet(1);
counter--;
}
break;
case YD717_BIND3:
switch (NRF24L01_packet_ack())
{
case PKT_PENDING:
return YD717_PACKET_CHKTIME; // packet send not yet complete
case PKT_ACKED:
phase = YD717_DATA;
BIND_DONE; // bind complete
break;
case PKT_TIMEOUT:
YD717_init1(); // change to bind rx/tx address
counter = YD717_BIND_COUNT;
phase = YD717_BIND2;
yd717_send_packet(1);
}
break;
case YD717_DATA:
if (NRF24L01_packet_ack() == PKT_PENDING)
return YD717_PACKET_CHKTIME; // packet send not yet complete
if (bind_counter == 0)
{
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); // set address
yd717_send_packet(0);
break;
}
BIND_DONE; // bind complete
}
else
{
yd717_send_packet(1);
bind_counter--;
}
}
return YD717_PACKET_PERIOD; // Packet every 8ms
}
uint16_t initYD717()
{
rx_tx_addr[4] = 0xC1; // always uses first data port
BIND_IN_PROGRESS; // autobind protocol
rx_tx_addr[4] = 0xC1; // always uses first data port
yd717_init();
phase = YD717_INIT1;
BIND_IN_PROGRESS; // autobind protocol
bind_counter = YD717_BIND_COUNT;
// Call callback in 50ms
return YD717_INITIAL_WAIT;
}
#endif
#endif

View File

@@ -13,56 +13,156 @@
along with Multiprotocol. If not, see <http://www.gnu.org/licenses/>.
*/
/**********************************************/
/** Multiprotocol module configuration file ***/
/**********************************************/
//Uncomment your TX type
#define TX_ER9X //ER9X AETR (988<->2012µs)
//#define TX_DEVO7 //DEVO7 EATR (1120<->1920µs)
//#define TX_SPEKTRUM //Spektrum TAER (1100<->1900µs)
//#define TX_HISKY //HISKY AETR (1100<->1900µs)
/*******************/
/*** TX SETTINGS ***/
/*******************/
//Modify the channel order based on your TX: AETR, TAER, RETA...
//For example a JR/Spektrum radio is TAER. Default is AETR.
#define AETR
//Uncomment to enable telemetry
/****************************/
/*** PROTOCOLS TO INCLUDE ***/
/****************************/
//In this section select the protocols you want to be accessible when using the module.
//All the protocols will not fit in the module so you need to pick and choose.
//There are 4 RF components supported. If one of them is not installed you must comment it using "//".
//This is also a quick way to reduce the number of protocols and save Flash space.
#define A7105_INSTALLED
#define CYRF6936_INSTALLED
#define CC2500_INSTALLED
#define NFR24L01_INSTALLED
//Bellow is the list of all available protocols. Comment the protocols you are not using with "//" to save Flash space.
#ifdef A7105_INSTALLED
#define FLYSKY_A7105_INO
#define HUBSAN_A7105_INO
#endif
#ifdef CYRF6936_INSTALLED
#define DEVO_CYRF6936_INO
#define DSM_CYRF6936_INO
#define J6PRO_CYRF6936_INO
#endif
#ifdef CC2500_INSTALLED
#define FRSKYD_CC2500_INO
#define FRSKYV_CC2500_INO
#define FRSKYX_CC2500_INO
#define SFHSS_CC2500_INO
#endif
#ifdef NFR24L01_INSTALLED
#define BAYANG_NRF24L01_INO
#define CG023_NRF24L01_INO
#define CX10_NRF24L01_INO
#define ESKY_NRF24L01_INO
#define HISKY_NRF24L01_INO
#define KN_NRF24L01_INO
#define SLT_NRF24L01_INO
#define SYMAX_NRF24L01_INO
#define V2X2_NRF24L01_INO
#define YD717_NRF24L01_INO
#define MT99XX_NRF24L01_INO
#define MJXQ_NRF24L01_INO
#define SHENQI_NRF24L01_INO
#define FY326_NRF24L01_INO
#define FQ777_NRF24L01_INO
#define ASSAN_NRF24L01_INO
#endif
/**************************/
/*** TELEMETRY SETTINGS ***/
/**************************/
//In this section you can configure the telemetry.
//If you do not plan using the telemetry comment this global setting using "//" and skip to the next section.
#define TELEMETRY
//Comment a protocol to exclude it from compilation
#define BAYANG_NRF24L01_INO
#define CG023_NRF24L01_INO
#define CX10_NRF24L01_INO
#define DEVO_CYRF6936_INO
#define DSM2_CYRF6936_INO
#define ESKY_NRF24L01_INO
#define FLYSKY_A7105_INO
#define FRSKY_CC2500_INO
#define HISKY_NRF24L01_INO
#define HUBSAN_A7105_INO
#define KN_NRF24L01_INO
#define SLT_NRF24L01_INO
#define SYMAX_NRF24L01_INO
#define V2X2_NRF24L01_INO
#define YD717_NRF24L01_INO
//#define FRSKYX_CC2500_INO
//Uncomment to invert the polarity of the telemetry serial signal.
//For ER9X and ERSKY9X it must be commented. For OpenTX it must be uncommented.
//#define INVERT_TELEMETRY 1
//Update this table to set which protocol and all associated settings are called for the corresponding dial number
static const PPM_Parameters PPM_prot[15]=
{
// Protocol Sub protocol RX_Num Power Auto Bind Option
{MODE_FLYSKY, Flysky , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=1
{MODE_HUBSAN, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=2
{MODE_FRSKY , 0 , 0 , P_HIGH , NO_AUTOBIND , 0xD7 }, //Dial=3
{MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=4
{MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=5
{MODE_DSM2 , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=6
{MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=7
{MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=8
{MODE_KN , WLTOYS , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=9
{MODE_SYMAX , SYMAX , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=10
{MODE_SLT , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=11
{MODE_CX10 , CX10_BLUE , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=12
{MODE_CG023 , CG023 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=13
{MODE_BAYANG, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 }, //Dial=14
{MODE_SYMAX , SYMAX5C , 0 , P_HIGH , NO_AUTOBIND , 0 } //Dial=15
//Comment a line to disable a protocol telemetry
#if defined(TELEMETRY)
#if defined DSM_CYRF6936_INO
#define DSM_TELEMETRY
#endif
#if defined FRSKYX_CC2500_INO
#define SPORT_TELEMETRY
#endif
#if defined FRSKYD_CC2500_INO
#define HUB_TELEMETRY
#endif
#endif
/****************************/
/*** SERIAL MODE SETTINGS ***/
/****************************/
//In this section you can configure the serial mode.
//The serial mode enables full editing of all the parameters in the GUI of the radio.
//This is available natively for ER9X and ERSKY9X. It is available for OpenTX on Taranis with a special version.
//If you do not plan to use the Serial mode comment this line using "//" to save Flash space
#define ENABLE_SERIAL
/*************************/
/*** 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µs)
//#define TX_DEVO7 //DEVO (1120<->1920µs)
//#define TX_SPEKTRUM //Spektrum (1100<->1900µs)
//#define TX_HISKY //HISKY (1100<->1900µs)
//#define TX_CUSTOM //Custom
// The lines below are used to set the end points in microseconds (µs) if you have selected TX_CUSTOM.
// A few things to considered:
// - 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 end
// - Centered stick value is usually 1500. It should match the middle between MIN and MAX, ie Center=(MAX-MIN)/2+MIN. If your TX is not centered you can adjust the value MIN or MAX.
// - 100% is the value when the model is by default, 125% is the value when you extend the servo travel which is only used by some protocols
#if defined(TX_CUSTOM)
#define PPM_MAX_100 1900 // 100%
#define PPM_MIN_100 1100 // 100%
#define PPM_MAX_125 2000 // 125%
#define PPM_MIN_125 1000 // 125%
#endif
//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)
const PPM_Parameters PPM_prot[15]= {
// Dial Protocol Sub protocol RX_Num Power Auto Bind Option
/* 1 */ {MODE_FLYSKY, Flysky , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 2 */ {MODE_HUBSAN, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 3 */ {MODE_FRSKYD, 0 , 0 , P_HIGH , NO_AUTOBIND , 40 }, // option=fine freq tuning
/* 4 */ {MODE_HISKY , Hisky , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 5 */ {MODE_V2X2 , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 6 */ {MODE_DSM , DSM2 , 0 , P_HIGH , NO_AUTOBIND , 2 }, // option=2=6 channels @ 22ms
/* 7 */ {MODE_DEVO , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 8 */ {MODE_YD717 , YD717 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 9 */ {MODE_KN , WLTOYS , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 10 */ {MODE_SYMAX , SYMAX , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 11 */ {MODE_SLT , 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 12 */ {MODE_CX10 , CX10_BLUE , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 13 */ {MODE_CG023 , CG023 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 14 */ {MODE_BAYANG, 0 , 0 , P_HIGH , NO_AUTOBIND , 0 },
/* 15 */ {MODE_SYMAX , SYMAX5C , 0 , P_HIGH , NO_AUTOBIND , 0 }
};
/* Available protocols and associated sub protocols:
/* Available protocols and associated sub protocols to pick and choose from
MODE_FLYSKY
Flysky
V9X9
@@ -70,14 +170,14 @@ static const PPM_Parameters PPM_prot[15]=
V912
MODE_HUBSAN
NONE
MODE_FRSKY
MODE_FRSKYD
NONE
MODE_HISKY
Hisky
HK310
MODE_V2X2
NONE
MODE_DSM2
MODE_DSM
DSM2
DSMX
MODE_DEVO
@@ -112,110 +212,46 @@ static const PPM_Parameters PPM_prot[15]=
MODE_BAYANG
NONE
MODE_FRSKYX
NONE
CH_16
CH_8
MODE_ESKY
NONE
RX_Num value between 0 and 15
Power P_HIGH or P_LOW
Auto Bind AUTOBIND or NO_AUTOBIND
Option value between 0 and 255. 0xD7 or 0x00 for Frsky fine tuning.
MODE_MT99XX
MT99
H7
YZ
LS
MODE_MJXQ
WLH08
X600
X800
H26D
E010
MODE_SHENQI
NONE
MODE_FY326
NONE
MODE_SFHSS
NONE
MODE_J6PRO
NONE
MODE_FQ777
NONE
MODE_ASSAN
NONE
MODE_FRSKYV
NONE
*/
//******************
//TX definitions with timing endpoints and channels order
// RX_Num is used for model match. Using RX_Num values different for each receiver will prevent starting a model with the false config loaded...
// RX_Num value is between 0 and 15.
// Turnigy PPM and channels
#if defined(TX_ER9X)
#define PPM_MAX 2140
#define PPM_MIN 860
#define PPM_MAX_100 2012
#define PPM_MIN_100 988
enum chan_order{
AILERON =0,
ELEVATOR,
THROTTLE,
RUDDER,
AUX1,
AUX2,
AUX3,
AUX4,
AUX5,
AUX6,
AUX7,
AUX8
};
#endif
// Power P_HIGH or P_LOW: High or low power setting for the transmission.
// For indoor P_LOW is more than enough.
// Devo PPM and channels
#if defined(TX_DEVO7)
#define PPM_MAX 2100
#define PPM_MIN 900
#define PPM_MAX_100 1920
#define PPM_MIN_100 1120
enum chan_order{
ELEVATOR=0,
AILERON,
THROTTLE,
RUDDER,
AUX1,
AUX2,
AUX3,
AUX4,
AUX5,
AUX6,
AUX7,
AUX8
};
#endif
// Auto Bind AUTOBIND or NO_AUTOBIND
// For protocols which does not require binding at each power up (like Flysky, FrSky...), you might still want a bind to be initiated each time you power up the TX.
// As an exxample, it's usefull for the WLTOYS F929/F939/F949/F959 (all using the Flysky protocol) which requires a bind at each power up.
// SPEKTRUM PPM and channels
#if defined(TX_SPEKTRUM)
#define PPM_MAX 2000
#define PPM_MIN 1000
#define PPM_MAX_100 1900
#define PPM_MIN_100 1100
enum chan_order{
THROTTLE=0,
AILERON,
ELEVATOR,
RUDDER,
AUX1,
AUX2,
AUX3,
AUX4,
AUX5,
AUX6,
AUX7,
AUX8
};
#endif
// HISKY
#if defined(TX_HISKY)
#define PPM_MAX 2000
#define PPM_MIN 1000
#define PPM_MAX_100 1900
#define PPM_MIN_100 1100
enum chan_order{
AILERON =0,
ELEVATOR,
THROTTLE,
RUDDER,
AUX1,
AUX2,
AUX3,
AUX4,
AUX5,
AUX6,
AUX7,
AUX8
};
#endif
#define PPM_MIN_COMMAND 1250
#define PPM_SWITCH 1550
#define PPM_MAX_COMMAND 1750
// Option: the value is between -127 and +127.
// The option value is only valid for some protocols, read this page for more information: https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/blob/master/Protocols_Details.md

View File

@@ -16,6 +16,16 @@
#ifndef _IFACE_CC2500_H_
#define _IFACE_CC2500_H_
enum {
FRSKY_BIND = 0,
FRSKY_BIND_DONE = 1000,
FRSKY_DATA1,
FRSKY_DATA2,
FRSKY_DATA3,
FRSKY_DATA4,
FRSKY_DATA5
};
enum {
CC2500_00_IOCFG2 = 0x00, // GDO2 output pin configuration
CC2500_01_IOCFG1 = 0x01, // GDO1 output pin configuration
@@ -146,4 +156,43 @@ enum {
//void CC2500_WriteData(u8 *packet, u8 length);
//void CC2500_ReadData(u8 *dpbuffer, int len);
//void CC2500_SetTxRxMode(enum TXRX_State);
const PROGMEM uint8_t cc2500_conf[][2]={
{ CC2500_02_IOCFG0, 0x06 },
{ CC2500_00_IOCFG2, 0x06 },
{ CC2500_17_MCSM1, 0x0c },
{ CC2500_18_MCSM0, 0x18 },
{ CC2500_06_PKTLEN, 0x19 },
{ CC2500_07_PKTCTRL1, 0x04 },
{ CC2500_08_PKTCTRL0, 0x05 },
{ CC2500_3E_PATABLE, 0xff },
{ CC2500_0B_FSCTRL1, 0x08 },
{ CC2500_0C_FSCTRL0, 0x00 }, // option
{ CC2500_0D_FREQ2, 0x5c },
{ CC2500_0E_FREQ1, 0x76 },
{ CC2500_0F_FREQ0, 0x27 },
{ CC2500_10_MDMCFG4, 0xAA },
{ CC2500_11_MDMCFG3, 0x39 },
{ CC2500_12_MDMCFG2, 0x11 },
{ CC2500_13_MDMCFG1, 0x23 },
{ CC2500_14_MDMCFG0, 0x7a },
{ CC2500_15_DEVIATN, 0x42 },
{ CC2500_19_FOCCFG, 0x16 },
{ CC2500_1A_BSCFG, 0x6c },
{ CC2500_1B_AGCCTRL2, 0x43 }, // bind ? 0x43 : 0x03
{ CC2500_1C_AGCCTRL1,0x40 },
{ CC2500_1D_AGCCTRL0,0x91 },
{ CC2500_21_FREND1, 0x56 },
{ CC2500_22_FREND0, 0x10 },
{ CC2500_23_FSCAL3, 0xa9 },
{ CC2500_24_FSCAL2, 0x0A },
{ CC2500_25_FSCAL1, 0x00 },
{ CC2500_26_FSCAL0, 0x11 },
{ CC2500_29_FSTEST, 0x59 },
{ CC2500_2C_TEST2, 0x88 },
{ CC2500_2D_TEST1, 0x31 },
{ CC2500_2E_TEST0, 0x0B },
{ CC2500_03_FIFOTHR, 0x07 },
{ CC2500_09_ADDR, 0x00 }
};
#endif

View File

@@ -102,18 +102,9 @@ enum {
#define REUSE_TX_PL 0xE3
//#define NOP 0xFF
/*
void NRF24L01_Initialize();
byte NRF24L01_WriteReg(byte reg, byte data);
byte NRF24L01_WriteRegisterMulti(byte reg, byte data[], byte length);
byte NRF24L01_WritePayload(byte *data, byte len);
byte NRF24L01_ReadReg(byte reg);
byte NRF24L01_ReadRegisterMulti(byte reg, byte data[], byte length);
byte NRF24L01_ReadPayload(byte *data, byte len);
byte NRF24L01_FlushTx();
byte NRF24L01_FlushRx();
byte NRF24L01_Activate(byte code);
*/
// XN297 emulation layer
enum {
XN297_UNSCRAMBLED = 0,
XN297_SCRAMBLED
};
#endif

View File

@@ -1,449 +0,0 @@
/*
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/>.
*/
//******************
// Protocols
//******************
enum PROTOCOLS
{
MODE_SERIAL = 0, // Serial commands
MODE_FLYSKY = 1, // =>A7105 / FLYSKY protocol
MODE_HUBSAN = 2, // =>A7105 / HUBSAN protocol
MODE_FRSKY = 3, // =>CC2500 / FRSKY protocol
MODE_HISKY = 4, // =>NRF24L01 / HISKY protocol
MODE_V2X2 = 5, // =>NRF24L01 / V2x2 protocol
MODE_DSM2 = 6, // =>CYRF6936 / DSM2 protocol
MODE_DEVO =7, // =>CYRF6936 / DEVO protocol
MODE_YD717 = 8, // =>NRF24L01 / YD717 protocol (CX10 red pcb)
MODE_KN = 9, // =>NRF24L01 / KN protocol
MODE_SYMAX = 10, // =>NRF24L01 / SYMAX protocol
MODE_SLT = 11, // =>NRF24L01 / SLT protocol
MODE_CX10 = 12, // =>NRF24L01 / CX-10 protocol
MODE_CG023 = 13, // =>NRF24L01 / CG023 protocol
MODE_BAYANG = 14, // =>NRF24L01 / BAYANG protocol
MODE_FRSKYX = 15, // =>CC2500 / FRSKYX protocol
MODE_ESKY = 16, // =>NRF24L01 / ESKY protocol
};
enum Flysky
{
Flysky=0,
V9X9=1,
V6X6=2,
V912=3
};
enum Hisky
{
Hisky=0,
HK310=1
};
enum DSM2{
DSM2=0,
DSMX=1
};
enum YD717
{
YD717=0,
SKYWLKR=1,
SYMAX4=2,
XINXUN=3,
NIHUI=4
};
enum KN
{
WLTOYS=0,
FEILUN=1
};
enum SYMAX
{
SYMAX=0,
SYMAX5C=1
};
enum CX10
{
CX10_GREEN = 0,
CX10_BLUE=1, // also compatible with CX10-A, CX12
DM007=2,
Q282=3,
JC3015_1=4,
JC3015_2=5,
MK33041=6,
Q242=7
};
enum CG023
{
CG023 = 0,
YD829 = 1,
H8_3D = 2
};
#define NONE 0
#define P_HIGH 1
#define P_LOW 0
#define AUTOBIND 1
#define NO_AUTOBIND 0
struct PPM_Parameters
{
uint8_t protocol : 5;
uint8_t sub_proto : 3;
uint8_t rx_num : 4;
uint8_t power : 1;
uint8_t autobind : 1;
uint8_t option;
};
//*******************
//*** Pinouts ***
//*******************
//#define BIND_pin 13
#define LED_pin 13 //Promini original led on B5
//
#define PPM_pin 3 //PPM -D3
#define SDI_pin 5 //SDIO-D5
#define SCLK_pin 4 //SCK-D4
#define CS_pin 2 //CS-D2
#define SDO_pin 6 //D6
//
#define CTRL1 1 //C1 (A1)
#define CTRL2 2 //C2 (A2)
//
#define CTRL1_on PORTC |= _BV(1)
#define CTRL1_off PORTC &= ~_BV(1)
//
#define CTRL2_on PORTC |= _BV(2)
#define CTRL2_off PORTC &= ~_BV(2)
//
#define CS_on PORTD |= _BV(2) //D2
#define CS_off PORTD &= ~_BV(2) //D2
//
#define SCK_on PORTD |= _BV(4) //D4
#define SCK_off PORTD &= ~_BV(4) //D4
//
#define SDI_on PORTD |= _BV(5) //D5
#define SDI_off PORTD &= ~_BV(5) //D5
#define SDI_1 (PIND & (1<<SDI_pin)) == (1<<SDI_pin) //D5
#define SDI_0 (PIND & (1<<SDI_pin)) == 0x00 //D5
//
#define SDI_SET_INPUT DDRD &= ~_BV(5) //D5
#define SDI_SET_OUTPUT DDRD |= _BV(5) //D5
//Hisky /CC2500/CYRF aditional pinout
#define CC25_CSN_pin 7
#define NRF_CSN_pin 8
#define CYRF_CSN_pin 9
//
#define CYRF_RST_pin A5 //reset pin
//
#define CC25_CSN_on PORTD |= _BV(7) //D7
#define CC25_CSN_off PORTD &= ~_BV(7) //D7
//
#define NRF_CSN_on PORTB |= _BV(0) //D8
#define NRF_CSN_off PORTB &= ~_BV(0) //D8
//
#define CYRF_CSN_on PORTB |= _BV(1) //D9
#define CYRF_CSN_off PORTB &= ~_BV(1) //D9
//
#define SDO_1 (PIND & (1<<SDO_pin)) == (1<<SDO_pin) //D6
#define SDO_0 (PIND & (1<<SDO_pin)) == 0x00 //D6
//
#define RS_HI PORTC|=_BV(5) //reset pin cyrf
#define RX_LO PORTB &= ~_BV(5)//
//
//
// LED
#define LED_ON PORTB |= _BV(5)
#define LED_OFF PORTB &= ~_BV(5)
#define LED_TOGGLE PORTB ^= _BV(5)
#define LED_SET_OUTPUT DDRB |= _BV(5)
#define IS_LED_on ( (PORTB & _BV(5)) != 0x00 )
// Macros
#define NOP() __asm__ __volatile__("nop")
#define BV(bit) (1 << bit)
//Serial flags definition
#define RX_FLAG_on protocol_flags |= _BV(0)
#define RX_FLAG_off protocol_flags &= ~_BV(0)
#define IS_RX_FLAG_on ( ( protocol_flags & _BV(0) ) !=0 )
//
#define CHANGE_PROTOCOL_FLAG_on protocol_flags |= _BV(1)
#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 RANGE_FLAG_on protocol_flags |= _BV(3)
#define RANGE_FLAG_off protocol_flags &= ~_BV(3)
#define IS_RANGE_FLAG_on ( ( protocol_flags & _BV(3) ) !=0 )
//
#define AUTOBIND_FLAG_on protocol_flags |= _BV(4)
#define AUTOBIND_FLAG_off protocol_flags &= ~_BV(4)
#define IS_AUTOBIND_FLAG_on ( ( protocol_flags & _BV(4) ) !=0 )
//
#define BIND_BUTTON_FLAG_on protocol_flags |= _BV(5)
#define BIND_BUTTON_FLAG_off protocol_flags &= ~_BV(5)
#define IS_BIND_BUTTON_FLAG_on ( ( protocol_flags & _BV(5) ) !=0 )
//PPM RX OK
#define PPM_FLAG_off protocol_flags &= ~_BV(6)
#define PPM_FLAG_on protocol_flags |= _BV(6)
#define IS_PPM_FLAG_on ( ( protocol_flags & _BV(6) ) !=0 )
//Bind flag for blinking
#define BIND_IN_PROGRESS protocol_flags &= ~_BV(7)
#define BIND_DONE protocol_flags |= _BV(7)
#define IS_BIND_DONE_on ( ( protocol_flags & _BV(7) ) !=0 )
#define BAD_PROTO_off protocol_flags2 &= ~_BV(0)
#define BAD_PROTO_on protocol_flags2 |= _BV(0)
#define IS_BAD_PROTO_on ( ( protocol_flags2 & _BV(0) ) !=0 )
#define BLINK_BIND_TIME 100
#define BLINK_SERIAL_TIME 500
#define BLINK_BAD_PROTO_TIME_LOW 1000
#define BLINK_BAD_PROTO_TIME_HIGH 50
//AUX flags definition
#define Servo_AUX1 Servo_AUX & _BV(0)
#define Servo_AUX2 Servo_AUX & _BV(1)
#define Servo_AUX3 Servo_AUX & _BV(2)
#define Servo_AUX4 Servo_AUX & _BV(3)
#define Servo_AUX5 Servo_AUX & _BV(4)
#define Servo_AUX6 Servo_AUX & _BV(5)
#define Servo_AUX7 Servo_AUX & _BV(6)
#define Servo_AUX8 Servo_AUX & _BV(7)
//************************
//*** Power settings ***
//************************
enum {
TXPOWER_100uW,
TXPOWER_300uW,
TXPOWER_1mW,
TXPOWER_3mW,
TXPOWER_10mW,
TXPOWER_30mW,
TXPOWER_100mW,
TXPOWER_150mW
};
// A7105 power
// Power amp is ~+16dBm so:
enum A7105_POWER
{
A7105_POWER_0 = 0x00<<3 | 0x00, // TXPOWER_100uW = -23dBm == PAC=0 TBG=0
A7105_POWER_1 = 0x00<<3 | 0x01, // TXPOWER_300uW = -20dBm == PAC=0 TBG=1
A7105_POWER_2 = 0x00<<3 | 0x02, // TXPOWER_1mW = -16dBm == PAC=0 TBG=2
A7105_POWER_3 = 0x00<<3 | 0x04, // TXPOWER_3mW = -11dBm == PAC=0 TBG=4
A7105_POWER_4 = 0x01<<3 | 0x05, // TXPOWER_10mW = -6dBm == PAC=1 TBG=5
A7105_POWER_5 = 0x02<<3 | 0x07, // TXPOWER_30mW = 0dBm == PAC=2 TBG=7
A7105_POWER_6 = 0x03<<3 | 0x07, // TXPOWER_100mW = 1dBm == PAC=3 TBG=7
A7105_POWER_7 = 0x03<<3 | 0x07 // TXPOWER_150mW = 1dBm == PAC=3 TBG=7
};
#define A7105_HIGH_POWER A7105_POWER_5
#define A7105_LOW_POWER A7105_POWER_3
#define A7105_BIND_POWER A7105_POWER_0
#define A7105_RANGE_POWER A7105_POWER_0
// NRF Power
// Power setting is 0..3 for nRF24L01
// Claimed power amp for nRF24L01 from eBay is 20dBm.
enum NRF_POWER
{ // Raw w 20dBm PA
NRF_POWER_0 = 0x00, // 0 : -18dBm (16uW) 2dBm (1.6mW)
NRF_POWER_1 = 0x01, // 1 : -12dBm (60uW) 8dBm (6mW)
NRF_POWER_2 = 0x02, // 2 : -6dBm (250uW) 14dBm (25mW)
NRF_POWER_3 = 0x03 // 3 : 0dBm (1mW) 20dBm (100mW)
};
#define NRF_HIGH_POWER NRF_POWER_2
#define NRF_LOW_POWER NRF_POWER_1
#define NRF_BIND_POWER NRF_POWER_0
#define NRF_RANGE_POWER NRF_POWER_0
// CC2500 power
enum CC2500_POWER
{
CC2500_POWER_0 = 0xC5, // -12dbm
CC2500_POWER_1 = 0x97, // -10dbm
CC2500_POWER_2 = 0x6E, // -8dbm
CC2500_POWER_3 = 0x7F, // -6dbm
CC2500_POWER_4 = 0xA9, // -4dbm
CC2500_POWER_5 = 0xBB, // -2dbm
CC2500_POWER_6 = 0xFE, // 0dbm
CC2500_POWER_7 = 0xFF // 1.5dbm
};
#define CC2500_HIGH_POWER CC2500_POWER_6
#define CC2500_LOW_POWER CC2500_POWER_3
#define CC2500_BIND_POWER CC2500_POWER_0
#define CC2500_RANGE_POWER CC2500_POWER_0
// CYRF power
enum CYRF_POWER
{
CYRF_POWER_0 = 0x00, // -35dbm
CYRF_POWER_1 = 0x01, // -30dbm
CYRF_POWER_2 = 0x02, // -24dbm
CYRF_POWER_3 = 0x03, // -18dbm
CYRF_POWER_4 = 0x04, // -13dbm
CYRF_POWER_5 = 0x05, // -5dbm
CYRF_POWER_6 = 0x06, // 0dbm
CYRF_POWER_7 = 0x07 // +4dbm
};
#define CYRF_HIGH_POWER CYRF_POWER_7
#define CYRF_LOW_POWER CYRF_POWER_3
#define CYRF_BIND_POWER CYRF_POWER_0
#define CYRF_RANGE_POWER CYRF_POWER_0
enum TXRX_State {
TXRX_OFF,
TX_EN,
RX_EN
};
// Packet ack status values
enum {
PKT_PENDING = 0,
PKT_ACKED,
PKT_TIMEOUT
};
//*******************
//*** CRC Table ***
//*******************
const uint16_t PROGMEM CRCTable[]=
{
0x0000,0x1189,0x2312,0x329b,0x4624,0x57ad,0x6536,0x74bf,
0x8c48,0x9dc1,0xaf5a,0xbed3,0xca6c,0xdbe5,0xe97e,0xf8f7,
0x1081,0x0108,0x3393,0x221a,0x56a5,0x472c,0x75b7,0x643e,
0x9cc9,0x8d40,0xbfdb,0xae52,0xdaed,0xcb64,0xf9ff,0xe876,
0x2102,0x308b,0x0210,0x1399,0x6726,0x76af,0x4434,0x55bd,
0xad4a,0xbcc3,0x8e58,0x9fd1,0xeb6e,0xfae7,0xc87c,0xd9f5,
0x3183,0x200a,0x1291,0x0318,0x77a7,0x662e,0x54b5,0x453c,
0xbdcb,0xac42,0x9ed9,0x8f50,0xfbef,0xea66,0xd8fd,0xc974,
0x4204,0x538d,0x6116,0x709f,0x0420,0x15a9,0x2732,0x36bb,
0xce4c,0xdfc5,0xed5e,0xfcd7,0x8868,0x99e1,0xab7a,0xbaf3,
0x5285,0x430c,0x7197,0x601e,0x14a1,0x0528,0x37b3,0x263a,
0xdecd,0xcf44,0xfddf,0xec56,0x98e9,0x8960,0xbbfb,0xaa72,
0x6306,0x728f,0x4014,0x519d,0x2522,0x34ab,0x0630,0x17b9,
0xef4e,0xfec7,0xcc5c,0xddd5,0xa96a,0xb8e3,0x8a78,0x9bf1,
0x7387,0x620e,0x5095,0x411c,0x35a3,0x242a,0x16b1,0x0738,
0xffcf,0xee46,0xdcdd,0xcd54,0xb9eb,0xa862,0x9af9,0x8b70,
0x8408,0x9581,0xa71a,0xb693,0xc22c,0xd3a5,0xe13e,0xf0b7,
0x0840,0x19c9,0x2b52,0x3adb,0x4e64,0x5fed,0x6d76,0x7cff,
0x9489,0x8500,0xb79b,0xa612,0xd2ad,0xc324,0xf1bf,0xe036,
0x18c1,0x0948,0x3bd3,0x2a5a,0x5ee5,0x4f6c,0x7df7,0x6c7e,
0xa50a,0xb483,0x8618,0x9791,0xe32e,0xf2a7,0xc03c,0xd1b5,
0x2942,0x38cb,0x0a50,0x1bd9,0x6f66,0x7eef,0x4c74,0x5dfd,
0xb58b,0xa402,0x9699,0x8710,0xf3af,0xe226,0xd0bd,0xc134,
0x39c3,0x284a,0x1ad1,0x0b58,0x7fe7,0x6e6e,0x5cf5,0x4d7c,
0xc60c,0xd785,0xe51e,0xf497,0x8028,0x91a1,0xa33a,0xb2b3,
0x4a44,0x5bcd,0x6956,0x78df,0x0c60,0x1de9,0x2f72,0x3efb,
0xd68d,0xc704,0xf59f,0xe416,0x90a9,0x8120,0xb3bb,0xa232,
0x5ac5,0x4b4c,0x79d7,0x685e,0x1ce1,0x0d68,0x3ff3,0x2e7a,
0xe70e,0xf687,0xc41c,0xd595,0xa12a,0xb0a3,0x8238,0x93b1,
0x6b46,0x7acf,0x4854,0x59dd,0x2d62,0x3ceb,0x0e70,0x1ff9,
0xf78f,0xe606,0xd49d,0xc514,0xb1ab,0xa022,0x92b9,0x8330,
0x7bc7,0x6a4e,0x58d5,0x495c,0x3de3,0x2c6a,0x1ef1,0x0f78
};
//****************************************
//*** MULTI protocol serial definition ***
//****************************************
/*
**************************
16 channels serial protocol
**************************
Serial: 100000 Baud 8e2 _ xxxx xxxx p --
Total of 26 bytes
Stream[0] = 0x55
header
Stream[1] = sub_protocol|BindBit|RangeCheckBit|AutoBindBit;
sub_protocol is 0..31 (bits 0..4)
=> Reserved 0
Flysky 1
Hubsan 2
Frsky 3
Hisky 4
V2x2 5
DSM2 6
Devo 7
YD717 8
KN 9
SymaX 10
SLT 11
CX10 12
CG023 13
Bayang 14
FrskyX 15
ESky 16
BindBit=> 0x80 1=Bind/0=No
AutoBindBit=> 0x40 1=Yes /0=No
RangeCheck=> 0x20 1=Yes /0=No
Stream[2] = RxNum | Power | Type;
RxNum value is 0..15 (bits 0..3)
Type is 0..7 <<4 (bit 4..6)
sub_protocol==Flysky
Flysky 0
V9x9 1
V6x6 2
V912 3
sub_protocol==Hisky
Hisky 0
HK310 1
sub_protocol==DSM2
DSM2 0
DSMX 1
sub_protocol==YD717
YD717 0
SKYWLKR 1
SYMAX4 2
XINXUN 3
NIHUI 4
sub_protocol==KN
WLTOYS 0
FEILUN 1
sub_protocol==SYMAX
SYMAX 0
SYMAX5C 1
sub_protocol==CX10
CX10_GREEN 0
CX10_BLUE 1 // also compatible with CX10-A, CX12
DM007 2
Q282 3
JC3015_1 4
JC3015_2 5
MK33041 6
Q242 7
sub_protocol==CG023
CG023 0
YD829 1
H8_3D 2
Power value => 0x80 0=High/1=Low
Stream[3] = option_protocol;
option_protocol value is -127..127
Stream[4] to [25] = Channels
16 Channels on 11 bits (0..2047)
0 -125%
204 -100%
1024 0%
1843 +100%
2047 +125%
Channels bits are concatenated to fit in 22 bytes like in SBUS protocol
*/

View File

@@ -1,63 +0,0 @@
/*
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/>.
*/
static void frskySendStuffed(uint8_t frame[])
{
Serial_write(0x7E);
for (uint8_t i = 0; i < 9; i++) {
if ((frame[i] == 0x7e) || (frame[i] == 0x7d)) {
Serial_write(0x7D);
frame[i] ^= 0x20;
}
Serial_write(frame[i]);
}
Serial_write(0x7E);
}
static void frskySendFrame()
{
uint8_t frame[9];
frame[0] = 0xfe;
if ((cur_protocol[0]&0x1F)==MODE_FRSKY)
{
compute_RSSIdbm();
frame[1] = pktt[3];
frame[2] = pktt[4];
frame[3] = (uint8_t)RSSI_dBm;
frame[4] = pktt[5]*2;//txrssi
frame[5] = frame[6] = frame[7] = frame[8] = 0;
}
else
if ((cur_protocol[0]&0x1F)==MODE_HUBSAN)
{
frame[1] = v_lipo*2;
frame[2] = 0;
frame[3] = 0x5A;//dummy value
frame[4] = 2 * 0x5A;//dummy value
frame[5] = frame[6] = frame[7] = frame[8] = 0;
}
frskySendStuffed(frame);
}
void frskyUpdate()
{
if(telemetry_link)
{
frskySendFrame();
telemetry_link=0;
}
}

View File

@@ -0,0 +1,412 @@
EESchema-LIBRARY Version 2.3 Date: 05/02/2016 16:56:43
#encoding utf-8
#
# +5V
#
DEF +5V #PWR 0 40 Y Y 1 F P
F0 "#PWR" 0 90 20 H I C CNN
F1 "+5V" 0 90 30 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
DRAW
X +5V 1 0 0 0 U 20 20 0 0 W N
C 0 50 20 0 1 0 N
P 4 0 1 0 0 0 0 30 0 30 0 30 N
ENDDRAW
ENDDEF
#
# +BATT
#
DEF +BATT #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -50 20 H I C CNN
F1 "+BATT" 0 100 30 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
DRAW
X +BATT 1 0 0 0 U 20 20 0 0 w N
C 0 60 20 0 1 0 N
P 3 0 1 0 0 0 0 40 0 40 N
ENDDRAW
ENDDEF
#
# 3V3
#
DEF 3V3 #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 100 40 H I C CNN
F1 "3V3" 0 125 40 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
DRAW
X 3V3 1 0 0 0 U 30 30 0 0 W N
P 2 0 1 0 0 60 0 0 N
P 6 0 1 0 0 60 20 40 0 90 -20 40 0 60 0 60 N
ENDDRAW
ENDDEF
#
# A7105
#
DEF A7105 U 0 40 Y Y 1 F N
F0 "U" 500 650 60 H V C CNN
F1 "A7105" 0 800 60 H V C CNN
F2 "~" 0 -400 60 H V C CNN
F3 "~" 0 -400 60 H V C CNN
DRAW
S 400 -800 -350 700 0 1 0 N
X 3V3 1 -650 550 300 R 70 70 1 1 I
X SCS 2 -650 400 300 R 70 70 1 1 I
X GND 3 -650 250 300 R 70 70 1 1 I
X SCK 4 -650 100 300 R 70 70 1 1 I
X SDIO 5 -650 -50 300 R 70 70 1 1 I
X GIO1 6 -650 -200 300 R 70 70 1 1 I
X GIO2 7 -650 -350 300 R 70 70 1 1 O
X RXEN 8 -650 -500 300 R 70 70 1 1 I
X TXEN 9 -650 -650 300 R 70 70 1 1 O
ENDDRAW
ENDDEF
#
# ATMEGA168A-A
#
DEF ATMEGA168A-A IC 0 40 Y Y 1 F N
F0 "IC" -750 1250 40 H V L BNN
F1 "ATMEGA168A-A" 400 -1400 40 H V L BNN
F2 "TQFP32" 0 0 30 H V C CIN
F3 "~" 0 0 60 H V C CNN
ALIAS ATMEGA48A-A ATMEGA48PA-A ATMEGA88A-A ATMEGA88PA-A ATMEGA168PA-A ATMEGA328-A ATMEGA328P-A
DRAW
S -750 1200 850 -1300 0 1 10 f
X (PCINT19/OC2B/INT1)PD3 1 1000 -800 150 L 40 40 1 1 B
X (PCINT20/XCK/T0)PD4 2 1000 -900 150 L 40 40 1 1 B
X GND 3 -900 -1200 150 R 40 40 1 1 W
X VCC 4 -900 1100 150 R 40 40 1 1 W
X GND 5 -900 -1100 150 R 40 40 1 1 W
X VCC 6 -900 1000 150 R 40 40 1 1 W
X (PCINT6/XTAL1/TOSC1)PB6 7 1000 500 150 L 40 40 1 1 B
X (PCINT7/XTAL2/TOSC2)PB7 8 1000 400 150 L 40 40 1 1 B
X (PCINT21/OC0B/T1)PD5 9 1000 -1000 150 L 40 40 1 1 B
X (PCINT22/OC0A/AIN0)PD6 10 1000 -1100 150 L 40 40 1 1 B
X AREF 20 -900 500 150 R 40 40 1 1 B
X (PCINT16/RXD)PD0 30 1000 -500 150 L 40 40 1 1 B
X (PCINT23/AIN1)PD7 11 1000 -1200 150 L 40 40 1 1 B
X GND 21 -900 -1000 150 R 40 40 1 1 W
X (PCINT17/TXD)PD1 31 1000 -600 150 L 40 40 1 1 B
X (PCINT0/CLKO/ICP1)PB0 12 1000 1100 150 L 40 40 1 1 B
X ADC7 22 -900 -350 150 R 40 40 1 1 N
X (PCINT18/INT0)PD2 32 1000 -700 150 L 40 40 1 1 B
X (PCINT1/OC1A)PB1 13 1000 1000 150 L 40 40 1 1 B
X (PCINT8/ADC0)PC0 23 1000 250 150 L 40 40 1 1 B
X (PCINT2/OC1B/~SS~)PB2 14 1000 900 150 L 40 40 1 1 B
X (PCINT9/ADC1)PC1 24 1000 150 150 L 40 40 1 1 B
X (PCINT3/OC2A/MOSI)PB3 15 1000 800 150 L 40 40 1 1 B
X (PCINT10/ADC2)PC2 25 1000 50 150 L 40 40 1 1 B
X (PCINT4/MISO)PB4 16 1000 700 150 L 40 40 1 1 B
X (PCINT11/ADC3)PC3 26 1000 -50 150 L 40 40 1 1 B
X (PCINT5/SCK)PB5 17 1000 600 150 L 40 40 1 1 B
X (PCINT12/SDA/ADC4)PC4 27 1000 -150 150 L 40 40 1 1 B
X AVCC 18 -900 800 150 R 40 40 1 1 W
X (PCINT14/SCL/ADC5)PC5 28 1000 -250 150 L 40 40 1 1 B
X ADC6 19 -900 -250 150 R 40 40 1 1 N
X (PCINT14/~RESET~)PC6 29 1000 -350 150 L 40 40 1 1 B
ENDDRAW
ENDDEF
#
# C
#
DEF C C 0 10 N Y 1 F N
F0 "C" 0 100 40 H V L CNN
F1 "C" 6 -85 40 H V L CNN
F2 "~" 38 -150 30 H V C CNN
F3 "~" 0 0 60 H V C CNN
$FPLIST
SM*
C?
C1-1
$ENDFPLIST
DRAW
P 2 0 1 20 -80 -30 80 -30 N
P 2 0 1 20 -80 30 80 30 N
X ~ 1 0 200 170 D 40 40 1 1 P
X ~ 2 0 -200 170 U 40 40 1 1 P
ENDDRAW
ENDDEF
#
# CC2500
#
DEF CC2500 U 0 40 Y Y 1 F N
F0 "U" 500 600 60 H V C CNN
F1 "CC2500" 0 700 60 H V C CNN
F2 "~" 0 -400 60 H V C CNN
F3 "~" 0 -400 60 H V C CNN
DRAW
S 400 -900 -350 650 0 1 0 N
X 3V3 1 -650 550 300 R 70 70 1 1 I
X SI 2 -650 400 300 R 70 70 1 1 I
X SCLK 3 -650 250 300 R 70 70 1 1 I
X SO 4 -650 100 300 R 70 70 1 1 I
X GDO2 5 -650 -50 300 R 70 70 1 1 I
X GND 6 -650 -200 300 R 70 70 1 1 I
X GDOo 7 -650 -350 300 R 70 70 1 1 I
X CSn 8 -650 -500 300 R 70 70 1 1 I
X PA_EN 9 -650 -650 300 R 70 70 1 1 I
X LNA_EN 10 -650 -800 300 R 70 70 1 1 I
ENDDRAW
ENDDEF
#
# CONN_2
#
DEF CONN_2 P 0 40 Y N 1 F N
F0 "P" -50 0 40 V V C CNN
F1 "CONN_2" 50 0 40 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
DRAW
S -100 150 100 -150 0 1 0 N
X P1 1 -350 100 250 R 60 60 1 1 P I
X PM 2 -350 -100 250 R 60 60 1 1 P I
ENDDRAW
ENDDEF
#
# CONN_3X2
#
DEF CONN_3X2 P 0 40 Y N 1 F N
F0 "P" 0 250 50 H V C CNN
F1 "CONN_3X2" 0 50 40 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
DRAW
S -100 200 100 -100 0 1 0 N
X 1 1 -400 150 300 R 60 60 1 1 P I
X 2 2 400 150 300 L 60 60 1 1 P I
X 3 3 -400 50 300 R 60 60 1 1 P I
X 4 4 400 50 300 L 60 60 1 1 P I
X 5 5 -400 -50 300 R 60 60 1 1 P I
X 6 6 400 -50 300 L 60 60 1 1 P I
ENDDRAW
ENDDEF
#
# CONN_5
#
DEF CONN_5 P 0 40 Y Y 1 F N
F0 "P" -50 0 50 V V C CNN
F1 "CONN_5" 50 0 50 V V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
DRAW
S -100 250 100 -250 0 1 0 f
X ~ 1 -400 200 300 R 60 60 1 1 P I
X ~ 2 -400 100 300 R 60 60 1 1 P I
X ~ 3 -400 0 300 R 60 60 1 1 P I
X ~ 4 -400 -100 300 R 60 60 1 1 P I
X ~ 5 -400 -200 300 R 60 60 1 1 P I
ENDDRAW
ENDDEF
#
# CP1
#
DEF CP1 C 0 10 N N 1 F N
F0 "C" 50 100 50 H V L CNN
F1 "CP1" 50 -100 50 H V L CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
$FPLIST
CP*
SM*
$ENDFPLIST
DRAW
T 0 -50 100 80 0 0 0 + Normal 0 C C
A 0 -200 180 563 1236 0 1 15 N 100 -50 -100 -50
P 4 0 1 15 -100 50 100 50 50 50 50 50 N
X ~ 1 0 200 150 D 40 40 1 1 P
X ~ 2 0 -200 180 U 40 40 1 1 P
ENDDRAW
ENDDEF
#
# CRYSTAL
#
DEF CRYSTAL X 0 40 N N 1 F N
F0 "X" 0 150 60 H V C CNN
F1 "CRYSTAL" 0 -150 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
DRAW
P 2 0 1 16 -100 100 -100 -100 N
P 2 0 1 16 100 100 100 -100 N
P 5 0 1 12 -50 50 50 50 50 -50 -50 -50 -50 50 f
X 1 1 -300 -50 200 R 40 40 1 1 P
X 2 2 -300 50 200 R 40 40 1 1 P
X 3 3 300 50 200 L 40 40 1 1 P
X 4 4 300 -50 200 L 40 40 1 1 P
ENDDRAW
ENDDEF
#
# CYRF6936
#
DEF CYRF6936 U 0 40 Y Y 1 F N
F0 "U" 0 1000 60 H V C CNN
F1 "CYRF6936" 0 800 60 H V C CNN
F2 "~" 0 -400 60 H V C CNN
F3 "~" 0 -400 60 H V C CNN
DRAW
S 400 -800 -350 700 0 1 0 N
X 5.0V 1 -650 500 300 R 70 70 1 1 I
X NCS 2 -650 350 300 R 70 70 1 1 I
X SCK 4 -650 200 300 R 70 70 1 1 I
X GND 5 -650 50 300 R 70 70 1 1 I
X GND 6 -650 -100 300 R 70 70 1 1 I
X MOSI 8 -650 -250 300 R 70 70 1 1 I
X RST 9 -650 -400 300 R 70 70 1 1 I
X MISO 10 -650 -600 300 R 70 70 1 1 I
ENDDRAW
ENDDEF
#
# GND
#
DEF ~GND #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 0 30 H I C CNN
F1 "GND" 0 -70 30 H I C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
DRAW
P 4 0 1 0 -50 0 0 -50 50 0 -50 0 N
X GND 1 0 0 0 U 30 30 1 1 W N
ENDDRAW
ENDDEF
#
# HEX_DIP
#
DEF HEX_DIP SW 0 40 Y Y 1 F N
F0 "SW" 0 -350 60 H V C CNN
F1 "HEX_DIP" 0 350 60 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
DRAW
S -200 250 200 -250 0 1 0 N
P 4 0 1 0 50 50 -50 0 50 -100 50 50 F
X 1 1 500 -150 300 L 50 50 1 1 O
X C 2 500 0 300 L 50 50 1 1 P
X 4 3 500 150 300 L 50 50 1 1 O
X 2 4 -500 150 300 R 50 50 1 1 O
X C 5 -500 0 300 R 50 50 1 1 P
X 8 6 -500 -150 300 R 50 50 1 1 O
ENDDRAW
ENDDEF
#
# JUMPER
#
DEF JUMPER JP 0 30 Y N 1 F N
F0 "JP" 0 150 60 H V C CNN
F1 "JUMPER" 0 -80 40 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
DRAW
A 0 -26 125 1426 373 0 1 0 N -98 50 99 50
C -100 0 35 0 1 0 N
C 100 0 35 0 1 0 N
X 1 1 -300 0 165 R 60 60 0 1 P
X 2 2 300 0 165 L 60 60 0 1 P
ENDDRAW
ENDDEF
#
# LED
#
DEF LED D 0 40 Y N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "LED" 0 -100 50 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
$FPLIST
LED-3MM
LED-5MM
LED-10MM
LED-0603
LED-0805
LED-1206
LEDV
$ENDFPLIST
DRAW
P 2 0 1 0 50 50 50 -50 N
P 3 0 1 0 -50 50 50 0 -50 -50 F
P 3 0 1 0 65 -40 110 -80 105 -55 N
P 3 0 1 0 80 -25 125 -65 120 -40 N
X A 1 -200 0 150 R 40 40 1 1 P
X K 2 200 0 150 L 40 40 1 1 P
ENDDRAW
ENDDEF
#
# NCP1117ST50T3G
#
DEF NCP1117ST50T3G U 0 30 Y Y 1 F N
F0 "U" 150 -196 40 H V C CNN
F1 "NCP1117ST50T3G" 0 200 40 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
ALIAS NCP1117ST12T3G NCP1117ST15T3G NCP1117ST18T3G NCP1117ST20T3G NCP1117ST25T3G NCP1117ST285T3G NCP1117ST33T3G
$FPLIST
SOT223
$ENDFPLIST
DRAW
S -250 -150 250 150 0 1 10 f
X GND 1 0 -250 100 U 40 40 1 1 W
X VO 2 400 50 150 L 40 40 1 1 w
X VI 3 -400 50 150 R 40 40 1 1 W
ENDDRAW
ENDDEF
#
# NRF24L01
#
DEF NRF24L01 U 0 40 Y Y 1 F N
F0 "U" 500 650 60 H V C CNN
F1 "NRF24L01" 0 800 60 H V C CNN
F2 "~" 0 -400 60 H V C CNN
F3 "~" 0 -400 60 H V C CNN
DRAW
S 400 -650 -350 700 0 1 0 N
X GND 1 -650 550 300 R 70 70 1 1 I
X 3V3 2 -650 400 300 R 70 70 1 1 I
X CE 3 -650 250 300 R 70 70 1 1 I
X CSN 4 -650 100 300 R 70 70 1 1 I
X SCK 5 -650 -50 300 R 70 70 1 1 I
X MOSI 6 -650 -200 300 R 70 70 1 1 I
X MISO 7 -650 -350 300 R 70 70 1 1 I
X IRQ 8 -650 -500 300 R 70 70 1 1 N
ENDDRAW
ENDDEF
#
# R
#
DEF R R 0 0 N Y 1 F N
F0 "R" 80 0 40 V V C CNN
F1 "R" 7 1 40 V V C CNN
F2 "~" -70 0 30 V V C CNN
F3 "~" 0 0 30 H V C CNN
$FPLIST
R?
SM0603
SM0805
R?-*
SM1206
$ENDFPLIST
DRAW
S -40 150 40 -150 0 1 12 N
X ~ 1 0 250 100 D 60 60 1 1 P
X ~ 2 0 -250 100 U 60 60 1 1 P
ENDDRAW
ENDDEF
#
# SW_PUSH_4_Pin
#
DEF SW_PUSH_4_Pin SW 0 40 N N 1 F N
F0 "SW" 150 110 50 H V C CNN
F1 "SW_PUSH_4_Pin" 0 -200 50 H V C CNN
F2 "~" 0 0 60 H V C CNN
F3 "~" 0 0 60 H V C CNN
DRAW
S -170 50 170 60 0 1 0 N
P 4 0 1 0 -40 60 -30 90 30 90 40 60 N
X 1 1 -300 0 200 R 60 60 0 1 P I
X 3 3 300 0 200 L 60 60 0 1 P I
X 2 2 -300 -100 200 R 50 50 1 1 I I
X 4 4 300 -100 200 L 50 50 1 1 I I
ENDDRAW
ENDDEF
#
#End Library

View File

@@ -0,0 +1,248 @@
Cmp-Mod V01 Created by CvPcb (2013-07-07 BZR 4022)-stable date = 05/02/2016 14:40:56
BeginCmp
TimeStamp = /53C2AE5B;
Reference = C1;
ValeurCmp = 22uF;
IdModule = c_tant_B;
EndCmp
BeginCmp
TimeStamp = /53BC5DA8;
Reference = C2;
ValeurCmp = 0.1uF;
IdModule = SM0603_Capa;
EndCmp
BeginCmp
TimeStamp = /53C2AE76;
Reference = C3;
ValeurCmp = 22uF;
IdModule = c_tant_B;
EndCmp
BeginCmp
TimeStamp = /53BC62F4;
Reference = C4;
ValeurCmp = 18pF;
IdModule = SM0603_Capa;
EndCmp
BeginCmp
TimeStamp = /53BC631E;
Reference = C5;
ValeurCmp = 18pF;
IdModule = SM0603_Capa;
EndCmp
BeginCmp
TimeStamp = /53C2B150;
Reference = C6;
ValeurCmp = 22uF;
IdModule = c_tant_B;
EndCmp
BeginCmp
TimeStamp = /54845FE2;
Reference = C7;
ValeurCmp = 0.1uF;
IdModule = SM0603_Capa;
EndCmp
BeginCmp
TimeStamp = /53BC617C;
Reference = D1;
ValeurCmp = LED;
IdModule = LED-0603;
EndCmp
BeginCmp
TimeStamp = /53C2D9F8;
Reference = D2;
ValeurCmp = LED;
IdModule = LED-0603;
EndCmp
BeginCmp
TimeStamp = /53BC5C99;
Reference = IC1;
ValeurCmp = ATMEGA328-A;
IdModule = TQFP32;
EndCmp
BeginCmp
TimeStamp = /53FE5887;
Reference = JP1;
ValeurCmp = JUMPER;
IdModule = c_0603;
EndCmp
BeginCmp
TimeStamp = /53FE5896;
Reference = JP2;
ValeurCmp = JUMPER;
IdModule = c_0603;
EndCmp
BeginCmp
TimeStamp = /56B4E4E1;
Reference = JP3;
ValeurCmp = JUMPER;
IdModule = c_0603;
EndCmp
BeginCmp
TimeStamp = /56B4EFD5;
Reference = JP4;
ValeurCmp = JUMPER;
IdModule = c_0603;
EndCmp
BeginCmp
TimeStamp = /53C2DBCC;
Reference = P1;
ValeurCmp = ISP;
IdModule = pin_array_3x2;
EndCmp
BeginCmp
TimeStamp = /53FE5423;
Reference = P2;
ValeurCmp = CONN_5;
IdModule = MOLEX_4455_N2X5;
EndCmp
BeginCmp
TimeStamp = /56B4E4CA;
Reference = P3;
ValeurCmp = CONN_2;
IdModule = PIN_ARRAY_2X1;
EndCmp
BeginCmp
TimeStamp = /53BC5FEA;
Reference = R1;
ValeurCmp = 10K;
IdModule = SM0603_Resistor;
EndCmp
BeginCmp
TimeStamp = /53C2B990;
Reference = R2;
ValeurCmp = 2K2;
IdModule = SM0603_Resistor;
EndCmp
BeginCmp
TimeStamp = /53C2B99F;
Reference = R3;
ValeurCmp = 1K;
IdModule = SM0603_Resistor;
EndCmp
BeginCmp
TimeStamp = /53BC6125;
Reference = R4;
ValeurCmp = 1K;
IdModule = SM0603_Resistor;
EndCmp
BeginCmp
TimeStamp = /53C2B787;
Reference = R5;
ValeurCmp = 2K2;
IdModule = SM0603_Resistor;
EndCmp
BeginCmp
TimeStamp = /53C2D8C4;
Reference = R6;
ValeurCmp = 1K;
IdModule = SM0603_Resistor;
EndCmp
BeginCmp
TimeStamp = /54DCE006;
Reference = R7;
ValeurCmp = 2K2;
IdModule = SM0603_Resistor;
EndCmp
BeginCmp
TimeStamp = /56B4E6D8;
Reference = R8;
ValeurCmp = 470;
IdModule = SM0603_Resistor;
EndCmp
BeginCmp
TimeStamp = /54394777;
Reference = SW1;
ValeurCmp = HEX_DIP;
IdModule = DIP-6__300;
EndCmp
BeginCmp
TimeStamp = /56B4EC6E;
Reference = SW2;
ValeurCmp = BIND;
IdModule = SW_PUSH_6x4.5MM;
EndCmp
BeginCmp
TimeStamp = /56B4EC7B;
Reference = SW3;
ValeurCmp = RESET;
IdModule = Switch_SMT5mm;
EndCmp
BeginCmp
TimeStamp = /53C2ACE9;
Reference = U1;
ValeurCmp = NCP1117ST50T3G;
IdModule = SOT223;
EndCmp
BeginCmp
TimeStamp = /53C2AD08;
Reference = U2;
ValeurCmp = NCP1117ST33T3G;
IdModule = SOT223;
EndCmp
BeginCmp
TimeStamp = /53C2BF57;
Reference = U3;
ValeurCmp = CYRF6936;
IdModule = CYRF6936;
EndCmp
BeginCmp
TimeStamp = /53C2C184;
Reference = U4;
ValeurCmp = A7105;
IdModule = XL7105-D03B;
EndCmp
BeginCmp
TimeStamp = /53C2C24E;
Reference = U5;
ValeurCmp = NRF24L01;
IdModule = NRF24L01;
EndCmp
BeginCmp
TimeStamp = /53C2C3F4;
Reference = U6;
ValeurCmp = CC2500;
IdModule = header_10_2mm;
EndCmp
BeginCmp
TimeStamp = /53BC62D3;
Reference = X1;
ValeurCmp = 16MHz;
IdModule = crystal_FA238-TSX3225;
EndCmp
EndListe

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,644 @@
(export (version D)
(design
(source "C:\\Documents and Settings\\Steve\\My Documents\\Multipro-tx\\MultiproV2.3d\\Multipro-txV2-3d.sch")
(date "05/02/2016 16:35:59")
(tool "eeschema (2013-07-07 BZR 4022)-stable"))
(components
(comp (ref IC1)
(value ATMEGA328-A)
(footprint TQFP32)
(libsource (lib atmel) (part ATMEGA328-A))
(sheetpath (names /) (tstamps /))
(tstamp 53BC5C99))
(comp (ref C2)
(value 0.1uF)
(libsource (lib device) (part C))
(sheetpath (names /) (tstamps /))
(tstamp 53BC5DA8))
(comp (ref R1)
(value 10K)
(libsource (lib device) (part R))
(sheetpath (names /) (tstamps /))
(tstamp 53BC5FEA))
(comp (ref R4)
(value 1K)
(libsource (lib device) (part R))
(sheetpath (names /) (tstamps /))
(tstamp 53BC6125))
(comp (ref D1)
(value LED)
(libsource (lib device) (part LED))
(sheetpath (names /) (tstamps /))
(tstamp 53BC617C))
(comp (ref X1)
(value 16MHz)
(libsource (lib device) (part CRYSTAL))
(sheetpath (names /) (tstamps /))
(tstamp 53BC62D3))
(comp (ref C4)
(value 18pF)
(libsource (lib device) (part C))
(sheetpath (names /) (tstamps /))
(tstamp 53BC62F4))
(comp (ref C5)
(value 18pF)
(libsource (lib device) (part C))
(sheetpath (names /) (tstamps /))
(tstamp 53BC631E))
(comp (ref U1)
(value NCP1117ST50T3G)
(libsource (lib regul) (part NCP1117ST50T3G))
(sheetpath (names /) (tstamps /))
(tstamp 53C2ACE9))
(comp (ref U2)
(value NCP1117ST33T3G)
(libsource (lib regul) (part NCP1117ST50T3G))
(sheetpath (names /) (tstamps /))
(tstamp 53C2AD08))
(comp (ref C1)
(value 22uF)
(libsource (lib device) (part CP1))
(sheetpath (names /) (tstamps /))
(tstamp 53C2AE5B))
(comp (ref C3)
(value 22uF)
(libsource (lib device) (part CP1))
(sheetpath (names /) (tstamps /))
(tstamp 53C2AE76))
(comp (ref C6)
(value 22uF)
(libsource (lib device) (part CP1))
(sheetpath (names /) (tstamps /))
(tstamp 53C2B150))
(comp (ref R5)
(value 2K2)
(libsource (lib device) (part R))
(sheetpath (names /) (tstamps /))
(tstamp 53C2B787))
(comp (ref R2)
(value 2K2)
(libsource (lib device) (part R))
(sheetpath (names /) (tstamps /))
(tstamp 53C2B990))
(comp (ref R3)
(value 1K)
(libsource (lib device) (part R))
(sheetpath (names /) (tstamps /))
(tstamp 53C2B99F))
(comp (ref U3)
(value CYRF6936)
(libsource (lib device) (part CYRF6936))
(sheetpath (names /) (tstamps /))
(tstamp 53C2BF57))
(comp (ref U4)
(value A7105)
(libsource (lib device) (part A7105))
(sheetpath (names /) (tstamps /))
(tstamp 53C2C184))
(comp (ref U5)
(value NRF24L01)
(libsource (lib device) (part NRF24L01))
(sheetpath (names /) (tstamps /))
(tstamp 53C2C24E))
(comp (ref U6)
(value CC2500)
(libsource (lib device) (part CC2500))
(sheetpath (names /) (tstamps /))
(tstamp 53C2C3F4))
(comp (ref R6)
(value 1K)
(libsource (lib device) (part R))
(sheetpath (names /) (tstamps /))
(tstamp 53C2D8C4))
(comp (ref D2)
(value LED)
(libsource (lib device) (part LED))
(sheetpath (names /) (tstamps /))
(tstamp 53C2D9F8))
(comp (ref P1)
(value ISP)
(libsource (lib conn) (part CONN_3X2))
(sheetpath (names /) (tstamps /))
(tstamp 53C2DBCC))
(comp (ref P2)
(value CONN_5)
(libsource (lib conn) (part CONN_5))
(sheetpath (names /) (tstamps /))
(tstamp 53FE5423))
(comp (ref JP2)
(value JUMPER)
(libsource (lib device) (part JUMPER))
(sheetpath (names /) (tstamps /))
(tstamp 53FE5887))
(comp (ref JP4)
(value JUMPER)
(libsource (lib device) (part JUMPER))
(sheetpath (names /) (tstamps /))
(tstamp 53FE5896))
(comp (ref SW1)
(value HEX_DIP)
(libsource (lib device) (part HEX_DIP))
(sheetpath (names /) (tstamps /))
(tstamp 54394777))
(comp (ref C7)
(value 0.1uF)
(libsource (lib device) (part C))
(sheetpath (names /) (tstamps /))
(tstamp 54845FE2))
(comp (ref R7)
(value 2K2)
(libsource (lib device) (part R))
(sheetpath (names /) (tstamps /))
(tstamp 54DCE006))
(comp (ref P3)
(value CONN_2)
(libsource (lib conn) (part CONN_2))
(sheetpath (names /) (tstamps /))
(tstamp 56B4E4CA))
(comp (ref JP3)
(value JUMPER)
(libsource (lib device) (part JUMPER))
(sheetpath (names /) (tstamps /))
(tstamp 56B4E4E1))
(comp (ref R8)
(value 470)
(libsource (lib device) (part R))
(sheetpath (names /) (tstamps /))
(tstamp 56B4E6D8))
(comp (ref SW2)
(value BIND)
(libsource (lib device) (part SW_PUSH_4_PIN))
(sheetpath (names /) (tstamps /))
(tstamp 56B4EC6E))
(comp (ref SW3)
(value RESET)
(libsource (lib device) (part SW_PUSH_4_PIN))
(sheetpath (names /) (tstamps /))
(tstamp 56B4EC7B))
(comp (ref JP1)
(value JUMPER)
(libsource (lib device) (part JUMPER))
(sheetpath (names /) (tstamps /))
(tstamp 56B4EFD5)))
(libparts
(libpart (lib device) (part A7105)
(fields
(field (name Reference) U)
(field (name Value) A7105)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name 3V3) (type input))
(pin (num 2) (name SCS) (type input))
(pin (num 3) (name GND) (type input))
(pin (num 4) (name SCK) (type input))
(pin (num 5) (name SDIO) (type input))
(pin (num 6) (name GIO1) (type input))
(pin (num 7) (name GIO2) (type output))
(pin (num 8) (name RXEN) (type input))
(pin (num 9) (name TXEN) (type output))))
(libpart (lib device) (part C)
(description "Condensateur non polarise")
(footprints
(fp SM*)
(fp C?)
(fp C1-1))
(fields
(field (name Reference) C)
(field (name Value) C)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))))
(libpart (lib device) (part CC2500)
(fields
(field (name Reference) U)
(field (name Value) CC2500)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name 3V3) (type input))
(pin (num 2) (name SI) (type input))
(pin (num 3) (name SCLK) (type input))
(pin (num 4) (name SO) (type input))
(pin (num 5) (name GDO2) (type input))
(pin (num 6) (name GND) (type input))
(pin (num 7) (name GDOo) (type input))
(pin (num 8) (name CSn) (type input))
(pin (num 9) (name PA_EN) (type input))
(pin (num 10) (name LNA_EN) (type input))))
(libpart (lib device) (part CP1)
(description "Condensateur polarise")
(footprints
(fp CP*)
(fp SM*))
(fields
(field (name Reference) C)
(field (name Value) CP1)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))))
(libpart (lib device) (part CRYSTAL)
(fields
(field (name Reference) X)
(field (name Value) CRYSTAL)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name 1) (type passive))
(pin (num 2) (name 2) (type passive))
(pin (num 3) (name 3) (type passive))
(pin (num 4) (name 4) (type passive))))
(libpart (lib device) (part CYRF6936)
(fields
(field (name Reference) U)
(field (name Value) CYRF6936)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name 5.0V) (type input))
(pin (num 2) (name NCS) (type input))
(pin (num 4) (name SCK) (type input))
(pin (num 5) (name GND) (type input))
(pin (num 6) (name GND) (type input))
(pin (num 8) (name MOSI) (type input))
(pin (num 9) (name RST) (type input))
(pin (num 10) (name MISO) (type input))))
(libpart (lib device) (part HEX_DIP)
(fields
(field (name Reference) SW)
(field (name Value) HEX_DIP)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name 1) (type output))
(pin (num 2) (name C) (type passive))
(pin (num 3) (name 4) (type output))
(pin (num 4) (name 2) (type output))
(pin (num 5) (name C) (type passive))
(pin (num 6) (name 8) (type output))))
(libpart (lib device) (part JUMPER)
(fields
(field (name Reference) JP)
(field (name Value) JUMPER)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name 1) (type passive))
(pin (num 2) (name 2) (type passive))))
(libpart (lib device) (part LED)
(footprints
(fp LED-3MM)
(fp LED-5MM)
(fp LED-10MM)
(fp LED-0603)
(fp LED-0805)
(fp LED-1206)
(fp LEDV))
(fields
(field (name Reference) D)
(field (name Value) LED)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name A) (type passive))
(pin (num 2) (name K) (type passive))))
(libpart (lib device) (part NRF24L01)
(fields
(field (name Reference) U)
(field (name Value) NRF24L01)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name GND) (type input))
(pin (num 2) (name 3V3) (type input))
(pin (num 3) (name CE) (type input))
(pin (num 4) (name CSN) (type input))
(pin (num 5) (name SCK) (type input))
(pin (num 6) (name MOSI) (type input))
(pin (num 7) (name MISO) (type input))
(pin (num 8) (name IRQ) (type NotConnected))))
(libpart (lib device) (part R)
(description Resistance)
(footprints
(fp R?)
(fp SM0603)
(fp SM0805)
(fp R?-*)
(fp SM1206))
(fields
(field (name Reference) R)
(field (name Value) R)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))))
(libpart (lib device) (part SW_PUSH_4_Pin)
(description "Push Button 4 Pin")
(fields
(field (name Reference) SW)
(field (name Value) SW_PUSH_4_Pin)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name 1) (type passive))
(pin (num 2) (name 2) (type input))
(pin (num 3) (name 3) (type passive))
(pin (num 4) (name 4) (type input))))
(libpart (lib conn) (part CONN_2)
(description "Symbole general de connecteur")
(fields
(field (name Reference) P)
(field (name Value) CONN_2)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name P1) (type passive))
(pin (num 2) (name PM) (type passive))))
(libpart (lib conn) (part CONN_3X2)
(description "Symbole general de connecteur")
(fields
(field (name Reference) P)
(field (name Value) CONN_3X2)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name 1) (type passive))
(pin (num 2) (name 2) (type passive))
(pin (num 3) (name 3) (type passive))
(pin (num 4) (name 4) (type passive))
(pin (num 5) (name 5) (type passive))
(pin (num 6) (name 6) (type passive))))
(libpart (lib conn) (part CONN_5)
(description "Symbole general de connecteur")
(fields
(field (name Reference) P)
(field (name Value) CONN_5)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name ~) (type passive))
(pin (num 2) (name ~) (type passive))
(pin (num 3) (name ~) (type passive))
(pin (num 4) (name ~) (type passive))
(pin (num 5) (name ~) (type passive))))
(libpart (lib regul) (part NCP1117ST50T3G)
(description "NCP1117ST50T3G, 1A Low drop-out regulator, Fixed Output 5V, SOT223")
(docs http://www.onsemi.com/pub_link/Collateral/NCP1117-D.PDF)
(footprints
(fp SOT223))
(fields
(field (name Reference) U)
(field (name Value) NCP1117ST50T3G)
(field (name Footprint) ~)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name GND) (type power_in))
(pin (num 2) (name VO) (type power_out))
(pin (num 3) (name VI) (type power_in))))
(libpart (lib atmel) (part ATMEGA168A-A)
(description "ATMEGA168A, TQFP32, 16k Flash, 1kB SRAM, 512B EEPROM")
(docs http://www.atmel.com/dyn/resources/prod_documents/doc8271.pdf)
(fields
(field (name Reference) IC)
(field (name Value) ATMEGA168A-A)
(field (name Footprint) TQFP32)
(field (name Datasheet) ~))
(pins
(pin (num 1) (name "(PCINT19/OC2B/INT1)PD3") (type BiDi))
(pin (num 2) (name "(PCINT20/XCK/T0)PD4") (type BiDi))
(pin (num 3) (name GND) (type power_in))
(pin (num 4) (name VCC) (type power_in))
(pin (num 5) (name GND) (type power_in))
(pin (num 6) (name VCC) (type power_in))
(pin (num 7) (name "(PCINT6/XTAL1/TOSC1)PB6") (type BiDi))
(pin (num 8) (name "(PCINT7/XTAL2/TOSC2)PB7") (type BiDi))
(pin (num 9) (name "(PCINT21/OC0B/T1)PD5") (type BiDi))
(pin (num 10) (name "(PCINT22/OC0A/AIN0)PD6") (type BiDi))
(pin (num 11) (name "(PCINT23/AIN1)PD7") (type BiDi))
(pin (num 12) (name "(PCINT0/CLKO/ICP1)PB0") (type BiDi))
(pin (num 13) (name "(PCINT1/OC1A)PB1") (type BiDi))
(pin (num 14) (name "(PCINT2/OC1B/~SS~)PB2") (type BiDi))
(pin (num 15) (name "(PCINT3/OC2A/MOSI)PB3") (type BiDi))
(pin (num 16) (name "(PCINT4/MISO)PB4") (type BiDi))
(pin (num 17) (name "(PCINT5/SCK)PB5") (type BiDi))
(pin (num 18) (name AVCC) (type power_in))
(pin (num 19) (name ADC6) (type NotConnected))
(pin (num 20) (name AREF) (type BiDi))
(pin (num 21) (name GND) (type power_in))
(pin (num 22) (name ADC7) (type NotConnected))
(pin (num 23) (name "(PCINT8/ADC0)PC0") (type BiDi))
(pin (num 24) (name "(PCINT9/ADC1)PC1") (type BiDi))
(pin (num 25) (name "(PCINT10/ADC2)PC2") (type BiDi))
(pin (num 26) (name "(PCINT11/ADC3)PC3") (type BiDi))
(pin (num 27) (name "(PCINT12/SDA/ADC4)PC4") (type BiDi))
(pin (num 28) (name "(PCINT14/SCL/ADC5)PC5") (type BiDi))
(pin (num 29) (name "(PCINT14/~RESET~)PC6") (type BiDi))
(pin (num 30) (name "(PCINT16/RXD)PD0") (type BiDi))
(pin (num 31) (name "(PCINT17/TXD)PD1") (type BiDi))
(pin (num 32) (name "(PCINT18/INT0)PD2") (type BiDi)))))
(libraries
(library (logical device)
(uri "C:\\Program Files\\KiCad\\share\\library\\device.lib"))
(library (logical conn)
(uri "C:\\Program Files\\KiCad\\share\\library\\conn.lib"))
(library (logical regul)
(uri "C:\\Program Files\\KiCad\\share\\library\\regul.lib"))
(library (logical atmel)
(uri "C:\\Program Files\\KiCad\\share\\library\\atmel.lib")))
(nets
(net (code 1) (name GND)
(node (ref P2) (pin 4))
(node (ref C7) (pin 2))
(node (ref SW1) (pin 5))
(node (ref SW1) (pin 2))
(node (ref C5) (pin 2))
(node (ref C4) (pin 1))
(node (ref X1) (pin 4))
(node (ref SW3) (pin 4))
(node (ref SW3) (pin 3))
(node (ref SW2) (pin 4))
(node (ref SW2) (pin 3))
(node (ref D1) (pin 2))
(node (ref R3) (pin 2))
(node (ref U6) (pin 6))
(node (ref U5) (pin 1))
(node (ref U4) (pin 3))
(node (ref U3) (pin 6))
(node (ref U3) (pin 5))
(node (ref C3) (pin 2))
(node (ref C1) (pin 2))
(node (ref U2) (pin 1))
(node (ref U1) (pin 1))
(node (ref C6) (pin 2))
(node (ref IC1) (pin 21))
(node (ref IC1) (pin 5))
(node (ref IC1) (pin 3))
(node (ref X1) (pin 2))
(node (ref C2) (pin 2))
(node (ref D2) (pin 2))
(node (ref P1) (pin 6)))
(net (code 2) (name "")
(node (ref D2) (pin 1))
(node (ref R6) (pin 2)))
(net (code 3) (name 3V3)
(node (ref R5) (pin 2))
(node (ref U6) (pin 1))
(node (ref U5) (pin 2))
(node (ref C7) (pin 1))
(node (ref U4) (pin 1))
(node (ref U2) (pin 2))
(node (ref IC1) (pin 18))
(node (ref IC1) (pin 6))
(node (ref P1) (pin 2))
(node (ref IC1) (pin 4))
(node (ref R1) (pin 1))
(node (ref C6) (pin 1)))
(net (code 4) (name /CC25_CSN)
(node (ref IC1) (pin 11))
(node (ref U6) (pin 8)))
(net (code 5) (name /MISO)
(node (ref U3) (pin 10))
(node (ref IC1) (pin 10))
(node (ref U5) (pin 7))
(node (ref U6) (pin 4)))
(net (code 6) (name /SCK)
(node (ref IC1) (pin 2))
(node (ref U4) (pin 4))
(node (ref U6) (pin 3))
(node (ref U3) (pin 4))
(node (ref U5) (pin 5)))
(net (code 7) (name /MOSI)
(node (ref U5) (pin 6))
(node (ref IC1) (pin 9))
(node (ref U6) (pin 2))
(node (ref U4) (pin 5))
(node (ref U3) (pin 8)))
(net (code 8) (name +5V)
(node (ref U2) (pin 3))
(node (ref U1) (pin 2))
(node (ref C3) (pin 1))
(node (ref U3) (pin 1))
(node (ref R6) (pin 1)))
(net (code 9) (name /D11)
(node (ref P1) (pin 4))
(node (ref SW1) (pin 4))
(node (ref IC1) (pin 15)))
(net (code 10) (name /RESET)
(node (ref IC1) (pin 29))
(node (ref SW3) (pin 1))
(node (ref P1) (pin 5))
(node (ref R1) (pin 2))
(node (ref SW3) (pin 2)))
(net (code 11) (name /D12)
(node (ref P1) (pin 1))
(node (ref IC1) (pin 16))
(node (ref SW1) (pin 3)))
(net (code 12) (name "")
(node (ref U4) (pin 7))
(node (ref U4) (pin 8)))
(net (code 13) (name "")
(node (ref U4) (pin 6))
(node (ref U4) (pin 9)))
(net (code 14) (name /A7105_CSN)
(node (ref IC1) (pin 32))
(node (ref U4) (pin 2)))
(net (code 15) (name /CC25_LANEN)
(node (ref U6) (pin 5))
(node (ref U6) (pin 10)))
(net (code 16) (name /CC25_PAEN)
(node (ref U6) (pin 9))
(node (ref U6) (pin 7)))
(net (code 17) (name /NRF_CE)
(node (ref R5) (pin 1))
(node (ref U5) (pin 3)))
(net (code 18) (name /NRF_CSN)
(node (ref U5) (pin 4))
(node (ref IC1) (pin 12)))
(net (code 19) (name "")
(node (ref R8) (pin 1))
(node (ref P3) (pin 2))
(node (ref JP3) (pin 2)))
(net (code 20) (name /PPM_IN)
(node (ref JP2) (pin 1))
(node (ref P2) (pin 1))
(node (ref R2) (pin 2)))
(net (code 21) (name "")
(node (ref JP3) (pin 1))
(node (ref P2) (pin 5)))
(net (code 22) (name "")
(node (ref JP4) (pin 2))
(node (ref P3) (pin 1)))
(net (code 23) (name "")
(node (ref JP2) (pin 2))
(node (ref R7) (pin 1)))
(net (code 24) (name "")
(node (ref R3) (pin 1))
(node (ref JP1) (pin 2)))
(net (code 25) (name /RX)
(node (ref IC1) (pin 30))
(node (ref R7) (pin 2)))
(net (code 26) (name "")
(node (ref P2) (pin 2))
(node (ref JP4) (pin 1)))
(net (code 27) (name /TX)
(node (ref IC1) (pin 31))
(node (ref R8) (pin 2)))
(net (code 28) (name /CYRF_RST)
(node (ref IC1) (pin 28))
(node (ref U3) (pin 9)))
(net (code 29) (name /CYRF_CSN)
(node (ref U3) (pin 2))
(node (ref IC1) (pin 13)))
(net (code 30) (name /A0)
(node (ref IC1) (pin 23))
(node (ref SW1) (pin 6)))
(net (code 31) (name /D10)
(node (ref SW1) (pin 1))
(node (ref IC1) (pin 14)))
(net (code 32) (name /xtl2)
(node (ref X1) (pin 1))
(node (ref IC1) (pin 8))
(node (ref C5) (pin 1)))
(net (code 33) (name /xtl1)
(node (ref IC1) (pin 7))
(node (ref X1) (pin 3))
(node (ref C4) (pin 2)))
(net (code 34) (name "")
(node (ref D1) (pin 1))
(node (ref SW2) (pin 1))
(node (ref SW2) (pin 2))
(node (ref R4) (pin 2)))
(net (code 35) (name /A3)
(node (ref IC1) (pin 26)))
(net (code 36) (name /D3)
(node (ref IC1) (pin 1))
(node (ref R2) (pin 1))
(node (ref JP1) (pin 1)))
(net (code 37) (name /A4)
(node (ref IC1) (pin 27)))
(net (code 38) (name /A2)
(node (ref IC1) (pin 25)))
(net (code 39) (name /A1)
(node (ref IC1) (pin 24)))
(net (code 40) (name /A6)
(node (ref IC1) (pin 19)))
(net (code 41) (name /A7)
(node (ref IC1) (pin 22)))
(net (code 42) (name /PB5)
(node (ref P1) (pin 3))
(node (ref IC1) (pin 17))
(node (ref R4) (pin 1)))
(net (code 43) (name "")
(node (ref IC1) (pin 20))
(node (ref C2) (pin 1)))
(net (code 44) (name "")
(node (ref U5) (pin 8)))
(net (code 45) (name /BATT)
(node (ref C1) (pin 1))
(node (ref P2) (pin 3))
(node (ref U1) (pin 3)))))

View File

@@ -0,0 +1,41 @@
update=04/02/2016 18:14:57
last_client=pcbnew
[pcbnew]
version=1
LastNetListRead=Multipro-txV2-3d.net
UseCmpFile=1
PadDrill=0.750000000000
PadDrillOvalY=0.750000000000
PadSizeH=1.250000000000
PadSizeV=1.250000000000
PcbTextSizeV=1.500000000000
PcbTextSizeH=1.500000000000
PcbTextThickness=0.300000000000
ModuleTextSizeV=1.000000000000
ModuleTextSizeH=1.000000000000
ModuleTextSizeThickness=0.150000000000
SolderMaskClearance=0.000000000000
SolderMaskMinWidth=0.000000000000
DrawSegmentWidth=0.400000000000
BoardOutlineThickness=0.100000000000
ModuleOutlineThickness=0.150000000000
[pcbnew/libraries]
LibDir=../Multipro-txV2
LibName1=sockets
LibName2=connect
LibName3=discret
LibName4=pin_array
LibName5=divers
LibName6=smd_capacitors
LibName7=smd_resistors
LibName8=smd_crystal&oscillator
LibName9=smd_dil
LibName10=smd_transistors
LibName11=libcms
LibName12=display
LibName13=led
LibName14=dip_sockets
LibName15=pga_sockets
LibName16=valves
LibName17=Logo
LibName18=LogoBsilk

File diff suppressed because it is too large Load Diff

BIN
PCB v2.3d/PCB_v2.3d.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 172 KiB

35
PCB v2.3d/Readme.txt Normal file
View File

@@ -0,0 +1,35 @@
These are KiCad files and you are free to do what you will with them. KiCad is a good, free, and fairly
easy to learn. Build your own BOM and gerber files.
This is a variant of the Multipro V2.3c circuit design. It is basicly the same as the 2.3c board as far
as component placement goes. What's changed is the added resistors for the serial protocol and also
the addition of solder jumpers on the bottom of the board for the various options to connect the TX, RX, and PPM
lines through them. See below for more detail.
The schematic has been updated to reflect the added components and jumper pads as well as cleaned
up a little. As it sits now, the .net file loads without any complaints and DRC checks pass.
The jumpers, and how they are used:
There are four solder type jumpers on the bottom side of the board near the lower left corner when the
bottom of the board is facing towards you. The silkscreen shows which jumper is which. These four jumpers
enable the board to be configured in several ways as explaned below.
(J-1) Use (PPM V/V) if the incoming PPM signal is at a higher voltage level, leave open if ~~5V.
(J-2) Use (Jumper 2) to connect the incomming PPM signal to the RX pin on the processor
(J-3) Short (TELEM) only if you have done a telemetry mod to your radio, leave open if not needed. When
connected, pin 2 of the two pin header (P3) is also connected.
(J-4) Use (MOD) only to connect the transmitter pin 2 to pin 1 of the two pin header (P3).
The direction this project is going, it is most likely J-2 will be the only one needing to be shorted for
the serial method of sending model protocols.
These files are submitted without any guarentee of accureacy or suitability for any intended use. I am strictly
an amature with time on his hands. Although I have done all I know to make it correct, things outside of my
knowledge base are beyond my control. Do not use untested equipment around persons not familiar with the hazards
of remote controlled vehicals.

Binary file not shown.

After

Width:  |  Height:  |  Size: 224 KiB

422
Protocols_Details.md Normal file
View File

@@ -0,0 +1,422 @@
#Protocols details
**You'll find below a detailed description of every supported protocols sorted by RF modules.**
Legend:
- Extended limits supported: -125%..+125% can be used and will be transmitted. Otherwise the default is -100%..+100% only.
- Autobind protocol: you do not need to press the bind button at power up to bind, this is done automatically.
The AETR mentionned here for all protocols depends on the TX settings compilation option set in _Config.h.
***
#A7105 RF Module
##FLYSKY
Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
Note that the RX ouput will be AETR.
###Sub_protocol V9X9
CH5|CH6|CH7|CH8
---|---|---|---
FLIP|LIGHT|PICTURE|VIDEO
###Sub_protocol V6X6
CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
---|---|---|---|---|---|---|---
FLIP|LIGHT|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL
###Sub_protocol V912
CH5|CH6
---|---
BTMBTN|TOPBTN
##HUBSAN
Models: Hubsan H102D, H107/L/C/D and Hubsan H107P/C+/D+
Autobind protocol
Telemetry enabled for battery voltage and TX RSSI
Option=vTX frequency (H107D) 5645 - 5900 MHz
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
---|---|---|---|---|---|---|---|---
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
***
#CC2500 RF Module
##FRSKYV = FrSky 1 way
Models: FrSky receivers V8R4, V8R7 and V8FR.
Extended limits supported
Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
CH1|CH2|CH3|CH4
---|---|---|---
CH1|CH2|CH3|CH4
##FRSKYD
Models: FrSky receivers D4R and D8R. DIY RX-F801 and RX-F802 receivers.
Extended limits supported
Telemetry enabled for A0, A1, RSSI, TSSI and Hub
Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
##FRSKYX
Models: FrSky receivers X4R, X6R and X8R.
Extended limits supported
Telemetry enabled for A1 (RxBatt), A2, RSSI, TSSI and Hub
Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
###Sub_protocol CH_16
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
---|---|---|---|---|---|---|---|---|----|----|----|----|----|----|----
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13|CH14|CH15|CH16
###Sub_protocol CH_8
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
##SFHSS
Models: Futaba RXs and XK models.
Option=fine frequency tuning. This value is different for each board. To determine the option value, find the two limits where the RX loses connection then set the option value to half way between them. If you have a 4in1 V2 board the value is around 40.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
***
#CYRF6936 RF Module
##DEVO
Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
Note that the RX ouput will be EATR.
Bind procedure using serial:
- With the TX off, put the binding plug in and power on the RX (RX LED slow blink), then power it down and remove the binding plug. Receiver should now be in autobind mode.
- Turn on the TX, set protocol = Devo with option=0, turn off the TX (TX is now in autobind mode).
- Turn on RX (RX LED fast blink).
- Turn on TX (RX LED solid, TX LED fast blink).
- Wait for bind on the TX to complete (TX LED solid).
- Make sure to set the RX_Num value for model match.
- Change option to 1 to use the global ID.
- Do not touch option/RX_Num anymore.
Bind procedure using PPM:
- With the TX off, put the binding plug in and power on the RX (RX LED slow blink), then power it down and remove the binding plug. Receiver should now be in autobind mode.
- Turn on RX (RX LED fast blink).
- Turn the dial to the model number running protocol DEVO on the module.
- Press the bind button and turn on the TX. TX is now in autobind mode.
- Release bind button after 1 second: RX LED solid, TX LED fast blink.
- Wait for bind on the TX to complete (TX LED solid).
- Press the bind button for 1 second. TX/RX is now in fixed ID mode.
- To verify that the TX is in fixed mode: power cycle the TX, the module LED should be solid ON (no blink).
- Note: Autobind/fixed ID mode is linked to the dial number. Which means that you can have multiple dial numbers set to the same protocol DEVO with different RX_Num and have different bind modes at the same time. It enables PPM users to get model match under DEVO.
##DSM
###Sub_protocol DSM2
Extended limits supported
Telemetry enabled for TSSI and plugins
option=number of channels and frame rate:
- 0 : 4 channels @22ms
- 1 : 5 channels @22ms
- 2 : 6 channels @22ms
- 3 : 7 channels @22ms
- 4 : 4 channels @11ms
- 5 : 5 channels @11ms
- 6 : 6 channels @11ms
- 7 : 7 channels @11ms
- 8 : 8 channels @22ms
- 9 : 9 channels @22ms
- 10 : 10 channels @22ms
- 11 : 11 channels @22ms
- 12 : 12 channels @22ms
Value 6 is usually giving the best results with most of the RX.
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
---|---|---|---|---|---|---|---|---|----|----|----
A|E|T|R|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
Note that the RX ouput will be TAER.
###Sub_protocol DSMX
Same as above
##J6Pro
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
---|---|---|---|---|---|---|---|---|----|----|----
A|E|T|R|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
***
#NRF24L01 RF Module
##ASSAN
Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10
---|---|---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10
The transmitter must be close to the receiver while binding.
##BAYANG
Models: EAchine H8(C) mini, BayangToys X6/X7/X9, JJRC JJ850, Floureon H101 ...
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10
---|---|---|---|---|---|---|---|---|----
A|E|T|R|FLIP|RTH|PICTURE|VIDEO|HEADLESS|INVERTED
##CG023
Models: EAchine CG023/CG031/3D X4
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
---|---|---|---|---|---|---|---|---
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
###Sub_protocol YD829
Models: Attop YD-822/YD-829/YD-829C ...
CH5|CH6|CH7|CH8|CH9
---|---|---|---|---
FLIP||PICTURE|VIDEO|HEADLESS
###Sub_protocol H8_3D
Models: EAchine H8 mini 3D, JJRC H20/H22
CH5|CH6|CH7|CH8|CH9
---|---|---|---|---
FLIP|LIGTH|OPT1|OPT2|CAL
JJRC H20: OPT1=Headless, OPT2=RTH
JJRC H22: OPT1=RTH, OPT2=180/360° flip mode
H8 3D: OPT1=RTH then press a direction to enter headless mode (like stock TX), OPT2=switch 180/360° flip mode
CAL: calibrate accelerometers
##CX10
Extended limits supported
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6
---|---|---|---|---|---
A|E|T|R|FLIP|RATE
Rate: -100%=rate 1, 0%=rate 2, +100%=rate 3
###Sub_protocol GREEN
Models: Cheerson CX-10 green pcb
Same channels assignement as above.
###Sub_protocol BLUE
Models: Cheerson CX-10 blue pcb & some newer red pcb, CX-10A, CX-10C, CX11, CX12, Floureon FX10, JJRC DHD D1
CH5|CH6|CH7|CH8
---|---|---|---
FLIP|RATE|PICTURE|VIDEO
Rate: -100%=rate 1, 0%=rate 2, +100%=rate 3 or headless for CX-10A
###Sub_protocol DM007
CH5|CH6|CH7|CH8|CH9
---|---|---|---|---
FLIP|MODE|PICTURE|VIDEO|HEADLESS
###Sub_protocol Q282 and Q242
CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
---|---|---|---|---|---|---|---
FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL
Model: JXD 509 is using Q282 with CH12=Start/Stop motors
###Sub_protocol JC3015_1
CH5|CH6|CH7|CH8
---|---|---|---
FLIP|MODE|PICTURE|VIDEO
###Sub_protocol JC3015_2
CH5|CH6|CH7|CH8
---|---|---|---
FLIP|MODE|LED|DFLIP
###Sub_protocol MK33041
CH5|CH6|CH7|CH8|CH9|CH10
---|---|---|---|---|---
FLIP|MODE|PICTURE|VIDEO|HEADLESS|RTH
##ESKY
CH1|CH2|CH3|CH4|CH5|CH6
---|---|---|---|---|---
A|E|T|R|GYRO|PITCH
##FY326
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
---|---|---|---|---|---|---|---|---
A|E|T|R|FLIP|RTH|HEADLESS|EXPERT|CALIBRATE
##FQ777
Model: FQ777-124
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|FLIP|RTH|HEADLESS|EXPERT
##HISKY
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|GEAR|PITCH|GYRO|CH8
GYRO: -100%=6G, +100%=3G
###HK310
Models: RX HK-3000, HK3100 and XY3000 (TX are HK-300, HK-310 and TL-3C)
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
|||T|R|AUX|T_FSAFE|R_FSAFE|AUX_FSAFE
##KN
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11
---|---|---|---|---|---|---|---|---|----|----
A|E|T|R|DR|THOLD|IDLEUP|GYRO|Ttrim|Atrim|Etrim
Dual Rate: +100%=full range, Throttle Hold: +100%=hold, Idle Up: +100%=3D, GYRO: -100%=6G, +100%=3G
###Sub_protocol WLTOYS
###Sub_protocol FEILUN
Same channels assignement as above.
##MJXQ
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12|CH13
---|---|---|---|---|---|---|---|---|---|---|---|---
A|E|T|R|FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|AUTOFLIP|PAN|TILT
###Sub_protocol WLH08
###Sub_protocol X600
Only 3 TX IDs available, change RX_Num value 0..2 to cycle through them
###Sub_protocol X800
Only 3 TX IDs available, change RX_Num value 0..2 to cycle through them
###Sub_protocol H26D
###Sub_protocol E010
Only 1 TX ID available
##MT99XX
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
---|---|---|---|---|---|---|---|---
A|E|T|R|FLIP|LED|PICTURE|VIDEO|HEADLESS
###Sub_protocol MT
Models: MT99xx
###Sub_protocol H7
Models: Eachine H7, Cheerson CX023
###Sub_protocol YZ
Model: Yi Zhan i6S
Only one model can be flown at the same time since the ID is hardcoded.
###Sub_protocol LS
Models: LS114, 124, 215
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
---|---|---|---|---|---|---|---|---
A|E|T|R|FLIP|INVERT|PICTURE|VIDEO|HEADLESS
##Shenqi
Autobind protocol
Model: Shenqiwei 1/20 Mini Motorcycle
CH1|CH2|CH3|CH4
---|---|---|---
| |T|R
Throttle +100%=full forward,0%=stop,-100%=full backward.
##SLT
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6
---|---|---|---|---|---
A|E|T|R|GEAR|PITCH
##Symax
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
---|---|---|---|---|---|---|---|---
A|E|T|R|FLIP||PICTURE|VIDEO|HEADLESS
###Sub_protocol SYMAX
Models: Syma X5C-1/X11/X11C/X12
###Sub_protocol SYMAX5C
Model: Syma X5C (original) and X2
##V2X2
Models: WLToys V202/252/272, JXD 385/388, JJRC H6C, Yizhan Tarantula X6 ...
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11
---|---|---|---|---|---|---|---|---|----|----
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS|MAG_CAL_X|MAG_CAL_Y
PICTURE: also automatic Missile Launcher and Hoist in one direction
VIDEO: also Sprayer, Bubbler, Missile Launcher(1), and Hoist in the other dir
##YD717
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
---|---|---|---|---|---|---|---|---
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
###Sub_protocol YD717
###Sub_protocol SKYWLKR
###Sub_protocol SYMAX4
###Sub_protocol XINXUN
###Sub_protocol NIHUI
Same channels assignement as above.

470
README.md
View File

@@ -1,4 +1,5 @@
# DIY-Multiprotocol-TX-Module
Multiprotocol is a 2.4GHz transmitter which enables any TX to control lot of different models available on the market.
The source code is partly based on the Deviation TX project, thanks to all the developpers for their great job on protocols.
@@ -17,7 +18,7 @@ The source code is partly based on the Deviation TX project, thanks to all the d
[Hardware](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#hardware)
[Compilation and programmation](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#compilation)
[Compilation and programmation](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#compilation-and-programmation)
[Troubleshooting](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#troubleshooting)
@@ -44,7 +45,7 @@ Settings per selection are located in _Config.h:
- Autobind: Yes or No. At the model selection (or power applied to the TX) a bind sequence will be initiated
###Using a serial output
The multiprotocol TX module takes full advantage of being used on a Turnigy 9X, 9XR, 9XR Pro, Taranis, 9Xtreme, AR9X, ... running [er9x or ersky9X](https://github.com/MikeBland/mbtx/tree/next). (A version for OpenTX is being looked at)
The multiprotocol TX module takes full advantage of being used on a Turnigy 9X, 9XR, 9XR Pro, Taranis, 9Xtreme, AR9X, ... running [er9x](http://openrcforums.com/forum/viewtopic.php?f=5&t=4598) or [ersky9X](http://openrcforums.com/forum/viewtopic.php?f=7&t=4676). An OpenTX version for Taranis is available [here](http://plaisthos.de/opentx/).
This enables full integration using the radio GUI to setup models with all the available protocols options.
@@ -65,21 +66,42 @@ Notes:
- Channels order is AETR by default but can be changed in _Config.h.
###Telemetry
Telemetry is available for er9x and ersky9x TXs.
There are only 2 protocols so far supporting telemetry: Hubsan and Frsky.
To enable telemetry on Turnigy 9X or 9XR you need to modify your TX following one of the Frsky mod like this [one](http://blog.oscarliang.net/turnigy-9x-advance-mod/).
There are 4 protocols supporting telemetry: Hubsan, DSM, FrSkyD and FrSkyX.
Enabling telemetry on 9XR PRO and may be other TXs does not require any hardware modifications. The additional required serial pin is already available on the TX back module pins.
Hubsan displays the battery voltage and TX RSSI.
Once the TX is telemetry enabled, it just needs to be configured on the model as usual.
DSM displays TX RSSI and full telemetry.
FrSkyD displays full telemetry (A0, A1, RX RSSI, TX RSSI and Hub).
FrSkyX displays full telemetry (A1, A2, RX RSSI, TX RSSI and Hub).
### If used in PPM mode
Telemetry is available as a serial 9600 8 n 1 output on the TX pin of the Atmega328p using the FrSky hub format for Hubsan, FrSkyD, FrSkyX and DSM format for DSM2/X.
You can connect it to your TX if it is telemetry enabled or use a bluetooth adapter (HC05/HC06) along with an app on your phone/tablet ([app example](https://play.google.com/store/apps/details?id=biz.onomato.frskydash&hl=fr)) to display telemetry information and setup alerts.
### If used in Serial mode
Telemetry is built in for er9x and ersky9x TXs.
To enable telemetry on a Turnigy 9X or 9XR you need to modify your TX following one of the Frsky mod like this [one](http://blog.oscarliang.net/turnigy-9x-advance-mod/).
Note: DSM telemetry is not available on er9x due to a lack of flash space.
Enabling telemetry on a 9XR PRO and may be other TXs does not require any hardware modifications. The additional required serial pin is already available on the TX back module pins.
Once the TX is telemetry enabled, it just needs to be configured on the model (see er9x/ersky9x documentation).
##Protocols
###TX ID
The multiprotocol TX module is using a 32bits ID generated randomly at first power up. This global ID is used by all protocols.
The multiprotocol TX module is using a 32bits ID generated randomly at first power up. This global ID is used by nearly all protocols.
There are little chances to get a duplicated ID.
For DSM2/X and Devo the CYRF6936 unique manufacturer ID is used.
It's possible to generate a new ID using bind button on the Hubsan protocol during power up.
###Bind
@@ -97,356 +119,181 @@ Notes:
####Using the dial for PPM input
PPM is only allowing access to a subset of existing protocols.
The default association dial position / protocol is listed below.
The protocols, subprotocols and all other settings can be personalized by modifying the **_Config.h** file.
The default association dial position / protocol in every release is listed below.
Dial|Protocol|Sub_protocol|RX Num|Power|Auto Bind|Option|RF Module
----|--------|------------|------|-----|---------|------|---------
0|Select serial||||||
1|FLYSKY|Flysky|0|High|No|0|A7105
2|HUBSAN|-|0|High|No|0|A7105
3|FRSKY|-|0|High|No|-41|CC2500
3|FRSKYD|-|0|High|No|-41|CC2500
4|HISKY|Hisky|0|High|No|0|NRF24L01
5|V2X2|-|0|High|No|0|NRF24L01
6|DSM2|DSM2|0|High|No|0|CYRF6936
6|DSM|DSM2|0|High|No|6|CYRF6936
7|DEVO|-|0|High|No|0|CYRF6936
8|YD717|YD717|0|High|No|0|NRF24L01
9|KN|WLTOYS|0|High|No|0|NRF24L01
10|SYMAX|SYMAX|0|High|No|0|NRF24L01
11|SLT|-|0|High|No|0|NRF24L01
12|CX10|CX10_BLUE|0|High|No|0|NRF24L01
12|CX10|BLUE|0|High|No|0|NRF24L01
13|CG023|CG023|0|High|No|0|NRF24L01
14|BAYANG|-|0|High|No|0|NRF24L01
15|SYMAX|SYMAX5C|0|High|No|0|NRF24L01
Notes:
Note:
- The dial selection must be done before the power is applied.
- The protocols, subprotocols and all other settings can be personalized by modifying the _Config.h file.
####Using serial input with er9x/ersky9x
Serial is allowing access to all existing protocols & sub_protocols listed below.
Protocol|Sub_protocol|RF Module
--------|------------|---------
Flysky||A7105
#####A7105 RF module
Protocol|Sub_protocol
--------|------------
Flysky|
|Flysky
|V9x9
|V6x6
|V912
Hubsan||A7105
Frsky||CC2500
Hisky||NRF24L01
|Hisky
|HK310
V2x2||NRF24L01
DSM2||CYRF6936
Hubsan|
#####CC2500 RF module
Protocol|Sub_protocol
--------|------------
FrSkyV|
FrSkyD|
FrSkyX|
|CH_16
|CH_8
SFHSS|
#####CYRF6936 RF module
Protocol|Sub_protocol
--------|------------
DSM|
|DSM2
|DSMX
Devo||CYRF6936
YD717||NRF24L01
Devo|
J6Pro|
#####NRF24L01 RF module
Protocol|Sub_protocol
--------|------------
Hisky|
|Hisky
|HK310
V2x2|
YD717|
|YD717
|SKYWLKR
|SYMAX4
|XINXUN
|NIHUI
KN||NRF24L01
KN|
|WLTOYS
|FEILUN
SymaX||NRF24L01
SymaX|
|SYMAX
|SYMAX5C
SLT||NRF24L01
CX10||NRF24L01
|CX10_GREEN
|CX10_BLUE
SLT|
CX10|
|GREEN
|BLUE
|DM007
|Q282
|JC3015_1
|JC3015_2
|MK33041
|Q242
CG023||NRF24L01
CG023|
|CG023
|YD829
|H8_3D
Bayang||NRF24L01
FrskyX||CC2500
ESky||NRF24L01
Bayang|
ESky|
MT99XX|
|MT
|H7
|YZ
|LS
MJXQ|
|WLH08
|X600
|X800
|H26D
|E010
Shenqi|
FY326|
FQ777|
ASSAN|
Note:
- The dial should be set to 0 for serial. Which means all protocol selection pins should be left unconnected.
###Protocol details
Extended limits supported: -125%..+125% can be used and will be transmitted. Otherwise the default is -100%..+100% only.
Autobind protocol: you do not need to press the bind button at power up to bind, this is done automatically.
####BAYANG
Models: EAchine H8(C) mini, BayangToys X6/X7/X9, JJRC JJ850, Floureon H101 ...
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10
---|---|---|---|---|---|---|---|---|----
A|E|T|R|FLIP|RTH|PICTURE|VIDEO|HEADLESS|INVERTED
####CG023
Models: EAchine CG023/CG031/3D X4
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
---|---|---|---|---|---|---|---|---
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
#####Sub_protocol YD829
Models: Attop YD-822/YD-829/YD-829C ...
CH5|CH6|CH7|CH8|CH9
---|---|---|---|---
FLIP||PICTURE|VIDEO|HEADLESS
#####Sub_protocol H8_3D
Models: EAchine H8 mini 3D, JJRC H20/H22
CH5|CH6|CH7|CH8|CH9
---|---|---|---|---
FLIP|LIGTH|OPT1|OPT2|CAL
JJRC H20: OPT1=Headless, OPT2=RTH
JJRC H22: OPT1=RTH, OPT2=180/360° flip mode
H8 3D: OPT1=RTH + headless, OPT2=180/360° flip mode
CAL: calibrate accelerometers
####CX10
Extended limits supported
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6
---|---|---|---|---|---
A|E|T|R|FLIP|RATE
Rate: -100%=rate 1, 0%=rate 2, +100%=rate 3
#####Sub_protocol CX10_GREEN
Models: Cheerson CX-10 green pcb
Same channels assignement as above.
#####Sub_protocol CX10_BLUE
Models: Cheerson CX-10 blue pcb & some newer red pcb, CX-10A, CX-10C, CX11, CX12, Floureon FX10, JJRC DHD D1
CH5|CH6|CH7|CH8
---|---|---|---
FLIP|RATE|PICTURE|VIDEO
Rate: -100%=rate 1, 0%=rate 2, +100%=rate 3 or headless for CX-10A
#####Sub_protocol CX10_DM007
CH5|CH6|CH7|CH8|CH9
---|---|---|---|---
FLIP|MODE|PICTURE|VIDEO|HEADLESS
#####Sub_protocol CX10_Q282 and CX10_Q242
CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
---|---|---|---|---|---|---|---
FLIP|LED|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL
#####Sub_protocol CX10_JC3015_1
CH5|CH6|CH7|CH8
---|---|---|---
FLIP|MODE|PICTURE|VIDEO
#####Sub_protocol CX10_JC3015_2
CH5|CH6|CH7|CH8
---|---|---|---
FLIP|MODE|LED|DFLIP
#####Sub_protocol CX10_MK33041
CH5|CH6|CH7|CH8|CH9|CH10
---|---|---|---|---|---
FLIP|MODE|PICTURE|VIDEO|HEADLESS|RTH
####DEVO
Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
####DSM2
Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
####ESKY
CH1|CH2|CH3|CH4|CH5|CH6
---|---|---|---|---|---
A|E|T|R|GYRO|PITCH
####FLYSKY
Extended limits supported
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|CH5|CH6|CH7|CH8
#####Sub_protocol V9X9
CH5|CH6|CH7|CH8
---|---|---|---
UNK|LIGHT|PICTURE|VIDEO
#####Sub_protocol V6X6
CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
---|---|---|---|---|---|---|---
FLIP|LIGHT|PICTURE|VIDEO|HEADLESS|RTH|XCAL|YCAL
#####Sub_protocol V912
CH5|CH6
---|---
BTMBTN|TOPBTN
####FRSKY
Extended limits supported
Telemetry enabled for A0, A1, RSSI
Option=fine frequency tuning, usually 0 or -41 based on the manufacturer boards
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
####HISKY
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
A|E|T|R|GEAR|PITCH|GYRO|CH8
GYRO: -100%=6G, +100%=3G
####HK310
Models: RX HK-3000, HK3100 and XY3000 (TX are HK-300, HK-310 and TL-3C)
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8
---|---|---|---|---|---|---|---
|||T|R|AUX|T_FSAFE|R_FSAFE|AUX_FSAFE
####HUBSAN
Models: Hubsan H102D, H107/L/C/D and Hubsan H107P/C+/D+
Autobind protocol
Telemetry enabled for battery voltage only
Option=vTX frequency (H107D) 5645 - 5900 MHz
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
---|---|---|---|---|---|---|---|---
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
####KN
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11
---|---|---|---|---|---|---|---|---|----|----
A|E|T|R|DR|THOLD|IDLEUP|GYRO|Ttrim|Atrim|Etrim
Dual Rate: +100%=full range, Throttle Hold: +100%=hold, Idle Up: +100%=3D, GYRO: -100%=6G, +100%=3G
#####Sub_protocol WLTOYS
#####Sub_protocol FEILUN
Same channels assignement as above.
####SLT
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6
---|---|---|---|---|---
A|E|T|R|GEAR|PITCH
####Symax
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
---|---|---|---|---|---|---|---|---
A|E|T|R|FLIP||PICTURE|VIDEO|HEADLESS
#####Sub_protocol SYMAX
Models: Syma X5C-1/X11/X11C/X12
#####Sub_protocol SYMAX5C
Model: Syma X5C (original) and X2
####V2X2
Models: WLToys V202/252/272, JXD 385/388, JJRC H6C, Yizhan Tarantula X6 ...
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11
---|---|---|---|---|---|---|---|---|----|----
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS|MAG_CAL_X|MAG_CAL_Y
PICTURE: also automatic Missile Launcher and Hoist in one direction
VIDEO: also Sprayer, Bubbler, Missile Launcher(1), and Hoist in the other dir
####YD717
Autobind protocol
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
---|---|---|---|---|---|---|---|---
A|E|T|R|FLIP|LIGHT|PICTURE|VIDEO|HEADLESS
#####Sub_protocol YD717
#####Sub_protocol SKYWLKR
#####Sub_protocol SYMAX4
#####Sub_protocol XINXUN
#####Sub_protocol NIHUI
Same channels assignement as above.
###Protocols details
**Check the [Protocols_Details.md](./Protocols_Details.md) file for a detailed description of every protocols with channels assignements.**
##Hardware
###RF modules
Up to 4 RF modules can be installed:
- [A7105](http://www.banggood.com/XL7105-D03-A7105-Modification-Module-Support-Deviation-Galee-Flysky-p-922603.html) for Flysky, Hubsan
- [CC2500](http://www.banggood.com/CC2500-PA-LNA-Romote-Wireless-Module-CC2500-SI4432-NRF24L01-p-922595.html) for Frsky
- [CYRF6936](http://www.ehirobo.com/walkera-wk-devo-s-mod-devo-8-or-12-to-devo-8s-or-12s-upgrade-module.html) for DSM2, DSMX, DEVO, Walkera
- [CC2500](http://www.banggood.com/CC2500-PA-LNA-Romote-Wireless-Module-CC2500-SI4432-NRF24L01-p-922595.html) for FrSkyV, FrSkyD, FrSkyX and SFHSS
- [CYRF6936](http://www.ehirobo.com/walkera-wk-devo-s-mod-devo-8-or-12-to-devo-8s-or-12s-upgrade-module.html) for DSM, DEVO, J6Pro
- [NRF24L01](http://www.banggood.com/2_4G-NRF24L01-PA-LNA-Wireless-Module-1632mm-Without-Antenna-p-922601.html) for Hisky, V2x2, CX-10, SYMAX and plenty other protocols
RF modules can be installed for protocols need only. Example: if you only need the Hubsan protocol then install only a A7105 on your board.
You also need some [antennas](http://www.banggood.com/2_4GHz-3dBi-RP-SMA-Connector-Booster-Wireless-Antenna-Modem-Router-p-979407.html) and [cables](http://www.banggood.com/10cm-PCI-UFL-IPX-to-RPSMA-Female-Jack-Pigtail-Cable-p-924933.html).
###Microcontroller
The main program is running on an ATMEGA328 running @16MHz and 3.3V.
An [Arduino pro mini](http://www.banggood.com/Wholesale-New-Ver-Pro-Mini-ATMEGA328-328p-5V-16MHz-Arduino-Compatible-Nano-Size-p-68534.html) can be used to build your own Multimodule.
###Board
The main program is running on an ATMEGA328p running @16MHz and 3.3V.
An [Arduino pro mini 16Mhz/5V](http://www.banggood.com/Wholesale-New-Ver-Pro-Mini-ATMEGA328-328p-5V-16MHz-Arduino-Compatible-Nano-Size-p-68534.html) powered at 3.3V (yes it works) can be used to build your own Multimodule. An Arduino Mini based on Atmega328p can also be used.
Using stripboard:
####Using stripboard:
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t8214655-87-thumb-uploadfromtaptalk1405598143749.jpg?d=1441459923)
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t8214656-102-thumb-uploadfromtaptalk1405598152484.jpg?d=1441459924)
Using a [home made PCB](http://www.rcgroups.com/forums/showpost.php?p=32645328&postcount=1621):
####Using a [home made PCB](http://www.rcgroups.com/forums/showpost.php?p=32645328&postcount=1621):
![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8226720-197-thumb-IMG_20150715_230603155.jpg?d=1441816457)
![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8226719-72-thumb-IMG_20150715_230024065.jpg?d=1441816456)
or build your own board using [SMD components](http://www.rcgroups.com/forums/showpost.php?p=31064232&postcount=1020) and an [associated PCB](https://oshpark.com/shared_projects/MaGYDg0y):
####Build your own board using [SMD components](http://www.rcgroups.com/forums/showpost.php?p=31064232&postcount=1020) and an [associated PCB v2.3c](https://oshpark.com/shared_projects/MaGYDg0y):
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7566755-3-thumb-i.png?d=1423810885)
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952726-108-thumb-image-62c29cf2.jpg?d=1433909893)
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952733-114-thumb-P4100002.JPG?d=1433910155) ![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t7952734-189-thumb-P4100003.JPG?d=1433910159)
If you build this PCB v2.3c and want to enable serial mode for er9x/ersky9x, you should do [this mod](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/a8180322-194-multi.jpg):
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/t8180322-35-thumb-multi.jpg?d=1440422869)
If you build this PCB v2.3c and want to enable serial mode for er9x/ersky9x, you have to do [this mod](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/a8667856-242-multi.jpg).
**[New PCB v2.3d!](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/tree/master/PCB%20v2.3d) available**
Repository includes Kicad files of schematic and pcb. This is a variant of the Multipro V2.3c circuit design. It is basicly the same as the 2.3c board as far as component placement goes. What's changed is the added resistors for the serial protocol and also
the addition of solder jumpers on the bottom of the board for the various options to connect the TX, RX, and PPM
lines through them.
![Screenshot](https://644db4de3505c40a0444-327723bce298e3ff5813fb42baeefbaa.ssl.cf1.rackcdn.com/b637193364a5e228dc8ab6ad90c0ca3c.png)
![Screenshot](https://644db4de3505c40a0444-327723bce298e3ff5813fb42baeefbaa.ssl.cf1.rackcdn.com/97b87a89b75785d70b354e5b033f5209.png)
[OSH Park link](https://oshpark.com/shared_projects/Ztus1ah8) if you want to order.
####Buy a ready to use and complete Multi module
![Screenshot](http://img.banggood.com/thumb/view/oaupload/banggood/images/1D/EB/19bb6434-4616-411e-b8fa-a4c21d9dca24.jpg)
This module can be purchased [here](http://www.banggood.com/2_4G-CC2500-A7105-Flysky-Frsky-Devo-DSM2-Multiprotocol-TX-Module-With-Antenna-p-1048377.html). All the 4 RF modules are already implemented A7105, NRF24L01, CC2500 and CYRF6936. The board is also equiped with an antenna switcher which means only one antenna for all.
**It is highly recommended to update the firmware** of this board as it is distributed with a really old and bugged one. For this you have to solder a 6 pin header (top left) and use an USBASP like explained [below](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#upload-the-code-using-isp-in-system-programming).
If you want to enable serial mode for er9x/ersky9x/Taranis/... and depending on your board revision, you have to do one of these modifications:
- 1st revision, add 2 resistors as shown here: ![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/a8895038-170-4in1%20module.jpg)
- 2nd revision, solder pads together as shown:
<img src="http://static.rcgroups.net/forums/attachments/4/8/3/5/8/4/a9206217-177-IMG_5790.jpg" width="350">
Note: if you have the 1st board revision (check pictures above), sometime bind occures at power up even without pressing the bind button or not having an autobind protocol. To solve this issue, replacing the BIND led resistor (on the board back) of 1.2K by a 4.7K.
###Schematic
![Screenshot](http://static.rcgroups.net/forums/attachments/4/0/8/5/8/3/a8443844-119-multiprotocol_diagram_rotary_serial_2.jpg)
@@ -456,19 +303,33 @@ Notes:
- For serial, the dial switch is not needed and the bind button optionnal
###Radio integration
You can 3D print your box (details [here](http://www.rcgroups.com/forums/showpost.php?p=33294140&postcount=2034)):
If you build your own version of the board you can 3D print this case (details [here](http://www.rcgroups.com/forums/showpost.php?p=33294140&postcount=2034)):
![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8462144-54-thumb-Multi_case_9XR.jpg?d=1448575289)
![Screenshot](http://static.rcgroups.net/forums/attachments/1/1/5/4/3/7/t8462145-106-thumb-Multi_case_v1.jpg?d=1448575293)
If you have the Banggood ready to use board you can 3D print this case (details [here](http://www.rcgroups.com/forums/showpost.php?p=35349049&postcount=3)):
<img src="http://static.rcgroups.net/forums/attachments/4/8/3/5/8/4/a9206211-97-Screen%20Shot%202016-07-27%20at%2011.02.35%20am.png" width="200">
<img src="http://static.rcgroups.net/forums/attachments/4/8/3/5/8/4/a9206411-90-IMG_5793.jpeg" width="200">
<img src="http://static.rcgroups.net/forums/attachments/4/8/3/5/8/4/a9206445-131-IMG_5796.jpeg" width="200">
##Compilation and programmation
###Toolchain
Arduino 1.6.5
Multiprotocol source can be compiled using the Arduino IDE.
Compilation of the code posted here works. So if it doesn't for you this is a problem with your setup, please double check everything before asking.
The currently supported Arduino version is [1.6.10](https://www.arduino.cc/download_handler.php?f=/arduino-1.6.10-windows.exe).
_Config.h file can be modified to compile with/without some protocols, change protocols/sub_protocols/settings associated with dial for PPM input, different channel orders, different channels timing, Telemetry or not, ...
Download the [zip file](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/archive/master.zip) of this repository, unzip it in a folder, navigate to the Multiprotocol directory and then click on Multiprotocol.ino. The Arduino environment will appear and the Multiprotocol project will be loaded.
**[_Config.h file](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/blob/master/Multiprotocol/_Config.h) must be modified** to select which protocols will be available, change protocols/sub_protocols/settings associated with dial for PPM input, different TX channel orders and timing, Telemetry or not, ...
This is mandatory since all available protocols will not fit in the ATmega328. You need to pick and choose what you want.
Notes:
- Make sure to select "Arduino Pro or Pro Mini, ATmega328 (5V,16MHz)" before compiling.
- Compilation of the code posted here works. So if it doesn't for you this is a problem with your setup, please double check everything before asking.
- If you want to reduce the code size even further, you can modify the file platform.txt located in "C:\Program Files (x86)\Arduino\hardware\arduino\avr". Set the line "compiler.c.elf.extra_flags=" to "compiler.c.elf.extra_flags=-Wl,--relax".
###Upload the code using ISP (In System Programming)
It is recommended to use an external programmer like [USBASP](http://www.banggood.com/USBASP-USBISP-3_3-5V-AVR-Downloader-Programmer-With-ATMEGA8-ATMEGA128-p-934425.html) to upload the code in the Atmega328. The programmer should be set to 3.3V or nothing to not supply any over voltage to the multimodule and avoid any damages.
@@ -479,11 +340,22 @@ From the Arduino environment, you can use this shortcut to compile and upload to
To flash the latest provided hex file under [Release](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/releases), you can use a tool like [AVR Burn-O-Mat](http://avr8-burn-o-mat.aaabbb.de/), set the microcontroller to m328p and flash it.
###Upload the code using FTDI (USB serial to TTL)
Use this method only for Arduino Pro Mini boards with bootloader.
Use an external FTDI adapter like [this one](http://www.banggood.com/FT232RL-FTDI-USB-To-TTL-Serial-Converter-Adapter-Module-For-Arduino-p-917226.html).
The programmer should be set to 3.3V or nothing to not supply any over voltage to the multimodule and avoid any damages.
From the Arduino environment, you can use Upload button which will compile and upload to the module: Skecth->Upload (Ctrl+U)
To upload the latest provided hex file under [Release](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/releases), you can use a tool like [XLoader](http://russemotto.com/xloader/), set the microcontroller to Atmega328 and upload it.
###Set fuses
Use a tool like [AVR Burn-O-Mat](http://avr8-burn-o-mat.aaabbb.de/) to set the fuses of the Atmega328 to:
- Low Fuse 0xFF
- Extended Fuse 0x05 (or 0xFD which is the same)
- High Fuse 0xD2
- Extended Fuse 0x05
- Low Fuse 0xFF
This will make sure your ATMEGA328 is well configured and the global TX ID is not erased at each updates.
@@ -491,21 +363,27 @@ This will make sure your ATMEGA328 is well configured and the global TX ID is no
###LED status
- off: program not running or a protocol selected with the associated module not installed.
- flash: invalid protocol selected (excluded from compilation or invalid protocol number)
- slow blink: serial has been selected but no valid signal has been seen on the RX pin.
- fast blink: bind in progress.
- flash(on=0.1s,off=1s): invalid protocol selected (excluded from compilation or invalid protocol number)
- slow blink(on=0.5s,off=0.5s): serial has been selected but no valid signal has been seen on the RX pin.
- fast blink(on=0.1s,off=0.1s): bind in progress.
- on: normal operation.
###Protocol selection
####Input Mode - PPM
- The protocol/mode selection must be done before the power is applied.
- Connect 1 to 4 of the selection protocol pins to GND.
####Input Mode - Serial
- Make sure you have done the mods to the v2.3c PCB by adding the 2.2k and 470 ohm resistors as indicated in the [Board section] (https://github.com/pascallanger/DIY-Multiprotocol-TX-Module#board).
- Leave all 4 selection pins unconnected.
###Bind
Make sure to follow this procedure: press the bind button, apply power and then release it after 1sec. The LED should be blinking fast indicating a bind status and then fixed on when the bind period is over. It's normal that the LED turns off when you press the bind button, this behavior is not controlled by the Atmega328.
For serial, the preffered method is to bind via the GUI protocol page.
It migth happen that your module is always binding at power up. If this is the case, there is a big chance that you are using an Arduino Pro Mini with an external status LED. To work around this issue connect a 10K resistor between D13 and 3.3V.
###Protocol selection
For serial, leave all 4 selection pins unconnected.
For PPM, connect 1 to 4 of the selection protocol pins to GND.
The protocol/mode selection must be done before the power is applied.
If your module is always/sometime binding at power up without pressing the button:
- Arduino Pro Mini with an external status LED: to work around this issue connect a 10K resistor between D13 and 3.3V.
- 4in1 module V1 (check 4in1 pictures): to solve this issue, replacing the BIND led resistor (on the board back) of 1.2K by a 4.7K.
###Report issues
You can report your problem using the [GitHub issue](https://github.com/pascallanger/DIY-Multiprotocol-TX-Module/issues) system or go to the [Main thread on RCGROUPS](http://www.rcgroups.com/forums/showthread.php?t=2165676) to ask your question.