mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 00:35:34 +03:00
Generic RCDevice support first submission
This commit is contained in:
parent
b3b7fece42
commit
51ab2adc74
19 changed files with 2430 additions and 711 deletions
3
Makefile
3
Makefile
|
@ -622,7 +622,8 @@ COMMON_SRC = \
|
||||||
io/serial_4way_avrootloader.c \
|
io/serial_4way_avrootloader.c \
|
||||||
io/serial_4way_stk500v2.c \
|
io/serial_4way_stk500v2.c \
|
||||||
io/statusindicator.c \
|
io/statusindicator.c \
|
||||||
io/rcsplit.c \
|
io/rcdevice.c \
|
||||||
|
io/rcdevice_cam.c \
|
||||||
msp/msp_serial.c \
|
msp/msp_serial.c \
|
||||||
rx/ibus.c \
|
rx/ibus.c \
|
||||||
rx/jetiexbus.c \
|
rx/jetiexbus.c \
|
||||||
|
|
|
@ -64,6 +64,7 @@
|
||||||
|
|
||||||
// For VISIBLE*
|
// For VISIBLE*
|
||||||
#include "io/osd.h"
|
#include "io/osd.h"
|
||||||
|
#include "io/rcdevice_cam.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
|
@ -1039,6 +1040,12 @@ uint16_t cmsHandleKeyWithRepeat(displayPort_t *pDisplay, uint8_t key, int repeat
|
||||||
|
|
||||||
void cmsUpdate(uint32_t currentTimeUs)
|
void cmsUpdate(uint32_t currentTimeUs)
|
||||||
{
|
{
|
||||||
|
#ifdef USE_RCDEVICE
|
||||||
|
if(rcdeviceInMenu) {
|
||||||
|
return ;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
static int16_t rcDelayMs = BUTTON_TIME;
|
static int16_t rcDelayMs = BUTTON_TIME;
|
||||||
static int holdCount = 1;
|
static int holdCount = 1;
|
||||||
static int repeatCount = 1;
|
static int repeatCount = 1;
|
||||||
|
|
|
@ -101,7 +101,7 @@
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
#include "io/pwmdriver_i2c.h"
|
#include "io/pwmdriver_i2c.h"
|
||||||
#include "io/osd.h"
|
#include "io/osd.h"
|
||||||
#include "io/rcsplit.h"
|
#include "io/rcdevice_cam.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/displayport_msp.h"
|
#include "io/displayport_msp.h"
|
||||||
#include "io/vtx_control.h"
|
#include "io/vtx_control.h"
|
||||||
|
@ -674,16 +674,15 @@ void init(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_RCDEVICE
|
||||||
|
rcdeviceInit();
|
||||||
|
#endif // USE_RCDEVICE
|
||||||
|
|
||||||
// Latch active features AGAIN since some may be modified by init().
|
// Latch active features AGAIN since some may be modified by init().
|
||||||
latchActiveFeatures();
|
latchActiveFeatures();
|
||||||
motorControlEnable = true;
|
motorControlEnable = true;
|
||||||
|
|
||||||
fcTasksInit();
|
fcTasksInit();
|
||||||
|
|
||||||
#ifdef USE_RCSPLIT
|
|
||||||
rcSplitInit();
|
|
||||||
#endif // USE_RCSPLIT
|
|
||||||
|
|
||||||
addBootlogEvent2(BOOT_EVENT_SYSTEM_READY, BOOT_EVENT_FLAGS_NONE);
|
addBootlogEvent2(BOOT_EVENT_SYSTEM_READY, BOOT_EVENT_FLAGS_NONE);
|
||||||
systemState |= SYSTEM_STATE_READY;
|
systemState |= SYSTEM_STATE_READY;
|
||||||
}
|
}
|
||||||
|
|
|
@ -227,7 +227,7 @@ void initActiveBoxIds(void)
|
||||||
activeBoxIds[activeBoxIdCount++] = BOXKILLSWITCH;
|
activeBoxIds[activeBoxIdCount++] = BOXKILLSWITCH;
|
||||||
activeBoxIds[activeBoxIdCount++] = BOXFAILSAFE;
|
activeBoxIds[activeBoxIdCount++] = BOXFAILSAFE;
|
||||||
|
|
||||||
#ifdef USE_RCSPLIT
|
#ifdef USE_RCDEVICE
|
||||||
activeBoxIds[activeBoxIdCount++] = BOXCAMERA1;
|
activeBoxIds[activeBoxIdCount++] = BOXCAMERA1;
|
||||||
activeBoxIds[activeBoxIdCount++] = BOXCAMERA2;
|
activeBoxIds[activeBoxIdCount++] = BOXCAMERA2;
|
||||||
activeBoxIds[activeBoxIdCount++] = BOXCAMERA3;
|
activeBoxIds[activeBoxIdCount++] = BOXCAMERA3;
|
||||||
|
|
|
@ -55,7 +55,7 @@
|
||||||
#include "io/osd.h"
|
#include "io/osd.h"
|
||||||
#include "io/pwmdriver_i2c.h"
|
#include "io/pwmdriver_i2c.h"
|
||||||
#include "io/serial.h"
|
#include "io/serial.h"
|
||||||
#include "io/rcsplit.h"
|
#include "io/rcdevice_cam.h"
|
||||||
|
|
||||||
#include "msp/msp_serial.h"
|
#include "msp/msp_serial.h"
|
||||||
|
|
||||||
|
@ -374,6 +374,9 @@ void fcTasksInit(void)
|
||||||
#ifdef USE_UAV_INTERCONNECT
|
#ifdef USE_UAV_INTERCONNECT
|
||||||
setTaskEnabled(TASK_UAV_INTERCONNECT, uavInterconnectBusIsInitialized());
|
setTaskEnabled(TASK_UAV_INTERCONNECT, uavInterconnectBusIsInitialized());
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef USE_RCDEVICE
|
||||||
|
setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled());
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
cfTask_t cfTasks[TASK_COUNT] = {
|
cfTask_t cfTasks[TASK_COUNT] = {
|
||||||
|
@ -585,10 +588,10 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_RCSPLIT
|
#ifdef USE_RCDEVICE
|
||||||
[TASK_RCSPLIT] = {
|
[TASK_RCDEVICE] = {
|
||||||
.taskName = "RCSPLIT",
|
.taskName = "RCDEVICE",
|
||||||
.taskFunc = rcSplitProcess,
|
.taskFunc = rcdeviceUpdate,
|
||||||
.desiredPeriod = TASK_PERIOD_HZ(10), // 10 Hz, 100ms
|
.desiredPeriod = TASK_PERIOD_HZ(10), // 10 Hz, 100ms
|
||||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||||
},
|
},
|
||||||
|
|
|
@ -129,6 +129,15 @@ static const uint8_t beep_launchModeBeep[] = {
|
||||||
static const uint8_t beep_hardwareFailure[] = {
|
static const uint8_t beep_hardwareFailure[] = {
|
||||||
10, 10, BEEPER_COMMAND_STOP
|
10, 10, BEEPER_COMMAND_STOP
|
||||||
};
|
};
|
||||||
|
// Cam connection opened
|
||||||
|
static const uint8_t beep_camOpenBeep[] = {
|
||||||
|
5, 15, 10, 15, 20, BEEPER_COMMAND_STOP
|
||||||
|
};
|
||||||
|
// Cam connection close
|
||||||
|
static const uint8_t beep_camCloseBeep[] = {
|
||||||
|
10, 8, 5, BEEPER_COMMAND_STOP
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
// array used for variable # of beeps (reporting GPS sat count, etc)
|
// array used for variable # of beeps (reporting GPS sat count, etc)
|
||||||
static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS + 2];
|
static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS + 2];
|
||||||
|
@ -185,9 +194,11 @@ typedef struct beeperTableEntry_s {
|
||||||
{ BEEPER_ENTRY(BEEPER_SYSTEM_INIT, 17, NULL, "SYSTEM_INIT") },
|
{ BEEPER_ENTRY(BEEPER_SYSTEM_INIT, 17, NULL, "SYSTEM_INIT") },
|
||||||
{ BEEPER_ENTRY(BEEPER_USB, 18, NULL, "ON_USB") },
|
{ BEEPER_ENTRY(BEEPER_USB, 18, NULL, "ON_USB") },
|
||||||
{ BEEPER_ENTRY(BEEPER_LAUNCH_MODE_ENABLED, 19, beep_launchModeBeep, "LAUNCH_MODE") },
|
{ BEEPER_ENTRY(BEEPER_LAUNCH_MODE_ENABLED, 19, beep_launchModeBeep, "LAUNCH_MODE") },
|
||||||
|
{ BEEPER_ENTRY(BEEPER_CAM_CONNECTION_OPEN, 20, beep_camOpenBeep, "CAM_CONNECTION_OPEN") },
|
||||||
|
{ BEEPER_ENTRY(BEEPER_CAM_CONNECTION_CLOSE, 21, beep_camCloseBeep, "CAM_CONNECTION_CLOSED") },
|
||||||
|
|
||||||
{ BEEPER_ENTRY(BEEPER_ALL, 20, NULL, "ALL") },
|
{ BEEPER_ENTRY(BEEPER_ALL, 22, NULL, "ALL") },
|
||||||
{ BEEPER_ENTRY(BEEPER_PREFERENCE, 21, NULL, "PREFERED") },
|
{ BEEPER_ENTRY(BEEPER_PREFERENCE, 23, NULL, "PREFERED") },
|
||||||
};
|
};
|
||||||
|
|
||||||
static const beeperTableEntry_t *currentBeeperEntry = NULL;
|
static const beeperTableEntry_t *currentBeeperEntry = NULL;
|
||||||
|
|
|
@ -43,6 +43,8 @@ typedef enum {
|
||||||
BEEPER_SYSTEM_INIT, // Initialisation beeps when board is powered on
|
BEEPER_SYSTEM_INIT, // Initialisation beeps when board is powered on
|
||||||
BEEPER_USB, // Some boards have beeper powered USB connected
|
BEEPER_USB, // Some boards have beeper powered USB connected
|
||||||
BEEPER_LAUNCH_MODE_ENABLED, // Fixed-wing launch mode enabled
|
BEEPER_LAUNCH_MODE_ENABLED, // Fixed-wing launch mode enabled
|
||||||
|
BEEPER_CAM_CONNECTION_OPEN, // When the 5 key simulation stated
|
||||||
|
BEEPER_CAM_CONNECTION_CLOSE, // When the 5 key simulation stop
|
||||||
|
|
||||||
BEEPER_ALL, // Turn ON or OFF all beeper conditions
|
BEEPER_ALL, // Turn ON or OFF all beeper conditions
|
||||||
BEEPER_PREFERENCE, // Save preferred beeper configuration
|
BEEPER_PREFERENCE, // Save preferred beeper configuration
|
||||||
|
|
310
src/main/io/rcdevice.c
Normal file
310
src/main/io/rcdevice.c
Normal file
|
@ -0,0 +1,310 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#include "common/crc.h"
|
||||||
|
#include "common/maths.h"
|
||||||
|
#include "common/streambuf.h"
|
||||||
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "drivers/time.h"
|
||||||
|
|
||||||
|
#include "io/serial.h"
|
||||||
|
|
||||||
|
#include "rcdevice.h"
|
||||||
|
|
||||||
|
#ifdef USE_RCDEVICE
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
RCDP_SETTING_PARSE_WAITING_ID,
|
||||||
|
RCDP_SETTING_PARSE_WAITING_NAME,
|
||||||
|
RCDP_SETTING_PARSE_WAITING_VALUE,
|
||||||
|
} runcamDeviceSettingParseStep_e;
|
||||||
|
|
||||||
|
// return 0xFF if expected resonse data length is variable
|
||||||
|
static uint8_t runcamDeviceGetResponseLength(uint8_t command)
|
||||||
|
{
|
||||||
|
switch (command) {
|
||||||
|
case RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO:
|
||||||
|
return 5;
|
||||||
|
case RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS:
|
||||||
|
case RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE:
|
||||||
|
return 2;
|
||||||
|
case RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION:
|
||||||
|
return 3;
|
||||||
|
default:
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Parse the variable length response, e.g the response of settings data and the detail of setting
|
||||||
|
static uint8_t runcamDeviceIsResponseReceiveDone(uint8_t command, uint8_t *data, uint8_t dataLen, bool *isDone)
|
||||||
|
{
|
||||||
|
if (isDone == NULL) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t expectedResponseDataLength = runcamDeviceGetResponseLength(command);
|
||||||
|
if (expectedResponseDataLength == 0xFF) {
|
||||||
|
uint8_t settingDataLength = 0x00;
|
||||||
|
// get setting datalen first
|
||||||
|
if (dataLen >= 3) {
|
||||||
|
settingDataLength = data[2];
|
||||||
|
if (dataLen >= (settingDataLength + 4)) {
|
||||||
|
*isDone = true;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (settingDataLength > 60) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
} else if (dataLen >= expectedResponseDataLength) {
|
||||||
|
*isDone = true;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// a common way to receive packet and verify it
|
||||||
|
static uint8_t runcamDeviceReceivePacket(runcamDevice_t *device, uint8_t command, uint8_t *data)
|
||||||
|
{
|
||||||
|
uint8_t dataPos = 0;
|
||||||
|
uint8_t crc = 0;
|
||||||
|
uint8_t responseDataLen = 0;
|
||||||
|
|
||||||
|
// wait 1000ms for reply
|
||||||
|
timeMs_t timeout = millis() + 1000;
|
||||||
|
bool isWaitingHeader = true;
|
||||||
|
while (millis() < timeout) {
|
||||||
|
if (serialRxBytesWaiting(device->serialPort) > 0) {
|
||||||
|
uint8_t c = serialRead(device->serialPort);
|
||||||
|
crc = crc8_dvb_s2(crc, c);
|
||||||
|
|
||||||
|
if (data) {
|
||||||
|
data[dataPos] = c;
|
||||||
|
}
|
||||||
|
dataPos++;
|
||||||
|
|
||||||
|
if (isWaitingHeader) {
|
||||||
|
if (c == RCDEVICE_PROTOCOL_HEADER) {
|
||||||
|
isWaitingHeader = false;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
bool isDone = false;
|
||||||
|
if (!runcamDeviceIsResponseReceiveDone(command, data, dataPos, &isDone)) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (isDone) {
|
||||||
|
responseDataLen = dataPos;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// check crc
|
||||||
|
if (crc != 0) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
return responseDataLen;
|
||||||
|
}
|
||||||
|
|
||||||
|
// every time send packet to device, and want to get something from device,
|
||||||
|
// it'd better call the method to clear the rx buffer before the packet send,
|
||||||
|
// else may be the useless data in rx buffer will cause the response decoding
|
||||||
|
// failed.
|
||||||
|
static void runcamDeviceFlushRxBuffer(runcamDevice_t *device)
|
||||||
|
{
|
||||||
|
while (serialRxBytesWaiting(device->serialPort) > 0) {
|
||||||
|
serialRead(device->serialPort);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// a common way to send packet to device
|
||||||
|
static void runcamDeviceSendPacket(runcamDevice_t *device, uint8_t command, uint8_t *paramData, int paramDataLen)
|
||||||
|
{
|
||||||
|
// is this device open?
|
||||||
|
if (!device->serialPort) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
sbuf_t buf;
|
||||||
|
// prepare pointer
|
||||||
|
buf.ptr = device->buffer;
|
||||||
|
buf.end = ARRAYEND(device->buffer);
|
||||||
|
|
||||||
|
sbufWriteU8(&buf, RCDEVICE_PROTOCOL_HEADER);
|
||||||
|
sbufWriteU8(&buf, command);
|
||||||
|
|
||||||
|
if (paramData) {
|
||||||
|
sbufWriteData(&buf, paramData, paramDataLen);
|
||||||
|
}
|
||||||
|
|
||||||
|
// add crc over (all) data
|
||||||
|
crc8_dvb_s2_sbuf_append(&buf, device->buffer);
|
||||||
|
|
||||||
|
// switch to reader
|
||||||
|
sbufSwitchToReader(&buf, device->buffer);
|
||||||
|
|
||||||
|
// send data if possible
|
||||||
|
serialWriteBuf(device->serialPort, sbufPtr(&buf), sbufBytesRemaining(&buf));
|
||||||
|
}
|
||||||
|
|
||||||
|
// a common way to send a packet to device, and get response from the device.
|
||||||
|
static bool runcamDeviceSendRequestAndWaitingResp(runcamDevice_t *device, uint8_t commandID, uint8_t *paramData, uint8_t paramDataLen, uint8_t *outputBuffer, uint8_t *outputBufferLen)
|
||||||
|
{
|
||||||
|
uint32_t max_retries = 3;
|
||||||
|
|
||||||
|
while (max_retries--) {
|
||||||
|
// flush rx buffer
|
||||||
|
runcamDeviceFlushRxBuffer(device);
|
||||||
|
|
||||||
|
// send packet
|
||||||
|
runcamDeviceSendPacket(device, commandID, paramData, paramDataLen);
|
||||||
|
|
||||||
|
// waiting response
|
||||||
|
uint8_t responseLength = runcamDeviceReceivePacket(device, commandID, outputBuffer);
|
||||||
|
if (responseLength) {
|
||||||
|
if (outputBufferLen) {
|
||||||
|
*outputBufferLen = responseLength;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// get the device info(firmware version, protocol version and features, see the
|
||||||
|
// definition of runcamDeviceInfo_t to know more)
|
||||||
|
static bool runcamDeviceGetDeviceInfo(runcamDevice_t *device, uint8_t *outputBuffer)
|
||||||
|
{
|
||||||
|
return runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO, NULL, 0, outputBuffer, NULL);
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool runcamDeviceSend5KeyOSDCableConnectionEvent(runcamDevice_t *device, uint8_t operation, uint8_t *outActionID, uint8_t *outErrorCode)
|
||||||
|
{
|
||||||
|
uint8_t outputDataLen = RCDEVICE_PROTOCOL_MAX_PACKET_SIZE;
|
||||||
|
uint8_t respBuf[RCDEVICE_PROTOCOL_MAX_PACKET_SIZE];
|
||||||
|
if (!runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION, &operation, sizeof(uint8_t), respBuf, &outputDataLen)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// the high 4 bits is the operationID that we sent
|
||||||
|
// the low 4 bits is the result code
|
||||||
|
uint8_t operationID = (respBuf[1] & 0xF0) >> 4;
|
||||||
|
bool errorCode = (respBuf[1] & 0x0F);
|
||||||
|
if (outActionID) {
|
||||||
|
*outActionID = operationID;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (outErrorCode) {
|
||||||
|
*outErrorCode = errorCode;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// init the runcam device, it'll search the UART port with FUNCTION_RCDEVICE id
|
||||||
|
// this function will delay 400ms in the first loop to wait the device prepared,
|
||||||
|
// as we know, there are has some camera need about 200~400ms to initialization,
|
||||||
|
// and then we can send/receive from it.
|
||||||
|
bool runcamDeviceInit(runcamDevice_t *device)
|
||||||
|
{
|
||||||
|
serialPortFunction_e portID = FUNCTION_RCDEVICE;
|
||||||
|
serialPortConfig_t *portConfig = findSerialPortConfig(portID);
|
||||||
|
if (portConfig != NULL) {
|
||||||
|
device->serialPort = openSerialPort(portConfig->identifier, portID, NULL, 115200, MODE_RXTX, SERIAL_NOT_INVERTED);
|
||||||
|
|
||||||
|
if (device->serialPort != NULL) {
|
||||||
|
// send RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO to device to retrive
|
||||||
|
// device info, e.g protocol version, supported features
|
||||||
|
uint8_t respBuf[RCDEVICE_PROTOCOL_MAX_PACKET_SIZE];
|
||||||
|
if (runcamDeviceGetDeviceInfo(device, respBuf)) {
|
||||||
|
device->info.protocolVersion = respBuf[1];
|
||||||
|
|
||||||
|
uint8_t featureLowBits = respBuf[2];
|
||||||
|
uint8_t featureHighBits = respBuf[3];
|
||||||
|
device->info.features = (featureHighBits << 8) | featureLowBits;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
closeSerialPort(device->serialPort);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
device->serialPort = NULL;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool runcamDeviceSimulateCameraButton(runcamDevice_t *device, uint8_t operation)
|
||||||
|
{
|
||||||
|
runcamDeviceSendPacket(device, RCDEVICE_PROTOCOL_COMMAND_CAMERA_CONTROL, &operation, sizeof(operation));
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// every time start to control the OSD menu of camera, must call this method to
|
||||||
|
// camera
|
||||||
|
bool runcamDeviceOpen5KeyOSDCableConnection(runcamDevice_t *device)
|
||||||
|
{
|
||||||
|
uint8_t actionID = 0xFF;
|
||||||
|
uint8_t code = 0xFF;
|
||||||
|
bool r = runcamDeviceSend5KeyOSDCableConnectionEvent(device, RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN, &actionID, &code);
|
||||||
|
return r && (code == 1) && (actionID == RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN);
|
||||||
|
}
|
||||||
|
|
||||||
|
// when the control was stop, must call this method to the camera to disconnect
|
||||||
|
// with camera.
|
||||||
|
bool runcamDeviceClose5KeyOSDCableConnection(runcamDevice_t *device)
|
||||||
|
{
|
||||||
|
uint8_t actionID = 0xFF;
|
||||||
|
uint8_t code = 0xFF;
|
||||||
|
bool r = runcamDeviceSend5KeyOSDCableConnectionEvent(device, RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE, &actionID, &code);
|
||||||
|
|
||||||
|
return r && (code == 1) && (actionID == RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE);
|
||||||
|
}
|
||||||
|
|
||||||
|
// simulate button press event of 5 key osd cable with special button
|
||||||
|
bool runcamDeviceSimulate5KeyOSDCableButtonPress(runcamDevice_t *device, uint8_t operation)
|
||||||
|
{
|
||||||
|
if (operation == RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS, &operation, sizeof(uint8_t), NULL, NULL)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// simulate button release event of 5 key osd cable
|
||||||
|
bool runcamDeviceSimulate5KeyOSDCableButtonRelease(runcamDevice_t *device)
|
||||||
|
{
|
||||||
|
return runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE, NULL, 0, NULL, NULL);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
138
src/main/io/rcdevice.h
Normal file
138
src/main/io/rcdevice.h
Normal file
|
@ -0,0 +1,138 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "drivers/serial.h"
|
||||||
|
|
||||||
|
//
|
||||||
|
// The protocol for Runcam Device definition
|
||||||
|
//
|
||||||
|
#define RCDEVICE_PROTOCOL_HEADER 0xCC
|
||||||
|
|
||||||
|
#define RCDEVICE_PROTOCOL_MAX_PACKET_SIZE 64
|
||||||
|
#define RCDEVICE_PROTOCOL_MAX_DATA_SIZE 62
|
||||||
|
#define RCDEVICE_PROTOCOL_MAX_DATA_SIZE_WITH_CRC_FIELD 63
|
||||||
|
|
||||||
|
// Commands
|
||||||
|
#define RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO 0x00
|
||||||
|
// camera control
|
||||||
|
#define RCDEVICE_PROTOCOL_COMMAND_CAMERA_CONTROL 0x01
|
||||||
|
// 5 key osd cable simulation
|
||||||
|
#define RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS 0x02
|
||||||
|
#define RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE 0x03
|
||||||
|
#define RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION 0x04
|
||||||
|
|
||||||
|
// Feature Flag sets, it's a uint16_t flag
|
||||||
|
typedef enum {
|
||||||
|
RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON = (1 << 0),
|
||||||
|
RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON = (1 << 1),
|
||||||
|
RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE = (1 << 2),
|
||||||
|
RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE = (1 << 3),
|
||||||
|
} rcdevice_features_e;
|
||||||
|
|
||||||
|
// Operation of Camera Button Simulation
|
||||||
|
typedef enum {
|
||||||
|
RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN = 0x00,
|
||||||
|
RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN = 0x01,
|
||||||
|
RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE = 0x02,
|
||||||
|
RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION = 0xFF
|
||||||
|
} rcdevice_camera_control_opeation_e;
|
||||||
|
|
||||||
|
// Operation Of 5 Key OSD Cable Simulation
|
||||||
|
typedef enum {
|
||||||
|
RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE = 0x00,
|
||||||
|
RCDEVICE_PROTOCOL_5KEY_SIMULATION_SET = 0x01,
|
||||||
|
RCDEVICE_PROTOCOL_5KEY_SIMULATION_LEFT = 0x02,
|
||||||
|
RCDEVICE_PROTOCOL_5KEY_SIMULATION_RIGHT = 0x03,
|
||||||
|
RCDEVICE_PROTOCOL_5KEY_SIMULATION_UP = 0x04,
|
||||||
|
RCDEVICE_PROTOCOL_5KEY_SIMULATION_DOWN = 0x05
|
||||||
|
} rcdevice_5key_simulation_operation_e;
|
||||||
|
|
||||||
|
// Operation of RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION
|
||||||
|
typedef enum {
|
||||||
|
RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN = 0x01,
|
||||||
|
RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE = 0x02
|
||||||
|
} RCDEVICE_5key_connection_event_e;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
RCDEVICE_CAM_KEY_NONE,
|
||||||
|
RCDEVICE_CAM_KEY_ENTER,
|
||||||
|
RCDEVICE_CAM_KEY_LEFT,
|
||||||
|
RCDEVICE_CAM_KEY_UP,
|
||||||
|
RCDEVICE_CAM_KEY_RIGHT,
|
||||||
|
RCDEVICE_CAM_KEY_DOWN,
|
||||||
|
RCDEVICE_CAM_KEY_CONNECTION_CLOSE,
|
||||||
|
RCDEVICE_CAM_KEY_CONNECTION_OPEN,
|
||||||
|
RCDEVICE_CAM_KEY_RELEASE,
|
||||||
|
} rcdeviceCamSimulationKeyEvent_e;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
RCDEVICE_PROTOCOL_RCSPLIT_VERSION = 0x00, // this is used to indicate the
|
||||||
|
// device that using rcsplit
|
||||||
|
// firmware version that <= 1.1.0
|
||||||
|
RCDEVICE_PROTOCOL_VERSION_1_0 = 0x01,
|
||||||
|
RCDEVICE_PROTOCOL_UNKNOWN
|
||||||
|
} rcdevice_protocol_version_e;
|
||||||
|
|
||||||
|
typedef struct runcamDeviceConnectionEventResponse_s {
|
||||||
|
uint8_t type : 4;
|
||||||
|
uint8_t resultCode : 4;
|
||||||
|
} runcamDeviceConnectionEventResponse_t;
|
||||||
|
|
||||||
|
typedef struct runcamDeviceGetDeviceInfoResponse_s {
|
||||||
|
uint8_t protocolVersion;
|
||||||
|
uint16_t features;
|
||||||
|
} runcamDeviceGetDeviceInfoResponse_t;
|
||||||
|
// end of Runcam Device definition
|
||||||
|
|
||||||
|
// Old version defination(RCSplit firmware v1.0.0 and v1.1.0)
|
||||||
|
// packet header and tail
|
||||||
|
#define RCSPLIT_PACKET_HEADER 0x55
|
||||||
|
#define RCSPLIT_PACKET_CMD_CTRL 0x01
|
||||||
|
#define RCSPLIT_PACKET_TAIL 0xaa
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
RCSPLIT_CTRL_ARGU_INVALID = 0x0,
|
||||||
|
RCSPLIT_CTRL_ARGU_WIFI_BTN = 0x1,
|
||||||
|
RCSPLIT_CTRL_ARGU_POWER_BTN = 0x2,
|
||||||
|
RCSPLIT_CTRL_ARGU_CHANGE_MODE = 0x3,
|
||||||
|
RCSPLIT_CTRL_ARGU_WHO_ARE_YOU = 0xFF,
|
||||||
|
} rcsplit_ctrl_argument_e;
|
||||||
|
// end of old version protocol definition
|
||||||
|
|
||||||
|
typedef struct runcamDeviceInfo_s {
|
||||||
|
rcdevice_protocol_version_e protocolVersion;
|
||||||
|
uint16_t features;
|
||||||
|
} runcamDeviceInfo_t;
|
||||||
|
|
||||||
|
typedef struct runcamDevice_s {
|
||||||
|
serialPort_t *serialPort;
|
||||||
|
uint8_t buffer[RCDEVICE_PROTOCOL_MAX_PACKET_SIZE];
|
||||||
|
runcamDeviceInfo_t info;
|
||||||
|
} runcamDevice_t;
|
||||||
|
|
||||||
|
bool runcamDeviceInit(runcamDevice_t *device);
|
||||||
|
|
||||||
|
// camera button simulation
|
||||||
|
bool runcamDeviceSimulateCameraButton(runcamDevice_t *device, uint8_t operation);
|
||||||
|
|
||||||
|
// 5 key osd cable simulation
|
||||||
|
bool runcamDeviceOpen5KeyOSDCableConnection(runcamDevice_t *device);
|
||||||
|
bool runcamDeviceClose5KeyOSDCableConnection(runcamDevice_t *device);
|
||||||
|
bool runcamDeviceSimulate5KeyOSDCableButtonPress(runcamDevice_t *device, uint8_t operation);
|
||||||
|
bool runcamDeviceSimulate5KeyOSDCableButtonRelease(runcamDevice_t *device);
|
279
src/main/io/rcdevice_cam.c
Normal file
279
src/main/io/rcdevice_cam.c
Normal file
|
@ -0,0 +1,279 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stddef.h>
|
||||||
|
|
||||||
|
#include "cms/cms.h"
|
||||||
|
#include "common/utils.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
#include "io/beeper.h"
|
||||||
|
#include "io/rcdevice_cam.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
|
|
||||||
|
#ifdef USE_RCDEVICE
|
||||||
|
|
||||||
|
#define IS_HI(X) (rcData[X] > 1750)
|
||||||
|
#define IS_LO(X) (rcData[X] < 1250)
|
||||||
|
#define IS_MID(X) (rcData[X] > 1250 && rcData[X] < 1750)
|
||||||
|
static runcamDevice_t runcamDevice;
|
||||||
|
runcamDevice_t *camDevice = &runcamDevice;
|
||||||
|
rcdeviceSwitchState_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1];
|
||||||
|
bool rcdeviceInMenu;
|
||||||
|
bool needRelease = false;
|
||||||
|
|
||||||
|
static bool isFeatureSupported(uint8_t feature)
|
||||||
|
{
|
||||||
|
if (camDevice->info.features & feature) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool rcdeviceIsCameraControlEnabled(void)
|
||||||
|
{
|
||||||
|
bool isPowerSimulationSupported = isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON);
|
||||||
|
bool isWiFiSimulationSupported = isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON);
|
||||||
|
bool isChangeModeSupported = isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE);
|
||||||
|
|
||||||
|
if (camDevice->serialPort != NULL && (isPowerSimulationSupported || isWiFiSimulationSupported || isChangeModeSupported)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool rcdeviceIsEnabled(void)
|
||||||
|
{
|
||||||
|
bool is5KeySimulationSupported = isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE);
|
||||||
|
|
||||||
|
if (camDevice->serialPort != NULL && (rcdeviceIsCameraControlEnabled() || is5KeySimulationSupported)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool rcdeviceIs5KeyEnabled(void)
|
||||||
|
{
|
||||||
|
if (camDevice->serialPort != NULL && isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void rcdeviceCameraControlProcess(void)
|
||||||
|
{
|
||||||
|
for (boxId_e i = BOXCAMERA1; i <= BOXCAMERA3; i++) {
|
||||||
|
uint8_t switchIndex = i - BOXCAMERA1;
|
||||||
|
|
||||||
|
if (IS_RC_MODE_ACTIVE(i)) {
|
||||||
|
// check last state of this mode, if it's true, then ignore it.
|
||||||
|
// Here is a logic to make a toggle control for this mode
|
||||||
|
if (switchStates[switchIndex].isActivated) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t behavior = RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION;
|
||||||
|
switch (i) {
|
||||||
|
case BOXCAMERA1:
|
||||||
|
if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON)) {
|
||||||
|
behavior = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case BOXCAMERA2:
|
||||||
|
if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON)) {
|
||||||
|
behavior = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case BOXCAMERA3:
|
||||||
|
if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE)) {
|
||||||
|
behavior = RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (behavior != RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION) {
|
||||||
|
runcamDeviceSimulateCameraButton(camDevice, behavior);
|
||||||
|
switchStates[switchIndex].isActivated = true;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
switchStates[switchIndex].isActivated = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool rcdeviceCamSimulate5KeyCablePress(rcdeviceCamSimulationKeyEvent_e key)
|
||||||
|
{
|
||||||
|
uint8_t operation = RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE;
|
||||||
|
switch (key) {
|
||||||
|
case RCDEVICE_CAM_KEY_LEFT:
|
||||||
|
operation = RCDEVICE_PROTOCOL_5KEY_SIMULATION_LEFT;
|
||||||
|
break;
|
||||||
|
case RCDEVICE_CAM_KEY_UP:
|
||||||
|
operation = RCDEVICE_PROTOCOL_5KEY_SIMULATION_UP;
|
||||||
|
break;
|
||||||
|
case RCDEVICE_CAM_KEY_RIGHT:
|
||||||
|
operation = RCDEVICE_PROTOCOL_5KEY_SIMULATION_RIGHT;
|
||||||
|
break;
|
||||||
|
case RCDEVICE_CAM_KEY_DOWN:
|
||||||
|
operation = RCDEVICE_PROTOCOL_5KEY_SIMULATION_DOWN;
|
||||||
|
break;
|
||||||
|
case RCDEVICE_CAM_KEY_ENTER:
|
||||||
|
operation = RCDEVICE_PROTOCOL_5KEY_SIMULATION_SET;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
operation = RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return runcamDeviceSimulate5KeyOSDCableButtonPress(camDevice, operation);
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool rcdeviceSend5KeyOSDCableSimualtionEvent(rcdeviceCamSimulationKeyEvent_e key)
|
||||||
|
{
|
||||||
|
bool reqResult = false;
|
||||||
|
switch (key) {
|
||||||
|
case RCDEVICE_CAM_KEY_CONNECTION_OPEN:
|
||||||
|
reqResult = runcamDeviceOpen5KeyOSDCableConnection(camDevice);
|
||||||
|
if (reqResult) {
|
||||||
|
rcdeviceInMenu = true;
|
||||||
|
beeper(BEEPER_CAM_CONNECTION_OPEN);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case RCDEVICE_CAM_KEY_CONNECTION_CLOSE:
|
||||||
|
reqResult = runcamDeviceClose5KeyOSDCableConnection(camDevice);
|
||||||
|
if (reqResult) {
|
||||||
|
rcdeviceInMenu = false;
|
||||||
|
beeper(BEEPER_CAM_CONNECTION_CLOSE);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case RCDEVICE_CAM_KEY_ENTER:
|
||||||
|
case RCDEVICE_CAM_KEY_LEFT:
|
||||||
|
case RCDEVICE_CAM_KEY_UP:
|
||||||
|
case RCDEVICE_CAM_KEY_RIGHT:
|
||||||
|
case RCDEVICE_CAM_KEY_DOWN:
|
||||||
|
reqResult = rcdeviceCamSimulate5KeyCablePress(key);
|
||||||
|
break;
|
||||||
|
case RCDEVICE_CAM_KEY_RELEASE:
|
||||||
|
reqResult = runcamDeviceSimulate5KeyOSDCableButtonRelease(camDevice);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
reqResult = false;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return reqResult;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs)
|
||||||
|
{
|
||||||
|
UNUSED(currentTimeUs);
|
||||||
|
|
||||||
|
#ifdef CMS
|
||||||
|
if (cmsInMenu) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (camDevice->serialPort == 0) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
rcdeviceCamSimulationKeyEvent_e key = RCDEVICE_CAM_KEY_NONE;
|
||||||
|
|
||||||
|
if (needRelease) {
|
||||||
|
if (IS_MID(YAW) && IS_MID(PITCH) && IS_MID(ROLL)) {
|
||||||
|
key = RCDEVICE_CAM_KEY_RELEASE;
|
||||||
|
if (rcdeviceSend5KeyOSDCableSimualtionEvent(key)) {
|
||||||
|
needRelease = false;
|
||||||
|
} else {
|
||||||
|
rcdeviceInMenu = false;
|
||||||
|
}
|
||||||
|
return;
|
||||||
|
} else {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (IS_MID(THROTTLE) && IS_MID(ROLL) && IS_MID(PITCH) && IS_LO(YAW)) { // Disconnect HI YAW
|
||||||
|
if (rcdeviceInMenu) {
|
||||||
|
key = RCDEVICE_CAM_KEY_CONNECTION_CLOSE;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (rcdeviceInMenu) {
|
||||||
|
if (IS_LO(ROLL)) { // Left LO ROLL
|
||||||
|
key = RCDEVICE_CAM_KEY_LEFT;
|
||||||
|
} else if (IS_HI(PITCH)) { // Up HI PITCH
|
||||||
|
key = RCDEVICE_CAM_KEY_UP;
|
||||||
|
} else if (IS_HI(ROLL)) { // Right HI ROLL
|
||||||
|
key = RCDEVICE_CAM_KEY_RIGHT;
|
||||||
|
} else if (IS_LO(PITCH)) { // Down LO PITCH
|
||||||
|
key = RCDEVICE_CAM_KEY_DOWN;
|
||||||
|
} else if (IS_MID(THROTTLE) && IS_MID(ROLL) && IS_MID(PITCH) && IS_HI(YAW)) { // Enter HI YAW
|
||||||
|
key = RCDEVICE_CAM_KEY_ENTER;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (IS_MID(THROTTLE) && IS_MID(ROLL) && IS_MID(PITCH) && IS_HI(YAW) && !ARMING_FLAG(ARMED)) { // Enter HI YAW
|
||||||
|
key = RCDEVICE_CAM_KEY_CONNECTION_OPEN;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (key != RCDEVICE_CAM_KEY_NONE) {
|
||||||
|
if (rcdeviceSend5KeyOSDCableSimualtionEvent(key)) {
|
||||||
|
needRelease = true;
|
||||||
|
} else {
|
||||||
|
rcdeviceInMenu = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void rcdeviceUpdate(timeUs_t currentTimeUs)
|
||||||
|
{
|
||||||
|
if (rcdeviceIsCameraControlEnabled()) {
|
||||||
|
rcdeviceCameraControlProcess();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (rcdeviceIs5KeyEnabled()) {
|
||||||
|
rcdevice5KeySimulationProcess(currentTimeUs);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool rcdeviceInit(void)
|
||||||
|
{
|
||||||
|
// open serial port
|
||||||
|
if (!runcamDeviceInit(camDevice)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (boxId_e i = BOXCAMERA1; i <= BOXCAMERA3; i++) {
|
||||||
|
uint8_t switchIndex = i - BOXCAMERA1;
|
||||||
|
switchStates[switchIndex].isActivated = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
42
src/main/io/rcdevice_cam.h
Normal file
42
src/main/io/rcdevice_cam.h
Normal file
|
@ -0,0 +1,42 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <ctype.h>
|
||||||
|
|
||||||
|
#include "common/time.h"
|
||||||
|
#include "io/rcdevice.h"
|
||||||
|
#include "fc/rc_modes.h"
|
||||||
|
|
||||||
|
typedef struct rcdeviceSwitchState_s {
|
||||||
|
bool isActivated;
|
||||||
|
} rcdeviceSwitchState_t;
|
||||||
|
|
||||||
|
extern runcamDevice_t *camDevice;
|
||||||
|
extern bool rcdeviceInMenu;
|
||||||
|
|
||||||
|
bool rcdeviceInit(void);
|
||||||
|
void rcdeviceUpdate(timeUs_t currentTimeUs);
|
||||||
|
|
||||||
|
bool rcdeviceIsEnabled(void);
|
||||||
|
|
||||||
|
// used for unit test
|
||||||
|
rcdeviceSwitchState_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1];
|
|
@ -1,166 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight.
|
|
||||||
*
|
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
|
||||||
* it under the terms of the GNU General Public License as published by
|
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
|
||||||
* (at your option) any later version.
|
|
||||||
*
|
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
* GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <stdio.h>
|
|
||||||
#include <ctype.h>
|
|
||||||
|
|
||||||
#include <platform.h>
|
|
||||||
|
|
||||||
#include "common/utils.h"
|
|
||||||
|
|
||||||
#include "config/parameter_group.h"
|
|
||||||
#include "config/parameter_group_ids.h"
|
|
||||||
|
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
|
|
||||||
#include "io/beeper.h"
|
|
||||||
#include "io/serial.h"
|
|
||||||
|
|
||||||
#include "scheduler/scheduler.h"
|
|
||||||
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
|
|
||||||
#include "io/rcsplit.h"
|
|
||||||
|
|
||||||
// communicate with camera device variables
|
|
||||||
serialPort_t *rcSplitSerialPort = NULL;
|
|
||||||
rcsplit_switch_state_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1];
|
|
||||||
rcsplit_state_e cameraState = RCSPLIT_STATE_UNKNOWN;
|
|
||||||
|
|
||||||
static uint8_t crc_high_first(uint8_t *ptr, uint8_t len)
|
|
||||||
{
|
|
||||||
uint8_t i;
|
|
||||||
uint8_t crc=0x00;
|
|
||||||
while (len--) {
|
|
||||||
crc ^= *ptr++;
|
|
||||||
for (i=8; i>0; --i) {
|
|
||||||
if (crc & 0x80)
|
|
||||||
crc = (crc << 1) ^ 0x31;
|
|
||||||
else
|
|
||||||
crc = (crc << 1);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return (crc);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void sendCtrlCommand(rcsplit_ctrl_argument_e argument)
|
|
||||||
{
|
|
||||||
if (!rcSplitSerialPort)
|
|
||||||
return ;
|
|
||||||
|
|
||||||
uint8_t uart_buffer[5] = {0};
|
|
||||||
uint8_t crc = 0;
|
|
||||||
|
|
||||||
uart_buffer[0] = RCSPLIT_PACKET_HEADER;
|
|
||||||
uart_buffer[1] = RCSPLIT_PACKET_CMD_CTRL;
|
|
||||||
uart_buffer[2] = argument;
|
|
||||||
uart_buffer[3] = RCSPLIT_PACKET_TAIL;
|
|
||||||
crc = crc_high_first(uart_buffer, 4);
|
|
||||||
|
|
||||||
// build up a full request [header]+[command]+[argument]+[crc]+[tail]
|
|
||||||
uart_buffer[3] = crc;
|
|
||||||
uart_buffer[4] = RCSPLIT_PACKET_TAIL;
|
|
||||||
|
|
||||||
// write to device
|
|
||||||
serialWriteBuf(rcSplitSerialPort, uart_buffer, 5);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void rcSplitProcessMode()
|
|
||||||
{
|
|
||||||
// if the device not ready, do not handle any mode change event
|
|
||||||
if (RCSPLIT_STATE_IS_READY != cameraState) {
|
|
||||||
printf("device not ready");
|
|
||||||
return ;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
for (boxId_e i = BOXCAMERA1; i <= BOXCAMERA3; i++) {
|
|
||||||
uint8_t switchIndex = i - BOXCAMERA1;
|
|
||||||
if (IS_RC_MODE_ACTIVE(i)) {
|
|
||||||
// check last state of this mode, if it's true, then ignore it.
|
|
||||||
// Here is a logic to make a toggle control for this mode
|
|
||||||
if (switchStates[switchIndex].isActivated) {
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t argument = RCSPLIT_CTRL_ARGU_INVALID;
|
|
||||||
switch (i) {
|
|
||||||
case BOXCAMERA1:
|
|
||||||
argument = RCSPLIT_CTRL_ARGU_WIFI_BTN;
|
|
||||||
break;
|
|
||||||
case BOXCAMERA2:
|
|
||||||
argument = RCSPLIT_CTRL_ARGU_POWER_BTN;
|
|
||||||
break;
|
|
||||||
case BOXCAMERA3:
|
|
||||||
argument = RCSPLIT_CTRL_ARGU_CHANGE_MODE;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
argument = RCSPLIT_CTRL_ARGU_INVALID;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (argument != RCSPLIT_CTRL_ARGU_INVALID) {
|
|
||||||
sendCtrlCommand(argument);
|
|
||||||
switchStates[switchIndex].isActivated = true;
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
switchStates[switchIndex].isActivated = false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
bool rcSplitInit(void)
|
|
||||||
{
|
|
||||||
// found the port config with FUNCTION_RUNCAM_SPLIT_CONTROL
|
|
||||||
// User must set some UART inteface with RunCam Split at peripherals column in Ports tab
|
|
||||||
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RCSPLIT);
|
|
||||||
if (portConfig) {
|
|
||||||
rcSplitSerialPort = openSerialPort(portConfig->identifier, FUNCTION_RCSPLIT, NULL, 115200, MODE_RXTX, 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!rcSplitSerialPort) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// set init value to true, to avoid the action auto run when the flight board start and the switch is on.
|
|
||||||
for (boxId_e i = BOXCAMERA1; i <= BOXCAMERA3; i++) {
|
|
||||||
uint8_t switchIndex = i - BOXCAMERA1;
|
|
||||||
switchStates[switchIndex].boxId = 1 << i;
|
|
||||||
switchStates[switchIndex].isActivated = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
cameraState = RCSPLIT_STATE_IS_READY;
|
|
||||||
|
|
||||||
#ifdef USE_RCSPLIT
|
|
||||||
setTaskEnabled(TASK_RCSPLIT, true);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void rcSplitProcess(timeUs_t currentTimeUs)
|
|
||||||
{
|
|
||||||
UNUSED(currentTimeUs);
|
|
||||||
|
|
||||||
if (rcSplitSerialPort == NULL)
|
|
||||||
return ;
|
|
||||||
|
|
||||||
// process rcsplit custom mode if has any changed
|
|
||||||
rcSplitProcessMode();
|
|
||||||
}
|
|
|
@ -1,59 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight.
|
|
||||||
*
|
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
|
||||||
* it under the terms of the GNU General Public License as published by
|
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
|
||||||
* (at your option) any later version.
|
|
||||||
*
|
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
* GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include "common/time.h"
|
|
||||||
#include "fc/fc_msp.h"
|
|
||||||
#include "fc/rc_modes.h"
|
|
||||||
|
|
||||||
typedef struct {
|
|
||||||
uint8_t boxId;
|
|
||||||
bool isActivated;
|
|
||||||
} rcsplit_switch_state_t;
|
|
||||||
|
|
||||||
typedef enum {
|
|
||||||
RCSPLIT_STATE_UNKNOWN = 0,
|
|
||||||
RCSPLIT_STATE_INITIALIZING,
|
|
||||||
RCSPLIT_STATE_IS_READY,
|
|
||||||
} rcsplit_state_e;
|
|
||||||
|
|
||||||
// packet header and tail
|
|
||||||
#define RCSPLIT_PACKET_HEADER 0x55
|
|
||||||
#define RCSPLIT_PACKET_CMD_CTRL 0x01
|
|
||||||
#define RCSPLIT_PACKET_TAIL 0xaa
|
|
||||||
|
|
||||||
|
|
||||||
// the commands of RunCam Split serial protocol
|
|
||||||
typedef enum {
|
|
||||||
RCSPLIT_CTRL_ARGU_INVALID = 0x0,
|
|
||||||
RCSPLIT_CTRL_ARGU_WIFI_BTN = 0x1,
|
|
||||||
RCSPLIT_CTRL_ARGU_POWER_BTN = 0x2,
|
|
||||||
RCSPLIT_CTRL_ARGU_CHANGE_MODE = 0x3,
|
|
||||||
RCSPLIT_CTRL_ARGU_WHO_ARE_YOU = 0xFF,
|
|
||||||
} rcsplit_ctrl_argument_e;
|
|
||||||
|
|
||||||
bool rcSplitInit(void);
|
|
||||||
void rcSplitProcess(timeUs_t currentTimeUs);
|
|
||||||
|
|
||||||
#ifdef UNIT_TEST
|
|
||||||
// only for unit test
|
|
||||||
extern rcsplit_state_e cameraState;
|
|
||||||
extern serialPort_t *rcSplitSerialPort;
|
|
||||||
extern rcsplit_switch_state_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1];
|
|
||||||
#endif
|
|
|
@ -41,7 +41,7 @@ typedef enum {
|
||||||
FUNCTION_BLACKBOX = (1 << 7), // 128
|
FUNCTION_BLACKBOX = (1 << 7), // 128
|
||||||
FUNCTION_TELEMETRY_MAVLINK = (1 << 8), // 256
|
FUNCTION_TELEMETRY_MAVLINK = (1 << 8), // 256
|
||||||
FUNCTION_TELEMETRY_IBUS = (1 << 9), // 512
|
FUNCTION_TELEMETRY_IBUS = (1 << 9), // 512
|
||||||
FUNCTION_RCSPLIT = (1 << 10), // 1024
|
FUNCTION_RCDEVICE = (1 << 10), // 1024
|
||||||
FUNCTION_VTX_SMARTAUDIO = (1 << 11), // 2048
|
FUNCTION_VTX_SMARTAUDIO = (1 << 11), // 2048
|
||||||
FUNCTION_VTX_TRAMP = (1 << 12), // 4096
|
FUNCTION_VTX_TRAMP = (1 << 12), // 4096
|
||||||
FUNCTION_UAV_INTERCONNECT = (1 << 13), // 8192
|
FUNCTION_UAV_INTERCONNECT = (1 << 13), // 8192
|
||||||
|
|
|
@ -107,8 +107,8 @@ typedef enum {
|
||||||
#ifdef USE_UAV_INTERCONNECT
|
#ifdef USE_UAV_INTERCONNECT
|
||||||
TASK_UAV_INTERCONNECT,
|
TASK_UAV_INTERCONNECT,
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_RCSPLIT
|
#ifdef USE_RCDEVICE
|
||||||
TASK_RCSPLIT,
|
TASK_RCDEVICE,
|
||||||
#endif
|
#endif
|
||||||
#ifdef VTX_CONTROL
|
#ifdef VTX_CONTROL
|
||||||
TASK_VTXCTRL,
|
TASK_VTXCTRL,
|
||||||
|
|
|
@ -99,7 +99,7 @@
|
||||||
#define PWM_DRIVER_PCA9685
|
#define PWM_DRIVER_PCA9685
|
||||||
#define NAV_MAX_WAYPOINTS 60
|
#define NAV_MAX_WAYPOINTS 60
|
||||||
#define MAX_BOOTLOG_ENTRIES 64
|
#define MAX_BOOTLOG_ENTRIES 64
|
||||||
#define USE_RCSPLIT
|
#define USE_RCDEVICE
|
||||||
#define PITOT
|
#define PITOT
|
||||||
#define USE_PITOT_ADC
|
#define USE_PITOT_ADC
|
||||||
|
|
||||||
|
|
|
@ -657,24 +657,35 @@ $(OBJECT_DIR)/sensor_gyro_unittest : \
|
||||||
|
|
||||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||||
|
|
||||||
$(OBJECT_DIR)/io/rcsplit.o : \
|
$(OBJECT_DIR)/io/rcdevice.o : \
|
||||||
$(USER_DIR)/io/rcsplit.c \
|
$(USER_DIR)/io/rcdevice.c \
|
||||||
$(USER_DIR)/io/rcsplit.h
|
$(USER_DIR)/io/rcdevice.h
|
||||||
|
|
||||||
@mkdir -p $(dir $@)
|
@mkdir -p $(dir $@)
|
||||||
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/rcsplit.c -o $@
|
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/rcdevice.c -o $@
|
||||||
|
|
||||||
$(OBJECT_DIR)/rcsplit_unittest.o : \
|
$(OBJECT_DIR)/io/rcdevice_cam.o : \
|
||||||
$(TEST_DIR)/rcsplit_unittest.cc \
|
$(USER_DIR)/io/rcdevice.c \
|
||||||
|
$(USER_DIR)/io/rcdevice.h \
|
||||||
|
$(USER_DIR)/io/rcdevice_cam.c \
|
||||||
|
$(USER_DIR)/io/rcdevice_cam.h
|
||||||
|
|
||||||
|
@mkdir -p $(dir $@)
|
||||||
|
$(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/rcdevice_cam.c -o $@
|
||||||
|
|
||||||
|
|
||||||
|
$(OBJECT_DIR)/rcdevice_unittest.o : \
|
||||||
|
$(TEST_DIR)/rcdevice_unittest.cc \
|
||||||
$(GTEST_HEADERS)
|
$(GTEST_HEADERS)
|
||||||
|
|
||||||
@mkdir -p $(dir $@)
|
@mkdir -p $(dir $@)
|
||||||
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/rcsplit_unittest.cc -o $@
|
$(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/rcdevice_unittest.cc -o $@
|
||||||
|
|
||||||
$(OBJECT_DIR)/rcsplit_unittest : \
|
$(OBJECT_DIR)/rcdevice_unittest : \
|
||||||
$(OBJECT_DIR)/rcsplit_unittest.o \
|
$(OBJECT_DIR)/rcdevice_unittest.o \
|
||||||
$(OBJECT_DIR)/common/bitarray.o \
|
$(OBJECT_DIR)/common/bitarray.o \
|
||||||
$(OBJECT_DIR)/io/rcsplit.o \
|
$(OBJECT_DIR)/io/rcdevice.o \
|
||||||
|
$(OBJECT_DIR)/io/rcdevice_cam.o \
|
||||||
$(OBJECT_DIR)/fc/rc_modes.o \
|
$(OBJECT_DIR)/fc/rc_modes.o \
|
||||||
$(OBJECT_DIR)/fc/rc_controls.o \
|
$(OBJECT_DIR)/fc/rc_controls.o \
|
||||||
$(OBJECT_DIR)/rx/rx.o \
|
$(OBJECT_DIR)/rx/rx.o \
|
||||||
|
|
1598
src/test/unit/rcdevice_unittest.cc
Normal file
1598
src/test/unit/rcdevice_unittest.cc
Normal file
File diff suppressed because it is too large
Load diff
|
@ -1,457 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight.
|
|
||||||
*
|
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
|
||||||
* it under the terms of the GNU General Public License as published by
|
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
|
||||||
* (at your option) any later version.
|
|
||||||
*
|
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
* GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
|
|
||||||
#include "gtest/gtest.h"
|
|
||||||
|
|
||||||
extern "C" {
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <ctype.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
|
||||||
|
|
||||||
#include "common/utils.h"
|
|
||||||
#include "common/maths.h"
|
|
||||||
|
|
||||||
#include "config/parameter_group.h"
|
|
||||||
#include "config/parameter_group_ids.h"
|
|
||||||
|
|
||||||
#include "fc/rc_controls.h"
|
|
||||||
#include "fc/rc_modes.h"
|
|
||||||
|
|
||||||
#include "io/beeper.h"
|
|
||||||
#include "io/serial.h"
|
|
||||||
|
|
||||||
#include "scheduler/scheduler.h"
|
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "io/rcsplit.h"
|
|
||||||
|
|
||||||
#include "rx/rx.h"
|
|
||||||
|
|
||||||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
|
||||||
|
|
||||||
rcsplit_state_e unitTestRCsplitState()
|
|
||||||
{
|
|
||||||
return cameraState;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool unitTestIsSwitchActivited(boxId_e boxId)
|
|
||||||
{
|
|
||||||
uint8_t adjustBoxID = boxId - BOXCAMERA1;
|
|
||||||
rcsplit_switch_state_t switchState = switchStates[adjustBoxID];
|
|
||||||
return switchState.isActivated;
|
|
||||||
}
|
|
||||||
|
|
||||||
void unitTestResetRCSplit()
|
|
||||||
{
|
|
||||||
rcSplitSerialPort = NULL;
|
|
||||||
cameraState = RCSPLIT_STATE_UNKNOWN;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
typedef struct testData_s {
|
|
||||||
bool isRunCamSplitPortConfigurated;
|
|
||||||
bool isRunCamSplitOpenPortSupported;
|
|
||||||
int8_t maxTimesOfRespDataAvailable;
|
|
||||||
bool isAllowBufferReadWrite;
|
|
||||||
} testData_t;
|
|
||||||
|
|
||||||
static testData_t testData;
|
|
||||||
|
|
||||||
TEST(RCSplitTest, TestRCSplitInitWithoutPortConfigurated)
|
|
||||||
{
|
|
||||||
memset(&testData, 0, sizeof(testData));
|
|
||||||
unitTestResetRCSplit();
|
|
||||||
bool result = rcSplitInit();
|
|
||||||
EXPECT_EQ(false, result);
|
|
||||||
EXPECT_EQ(RCSPLIT_STATE_UNKNOWN, unitTestRCsplitState());
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(RCSplitTest, TestRCSplitInitWithoutOpenPortConfigurated)
|
|
||||||
{
|
|
||||||
memset(&testData, 0, sizeof(testData));
|
|
||||||
unitTestResetRCSplit();
|
|
||||||
testData.isRunCamSplitOpenPortSupported = false;
|
|
||||||
testData.isRunCamSplitPortConfigurated = true;
|
|
||||||
|
|
||||||
bool result = rcSplitInit();
|
|
||||||
EXPECT_EQ(false, result);
|
|
||||||
EXPECT_EQ(RCSPLIT_STATE_UNKNOWN, unitTestRCsplitState());
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(RCSplitTest, TestRCSplitInit)
|
|
||||||
{
|
|
||||||
memset(&testData, 0, sizeof(testData));
|
|
||||||
unitTestResetRCSplit();
|
|
||||||
testData.isRunCamSplitOpenPortSupported = true;
|
|
||||||
testData.isRunCamSplitPortConfigurated = true;
|
|
||||||
|
|
||||||
bool result = rcSplitInit();
|
|
||||||
EXPECT_EQ(true, result);
|
|
||||||
EXPECT_EQ(RCSPLIT_STATE_IS_READY, unitTestRCsplitState());
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(RCSplitTest, TestRecvWhoAreYouResponse)
|
|
||||||
{
|
|
||||||
memset(&testData, 0, sizeof(testData));
|
|
||||||
unitTestResetRCSplit();
|
|
||||||
testData.isRunCamSplitOpenPortSupported = true;
|
|
||||||
testData.isRunCamSplitPortConfigurated = true;
|
|
||||||
|
|
||||||
bool result = rcSplitInit();
|
|
||||||
EXPECT_EQ(true, result);
|
|
||||||
|
|
||||||
// here will generate a number in [6-255], it's make the serialRxBytesWaiting() and serialRead() run at least 5 times,
|
|
||||||
// so the "who are you response" will full received, and cause the state change to RCSPLIT_STATE_IS_READY;
|
|
||||||
int8_t randNum = rand() % 127 + 6;
|
|
||||||
testData.maxTimesOfRespDataAvailable = randNum;
|
|
||||||
rcSplitProcess((timeUs_t)0);
|
|
||||||
|
|
||||||
EXPECT_EQ(RCSPLIT_STATE_IS_READY, unitTestRCsplitState());
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(RCSplitTest, TestWifiModeChangeWithDeviceUnready)
|
|
||||||
{
|
|
||||||
memset(&testData, 0, sizeof(testData));
|
|
||||||
unitTestResetRCSplit();
|
|
||||||
testData.isRunCamSplitOpenPortSupported = true;
|
|
||||||
testData.isRunCamSplitPortConfigurated = true;
|
|
||||||
testData.maxTimesOfRespDataAvailable = 0;
|
|
||||||
|
|
||||||
bool result = rcSplitInit();
|
|
||||||
EXPECT_EQ(true, result);
|
|
||||||
|
|
||||||
// bind aux1, aux2, aux3 channel to wifi button, power button and change mode
|
|
||||||
for (uint8_t i = 0; i <= (BOXCAMERA3 - BOXCAMERA1); i++) {
|
|
||||||
memset(modeActivationConditionsMutable(i), 0, sizeof(modeActivationCondition_t));
|
|
||||||
}
|
|
||||||
|
|
||||||
// bind aux1 to wifi button with range [900,1600]
|
|
||||||
modeActivationConditionsMutable(0)->auxChannelIndex = 0;
|
|
||||||
modeActivationConditionsMutable(0)->modeId = BOXCAMERA1;
|
|
||||||
modeActivationConditionsMutable(0)->range.startStep = CHANNEL_VALUE_TO_STEP(CHANNEL_RANGE_MIN);
|
|
||||||
modeActivationConditionsMutable(0)->range.endStep = CHANNEL_VALUE_TO_STEP(1600);
|
|
||||||
|
|
||||||
// bind aux2 to power button with range [1900, 2100]
|
|
||||||
modeActivationConditionsMutable(1)->auxChannelIndex = 1;
|
|
||||||
modeActivationConditionsMutable(1)->modeId = BOXCAMERA2;
|
|
||||||
modeActivationConditionsMutable(1)->range.startStep = CHANNEL_VALUE_TO_STEP(1900);
|
|
||||||
modeActivationConditionsMutable(1)->range.endStep = CHANNEL_VALUE_TO_STEP(2100);
|
|
||||||
|
|
||||||
// bind aux3 to change mode with range [1300, 1600]
|
|
||||||
modeActivationConditionsMutable(2)->auxChannelIndex = 2;
|
|
||||||
modeActivationConditionsMutable(2)->modeId = BOXCAMERA3;
|
|
||||||
modeActivationConditionsMutable(2)->range.startStep = CHANNEL_VALUE_TO_STEP(1300);
|
|
||||||
modeActivationConditionsMutable(2)->range.endStep = CHANNEL_VALUE_TO_STEP(1600);
|
|
||||||
|
|
||||||
// make the binded mode inactive
|
|
||||||
rcData[modeActivationConditions(0)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 1800;
|
|
||||||
rcData[modeActivationConditions(1)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 900;
|
|
||||||
rcData[modeActivationConditions(2)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 900;
|
|
||||||
|
|
||||||
updateUsedModeActivationConditionFlags();
|
|
||||||
updateActivatedModes();
|
|
||||||
|
|
||||||
// runn process loop
|
|
||||||
rcSplitProcess(0);
|
|
||||||
|
|
||||||
EXPECT_EQ(false, unitTestIsSwitchActivited(BOXCAMERA1));
|
|
||||||
EXPECT_EQ(false, unitTestIsSwitchActivited(BOXCAMERA2));
|
|
||||||
EXPECT_EQ(false, unitTestIsSwitchActivited(BOXCAMERA3));
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(RCSplitTest, TestWifiModeChangeWithDeviceReady)
|
|
||||||
{
|
|
||||||
memset(&testData, 0, sizeof(testData));
|
|
||||||
unitTestResetRCSplit();
|
|
||||||
testData.isRunCamSplitOpenPortSupported = true;
|
|
||||||
testData.isRunCamSplitPortConfigurated = true;
|
|
||||||
testData.maxTimesOfRespDataAvailable = 0;
|
|
||||||
|
|
||||||
bool result = rcSplitInit();
|
|
||||||
EXPECT_EQ(true, result);
|
|
||||||
|
|
||||||
// bind aux1, aux2, aux3 channel to wifi button, power button and change mode
|
|
||||||
for (uint8_t i = 0; i <= BOXCAMERA3 - BOXCAMERA1; i++) {
|
|
||||||
memset(modeActivationConditionsMutable(i), 0, sizeof(modeActivationCondition_t));
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
// bind aux1 to wifi button with range [900,1600]
|
|
||||||
modeActivationConditionsMutable(0)->auxChannelIndex = 0;
|
|
||||||
modeActivationConditionsMutable(0)->modeId = BOXCAMERA1;
|
|
||||||
modeActivationConditionsMutable(0)->range.startStep = CHANNEL_VALUE_TO_STEP(CHANNEL_RANGE_MIN);
|
|
||||||
modeActivationConditionsMutable(0)->range.endStep = CHANNEL_VALUE_TO_STEP(1600);
|
|
||||||
|
|
||||||
// bind aux2 to power button with range [1900, 2100]
|
|
||||||
modeActivationConditionsMutable(1)->auxChannelIndex = 1;
|
|
||||||
modeActivationConditionsMutable(1)->modeId = BOXCAMERA2;
|
|
||||||
modeActivationConditionsMutable(1)->range.startStep = CHANNEL_VALUE_TO_STEP(1900);
|
|
||||||
modeActivationConditionsMutable(1)->range.endStep = CHANNEL_VALUE_TO_STEP(2100);
|
|
||||||
|
|
||||||
// bind aux3 to change mode with range [1300, 1600]
|
|
||||||
modeActivationConditionsMutable(2)->auxChannelIndex = 2;
|
|
||||||
modeActivationConditionsMutable(2)->modeId = BOXCAMERA3;
|
|
||||||
modeActivationConditionsMutable(2)->range.startStep = CHANNEL_VALUE_TO_STEP(1900);
|
|
||||||
modeActivationConditionsMutable(2)->range.endStep = CHANNEL_VALUE_TO_STEP(2100);
|
|
||||||
|
|
||||||
rcData[modeActivationConditions(0)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 1700;
|
|
||||||
rcData[modeActivationConditions(1)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 2000;
|
|
||||||
rcData[modeActivationConditions(2)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 1700;
|
|
||||||
|
|
||||||
updateUsedModeActivationConditionFlags();
|
|
||||||
updateActivatedModes();
|
|
||||||
|
|
||||||
// runn process loop
|
|
||||||
int8_t randNum = rand() % 127 + 6;
|
|
||||||
testData.maxTimesOfRespDataAvailable = randNum;
|
|
||||||
rcSplitProcess((timeUs_t)0);
|
|
||||||
|
|
||||||
EXPECT_EQ(RCSPLIT_STATE_IS_READY, unitTestRCsplitState());
|
|
||||||
|
|
||||||
EXPECT_EQ(false, unitTestIsSwitchActivited(BOXCAMERA1));
|
|
||||||
EXPECT_EQ(true, unitTestIsSwitchActivited(BOXCAMERA2));
|
|
||||||
EXPECT_EQ(false, unitTestIsSwitchActivited(BOXCAMERA3));
|
|
||||||
}
|
|
||||||
|
|
||||||
TEST(RCSplitTest, TestWifiModeChangeCombine)
|
|
||||||
{
|
|
||||||
memset(&testData, 0, sizeof(testData));
|
|
||||||
unitTestResetRCSplit();
|
|
||||||
testData.isRunCamSplitOpenPortSupported = true;
|
|
||||||
testData.isRunCamSplitPortConfigurated = true;
|
|
||||||
testData.maxTimesOfRespDataAvailable = 0;
|
|
||||||
|
|
||||||
bool result = rcSplitInit();
|
|
||||||
EXPECT_EQ(true, result);
|
|
||||||
|
|
||||||
// bind aux1, aux2, aux3 channel to wifi button, power button and change mode
|
|
||||||
for (uint8_t i = 0; i <= BOXCAMERA3 - BOXCAMERA1; i++) {
|
|
||||||
memset(modeActivationConditionsMutable(i), 0, sizeof(modeActivationCondition_t));
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
// bind aux1 to wifi button with range [900,1600]
|
|
||||||
modeActivationConditionsMutable(0)->auxChannelIndex = 0;
|
|
||||||
modeActivationConditionsMutable(0)->modeId = BOXCAMERA1;
|
|
||||||
modeActivationConditionsMutable(0)->range.startStep = CHANNEL_VALUE_TO_STEP(CHANNEL_RANGE_MIN);
|
|
||||||
modeActivationConditionsMutable(0)->range.endStep = CHANNEL_VALUE_TO_STEP(1600);
|
|
||||||
|
|
||||||
// bind aux2 to power button with range [1900, 2100]
|
|
||||||
modeActivationConditionsMutable(1)->auxChannelIndex = 1;
|
|
||||||
modeActivationConditionsMutable(1)->modeId = BOXCAMERA2;
|
|
||||||
modeActivationConditionsMutable(1)->range.startStep = CHANNEL_VALUE_TO_STEP(1900);
|
|
||||||
modeActivationConditionsMutable(1)->range.endStep = CHANNEL_VALUE_TO_STEP(2100);
|
|
||||||
|
|
||||||
// bind aux3 to change mode with range [1300, 1600]
|
|
||||||
modeActivationConditionsMutable(2)->auxChannelIndex = 2;
|
|
||||||
modeActivationConditionsMutable(2)->modeId = BOXCAMERA3;
|
|
||||||
modeActivationConditionsMutable(2)->range.startStep = CHANNEL_VALUE_TO_STEP(1900);
|
|
||||||
modeActivationConditionsMutable(2)->range.endStep = CHANNEL_VALUE_TO_STEP(2100);
|
|
||||||
|
|
||||||
// // make the binded mode inactive
|
|
||||||
rcData[modeActivationConditions(0)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 1700;
|
|
||||||
rcData[modeActivationConditions(1)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 2000;
|
|
||||||
rcData[modeActivationConditions(2)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 1700;
|
|
||||||
|
|
||||||
updateUsedModeActivationConditionFlags();
|
|
||||||
updateActivatedModes();
|
|
||||||
|
|
||||||
// runn process loop
|
|
||||||
int8_t randNum = rand() % 127 + 6;
|
|
||||||
testData.maxTimesOfRespDataAvailable = randNum;
|
|
||||||
rcSplitProcess((timeUs_t)0);
|
|
||||||
|
|
||||||
EXPECT_EQ(RCSPLIT_STATE_IS_READY, unitTestRCsplitState());
|
|
||||||
|
|
||||||
EXPECT_EQ(false, unitTestIsSwitchActivited(BOXCAMERA1));
|
|
||||||
EXPECT_EQ(true, unitTestIsSwitchActivited(BOXCAMERA2));
|
|
||||||
EXPECT_EQ(false, unitTestIsSwitchActivited(BOXCAMERA3));
|
|
||||||
|
|
||||||
|
|
||||||
// // make the binded mode inactive
|
|
||||||
rcData[modeActivationConditions(0)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 1500;
|
|
||||||
rcData[modeActivationConditions(1)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 1300;
|
|
||||||
rcData[modeActivationConditions(2)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 1900;
|
|
||||||
updateUsedModeActivationConditionFlags();
|
|
||||||
updateActivatedModes();
|
|
||||||
rcSplitProcess((timeUs_t)0);
|
|
||||||
EXPECT_EQ(true, unitTestIsSwitchActivited(BOXCAMERA1));
|
|
||||||
EXPECT_EQ(false, unitTestIsSwitchActivited(BOXCAMERA2));
|
|
||||||
EXPECT_EQ(true, unitTestIsSwitchActivited(BOXCAMERA3));
|
|
||||||
|
|
||||||
|
|
||||||
rcData[modeActivationConditions(2)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 1899;
|
|
||||||
updateUsedModeActivationConditionFlags();
|
|
||||||
updateActivatedModes();
|
|
||||||
rcSplitProcess((timeUs_t)0);
|
|
||||||
EXPECT_EQ(false, unitTestIsSwitchActivited(BOXCAMERA3));
|
|
||||||
|
|
||||||
rcData[modeActivationConditions(1)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 2001;
|
|
||||||
updateUsedModeActivationConditionFlags();
|
|
||||||
updateActivatedModes();
|
|
||||||
rcSplitProcess((timeUs_t)0);
|
|
||||||
EXPECT_EQ(true, unitTestIsSwitchActivited(BOXCAMERA1));
|
|
||||||
EXPECT_EQ(true, unitTestIsSwitchActivited(BOXCAMERA2));
|
|
||||||
EXPECT_EQ(false, unitTestIsSwitchActivited(BOXCAMERA3));
|
|
||||||
}
|
|
||||||
|
|
||||||
extern "C" {
|
|
||||||
serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
UNUSED(identifier);
|
|
||||||
UNUSED(functionMask);
|
|
||||||
UNUSED(baudRate);
|
|
||||||
UNUSED(callback);
|
|
||||||
UNUSED(mode);
|
|
||||||
UNUSED(options);
|
|
||||||
|
|
||||||
if (testData.isRunCamSplitOpenPortSupported) {
|
|
||||||
static serialPort_t s;
|
|
||||||
s.vTable = NULL;
|
|
||||||
|
|
||||||
// common serial initialisation code should move to serialPort::init()
|
|
||||||
s.rxBufferHead = s.rxBufferTail = 0;
|
|
||||||
s.txBufferHead = s.txBufferTail = 0;
|
|
||||||
s.rxBufferSize = 0;
|
|
||||||
s.txBufferSize = 0;
|
|
||||||
s.rxBuffer = s.rxBuffer;
|
|
||||||
s.txBuffer = s.txBuffer;
|
|
||||||
|
|
||||||
// callback works for IRQ-based RX ONLY
|
|
||||||
s.rxCallback = NULL;
|
|
||||||
s.baudRate = 0;
|
|
||||||
|
|
||||||
return (serialPort_t *)&s;
|
|
||||||
}
|
|
||||||
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
|
|
||||||
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
|
|
||||||
{
|
|
||||||
UNUSED(function);
|
|
||||||
if (testData.isRunCamSplitPortConfigurated) {
|
|
||||||
static serialPortConfig_t portConfig;
|
|
||||||
|
|
||||||
portConfig.identifier = SERIAL_PORT_USART3;
|
|
||||||
portConfig.msp_baudrateIndex = BAUD_115200;
|
|
||||||
portConfig.gps_baudrateIndex = BAUD_57600;
|
|
||||||
portConfig.telemetry_baudrateIndex = BAUD_AUTO;
|
|
||||||
portConfig.peripheral_baudrateIndex = BAUD_115200;
|
|
||||||
portConfig.functionMask = FUNCTION_MSP;
|
|
||||||
|
|
||||||
return &portConfig;
|
|
||||||
}
|
|
||||||
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t serialRxBytesWaiting(const serialPort_t *instance)
|
|
||||||
{
|
|
||||||
UNUSED(instance);
|
|
||||||
|
|
||||||
testData.maxTimesOfRespDataAvailable--;
|
|
||||||
if (testData.maxTimesOfRespDataAvailable > 0) {
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t serialRead(serialPort_t *instance)
|
|
||||||
{
|
|
||||||
UNUSED(instance);
|
|
||||||
|
|
||||||
if (testData.maxTimesOfRespDataAvailable > 0) {
|
|
||||||
static uint8_t i = 0;
|
|
||||||
static uint8_t buffer[] = { 0x55, 0x01, 0xFF, 0xad, 0xaa };
|
|
||||||
|
|
||||||
if (i >= 5) {
|
|
||||||
i = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
return buffer[i++];
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
void sbufWriteString(sbuf_t *dst, const char *string)
|
|
||||||
{
|
|
||||||
UNUSED(dst); UNUSED(string);
|
|
||||||
|
|
||||||
if (testData.isAllowBufferReadWrite) {
|
|
||||||
sbufWriteData(dst, string, strlen(string));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
void sbufWriteU8(sbuf_t *dst, uint8_t val)
|
|
||||||
{
|
|
||||||
UNUSED(dst); UNUSED(val);
|
|
||||||
|
|
||||||
if (testData.isAllowBufferReadWrite) {
|
|
||||||
*dst->ptr++ = val;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void sbufWriteData(sbuf_t *dst, const void *data, int len)
|
|
||||||
{
|
|
||||||
UNUSED(dst); UNUSED(data); UNUSED(len);
|
|
||||||
|
|
||||||
if (testData.isAllowBufferReadWrite) {
|
|
||||||
memcpy(dst->ptr, data, len);
|
|
||||||
dst->ptr += len;
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// modifies streambuf so that written data are prepared for reading
|
|
||||||
void sbufSwitchToReader(sbuf_t *buf, uint8_t *base)
|
|
||||||
{
|
|
||||||
UNUSED(buf); UNUSED(base);
|
|
||||||
|
|
||||||
if (testData.isAllowBufferReadWrite) {
|
|
||||||
buf->end = buf->ptr;
|
|
||||||
buf->ptr = base;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
bool feature(uint32_t) { return false;}
|
|
||||||
void serialWriteBuf(serialPort_t *instance, const uint8_t *data, int count) { UNUSED(instance); UNUSED(data); UNUSED(count); }
|
|
||||||
|
|
||||||
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired) { UNUSED(calibrationCyclesRequired); }
|
|
||||||
void applyAndSaveBoardAlignmentDelta(int16_t roll, int16_t pitch) { UNUSED(roll); UNUSED(pitch); }
|
|
||||||
|
|
||||||
uint16_t armingFlags = 0;
|
|
||||||
void beeper(beeperMode_e) {}
|
|
||||||
bool failsafeIsActive(void) { return false; }
|
|
||||||
void gyroSetCalibrationCycles(uint16_t calibrationCyclesRequired) { UNUSED(calibrationCyclesRequired); };
|
|
||||||
timeMs_t millis(void) { return 0; }
|
|
||||||
void mwArm(void) {}
|
|
||||||
void mwDisarm(void) {}
|
|
||||||
|
|
||||||
void saveConfigAndNotify(void) {}
|
|
||||||
void setConfigProfileAndWriteEEPROM(uint8_t profileIndex) { UNUSED(profileIndex); }
|
|
||||||
uint8_t stateFlags;
|
|
||||||
|
|
||||||
void failsafeOnRxResume(void) {}
|
|
||||||
void failsafeOnRxSuspend(uint32_t usSuspendPeriod) { UNUSED(usSuspendPeriod); }
|
|
||||||
void failsafeOnValidDataFailed(void) { }
|
|
||||||
void failsafeOnValidDataReceived(void) { }
|
|
||||||
uint32_t micros(void) { return 0; }
|
|
||||||
}
|
|
Loading…
Add table
Add a link
Reference in a new issue