mirror of
https://github.com/pascallanger/DIY-Multiprotocol-TX-Module.git
synced 2025-02-04 20:48:12 +00:00
HoTT: Failsafe
Failsafe MUST be configured once with the desired channel values (hold or position) while the RX is up (wait 10+sec for the RX to learn the config) and then failsafe MUST be set to RX/Receiver otherwise the servos will jitter!!!
This commit is contained in:
parent
c048e97d3a
commit
c4c5ffec4f
@ -133,7 +133,7 @@ static void __attribute__((unused)) HOTT_init()
|
|||||||
memcpy(rx_tx_addr,"\x7C\x94\x00\x0D\x50",5);
|
memcpy(rx_tx_addr,"\x7C\x94\x00\x0D\x50",5);
|
||||||
#endif
|
#endif
|
||||||
memset(&packet[30],0xFF,9);
|
memset(&packet[30],0xFF,9);
|
||||||
packet[39]=0x07; // unknown
|
packet[39]=0x07; // unknown and constant
|
||||||
if(IS_BIND_IN_PROGRESS)
|
if(IS_BIND_IN_PROGRESS)
|
||||||
{
|
{
|
||||||
packet[28] = 0x80; // unknown 0x80 when bind starts then when RX replies start normal, 0x89/8A/8B/8C/8D/8E during normal packets
|
packet[28] = 0x80; // unknown 0x80 when bind starts then when RX replies start normal, 0x89/8A/8B/8C/8D/8E during normal packets
|
||||||
@ -144,7 +144,7 @@ static void __attribute__((unused)) HOTT_init()
|
|||||||
else
|
else
|
||||||
{
|
{
|
||||||
packet[28] = 0x8C; // unknown 0x80 when bind starts then when RX replies start normal, 0x89/8A/8B/8C/8D/8E during normal packets
|
packet[28] = 0x8C; // unknown 0x80 when bind starts then when RX replies start normal, 0x89/8A/8B/8C/8D/8E during normal packets
|
||||||
packet[29] = 0x02; // unknown 0x02 when bind starts then when RX replies cycle in sequence 0x1A/22/2A/0A/12, 0x02 during normal packets, 0x8C&0x0A->no telemetry
|
packet[29] = 0x02; // unknown 0x02 when bind starts then when RX replies cycle in sequence 0x1A/22/2A/0A/12, 0x02 during normal packets, 0x0A->no more RX telemetry
|
||||||
memcpy(&packet[40],rx_tx_addr,5);
|
memcpy(&packet[40],rx_tx_addr,5);
|
||||||
|
|
||||||
uint8_t addr=HOTT_EEPROM_OFFSET+RX_num*5;
|
uint8_t addr=HOTT_EEPROM_OFFSET+RX_num*5;
|
||||||
@ -157,13 +157,50 @@ static void __attribute__((unused)) HOTT_data_packet()
|
|||||||
{
|
{
|
||||||
packet[2] = hopping_frequency_no;
|
packet[2] = hopping_frequency_no;
|
||||||
|
|
||||||
packet[3] = 0x00; // unknown, may be for additional channels?
|
packet[3] = 0x00; // used for failsafe but may also be used for additional channels
|
||||||
|
#ifdef FAILSAFE_ENABLE
|
||||||
|
static uint8_t failsafe_count=0;
|
||||||
|
if(IS_FAILSAFE_VALUES_on && IS_BIND_DONE)
|
||||||
|
{
|
||||||
|
failsafe_count++;
|
||||||
|
if(failsafe_count>=3)
|
||||||
|
{
|
||||||
|
FAILSAFE_VALUES_off;
|
||||||
|
failsafe_count=0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
failsafe_count=0;
|
||||||
|
#endif
|
||||||
|
|
||||||
// Channels value are PPM*2, -100%=1100µs, +100%=1900µs, order TAER
|
// Channels value are PPM*2, -100%=1100µs, +100%=1900µs, order TAER
|
||||||
|
uint16_t val;
|
||||||
for(uint8_t i=4;i<28;i+=2)
|
for(uint8_t i=4;i<28;i+=2)
|
||||||
{
|
{
|
||||||
uint16_t val=Channel_data[(i-4)>>1];
|
val=Channel_data[(i-4)>>1];
|
||||||
val=(((val<<2)+val)>>2)+860*2; //value range 860<->2140 *2 <-> -125%<->+125%
|
val=(((val<<2)+val)>>2)+860*2; // value range 860<->2140 *2 <-> -125%<->+125%
|
||||||
|
#ifdef FAILSAFE_ENABLE
|
||||||
|
if(failsafe_count==1)
|
||||||
|
{ // first failsafe packet
|
||||||
|
packet[3]=0x40;
|
||||||
|
uint16_t fs=Failsafe_data[(i-4)>>1];
|
||||||
|
if( fs == FAILSAFE_CHANNEL_HOLD || fs == FAILSAFE_CHANNEL_NOPULSES)
|
||||||
|
val|=0x8000; // channel hold flag
|
||||||
|
else
|
||||||
|
{
|
||||||
|
val=(((fs<<2)+fs)>>2)+860*2; // value range 860<->2140 *2 <-> -125%<->+125%
|
||||||
|
val|=0x4000; // channel specific position flag
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if(failsafe_count==2)
|
||||||
|
{ // second failsafe packet=timing?
|
||||||
|
packet[3]=0x50;
|
||||||
|
if(i==4)
|
||||||
|
val=2;
|
||||||
|
else
|
||||||
|
val=0;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
packet[i] = val;
|
packet[i] = val;
|
||||||
packet[i+1] = val>>8;
|
packet[i+1] = val>>8;
|
||||||
}
|
}
|
||||||
|
@ -19,7 +19,7 @@
|
|||||||
#define VERSION_MAJOR 1
|
#define VERSION_MAJOR 1
|
||||||
#define VERSION_MINOR 3
|
#define VERSION_MINOR 3
|
||||||
#define VERSION_REVISION 0
|
#define VERSION_REVISION 0
|
||||||
#define VERSION_PATCH_LEVEL 37
|
#define VERSION_PATCH_LEVEL 38
|
||||||
|
|
||||||
//******************
|
//******************
|
||||||
// Protocols
|
// Protocols
|
||||||
|
@ -162,11 +162,12 @@ static void multi_send_status()
|
|||||||
case PROTO_J6PRO:
|
case PROTO_J6PRO:
|
||||||
flags |= 0x40; //Disable_ch_mapping supported
|
flags |= 0x40; //Disable_ch_mapping supported
|
||||||
break;
|
break;
|
||||||
case PROTO_FRSKYX:
|
|
||||||
#ifdef FAILSAFE_ENABLE
|
#ifdef FAILSAFE_ENABLE
|
||||||
|
case PROTO_HOTT:
|
||||||
|
case PROTO_FRSKYX:
|
||||||
flags |= 0x20; //Failsafe supported
|
flags |= 0x20; //Failsafe supported
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
if(IS_DATA_BUFFER_LOW_on)
|
if(IS_DATA_BUFFER_LOW_on)
|
||||||
flags |= 0x80;
|
flags |= 0x80;
|
||||||
|
@ -29,7 +29,7 @@ Here are detailed descriptions of every supported protocols (sorted by RF module
|
|||||||
## Protocol selection in PPM mode
|
## Protocol selection in PPM mode
|
||||||
The protocol selection is based on 2 parameters:
|
The protocol selection is based on 2 parameters:
|
||||||
* selection switch: this is the rotary switch on the module numbered from 0 to 15
|
* selection switch: this is the rotary switch on the module numbered from 0 to 15
|
||||||
- switch position 0 is to select the Serial mode for er9x/ersky9x/OpenTX radio
|
- switch position 0 is to select the Serial mode for er9x/erskyTX/OpenTX radio
|
||||||
- switch position 15 is to select the bank
|
- switch position 15 is to select the bank
|
||||||
- switch position 1..14 will select the protocol 1..14 in the bank *X*
|
- switch position 1..14 will select the protocol 1..14 in the bank *X*
|
||||||
* banks are used to increase the amount of accessible protocols by the switch. There are up to 5 banks giving acces to up to 70 protocol entries (5 * 14). To modify or verify which bank is currenlty active do the following:
|
* banks are used to increase the amount of accessible protocols by the switch. There are up to 5 banks giving acces to up to 70 protocol entries (5 * 14). To modify or verify which bank is currenlty active do the following:
|
||||||
@ -56,7 +56,7 @@ Notes:
|
|||||||
Serial mode is selected by placing the rotary switch to position 0 before power on of the radio.
|
Serial mode is selected by placing the rotary switch to position 0 before power on of the radio.
|
||||||
|
|
||||||
You've upgraded the module but the radio does not display the name of the protocol you are loking for:
|
You've upgraded the module but the radio does not display the name of the protocol you are loking for:
|
||||||
* ersky9x:
|
* erskyTX:
|
||||||
- Place the file [Multi.txt](https://raw.githubusercontent.com/pascallanger/DIY-Multiprotocol-TX-Module/master/Multiprotocol/Multi.txt) (which is part of the MPM source files) on the root of your SD card.
|
- Place the file [Multi.txt](https://raw.githubusercontent.com/pascallanger/DIY-Multiprotocol-TX-Module/master/Multiprotocol/Multi.txt) (which is part of the MPM source files) on the root of your SD card.
|
||||||
- If the entry still does not appear or is broken, [upgrade](https://openrcforums.com/forum/viewtopic.php?f=7&t=4676) to version R222d2 or newer.
|
- If the entry still does not appear or is broken, [upgrade](https://openrcforums.com/forum/viewtopic.php?f=7&t=4676) to version R222d2 or newer.
|
||||||
* OpenTX:
|
* OpenTX:
|
||||||
@ -98,6 +98,7 @@ CFlie|38|CFlie||||||||NRF24L01|
|
|||||||
[Hisky](Protocols_Details.md#HISKY---4)|4|Hisky|HK310|||||||NRF24L01|
|
[Hisky](Protocols_Details.md#HISKY---4)|4|Hisky|HK310|||||||NRF24L01|
|
||||||
[Hitec](Protocols_Details.md#HITEC---39)|39|OPT_FW|OPT_HUB|MINIMA||||||CC2500|
|
[Hitec](Protocols_Details.md#HITEC---39)|39|OPT_FW|OPT_HUB|MINIMA||||||CC2500|
|
||||||
[Hontai](Protocols_Details.md#HONTAI---26)|26|HONTAI|JJRCX1|X5C1|FQ777_951|||||NRF24L01|XN297
|
[Hontai](Protocols_Details.md#HONTAI---26)|26|HONTAI|JJRCX1|X5C1|FQ777_951|||||NRF24L01|XN297
|
||||||
|
[HoTT](Protocols_Details.md#HoTT---57)|57|||||||||CC2500|
|
||||||
[Hubsan](Protocols_Details.md#HUBSAN---2)|2|H107|H301|H501||||||A7105|
|
[Hubsan](Protocols_Details.md#HUBSAN---2)|2|H107|H301|H501||||||A7105|
|
||||||
[J6Pro](Protocols_Details.md#J6Pro---22)|22|J6PRO||||||||CYRF6936|
|
[J6Pro](Protocols_Details.md#J6Pro---22)|22|J6PRO||||||||CYRF6936|
|
||||||
[KF606](Protocols_Details.md#KF606---49)|49|KF606*||||||||NRF24L01|XN297
|
[KF606](Protocols_Details.md#KF606---49)|49|KF606*||||||||NRF24L01|XN297
|
||||||
@ -166,7 +167,7 @@ Extended limits and failsafe supported
|
|||||||
|
|
||||||
Telemetry enabled protocol:
|
Telemetry enabled protocol:
|
||||||
- by defaut using FrSky Hub protocol (for example er9x): RX(A1), battery voltage FS-CVT01(A2) and RX&TX RSSI
|
- by defaut using FrSky Hub protocol (for example er9x): RX(A1), battery voltage FS-CVT01(A2) and RX&TX RSSI
|
||||||
- if using ersky9x and OpenTX: full telemetry information available
|
- if using erskyTX and OpenTX: full telemetry information available
|
||||||
|
|
||||||
Option is used to change the servo refresh rate. A value of 0 gives 50Hz (min), 70 gives 400Hz (max). Specific refresh rate value can be calculated like this option=(refresh_rate-50)/5.
|
Option is used to change the servo refresh rate. A value of 0 gives 50Hz (min), 70 gives 400Hz (max). Specific refresh rate value can be calculated like this option=(refresh_rate-50)/5.
|
||||||
|
|
||||||
@ -395,20 +396,38 @@ CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9
|
|||||||
### Sub_protocol OPT_FW - *0*
|
### Sub_protocol OPT_FW - *0*
|
||||||
OPTIMA RXs
|
OPTIMA RXs
|
||||||
|
|
||||||
Full telemetry available on ersky9x and OpenTX. This is still a WIP.
|
Full telemetry available on OpenTX 2.3.2+, still in progress for erskyTx.
|
||||||
|
|
||||||
**The TX must be close to the RX for the bind negotiation to complete successfully**
|
**The TX must be close to the RX for the bind negotiation to complete successfully**
|
||||||
|
|
||||||
### Sub_protocol OPT_HUB - *1*
|
### Sub_protocol OPT_HUB - *1*
|
||||||
OPTIMA RXs
|
OPTIMA RXs
|
||||||
|
|
||||||
Basic telemetry using FrSky Hub on er9x, ersky9x, OpenTX and any radio with FrSky telemetry support with RX voltage, VOLT2 voltage, TX RSSI and TX LQI.
|
Basic telemetry using FrSky Hub on er9x, erskyTX, OpenTX and any radio with FrSky telemetry support with RX voltage, VOLT2 voltage, TX RSSI and TX LQI.
|
||||||
|
|
||||||
**The TX must be close to the RX for the bind negotiation to complete successfully**
|
**The TX must be close to the RX for the bind negotiation to complete successfully**
|
||||||
|
|
||||||
### Sub_protocol MINIMA - *2*
|
### Sub_protocol MINIMA - *2*
|
||||||
MINIMA, MICRO and RED receivers
|
MINIMA, MICRO and RED receivers
|
||||||
|
|
||||||
|
## HoTT - *57*
|
||||||
|
Models: Graupner HoTT receivers (tested on GR-12L and GR-16L).
|
||||||
|
|
||||||
|
Extended limits and failsafe supported
|
||||||
|
|
||||||
|
**Failsafe MUST be configured once with the desired channel values (hold or position) while the RX is up (wait 10+sec for the RX to learn the config) and then failsafe MUST be set to RX/Receiver otherwise the servos will jitter!!!**
|
||||||
|
|
||||||
|
**The RX features must be configured first on a Graupner radio before binding it with Multi (RX config not implemented).**
|
||||||
|
|
||||||
|
Option for this protocol corresponds to fine frequency tuning. This value is different for each Module and **must** be accurate otherwise the link will not be stable.
|
||||||
|
Check the [Frequency Tuning page](/docs/Frequency_Tuning.md) to determine it.
|
||||||
|
|
||||||
|
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
|
||||||
|
---|---|---|---|---|---|---|---|---|----|----|----
|
||||||
|
CH1|CH2|CH3|CH4|CH5|CH6|CH7|CH8|CH9|CH10|CH11|CH12
|
||||||
|
|
||||||
|
Basic telemetry is available on OpenTX 2.3.2+ with RX voltage, Rx temperature, RX RSSI, RX LQI, TX RSSI and TX LQI.
|
||||||
|
|
||||||
## SFHSS - *21*
|
## SFHSS - *21*
|
||||||
Models: Futaba RXs and XK models.
|
Models: Futaba RXs and XK models.
|
||||||
|
|
||||||
@ -562,9 +581,9 @@ DSMX, Resolution 2048, refresh rate 11ms
|
|||||||
### Sub_protocol AUTO - *4*
|
### Sub_protocol AUTO - *4*
|
||||||
The "AUTO" feature enables the TX to automatically choose what are the best settings for your DSM RX and update your model protocol settings accordingly.
|
The "AUTO" feature enables the TX to automatically choose what are the best settings for your DSM RX and update your model protocol settings accordingly.
|
||||||
|
|
||||||
The current radio firmware which are able to use the "AUTO" feature are ersky9x (9XR Pro, 9Xtreme, Taranis, ...), er9x for M128(9XR)&M2561 and OpenTX (mostly Taranis).
|
The current radio firmware which are able to use the "AUTO" feature are erskyTX (9XR Pro, 9Xtreme, Taranis, ...), er9x for M128(9XR)&M2561 and OpenTX (mostly Taranis).
|
||||||
For these firmwares, you must have a telemetry enabled TX and you have to make sure you set the Telemetry "Usr proto" to "DSMx".
|
For these firmwares, you must have a telemetry enabled TX and you have to make sure you set the Telemetry "Usr proto" to "DSMx".
|
||||||
Also on er9x you will need to be sure to match the polarity of the telemetry serial (normal or inverted by bitbashing), while on ersky9x you can set "Invert COM1" accordinlgy.
|
Also on er9x you will need to be sure to match the polarity of the telemetry serial (normal or inverted by bitbashing), while on erskyTX you can set "Invert COM1" accordinlgy.
|
||||||
|
|
||||||
## J6Pro - *22*
|
## J6Pro - *22*
|
||||||
|
|
||||||
|
@ -8,16 +8,17 @@ The protocols which require frequency tuning are:
|
|||||||
* **S-FHSS** (e.g. Futaba S-FHSS receivers)
|
* **S-FHSS** (e.g. Futaba S-FHSS receivers)
|
||||||
* **Corona** (e.g. Corona V1 FSS, Corona V2 DSSS CR8D/CR6D/CR4D and FlyDream IS-4R/IS-4R0 receivers)
|
* **Corona** (e.g. Corona V1 FSS, Corona V2 DSSS CR8D/CR6D/CR4D and FlyDream IS-4R/IS-4R0 receivers)
|
||||||
* **Hitec** (e.g. Optima, Minima, Micro and RED receivers)
|
* **Hitec** (e.g. Optima, Minima, Micro and RED receivers)
|
||||||
|
* **HoTT** (e.g. Graupner receivers)
|
||||||
|
|
||||||
There is a [video](#video) at the end of this page which gives an example of the tuning process.
|
There is a [video](#video) at the end of this page which gives an example of the tuning process.
|
||||||
|
|
||||||
## More information
|
## More information
|
||||||
Original FrSky, Futaba, Corona and Hitec receivers have been frequency-tuned by the manufacturer at the factory. Because of variations in the oscillator crystals used in multiprotocol modules it is necessary to fine-tune the module to match the manufacturer frequencies.
|
Original FrSky, Futaba, Corona Hitec and HoTT receivers have been frequency-tuned by the manufacturer at the factory. Because of variations in the oscillator crystals used in multiprotocol modules it is necessary to fine-tune the module to match the manufacturer frequencies.
|
||||||
|
|
||||||
'Compatible' receivers suffer the same variation in crystal oscillators as multiprotocol modules, but have to be compatible with genuine (manufacturer-tuned) transmitters so they will typically have auto-tuning built in, and will self-tune to the radio's frequency when they are bound.
|
'Compatible' receivers suffer the same variation in crystal oscillators as multiprotocol modules, but have to be compatible with genuine (manufacturer-tuned) transmitters so they will typically have auto-tuning built in, and will self-tune to the radio's frequency when they are bound.
|
||||||
|
|
||||||
## Fine-tuning procedure
|
## Fine-tuning procedure
|
||||||
**Note:** For best results, the fine-tuning procedure should be carried out with a genuine FrSky/Futaba/Corona/Hitec receiver.
|
**Note:** For best results, the fine-tuning procedure should be carried out with a genuine FrSky/Futaba/Corona/Hitec/HoTT receiver.
|
||||||
|
|
||||||
The procedure can be performed in serial or PPM mode, but is easier with in serial mode where the effect of the change can be seen in real-time.
|
The procedure can be performed in serial or PPM mode, but is easier with in serial mode where the effect of the change can be seen in real-time.
|
||||||
|
|
||||||
@ -49,7 +50,7 @@ Connection is lost at -73 and +35; the median is -19:
|
|||||||
### Finally
|
### Finally
|
||||||
Once the **Freq** value is known it should be applied to all other models which use this protocol and, if they were previously bound, the receivers must be re-bound.
|
Once the **Freq** value is known it should be applied to all other models which use this protocol and, if they were previously bound, the receivers must be re-bound.
|
||||||
|
|
||||||
For convenience this can be done in the `_Config.h` (or `_MyConfig.h`) configuration file.
|
For convenience this can be applied once for all per protocol using the FORCE commands described below in `_Config.h` (or `_MyConfig.h`) configuration file.
|
||||||
|
|
||||||
#### Forced tuning values
|
#### Forced tuning values
|
||||||
Once known-good tuning values have been determined, they can be stored in the configuration file to be automatically applied to all models which use the given protocol.
|
Once known-good tuning values have been determined, they can be stored in the configuration file to be automatically applied to all models which use the given protocol.
|
||||||
@ -73,6 +74,7 @@ These settings can also be used to force different tuning values for different m
|
|||||||
//#define FORCE_SFHSS_TUNING 0
|
//#define FORCE_SFHSS_TUNING 0
|
||||||
//#define FORCE_CORONA_TUNING 0
|
//#define FORCE_CORONA_TUNING 0
|
||||||
//#define FORCE_HITEC_TUNING 0
|
//#define FORCE_HITEC_TUNING 0
|
||||||
|
//#define FORCE_HOTT_TUNING 0
|
||||||
```
|
```
|
||||||
|
|
||||||
## Video
|
## Video
|
||||||
|
Loading…
x
Reference in New Issue
Block a user