mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: bootstrap Ghost to correct baudrate
This commit is contained in:
parent
0da6989c8e
commit
0df36a8d81
|
@ -301,16 +301,12 @@ static const AP_RCProtocol::SerialConfig serial_configs[] {
|
||||||
// FastSBUS:
|
// FastSBUS:
|
||||||
{ 200000, 2, 2, true },
|
{ 200000, 2, 2, true },
|
||||||
#endif
|
#endif
|
||||||
#if AP_RCPROTOCOL_CRSF_ENABLED
|
#if AP_RCPROTOCOL_CRSF_ENABLED || AP_RCPROTOCOL_GHST_ENABLED
|
||||||
// CrossFire:
|
// CrossFire:
|
||||||
{ 416666, 0, 1, false },
|
{ 416666, 0, 1, false },
|
||||||
// CRSFv3 can negotiate higher rates which are sticky on soft reboot
|
// CRSFv3 can negotiate higher rates which are sticky on soft reboot
|
||||||
{ 2000000, 0, 1, false },
|
{ 2000000, 0, 1, false },
|
||||||
#endif
|
#endif
|
||||||
#if AP_RCPROTOCOL_GHST_ENABLED
|
|
||||||
// Ghost:
|
|
||||||
{ 420000, 0, 1, false },
|
|
||||||
#endif
|
|
||||||
};
|
};
|
||||||
|
|
||||||
static_assert(ARRAY_SIZE(serial_configs) > 1, "must have at least one serial config");
|
static_assert(ARRAY_SIZE(serial_configs) > 1, "must have at least one serial config");
|
||||||
|
|
|
@ -21,6 +21,8 @@
|
||||||
|
|
||||||
#if AP_RCPROTOCOL_GHST_ENABLED
|
#if AP_RCPROTOCOL_GHST_ENABLED
|
||||||
|
|
||||||
|
#define CRSF_BAUDRATE 416666U
|
||||||
|
|
||||||
#include "AP_RCProtocol.h"
|
#include "AP_RCProtocol.h"
|
||||||
#include "AP_RCProtocol_GHST.h"
|
#include "AP_RCProtocol_GHST.h"
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
@ -413,12 +415,29 @@ bool AP_RCProtocol_GHST::is_telemetry_supported() const
|
||||||
void AP_RCProtocol_GHST::process_byte(uint8_t byte, uint32_t baudrate)
|
void AP_RCProtocol_GHST::process_byte(uint8_t byte, uint32_t baudrate)
|
||||||
{
|
{
|
||||||
// reject RC data if we have been configured for standalone mode
|
// reject RC data if we have been configured for standalone mode
|
||||||
if (baudrate != GHST_BAUDRATE) {
|
if (baudrate != CRSF_BAUDRATE && baudrate != GHST_BAUDRATE) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
_process_byte(AP_HAL::micros(), byte);
|
_process_byte(AP_HAL::micros(), byte);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// change the bootstrap baud rate to ELRS standard if configured
|
||||||
|
void AP_RCProtocol_GHST::process_handshake(uint32_t baudrate)
|
||||||
|
{
|
||||||
|
AP_HAL::UARTDriver *uart = get_current_UART();
|
||||||
|
|
||||||
|
// only change the baudrate if we are bootstrapping CRSF
|
||||||
|
if (uart == nullptr
|
||||||
|
|| baudrate != CRSF_BAUDRATE
|
||||||
|
|| baudrate == GHST_BAUDRATE
|
||||||
|
|| uart->get_baud_rate() == GHST_BAUDRATE
|
||||||
|
|| (get_rc_protocols_mask() & ((1U<<(uint8_t(AP_RCProtocol::GHST)+1))+1)) == 0) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
uart->begin(GHST_BAUDRATE);
|
||||||
|
}
|
||||||
|
|
||||||
//returns uplink link quality on 0-255 scale
|
//returns uplink link quality on 0-255 scale
|
||||||
int16_t AP_RCProtocol_GHST::derive_scaled_lq_value(uint8_t uplink_lq)
|
int16_t AP_RCProtocol_GHST::derive_scaled_lq_value(uint8_t uplink_lq)
|
||||||
{
|
{
|
||||||
|
|
|
@ -36,6 +36,7 @@ public:
|
||||||
AP_RCProtocol_GHST(AP_RCProtocol &_frontend);
|
AP_RCProtocol_GHST(AP_RCProtocol &_frontend);
|
||||||
virtual ~AP_RCProtocol_GHST();
|
virtual ~AP_RCProtocol_GHST();
|
||||||
void process_byte(uint8_t byte, uint32_t baudrate) override;
|
void process_byte(uint8_t byte, uint32_t baudrate) override;
|
||||||
|
void process_handshake(uint32_t baudrate) override;
|
||||||
void update(void) override;
|
void update(void) override;
|
||||||
|
|
||||||
// is the receiver active, used to detect power loss and baudrate changes
|
// is the receiver active, used to detect power loss and baudrate changes
|
||||||
|
|
Loading…
Reference in New Issue