mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-19 22:35:19 +03:00
Merge pull request #10166 from iNavFlight/mmosca-crsf-bind
bind_rx cli command now supports CRSF based receivers
This commit is contained in:
commit
addfa59d7a
5 changed files with 63 additions and 1 deletions
|
@ -104,6 +104,7 @@ bool cliMode = false;
|
|||
#include "rx/rx.h"
|
||||
#include "rx/spektrum.h"
|
||||
#include "rx/srxl2.h"
|
||||
#include "rx/crsf.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
|
@ -3224,6 +3225,12 @@ void cliRxBind(char *cmdline){
|
|||
srxl2Bind();
|
||||
cliPrint("Binding SRXL2 receiver...");
|
||||
break;
|
||||
#endif
|
||||
#if defined(USE_SERIALRX_CRSF)
|
||||
case SERIALRX_CRSF:
|
||||
crsfBind();
|
||||
cliPrint("Binding CRSF receiver...");
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
|
@ -110,6 +110,8 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
#include "rx/srxl2.h"
|
||||
#include "rx/crsf.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
|
@ -1030,6 +1032,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
case MSP_MIXER:
|
||||
sbufWriteU8(dst, 3); // mixerMode no longer supported, send 3 (QuadX) as fallback
|
||||
break;
|
||||
|
||||
|
||||
case MSP_RX_CONFIG:
|
||||
sbufWriteU8(dst, rxConfig()->serialrx_provider);
|
||||
|
@ -2887,7 +2890,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
|
||||
case MSP_SET_FAILSAFE_CONFIG:
|
||||
if (dataSize == 20) {
|
||||
failsafeConfigMutable()->failsafe_delay = sbufReadU8(src);
|
||||
|
@ -3352,6 +3355,26 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
|
||||
break;
|
||||
|
||||
case MSP2_BETAFLIGHT_BIND:
|
||||
if (rxConfig()->receiverType == RX_TYPE_SERIAL) {
|
||||
switch (rxConfig()->serialrx_provider) {
|
||||
default:
|
||||
return MSP_RESULT_ERROR;
|
||||
#if defined(USE_SERIALRX_SRXL2)
|
||||
case SERIALRX_SRXL2:
|
||||
srxl2Bind();
|
||||
break;
|
||||
#endif
|
||||
#if defined(USE_SERIALRX_CRSF)
|
||||
case SERIALRX_CRSF:
|
||||
crsfBind();
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
return MSP_RESULT_ERROR;
|
||||
|
|
|
@ -33,3 +33,4 @@
|
|||
#define MSP2_COMMON_SET_RADAR_POS 0x100B //SET radar position information
|
||||
#define MSP2_COMMON_SET_RADAR_ITD 0x100C //SET radar information to display
|
||||
|
||||
#define MSP2_BETAFLIGHT_BIND 0x3000
|
||||
|
|
|
@ -331,4 +331,24 @@ bool crsfRxIsActive(void)
|
|||
{
|
||||
return serialPort != NULL;
|
||||
}
|
||||
|
||||
|
||||
void crsfBind(void)
|
||||
{
|
||||
if (serialPort != NULL) {
|
||||
uint8_t bindFrame[] = {
|
||||
CRSF_SYNC_BYTE,
|
||||
0x07, // frame length
|
||||
CRSF_FRAMETYPE_COMMAND,
|
||||
CRSF_ADDRESS_CRSF_RECEIVER,
|
||||
CRSF_ADDRESS_FLIGHT_CONTROLLER,
|
||||
CRSF_COMMAND_SUBCMD_RX,
|
||||
CRSF_COMMAND_SUBCMD_RX_BIND,
|
||||
0x9E, // Command CRC8
|
||||
0xE8, // Packet CRC8
|
||||
};
|
||||
serialWriteBuf(serialPort, bindFrame, 9);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -104,6 +104,15 @@ typedef enum {
|
|||
CRSF_FRAMETYPE_DISPLAYPORT_CMD = 0x7D, // displayport control command
|
||||
} crsfFrameType_e;
|
||||
|
||||
enum {
|
||||
CRSF_COMMAND_SUBCMD_RX = 0x10, // receiver command
|
||||
CRSF_COMMAND_SUBCMD_GENERAL = 0x0A, // general command
|
||||
};
|
||||
|
||||
enum {
|
||||
CRSF_COMMAND_SUBCMD_RX_BIND = 0x01, // bind command
|
||||
};
|
||||
|
||||
typedef struct crsfFrameDef_s {
|
||||
uint8_t deviceAddress;
|
||||
uint8_t frameLength;
|
||||
|
@ -124,3 +133,5 @@ struct rxConfig_s;
|
|||
struct rxRuntimeConfig_s;
|
||||
bool crsfRxInit(const struct rxConfig_s *initialRxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
bool crsfRxIsActive(void);
|
||||
|
||||
void crsfBind(void);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue