mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RCProtocol: move configure_vtx method to AP_RCProtocol_Backend
this is called as a static method from DSM to SRXL2 which isn't good.
This commit is contained in:
parent
1d8a5ac92d
commit
ff441de8ec
@ -91,7 +91,11 @@ public:
|
||||
return true;
|
||||
}
|
||||
|
||||
// called by static methods to confiig video transmitters:
|
||||
static void configure_vtx(uint8_t band, uint8_t channel, uint8_t power, uint8_t pitmode);
|
||||
|
||||
protected:
|
||||
|
||||
struct Channels11Bit_8Chan {
|
||||
#if __BYTE_ORDER != __LITTLE_ENDIAN
|
||||
#error "Only supported on little-endian architectures"
|
||||
|
@ -239,7 +239,7 @@ bool AP_RCProtocol_DSM::dsm_decode(uint32_t frame_time_ms, const uint8_t dsm_fra
|
||||
// Handle VTX control frame.
|
||||
#if AP_VIDEOTX_ENABLED
|
||||
if (haveVtxControl) {
|
||||
AP_RCProtocol_SRXL2::configure_vtx(
|
||||
configure_vtx(
|
||||
(vtxControl & SPEKTRUM_VTX_BAND_MASK) >> SPEKTRUM_VTX_BAND_SHIFT,
|
||||
(vtxControl & SPEKTRUM_VTX_CHANNEL_MASK) >> SPEKTRUM_VTX_CHANNEL_SHIFT,
|
||||
(vtxControl & SPEKTRUM_VTX_POWER_MASK) >> SPEKTRUM_VTX_POWER_SHIFT,
|
||||
|
@ -301,7 +301,7 @@ void AP_RCProtocol_SRXL2::send_on_uart(uint8_t* pBuffer, uint8_t length)
|
||||
|
||||
#if AP_VIDEOTX_ENABLED
|
||||
// configure the video transmitter, the input values are Spektrum-oriented
|
||||
void AP_RCProtocol_SRXL2::configure_vtx(uint8_t band, uint8_t channel, uint8_t power, uint8_t pitmode)
|
||||
void AP_RCProtocol_Backend::configure_vtx(uint8_t band, uint8_t channel, uint8_t power, uint8_t pitmode)
|
||||
{
|
||||
AP_VideoTX& vtx = AP::vtx();
|
||||
// VTX Band (0 = Fatshark, 1 = Raceband, 2 = E, 3 = B, 4 = A)
|
||||
@ -458,6 +458,6 @@ bool srxlOnBind(SrxlFullID device, SrxlBindData info)
|
||||
void srxlOnVtx(SrxlVtxData* pVtxData)
|
||||
{
|
||||
#if AP_VIDEOTX_ENABLED
|
||||
AP_RCProtocol_SRXL2::configure_vtx(pVtxData->band, pVtxData->channel, pVtxData->power, pVtxData->pit);
|
||||
AP_RCProtocol_Backend::configure_vtx(pVtxData->band, pVtxData->channel, pVtxData->power, pVtxData->pit);
|
||||
#endif
|
||||
}
|
||||
|
@ -42,7 +42,6 @@ public:
|
||||
static void send_on_uart(uint8_t* pBuffer, uint8_t length);
|
||||
static void change_baud_rate(uint32_t baudrate);
|
||||
// configure the VTX from Spektrum data
|
||||
static void configure_vtx(uint8_t band, uint8_t channel, uint8_t power, uint8_t pitmode);
|
||||
|
||||
private:
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user