mirror of https://github.com/ArduPilot/ardupilot
AP_SmartAudio: Add pull down VTX option
This commit is contained in:
parent
49536ceecb
commit
9056cd35ea
|
@ -247,6 +247,8 @@ void AP_SmartAudio::update_vtx_params()
|
||||||
*/
|
*/
|
||||||
void AP_SmartAudio::send_request(const Frame& requestFrame, uint8_t size)
|
void AP_SmartAudio::send_request(const Frame& requestFrame, uint8_t size)
|
||||||
{
|
{
|
||||||
|
AP_VideoTX &vtx = AP::vtx();
|
||||||
|
|
||||||
if (size <= 0 || _port == nullptr) {
|
if (size <= 0 || _port == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -254,6 +256,9 @@ void AP_SmartAudio::send_request(const Frame& requestFrame, uint8_t size)
|
||||||
const uint8_t *request = reinterpret_cast<const uint8_t*>(&requestFrame);
|
const uint8_t *request = reinterpret_cast<const uint8_t*>(&requestFrame);
|
||||||
|
|
||||||
// write request
|
// write request
|
||||||
|
if (vtx.has_option(AP_VideoTX::VideoOptions::VTX_PULLDOWN)) {
|
||||||
|
_port->write((uint8_t)0x00);
|
||||||
|
}
|
||||||
_port->write(request, size);
|
_port->write(request, size);
|
||||||
_port->flush();
|
_port->flush();
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue