mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_RCProtocol: move code from SRXL2.cpp into Backend.cpp
NFC, just moving from one cpp to another
This commit is contained in:
parent
ff441de8ec
commit
75a0c592ab
@ -23,9 +23,7 @@
|
|||||||
#include "AP_RCProtocol_SBUS.h"
|
#include "AP_RCProtocol_SBUS.h"
|
||||||
#include "AP_RCProtocol_SUMD.h"
|
#include "AP_RCProtocol_SUMD.h"
|
||||||
#include "AP_RCProtocol_SRXL.h"
|
#include "AP_RCProtocol_SRXL.h"
|
||||||
#ifndef IOMCU_FW
|
|
||||||
#include "AP_RCProtocol_SRXL2.h"
|
#include "AP_RCProtocol_SRXL2.h"
|
||||||
#endif
|
|
||||||
#include "AP_RCProtocol_CRSF.h"
|
#include "AP_RCProtocol_CRSF.h"
|
||||||
#include "AP_RCProtocol_ST24.h"
|
#include "AP_RCProtocol_ST24.h"
|
||||||
#include "AP_RCProtocol_FPort.h"
|
#include "AP_RCProtocol_FPort.h"
|
||||||
|
@ -20,6 +20,15 @@
|
|||||||
#include <RC_Channel/RC_Channel.h>
|
#include <RC_Channel/RC_Channel.h>
|
||||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
#include <AP_VideoTX/AP_VideoTX_config.h>
|
||||||
|
|
||||||
|
// for video TX configuration:
|
||||||
|
#if AP_VIDEOTX_ENABLED
|
||||||
|
#include <AP_VideoTX/AP_VideoTX.h>
|
||||||
|
#include "spm_srxl.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
AP_RCProtocol_Backend::AP_RCProtocol_Backend(AP_RCProtocol &_frontend) :
|
AP_RCProtocol_Backend::AP_RCProtocol_Backend(AP_RCProtocol &_frontend) :
|
||||||
frontend(_frontend),
|
frontend(_frontend),
|
||||||
@ -105,6 +114,61 @@ void AP_RCProtocol_Backend::decode_11bit_channels(const uint8_t* data, uint8_t n
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_VIDEOTX_ENABLED
|
||||||
|
// configure the video transmitter, the input values are Spektrum-oriented
|
||||||
|
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)
|
||||||
|
// map to TBS band A, B, E, Race, Airwave, LoRace
|
||||||
|
switch (band) {
|
||||||
|
case VTX_BAND_FATSHARK:
|
||||||
|
vtx.set_configured_band(AP_VideoTX::VideoBand::FATSHARK);
|
||||||
|
break;
|
||||||
|
case VTX_BAND_RACEBAND:
|
||||||
|
vtx.set_configured_band(AP_VideoTX::VideoBand::RACEBAND);
|
||||||
|
break;
|
||||||
|
case VTX_BAND_E_BAND:
|
||||||
|
vtx.set_configured_band(AP_VideoTX::VideoBand::BAND_E);
|
||||||
|
break;
|
||||||
|
case VTX_BAND_B_BAND:
|
||||||
|
vtx.set_configured_band(AP_VideoTX::VideoBand::BAND_B);
|
||||||
|
break;
|
||||||
|
case VTX_BAND_A_BAND:
|
||||||
|
vtx.set_configured_band(AP_VideoTX::VideoBand::BAND_A);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
// VTX Channel (0-7)
|
||||||
|
vtx.set_configured_channel(channel);
|
||||||
|
if (pitmode) {
|
||||||
|
vtx.set_configured_options(vtx.get_options() | uint8_t(AP_VideoTX::VideoOptions::VTX_PITMODE));
|
||||||
|
} else {
|
||||||
|
vtx.set_configured_options(vtx.get_options() & ~uint8_t(AP_VideoTX::VideoOptions::VTX_PITMODE));
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (power) {
|
||||||
|
case VTX_POWER_1MW_14MW:
|
||||||
|
case VTX_POWER_15MW_25MW:
|
||||||
|
vtx.set_configured_power_mw(25);
|
||||||
|
break;
|
||||||
|
case VTX_POWER_26MW_99MW:
|
||||||
|
case VTX_POWER_100MW_299MW:
|
||||||
|
vtx.set_configured_power_mw(100);
|
||||||
|
break;
|
||||||
|
case VTX_POWER_300MW_600MW:
|
||||||
|
vtx.set_configured_power_mw(400);
|
||||||
|
break;
|
||||||
|
case VTX_POWER_601_PLUS:
|
||||||
|
vtx.set_configured_power_mw(800);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif // AP_VIDEOTX_ENABLED
|
||||||
|
|
||||||
/*
|
/*
|
||||||
optionally log RC input data
|
optionally log RC input data
|
||||||
*/
|
*/
|
||||||
|
@ -19,6 +19,7 @@
|
|||||||
|
|
||||||
#include "AP_RCProtocol.h"
|
#include "AP_RCProtocol.h"
|
||||||
#include <AP_HAL/utility/sparse-endian.h>
|
#include <AP_HAL/utility/sparse-endian.h>
|
||||||
|
#include <AP_VideoTX/AP_VideoTX_config.h>
|
||||||
|
|
||||||
class AP_RCProtocol_Backend {
|
class AP_RCProtocol_Backend {
|
||||||
friend class AP_RCProtcol;
|
friend class AP_RCProtcol;
|
||||||
@ -91,8 +92,10 @@ public:
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_VIDEOTX_ENABLED
|
||||||
// called by static methods to confiig video transmitters:
|
// called by static methods to confiig video transmitters:
|
||||||
static void configure_vtx(uint8_t band, uint8_t channel, uint8_t power, uint8_t pitmode);
|
static void configure_vtx(uint8_t band, uint8_t channel, uint8_t power, uint8_t pitmode);
|
||||||
|
#endif
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
@ -19,10 +19,6 @@
|
|||||||
*/
|
*/
|
||||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
#include "AP_RCProtocol_DSM.h"
|
#include "AP_RCProtocol_DSM.h"
|
||||||
#if !APM_BUILD_TYPE(APM_BUILD_iofirmware)
|
|
||||||
#include "AP_RCProtocol_SRXL2.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include <AP_VideoTX/AP_VideoTX_config.h>
|
#include <AP_VideoTX/AP_VideoTX_config.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
@ -299,61 +299,6 @@ 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_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)
|
|
||||||
// map to TBS band A, B, E, Race, Airwave, LoRace
|
|
||||||
switch (band) {
|
|
||||||
case VTX_BAND_FATSHARK:
|
|
||||||
vtx.set_configured_band(AP_VideoTX::VideoBand::FATSHARK);
|
|
||||||
break;
|
|
||||||
case VTX_BAND_RACEBAND:
|
|
||||||
vtx.set_configured_band(AP_VideoTX::VideoBand::RACEBAND);
|
|
||||||
break;
|
|
||||||
case VTX_BAND_E_BAND:
|
|
||||||
vtx.set_configured_band(AP_VideoTX::VideoBand::BAND_E);
|
|
||||||
break;
|
|
||||||
case VTX_BAND_B_BAND:
|
|
||||||
vtx.set_configured_band(AP_VideoTX::VideoBand::BAND_B);
|
|
||||||
break;
|
|
||||||
case VTX_BAND_A_BAND:
|
|
||||||
vtx.set_configured_band(AP_VideoTX::VideoBand::BAND_A);
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
// VTX Channel (0-7)
|
|
||||||
vtx.set_configured_channel(channel);
|
|
||||||
if (pitmode) {
|
|
||||||
vtx.set_configured_options(vtx.get_options() | uint8_t(AP_VideoTX::VideoOptions::VTX_PITMODE));
|
|
||||||
} else {
|
|
||||||
vtx.set_configured_options(vtx.get_options() & ~uint8_t(AP_VideoTX::VideoOptions::VTX_PITMODE));
|
|
||||||
}
|
|
||||||
|
|
||||||
switch (power) {
|
|
||||||
case VTX_POWER_1MW_14MW:
|
|
||||||
case VTX_POWER_15MW_25MW:
|
|
||||||
vtx.set_configured_power_mw(25);
|
|
||||||
break;
|
|
||||||
case VTX_POWER_26MW_99MW:
|
|
||||||
case VTX_POWER_100MW_299MW:
|
|
||||||
vtx.set_configured_power_mw(100);
|
|
||||||
break;
|
|
||||||
case VTX_POWER_300MW_600MW:
|
|
||||||
vtx.set_configured_power_mw(400);
|
|
||||||
break;
|
|
||||||
case VTX_POWER_601_PLUS:
|
|
||||||
vtx.set_configured_power_mw(800);
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif // AP_VIDEOTX_ENABLED
|
|
||||||
|
|
||||||
// send data to the uart
|
// send data to the uart
|
||||||
void AP_RCProtocol_SRXL2::_send_on_uart(uint8_t* pBuffer, uint8_t length)
|
void AP_RCProtocol_SRXL2::_send_on_uart(uint8_t* pBuffer, uint8_t length)
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user