mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: add and use AP_VIDEOTX_ENABLED
This commit is contained in:
parent
2656bcf5fa
commit
c139f7c730
|
@ -23,6 +23,8 @@
|
|||
#include "AP_RCProtocol_SRXL2.h"
|
||||
#endif
|
||||
|
||||
#include <AP_VideoTX/AP_VideoTX_config.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// #define DSM_DEBUG
|
||||
|
@ -235,15 +237,15 @@ 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) {
|
||||
#if !APM_BUILD_TYPE(APM_BUILD_iofirmware)
|
||||
AP_RCProtocol_SRXL2::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,
|
||||
(vtxControl & SPEKTRUM_VTX_PIT_MODE_MASK) >> SPEKTRUM_VTX_PIT_MODE_SHIFT);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
* The encoding of the first two bytes is uncertain, so we're
|
||||
|
|
|
@ -299,6 +299,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)
|
||||
{
|
||||
|
@ -351,6 +352,7 @@ void AP_RCProtocol_SRXL2::configure_vtx(uint8_t band, uint8_t channel, uint8_t p
|
|||
break;
|
||||
}
|
||||
}
|
||||
#endif // AP_VIDEOTX_ENABLED
|
||||
|
||||
// send data to the uart
|
||||
void AP_RCProtocol_SRXL2::_send_on_uart(uint8_t* pBuffer, uint8_t length)
|
||||
|
@ -455,5 +457,7 @@ bool srxlOnBind(SrxlFullID device, SrxlBindData info)
|
|||
// User-provided callback routine to handle reception of a VTX control packet.
|
||||
void srxlOnVtx(SrxlVtxData* pVtxData)
|
||||
{
|
||||
#if AP_VIDEOTX_ENABLED
|
||||
AP_RCProtocol_SRXL2::configure_vtx(pVtxData->band, pVtxData->channel, pVtxData->power, pVtxData->pit);
|
||||
#endif
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue