mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +03:00
Change rcsplit protocol to async
This commit is contained in:
parent
713e72321b
commit
53458d4cf1
13 changed files with 517 additions and 2105 deletions
|
@ -141,12 +141,10 @@ FC_SRC = \
|
|||
io/displayport_max7456.c \
|
||||
io/displayport_msp.c \
|
||||
io/displayport_oled.c \
|
||||
io/displayport_rcdevice.c \
|
||||
io/displayport_srxl.c \
|
||||
io/displayport_crsf.c \
|
||||
io/rcdevice_cam.c \
|
||||
io/rcdevice.c \
|
||||
io/rcdevice_osd.c \
|
||||
io/gps.c \
|
||||
io/ledstrip.c \
|
||||
io/osd.c \
|
||||
|
|
|
@ -111,7 +111,6 @@
|
|||
|
||||
#include "io/beeper.h"
|
||||
#include "io/displayport_max7456.h"
|
||||
#include "io/displayport_rcdevice.h"
|
||||
#include "io/displayport_srxl.h"
|
||||
#include "io/displayport_crsf.h"
|
||||
#include "io/serial.h"
|
||||
|
|
|
@ -591,7 +591,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
[TASK_RCDEVICE] = {
|
||||
.taskName = "RCDEVICE",
|
||||
.taskFunc = rcdeviceUpdate,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(10), // 10 Hz, 100ms
|
||||
.desiredPeriod = TASK_PERIOD_HZ(20), // 10 Hz, 100ms
|
||||
.staticPriority = TASK_PRIORITY_MEDIUM,
|
||||
},
|
||||
#endif
|
||||
|
|
|
@ -1,65 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software 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 and Betaflight are distributed in the hope that they
|
||||
* 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 this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_RCDEVICE
|
||||
|
||||
#include "drivers/display.h"
|
||||
|
||||
#include "io/rcdevice.h"
|
||||
#include "io/rcdevice_osd.h"
|
||||
|
||||
#include "pg/vcd.h"
|
||||
|
||||
#include "displayport_rcdevice.h"
|
||||
|
||||
displayPort_t rcdeviceOSDDisplayPort;
|
||||
|
||||
static const displayPortVTable_t rcdeviceOSDVTable = {
|
||||
.grab = rcdeviceOSDGrab,
|
||||
.release = rcdeviceOSDRelease,
|
||||
.clearScreen = rcdeviceOSDClearScreen,
|
||||
.drawScreen = rcdeviceOSDDrawScreen,
|
||||
.writeString = rcdeviceOSDWriteString,
|
||||
.writeChar = rcdeviceOSDWriteChar,
|
||||
.isTransferInProgress = rcdeviceOSDIsTransferInProgress,
|
||||
.heartbeat = rcdeviceOSDHeartbeat,
|
||||
.resync = rcdeviceOSDResync,
|
||||
.isSynced = rcdeviceOSDIsSynced,
|
||||
.txBytesFree = rcdeviceOSDTxBytesFree,
|
||||
.screenSize = rcdeviceScreenSize,
|
||||
};
|
||||
|
||||
displayPort_t *rcdeviceDisplayPortInit(const vcdProfile_t *vcdProfile)
|
||||
{
|
||||
if (rcdeviceOSDInit(vcdProfile)) {
|
||||
displayInit(&rcdeviceOSDDisplayPort, &rcdeviceOSDVTable);
|
||||
rcdeviceOSDResync(&rcdeviceOSDDisplayPort);
|
||||
return &rcdeviceOSDDisplayPort;
|
||||
} else {
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // defined(USE_RCDEVICE)
|
|
@ -1,24 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software 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 and Betaflight are distributed in the hope that they
|
||||
* 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 this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
struct vcdProfile_s;
|
||||
displayPort_t *rcdeviceDisplayPortInit(const struct vcdProfile_s *vcdProfile);
|
|
@ -32,13 +32,10 @@
|
|||
|
||||
#include "rcdevice.h"
|
||||
|
||||
#ifdef USE_RCDEVICE
|
||||
#include "fc/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
typedef enum {
|
||||
RCDP_SETTING_PARSE_WAITING_ID,
|
||||
RCDP_SETTING_PARSE_WAITING_NAME,
|
||||
RCDP_SETTING_PARSE_WAITING_VALUE,
|
||||
} runcamDeviceSettingParseStep_e;
|
||||
#ifdef USE_RCDEVICE
|
||||
|
||||
typedef struct runcamDeviceExpectedResponseLength_s {
|
||||
uint8_t command;
|
||||
|
@ -46,16 +43,15 @@ typedef struct runcamDeviceExpectedResponseLength_s {
|
|||
} runcamDeviceExpectedResponseLength_t;
|
||||
|
||||
static runcamDeviceExpectedResponseLength_t expectedResponsesLength[] = {
|
||||
{ RCDEVICE_PROTOCOL_COMMAND_GET_SETTINGS, 0xFF},
|
||||
{ RCDEVICE_PROTOCOL_COMMAND_READ_SETTING_DETAIL, 0xFF},
|
||||
{ RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO, 5},
|
||||
{ RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS, 2},
|
||||
{ RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE, 2},
|
||||
{ RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION, 3},
|
||||
{ RCDEVICE_PROTOCOL_COMMAND_WRITE_SETTING, 4},
|
||||
};
|
||||
|
||||
static uint8_t runcamDeviceGetResponseLength(uint8_t command)
|
||||
rcdeviceWaitingResponseQueue watingResponseQueue;
|
||||
|
||||
static uint8_t runcamDeviceGetRespLen(uint8_t command)
|
||||
{
|
||||
for (unsigned int i = 0; i < ARRAYLEN(expectedResponsesLength); i++) {
|
||||
if (expectedResponsesLength[i].command == command) {
|
||||
|
@ -66,76 +62,49 @@ static uint8_t runcamDeviceGetResponseLength(uint8_t command)
|
|||
return 0;
|
||||
}
|
||||
|
||||
// Verify the response data has received done, return true if the data is still receiving or it was received done.
|
||||
// return false if the packet has incorrect
|
||||
static uint8_t runcamDeviceIsResponseReceiveDone(uint8_t command, uint8_t *data, uint8_t dataLen, bool *isDone)
|
||||
static bool rcdeviceRespCtxQueuePushRespCtx(rcdeviceWaitingResponseQueue *queue, rcdeviceResponseParseContext_t *respCtx)
|
||||
{
|
||||
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) {
|
||||
if (queue == NULL || (queue->itemCount + 1) > MAX_WAITING_RESPONSES || queue->tailPos >= MAX_WAITING_RESPONSES) {
|
||||
return false;
|
||||
}
|
||||
} else if (dataLen >= expectedResponseDataLength) {
|
||||
*isDone = true;
|
||||
return true;
|
||||
|
||||
queue->buffer[queue->tailPos] = *respCtx;
|
||||
|
||||
int newTailPos = queue->tailPos + 1;
|
||||
if (newTailPos >= MAX_WAITING_RESPONSES) {
|
||||
newTailPos = 0;
|
||||
}
|
||||
queue->itemCount += 1;
|
||||
queue->tailPos = newTailPos;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// a common way to receive packet and verify it
|
||||
static uint8_t runcamDeviceReceivePacket(runcamDevice_t *device, uint8_t command, uint8_t *data, int timeoutms)
|
||||
static rcdeviceResponseParseContext_t* rcdeviceRespCtxQueuePeekFront(rcdeviceWaitingResponseQueue *queue)
|
||||
{
|
||||
uint8_t dataPos = 0;
|
||||
uint8_t crc = 0;
|
||||
uint8_t responseDataLen = 0;
|
||||
|
||||
// wait for reply until timeout(specialy by timeoutms)
|
||||
timeMs_t timeout = millis() + timeoutms;
|
||||
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 (queue == NULL || queue->itemCount == 0 || queue->headPos >= MAX_WAITING_RESPONSES) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
if (isDone) {
|
||||
responseDataLen = dataPos;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
rcdeviceResponseParseContext_t *ctx = &queue->buffer[queue->headPos];
|
||||
return ctx;
|
||||
}
|
||||
|
||||
// check crc
|
||||
if (crc != 0) {
|
||||
return 0;
|
||||
static rcdeviceResponseParseContext_t* rcdeviceRespCtxQueueShift(rcdeviceWaitingResponseQueue *queue)
|
||||
{
|
||||
if (queue == NULL || queue->itemCount == 0 || queue->headPos >= MAX_WAITING_RESPONSES) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
return responseDataLen;
|
||||
rcdeviceResponseParseContext_t *ctx = &queue->buffer[queue->headPos];
|
||||
int newHeadPos = queue->headPos + 1;
|
||||
if (newHeadPos >= MAX_WAITING_RESPONSES) {
|
||||
newHeadPos = 0;
|
||||
}
|
||||
queue->itemCount -= 1;
|
||||
queue->headPos = newHeadPos;
|
||||
|
||||
return ctx;
|
||||
}
|
||||
|
||||
// every time send packet to device, and want to get something from device,
|
||||
|
@ -180,39 +149,27 @@ static void runcamDeviceSendPacket(runcamDevice_t *device, uint8_t command, uint
|
|||
}
|
||||
|
||||
// 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)
|
||||
static void runcamDeviceSendRequestAndWaitingResp(runcamDevice_t *device, uint8_t commandID, uint8_t *paramData, uint8_t paramDataLen, timeUs_t tiemout, int maxRetryTimes, void *userInfo, rcdeviceRespParseFunc parseFunc)
|
||||
{
|
||||
int max_retries = 1;
|
||||
// here using 1000ms as timeout, because the response from 5 key simulation command need a long time about >= 600ms,
|
||||
// so set a max value to ensure we can receive the response
|
||||
int timeoutMs = 1000;
|
||||
|
||||
// only the command sending on initializing step need retry logic,
|
||||
// otherwise, the timeout of 1000 ms is enough for the response from device
|
||||
if (commandID == RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO) {
|
||||
max_retries = 5;
|
||||
timeoutMs = 60; // we have test some device, 60ms as timeout, and retry times be 5, it's stable for most case
|
||||
}
|
||||
|
||||
for (int i = 0; i < max_retries; i++) {
|
||||
// flush rx buffer
|
||||
runcamDeviceFlushRxBuffer(device);
|
||||
|
||||
rcdeviceResponseParseContext_t responseCtx;
|
||||
memset(&responseCtx, 0, sizeof(rcdeviceResponseParseContext_t));
|
||||
responseCtx.command = commandID;
|
||||
responseCtx.maxRetryTimes = maxRetryTimes;
|
||||
responseCtx.expectedRespLen = runcamDeviceGetRespLen(commandID);
|
||||
responseCtx.timeout = tiemout;
|
||||
responseCtx.timeoutTimestamp = millis() + tiemout;
|
||||
responseCtx.parserFunc = parseFunc;
|
||||
responseCtx.device = device;
|
||||
responseCtx.protocolVer = RCDEVICE_PROTOCOL_VERSION_1_0;
|
||||
memcpy(responseCtx.paramData, paramData, paramDataLen);
|
||||
responseCtx.paramDataLen = paramDataLen;
|
||||
responseCtx.userInfo = userInfo;
|
||||
rcdeviceRespCtxQueuePushRespCtx(&watingResponseQueue, &responseCtx);
|
||||
|
||||
// send packet
|
||||
runcamDeviceSendPacket(device, commandID, paramData, paramDataLen);
|
||||
|
||||
// waiting response
|
||||
uint8_t responseLength = runcamDeviceReceivePacket(device, commandID, outputBuffer, timeoutMs);
|
||||
if (responseLength) {
|
||||
if (outputBufferLen) {
|
||||
*outputBufferLen = responseLength;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
static uint8_t calcCRCFromData(uint8_t *ptr, uint8_t len)
|
||||
|
@ -232,110 +189,40 @@ static uint8_t calcCRCFromData(uint8_t *ptr, uint8_t len)
|
|||
return crc;
|
||||
}
|
||||
|
||||
static void sendCtrlCommand(runcamDevice_t *device, rcsplit_ctrl_argument_e argument)
|
||||
static void runcamDeviceParseV2DeviceInfo(rcdeviceResponseParseContext_t *ctx)
|
||||
{
|
||||
if (!device->serialPort) {
|
||||
if (ctx->result != RCDEVICE_RESP_SUCCESS) {
|
||||
ctx->device->isReady = false;
|
||||
return;
|
||||
}
|
||||
runcamDevice_t *device = ctx->device;
|
||||
device->info.protocolVersion = ctx->recvBuf[1];
|
||||
|
||||
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 = calcCRCFromData(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(device->serialPort, uart_buffer, 5);
|
||||
uint8_t featureLowBits = ctx->recvBuf[2];
|
||||
uint8_t featureHighBits = ctx->recvBuf[3];
|
||||
device->info.features = (featureHighBits << 8) | featureLowBits;
|
||||
device->isReady = true;
|
||||
}
|
||||
|
||||
// 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)
|
||||
static void runcamDeviceGetDeviceInfo(runcamDevice_t *device)
|
||||
{
|
||||
// Send "who are you" command to device to detect the device whether is running RCSplit FW1.0 or RCSplit FW1.1
|
||||
int max_retries = 2;
|
||||
for (int i = 0; i < max_retries; i++) {
|
||||
runcamDeviceFlushRxBuffer(device);
|
||||
sendCtrlCommand(device, RCSPLIT_CTRL_ARGU_WHO_ARE_YOU);
|
||||
|
||||
timeMs_t timeout = millis() + 500;
|
||||
uint8_t response[5] = { 0 };
|
||||
while (millis() < timeout) {
|
||||
if (serialRxBytesWaiting(device->serialPort) >= 5) {
|
||||
response[0] = serialRead(device->serialPort);
|
||||
response[1] = serialRead(device->serialPort);
|
||||
response[2] = serialRead(device->serialPort);
|
||||
response[3] = serialRead(device->serialPort);
|
||||
response[4] = serialRead(device->serialPort);
|
||||
if (response[0] != RCSPLIT_PACKET_HEADER || response[1] != RCSPLIT_PACKET_CMD_CTRL || response[2] != RCSPLIT_CTRL_ARGU_WHO_ARE_YOU || response[4] != RCSPLIT_PACKET_TAIL) {
|
||||
break;
|
||||
runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO, NULL, 0, 5000, 0, NULL, runcamDeviceParseV2DeviceInfo);
|
||||
}
|
||||
|
||||
uint8_t crcFromPacket = response[3];
|
||||
response[3] = response[4]; // move packet tail field to crc field, and calc crc with first 4 bytes
|
||||
uint8_t crc = calcCRCFromData(response, 4);
|
||||
if (crc != crcFromPacket) {
|
||||
break;
|
||||
}
|
||||
|
||||
// generate response for RCSplit FW 1.0 and FW 1.1
|
||||
outputBuffer[0] = RCDEVICE_PROTOCOL_HEADER;
|
||||
// protocol version
|
||||
outputBuffer[1] = RCDEVICE_PROTOCOL_RCSPLIT_VERSION;
|
||||
// features
|
||||
outputBuffer[2] = RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON | RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON | RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE;
|
||||
outputBuffer[3] = 0;
|
||||
|
||||
crc = 0;
|
||||
const uint8_t * const end = outputBuffer + 4;
|
||||
for (const uint8_t *ptr = outputBuffer; ptr < end; ++ptr) {
|
||||
crc = crc8_dvb_s2(crc, *ptr);
|
||||
}
|
||||
outputBuffer[4] = crc;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
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)
|
||||
static void runcamDeviceSend5KeyOSDCableConnectionEvent(runcamDevice_t *device, uint8_t operation, rcdeviceRespParseFunc parseFunc)
|
||||
{
|
||||
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;
|
||||
runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION, &operation, sizeof(uint8_t), 200, 1, NULL, parseFunc);
|
||||
}
|
||||
|
||||
// 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)
|
||||
void runcamDeviceInit(runcamDevice_t *device)
|
||||
{
|
||||
device->isReady = false;
|
||||
serialPortFunction_e portID = FUNCTION_RCDEVICE;
|
||||
serialPortConfig_t *portConfig = findSerialPortConfig(portID);
|
||||
if (portConfig != NULL) {
|
||||
|
@ -344,30 +231,14 @@ bool runcamDeviceInit(runcamDevice_t *device)
|
|||
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);
|
||||
runcamDeviceGetDeviceInfo(device);
|
||||
}
|
||||
}
|
||||
|
||||
device->serialPort = NULL;
|
||||
return false;
|
||||
}
|
||||
|
||||
bool runcamDeviceSimulateCameraButton(runcamDevice_t *device, uint8_t operation)
|
||||
{
|
||||
if (device->info.protocolVersion == RCDEVICE_PROTOCOL_RCSPLIT_VERSION) {
|
||||
sendCtrlCommand(device, operation + 1);
|
||||
} else if (device->info.protocolVersion == RCDEVICE_PROTOCOL_VERSION_1_0) {
|
||||
if (device->info.protocolVersion == RCDEVICE_PROTOCOL_VERSION_1_0) {
|
||||
runcamDeviceSendPacket(device, RCDEVICE_PROTOCOL_COMMAND_CAMERA_CONTROL, &operation, sizeof(operation));
|
||||
} else {
|
||||
return false;
|
||||
|
@ -378,392 +249,95 @@ bool runcamDeviceSimulateCameraButton(runcamDevice_t *device, uint8_t operation)
|
|||
|
||||
// every time start to control the OSD menu of camera, must call this method to
|
||||
// camera
|
||||
bool runcamDeviceOpen5KeyOSDCableConnection(runcamDevice_t *device)
|
||||
void runcamDeviceOpen5KeyOSDCableConnection(runcamDevice_t *device, rcdeviceRespParseFunc parseFunc)
|
||||
{
|
||||
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);
|
||||
runcamDeviceSend5KeyOSDCableConnectionEvent(device, RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN, parseFunc);
|
||||
}
|
||||
|
||||
// when the control was stop, must call this method to the camera to disconnect
|
||||
// with camera.
|
||||
bool runcamDeviceClose5KeyOSDCableConnection(runcamDevice_t *device, uint8_t *resultCode)
|
||||
void runcamDeviceClose5KeyOSDCableConnection(runcamDevice_t *device, rcdeviceRespParseFunc parseFunc)
|
||||
{
|
||||
uint8_t actionID = 0xFF;
|
||||
uint8_t code = 0xFF;
|
||||
bool r = runcamDeviceSend5KeyOSDCableConnectionEvent(device, RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE, &actionID, &code);
|
||||
if (resultCode) {
|
||||
*resultCode = code;
|
||||
}
|
||||
return r;
|
||||
runcamDeviceSend5KeyOSDCableConnectionEvent(device, RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE, parseFunc);
|
||||
}
|
||||
|
||||
// simulate button press event of 5 key osd cable with special button
|
||||
bool runcamDeviceSimulate5KeyOSDCableButtonPress(runcamDevice_t *device, uint8_t operation)
|
||||
void runcamDeviceSimulate5KeyOSDCableButtonPress(runcamDevice_t *device, uint8_t operation, rcdeviceRespParseFunc parseFunc)
|
||||
{
|
||||
if (operation == RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE) {
|
||||
return false;
|
||||
return;
|
||||
}
|
||||
|
||||
if (runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS, &operation, sizeof(uint8_t), NULL, NULL)) {
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS, &operation, sizeof(uint8_t), 200, 1, NULL, parseFunc);
|
||||
}
|
||||
|
||||
// simulate button release event of 5 key osd cable
|
||||
bool runcamDeviceSimulate5KeyOSDCableButtonRelease(runcamDevice_t *device)
|
||||
void runcamDeviceSimulate5KeyOSDCableButtonRelease(runcamDevice_t *device, rcdeviceRespParseFunc parseFunc)
|
||||
{
|
||||
return runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE, NULL, 0, NULL, NULL);
|
||||
runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE, NULL, 0, 200, 1, NULL, parseFunc);
|
||||
}
|
||||
|
||||
// fill a region with same char on screen, this is used to DisplayPort feature
|
||||
// support
|
||||
void runcamDeviceDispFillRegion(runcamDevice_t *device, uint8_t x, uint8_t y, uint8_t width, uint8_t height, uint8_t c)
|
||||
static rcdeviceResponseParseContext_t* getWaitingResponse(timeUs_t currentTimeUs)
|
||||
{
|
||||
uint8_t paramsBuf[5];
|
||||
|
||||
// fill parameters buf
|
||||
paramsBuf[0] = x;
|
||||
paramsBuf[1] = y;
|
||||
paramsBuf[2] = width;
|
||||
paramsBuf[3] = height;
|
||||
paramsBuf[4] = c;
|
||||
|
||||
runcamDeviceSendPacket(device, RCDEVICE_PROTOCOL_COMMAND_DISP_FILL_REGION, paramsBuf, sizeof(paramsBuf));
|
||||
rcdeviceResponseParseContext_t *respCtx = rcdeviceRespCtxQueuePeekFront(&watingResponseQueue);
|
||||
while (respCtx != NULL && respCtx->timeoutTimestamp != 0 && currentTimeUs > respCtx->timeoutTimestamp) {
|
||||
if (respCtx->timeoutTimestamp != 0 && currentTimeUs > respCtx->timeoutTimestamp) {
|
||||
if (respCtx->maxRetryTimes > 0) {
|
||||
runcamDeviceSendPacket(respCtx->device, respCtx->command, respCtx->paramData, respCtx->paramDataLen);
|
||||
respCtx->timeoutTimestamp = currentTimeUs + respCtx->timeout;
|
||||
respCtx->maxRetryTimes -= 1;
|
||||
respCtx = NULL;
|
||||
break;
|
||||
} else {
|
||||
respCtx->result = RCDEVICE_RESP_TIMEOUT;
|
||||
if (respCtx->parserFunc != NULL) {
|
||||
respCtx->parserFunc(respCtx);
|
||||
}
|
||||
|
||||
// draw a single char on special position on screen, this is used to DisplayPort
|
||||
// feature support
|
||||
void runcamDeviceDispWriteChar(runcamDevice_t *device, uint8_t x, uint8_t y, uint8_t c)
|
||||
// dequeue and get next waiting response context
|
||||
rcdeviceRespCtxQueueShift(&watingResponseQueue);
|
||||
respCtx = rcdeviceRespCtxQueuePeekFront(&watingResponseQueue);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return respCtx;
|
||||
}
|
||||
|
||||
void rcdeviceReceive(timeUs_t currentTimeUs)
|
||||
{
|
||||
uint8_t paramsBuf[3];
|
||||
UNUSED(currentTimeUs);
|
||||
rcdeviceResponseParseContext_t *respCtx = NULL;
|
||||
while ((respCtx = getWaitingResponse(millis())) != NULL && serialRxBytesWaiting(respCtx->device->serialPort)) {
|
||||
const uint8_t c = serialRead(respCtx->device->serialPort);
|
||||
respCtx->recvBuf[respCtx->recvRespLen] = c;
|
||||
respCtx->recvRespLen += 1;
|
||||
|
||||
// fill parameters buf
|
||||
paramsBuf[0] = x;
|
||||
paramsBuf[1] = y;
|
||||
paramsBuf[2] = c;
|
||||
// if data received done, trigger callback to parse response data, and update rcdevice state
|
||||
if (respCtx->recvRespLen == respCtx->expectedRespLen) {
|
||||
// verify the crc value
|
||||
if (respCtx->protocolVer == RCDEVICE_PROTOCOL_RCSPLIT_VERSION) {
|
||||
uint8_t crcFromPacket = respCtx->recvBuf[3];
|
||||
respCtx->recvBuf[3] = respCtx->recvBuf[4]; // move packet tail field to crc field, and calc crc with first 4 bytes
|
||||
uint8_t crc = calcCRCFromData(respCtx->recvBuf, 4);
|
||||
respCtx->result = (crc == crcFromPacket) ? RCDEVICE_RESP_SUCCESS : RCDEVICE_RESP_INCORRECT_CRC;
|
||||
|
||||
runcamDeviceSendPacket(device, RCDEVICE_PROTOCOL_COMMAND_DISP_WRITE_CHAR, paramsBuf, sizeof(paramsBuf));
|
||||
} else if (respCtx->protocolVer == RCDEVICE_PROTOCOL_VERSION_1_0) {
|
||||
uint8_t crc = 0;
|
||||
for (int i = 0; i < respCtx->recvRespLen; i++) {
|
||||
crc = crc8_dvb_s2(crc, respCtx->recvBuf[i]);
|
||||
}
|
||||
respCtx->result = (crc == 0) ? RCDEVICE_RESP_SUCCESS : RCDEVICE_RESP_INCORRECT_CRC;
|
||||
}
|
||||
|
||||
static void runcamDeviceDispWriteString(runcamDevice_t *device, uint8_t x, uint8_t y, const char *text, bool isHorizontal)
|
||||
{
|
||||
uint8_t textLen = strlen(text);
|
||||
if (textLen > 60) { // if text len more then 60 chars, cut it to 60
|
||||
textLen = 60;
|
||||
if (respCtx->parserFunc != NULL) {
|
||||
respCtx->parserFunc(respCtx);
|
||||
}
|
||||
|
||||
uint8_t paramsBufLen = 3 + textLen;
|
||||
uint8_t paramsBuf[RCDEVICE_PROTOCOL_MAX_DATA_SIZE];
|
||||
|
||||
paramsBuf[0] = paramsBufLen - 1;
|
||||
paramsBuf[1] = x;
|
||||
paramsBuf[2] = y;
|
||||
memcpy(paramsBuf + 3, text, textLen);
|
||||
|
||||
uint8_t command = isHorizontal ? RCDEVICE_PROTOCOL_COMMAND_DISP_WRITE_HORIZONTAL_STRING : RCDEVICE_PROTOCOL_COMMAND_DISP_WRITE_VERTICAL_STRING;
|
||||
runcamDeviceSendPacket(device, command, paramsBuf, paramsBufLen);
|
||||
}
|
||||
|
||||
// draw a string on special position on screen, this is used to DisplayPort
|
||||
// feature support
|
||||
void runcamDeviceDispWriteHorizontalString(runcamDevice_t *device, uint8_t x, uint8_t y, const char *text)
|
||||
{
|
||||
runcamDeviceDispWriteString(device, x, y, text, true);
|
||||
}
|
||||
|
||||
void runcamDeviceDispWriteVerticalString(runcamDevice_t *device, uint8_t x, uint8_t y, const char *text)
|
||||
{
|
||||
runcamDeviceDispWriteString(device, x, y, text, false);
|
||||
}
|
||||
|
||||
void runcamDeviceDispWriteChars(runcamDevice_t *device, uint8_t *data, uint8_t datalen)
|
||||
{
|
||||
uint8_t adjustedDataLen = datalen;
|
||||
if (adjustedDataLen > 60) { // if data len more then 60 chars, cut it to 60
|
||||
adjustedDataLen = 60;
|
||||
}
|
||||
|
||||
uint8_t paramsBufLen = adjustedDataLen + 1;
|
||||
uint8_t paramsBuf[RCDEVICE_PROTOCOL_MAX_DATA_SIZE];
|
||||
|
||||
paramsBuf[0] = adjustedDataLen;
|
||||
memcpy(paramsBuf + 1, data, adjustedDataLen);
|
||||
|
||||
runcamDeviceSendPacket(device, RCDEVICE_PROTOCOL_COMMAND_DISP_WRITE_CHARS, paramsBuf, paramsBufLen);
|
||||
}
|
||||
|
||||
static bool runcamDeviceDecodeSettings(sbuf_t *buf, runcamDeviceSetting_t *outSettingList, int maxSettingItemCount)
|
||||
{
|
||||
if (outSettingList == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (maxSettingItemCount > RCDEVICE_PROTOCOL_MAX_MENUITEM_PER_PAGE)
|
||||
maxSettingItemCount = RCDEVICE_PROTOCOL_MAX_MENUITEM_PER_PAGE;
|
||||
|
||||
runcamDeviceSettingParseStep_e parseStep = RCDP_SETTING_PARSE_WAITING_ID;
|
||||
memset(outSettingList, 0, maxSettingItemCount * sizeof(runcamDeviceSetting_t));
|
||||
runcamDeviceSetting_t *settingIterator = outSettingList;
|
||||
while (sbufBytesRemaining(buf) > 0) {
|
||||
if (settingIterator >= (outSettingList + maxSettingItemCount)) {
|
||||
break;
|
||||
}
|
||||
|
||||
switch (parseStep) {
|
||||
case RCDP_SETTING_PARSE_WAITING_ID: {
|
||||
settingIterator->id = sbufReadU8(buf);
|
||||
parseStep = RCDP_SETTING_PARSE_WAITING_NAME;
|
||||
}
|
||||
break;
|
||||
case RCDP_SETTING_PARSE_WAITING_NAME: {
|
||||
const char *str = (const char *)sbufConstPtr(buf);
|
||||
uint8_t nameLen = strlen(str) + 1;
|
||||
memset(settingIterator->name, 0, RCDEVICE_PROTOCOL_MAX_SETTING_NAME_LENGTH);
|
||||
strncpy(settingIterator->name, str, RCDEVICE_PROTOCOL_MAX_SETTING_NAME_LENGTH);
|
||||
sbufAdvance(buf, nameLen);
|
||||
|
||||
parseStep = RCDP_SETTING_PARSE_WAITING_VALUE;
|
||||
}
|
||||
break;
|
||||
case RCDP_SETTING_PARSE_WAITING_VALUE: {
|
||||
const char *str = (const char *)sbufConstPtr(buf);
|
||||
uint8_t valueLen = strlen(str) + 1;
|
||||
memset(settingIterator->value, 0, RCDEVICE_PROTOCOL_MAX_SETTING_VALUE_LENGTH);
|
||||
strcpy(settingIterator->value, str);
|
||||
sbufAdvance(buf, valueLen);
|
||||
parseStep = RCDP_SETTING_PARSE_WAITING_ID;
|
||||
|
||||
settingIterator++;
|
||||
}
|
||||
break;
|
||||
// dequeue current response context
|
||||
rcdeviceRespCtxQueueShift(&watingResponseQueue);
|
||||
}
|
||||
}
|
||||
|
||||
if (RCDP_SETTING_PARSE_WAITING_ID != parseStep) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool runcamDeviceGetResponseWithMultipleChunk(runcamDevice_t *device, uint8_t command, uint8_t settingID, uint8_t *responseData, uint16_t *responseDatalen)
|
||||
{
|
||||
if (responseData == NULL || responseDatalen == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// fill parameters buf
|
||||
uint8_t paramsBuf[2];
|
||||
uint8_t chunkIndex = 0;
|
||||
paramsBuf[0] = settingID; // parent setting id
|
||||
paramsBuf[1] = chunkIndex; // chunk index
|
||||
|
||||
uint8_t outputBufLen = RCDEVICE_PROTOCOL_MAX_PACKET_SIZE;
|
||||
uint8_t outputBuf[RCDEVICE_PROTOCOL_MAX_PACKET_SIZE];
|
||||
bool result = runcamDeviceSendRequestAndWaitingResp(device, command, paramsBuf, sizeof(paramsBuf), outputBuf, &outputBufLen);
|
||||
if (!result) {
|
||||
return false;
|
||||
}
|
||||
|
||||
uint8_t remainingChunk = outputBuf[1];
|
||||
// Every response chunk count must less than or equal to RCDEVICE_PROTOCOL_MAX_CHUNK_PER_RESPONSE
|
||||
if (remainingChunk >= RCDEVICE_PROTOCOL_MAX_CHUNK_PER_RESPONSE) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// save setting data to sbuf_t object
|
||||
const uint16_t maxDataLen = RCDEVICE_PROTOCOL_MAX_CHUNK_PER_RESPONSE * RCDEVICE_PROTOCOL_MAX_DATA_SIZE;
|
||||
// uint8_t data[maxDataLen];
|
||||
sbuf_t dataBuf;
|
||||
dataBuf.ptr = responseData;
|
||||
dataBuf.end = responseData + maxDataLen;
|
||||
sbufWriteData(&dataBuf, outputBuf + 3, outputBufLen - 4);
|
||||
|
||||
// get the remaining chunks
|
||||
while (remainingChunk > 0) {
|
||||
paramsBuf[1] = ++chunkIndex; // chunk index
|
||||
|
||||
outputBufLen = RCDEVICE_PROTOCOL_MAX_PACKET_SIZE;
|
||||
result = runcamDeviceSendRequestAndWaitingResp(device, command, paramsBuf, sizeof(paramsBuf), outputBuf, &outputBufLen);
|
||||
|
||||
if (!result) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// append the trailing chunk to the sbuf_t object,
|
||||
// but only append the actually setting data
|
||||
sbufWriteData(&dataBuf, outputBuf + 3, outputBufLen - 4);
|
||||
|
||||
remainingChunk--;
|
||||
}
|
||||
|
||||
sbufSwitchToReader(&dataBuf, responseData);
|
||||
*responseDatalen = sbufBytesRemaining(&dataBuf);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// get settings with parent setting id, the type of parent setting must be a
|
||||
// FOLDER after this function called, the settings will fill into outSettingList
|
||||
// argument
|
||||
bool runcamDeviceGetSettings(runcamDevice_t *device, uint8_t parentSettingID, runcamDeviceSetting_t *outSettingList, int maxSettingItemCount)
|
||||
{
|
||||
if (outSettingList == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
uint16_t responseDataLength = 0;
|
||||
uint8_t data[RCDEVICE_PROTOCOL_MAX_CHUNK_PER_RESPONSE * RCDEVICE_PROTOCOL_MAX_DATA_SIZE];
|
||||
if (!runcamDeviceGetResponseWithMultipleChunk(device, RCDEVICE_PROTOCOL_COMMAND_GET_SETTINGS, parentSettingID, data, &responseDataLength)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
sbuf_t dataBuf;
|
||||
dataBuf.ptr = data;
|
||||
dataBuf.end = data + responseDataLength;
|
||||
|
||||
// parse the settings data and convert them into a runcamDeviceSetting_t list
|
||||
if (!runcamDeviceDecodeSettings(&dataBuf, outSettingList, maxSettingItemCount)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool runcamDeviceDecodeSettingDetail(sbuf_t *buf, runcamDeviceSettingDetail_t *outSettingDetail)
|
||||
{
|
||||
if (outSettingDetail == NULL || sbufBytesRemaining(buf) == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
rcdeviceSettingType_e settingType = sbufReadU8(buf);
|
||||
outSettingDetail->type = settingType;
|
||||
switch (settingType) {
|
||||
case RCDEVICE_PROTOCOL_SETTINGTYPE_UINT8:
|
||||
case RCDEVICE_PROTOCOL_SETTINGTYPE_INT8:
|
||||
outSettingDetail->value = sbufReadU8(buf);
|
||||
outSettingDetail->minValue = sbufReadU8(buf);
|
||||
outSettingDetail->maxValue = sbufReadU8(buf);
|
||||
outSettingDetail->stepSize = sbufReadU8(buf);
|
||||
break;
|
||||
case RCDEVICE_PROTOCOL_SETTINGTYPE_UINT16:
|
||||
case RCDEVICE_PROTOCOL_SETTINGTYPE_INT16:
|
||||
outSettingDetail->value = sbufReadU16(buf);
|
||||
outSettingDetail->minValue = sbufReadU16(buf);
|
||||
outSettingDetail->maxValue = sbufReadU16(buf);
|
||||
outSettingDetail->stepSize = sbufReadU8(buf);
|
||||
break;
|
||||
case RCDEVICE_PROTOCOL_SETTINGTYPE_FLOAT:
|
||||
outSettingDetail->value = sbufReadU32(buf);
|
||||
outSettingDetail->minValue = sbufReadU32(buf);
|
||||
outSettingDetail->maxValue = sbufReadU32(buf);
|
||||
outSettingDetail->decimalPoint = sbufReadU8(buf);
|
||||
outSettingDetail->stepSize = sbufReadU32(buf);
|
||||
break;
|
||||
case RCDEVICE_PROTOCOL_SETTINGTYPE_TEXT_SELECTION: {
|
||||
outSettingDetail->value = sbufReadU8(buf);
|
||||
|
||||
const char *tmp = (const char *)sbufConstPtr(buf);
|
||||
const uint16_t maxLen = RCDEVICE_PROTOCOL_MAX_DATA_SIZE * RCDEVICE_PROTOCOL_MAX_TEXT_SELECTIONS;
|
||||
char textSels[maxLen];
|
||||
memset(textSels, 0, maxLen);
|
||||
strncpy(textSels, tmp, maxLen);
|
||||
char delims[] = ";";
|
||||
char *result = strtok(textSels, delims);
|
||||
int i = 0;
|
||||
runcamDeviceSettingTextSelection_t *iterator = outSettingDetail->textSelections;
|
||||
while (result != NULL) {
|
||||
if (i >= RCDEVICE_PROTOCOL_MAX_TEXT_SELECTIONS) {
|
||||
break;
|
||||
}
|
||||
|
||||
memset(iterator->text, 0, RCDEVICE_PROTOCOL_MAX_SETTING_VALUE_LENGTH);
|
||||
strncpy(iterator->text, result, RCDEVICE_PROTOCOL_MAX_SETTING_VALUE_LENGTH);
|
||||
iterator++;
|
||||
result = strtok(NULL, delims);
|
||||
i++;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case RCDEVICE_PROTOCOL_SETTINGTYPE_STRING: {
|
||||
const char *tmp = (const char *)sbufConstPtr(buf);
|
||||
strncpy(outSettingDetail->stringValue, tmp, RCDEVICE_PROTOCOL_MAX_STRING_LENGTH);
|
||||
sbufAdvance(buf, strlen(tmp) + 1);
|
||||
|
||||
outSettingDetail->maxStringSize = sbufReadU8(buf);
|
||||
}
|
||||
break;
|
||||
case RCDEVICE_PROTOCOL_SETTINGTYPE_FOLDER:
|
||||
break;
|
||||
case RCDEVICE_PROTOCOL_SETTINGTYPE_INFO: {
|
||||
const char *tmp = (const char *)sbufConstPtr(buf);
|
||||
strncpy(outSettingDetail->stringValue, tmp, RCDEVICE_PROTOCOL_MAX_STRING_LENGTH);
|
||||
sbufAdvance(buf, strlen(outSettingDetail->stringValue) + 1);
|
||||
}
|
||||
break;
|
||||
case RCDEVICE_PROTOCOL_SETTINGTYPE_UNKNOWN:
|
||||
break;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// get the setting details with setting id
|
||||
// after this function called, the setting detail will fill into
|
||||
// outSettingDetail argument
|
||||
bool runcamDeviceGetSettingDetail(runcamDevice_t *device, uint8_t settingID, runcamDeviceSettingDetail_t *outSettingDetail)
|
||||
{
|
||||
if (outSettingDetail == NULL)
|
||||
return false;
|
||||
|
||||
uint16_t responseDataLength = 0;
|
||||
uint8_t data[RCDEVICE_PROTOCOL_MAX_CHUNK_PER_RESPONSE * RCDEVICE_PROTOCOL_MAX_DATA_SIZE];
|
||||
if (!runcamDeviceGetResponseWithMultipleChunk(device, RCDEVICE_PROTOCOL_COMMAND_READ_SETTING_DETAIL, settingID, data, &responseDataLength)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
sbuf_t dataBuf;
|
||||
dataBuf.ptr = data;
|
||||
dataBuf.end = data + responseDataLength;
|
||||
|
||||
// parse the settings data and convert them into a runcamDeviceSettingDetail_t
|
||||
if (!runcamDeviceDecodeSettingDetail(&dataBuf, outSettingDetail)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// write new value with to the setting
|
||||
bool runcamDeviceWriteSetting(runcamDevice_t *device, uint8_t settingID, uint8_t *paramData, uint8_t paramDataLen, runcamDeviceWriteSettingResponse_t *response)
|
||||
{
|
||||
if (response == NULL || paramDataLen > (RCDEVICE_PROTOCOL_MAX_DATA_SIZE - 1)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
memset(response, 0, sizeof(runcamDeviceWriteSettingResponse_t));
|
||||
response->resultCode = 1; // initialize the result code to failed
|
||||
|
||||
uint8_t paramsBufLen = sizeof(uint8_t) + paramDataLen;
|
||||
uint8_t paramsBuf[RCDEVICE_PROTOCOL_MAX_DATA_SIZE];
|
||||
paramsBuf[0] = settingID;
|
||||
memcpy(paramsBuf + 1, paramData, paramDataLen);
|
||||
|
||||
uint8_t outputBufLen = RCDEVICE_PROTOCOL_MAX_PACKET_SIZE;
|
||||
uint8_t outputBuf[RCDEVICE_PROTOCOL_MAX_PACKET_SIZE];
|
||||
bool result = runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_WRITE_SETTING, paramsBuf, paramsBufLen, outputBuf, &outputBufLen);
|
||||
if (!result) {
|
||||
return false;
|
||||
}
|
||||
|
||||
response->resultCode = outputBuf[1];
|
||||
response->needUpdateMenuItems = outputBuf[2];
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -29,13 +29,6 @@
|
|||
|
||||
#define RCDEVICE_PROTOCOL_MAX_PACKET_SIZE 64
|
||||
#define RCDEVICE_PROTOCOL_MAX_DATA_SIZE 62
|
||||
#define RCDEVICE_PROTOCOL_MAX_DATA_SIZE_WITH_CRC_FIELD 63
|
||||
#define RCDEVICE_PROTOCOL_MAX_MENUITEM_PER_PAGE 32
|
||||
#define RCDEVICE_PROTOCOL_MAX_SETTING_NAME_LENGTH 20
|
||||
#define RCDEVICE_PROTOCOL_MAX_SETTING_VALUE_LENGTH 20
|
||||
#define RCDEVICE_PROTOCOL_MAX_CHUNK_PER_RESPONSE 12
|
||||
#define RCDEVICE_PROTOCOL_MAX_TEXT_SELECTIONS 30
|
||||
#define RCDEVICE_PROTOCOL_MAX_STRING_LENGTH 58
|
||||
|
||||
// Commands
|
||||
#define RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO 0x00
|
||||
|
@ -45,17 +38,6 @@
|
|||
#define RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS 0x02
|
||||
#define RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE 0x03
|
||||
#define RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION 0x04
|
||||
// device setting access
|
||||
#define RCDEVICE_PROTOCOL_COMMAND_GET_SETTINGS 0x10
|
||||
#define RCDEVICE_PROTOCOL_COMMAND_READ_SETTING_DETAIL 0x11
|
||||
#define RCDEVICE_PROTOCOL_COMMAND_READ_SETTING 0x12
|
||||
#define RCDEVICE_PROTOCOL_COMMAND_WRITE_SETTING 0x13
|
||||
// display port support
|
||||
#define RCDEVICE_PROTOCOL_COMMAND_DISP_FILL_REGION 0x20
|
||||
#define RCDEVICE_PROTOCOL_COMMAND_DISP_WRITE_CHAR 0x21
|
||||
#define RCDEVICE_PROTOCOL_COMMAND_DISP_WRITE_HORIZONTAL_STRING 0x22
|
||||
#define RCDEVICE_PROTOCOL_COMMAND_DISP_WRITE_VERTICAL_STRING 0x23
|
||||
#define RCDEVICE_PROTOCOL_COMMAND_DISP_WRITE_CHARS 0x24
|
||||
|
||||
// Feature Flag sets, it's a uint16_t flag
|
||||
typedef enum {
|
||||
|
@ -63,8 +45,6 @@ typedef enum {
|
|||
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_PROTOCOL_FEATURE_DEVICE_SETTINGS_ACCESS = (1 << 4),
|
||||
RCDEVICE_PROTOCOL_FEATURE_DISPLAYP_PORT = (1 << 5),
|
||||
RCDEVICE_PROTOCOL_FEATURE_START_RECORDING = (1 << 6),
|
||||
RCDEVICE_PROTOCOL_FEATURE_STOP_RECORDING = (1 << 7),
|
||||
RCDEVICE_PROTOCOL_FEATURE_CMS_MENU = (1 << 8),
|
||||
|
@ -116,127 +96,65 @@ typedef enum {
|
|||
RCDEVICE_PROTOCOL_UNKNOWN
|
||||
} rcdevice_protocol_version_e;
|
||||
|
||||
// Reserved setting ids
|
||||
typedef enum {
|
||||
RCDEVICE_PROTOCOL_SETTINGID_DISP_CHARSET = 0, // type: text_selection, read&write, 0: use charset with betaflight logo, 1 use
|
||||
// charset with cleanflight logo, other id are not used
|
||||
RCDEVICE_PROTOCOL_SETTINGID_DISP_COLUMNS = 1, // type: uint8_t, read only, the column count of the OSD layer
|
||||
RCDEVICE_PROTOCOL_SETTINGID_DISP_TV_MODE = 2, // type: text_selection, read&write, 0:NTSC, 1:PAL
|
||||
RCDEVICE_PROTOCOL_SETTINGID_SDCARD_CAPACITY = 3, // type: info, read only, return sd card capacity
|
||||
RCDEVICE_PROTOCOL_SETTINGID_REMAINING_RECORDING_TIME = 4, // type: info, read only, return remaining recording time
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESOLUTION = 5, // type: text selection, read&write, return the current resolution and all available resolutions
|
||||
RCDEVICE_PROTOCOL_SETTINGID_CAMERA_TIME = 6, // type: string, read&write, update the camera time, the time attribute of medias file in camera will use this time.
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED7 = 7,
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED8 = 8,
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED9 = 9,
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED10 = 10,
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED11 = 11,
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED12 = 12,
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED13 = 13,
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED14 = 14,
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED15 = 15,
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED16 = 16,
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED17 = 17,
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED18 = 18,
|
||||
RCDEVICE_PROTOCOL_SETTINGID_RESERVED19 = 19,
|
||||
} rcdeviceReservedSettingID_e;
|
||||
|
||||
typedef enum {
|
||||
RCDEVICE_PROTOCOL_SETTINGTYPE_UINT8 = 0,
|
||||
RCDEVICE_PROTOCOL_SETTINGTYPE_INT8 = 1,
|
||||
RCDEVICE_PROTOCOL_SETTINGTYPE_UINT16 = 2,
|
||||
RCDEVICE_PROTOCOL_SETTINGTYPE_INT16 = 3,
|
||||
RCDEVICE_PROTOCOL_SETTINGTYPE_FLOAT = 8,
|
||||
RCDEVICE_PROTOCOL_SETTINGTYPE_TEXT_SELECTION = 9,
|
||||
RCDEVICE_PROTOCOL_SETTINGTYPE_STRING = 10,
|
||||
RCDEVICE_PROTOCOL_SETTINGTYPE_FOLDER = 11,
|
||||
RCDEVICE_PROTOCOL_SETTINGTYPE_INFO = 12,
|
||||
RCDEVICE_PROTOCOL_SETTINGTYPE_UNKNOWN
|
||||
} rcdeviceSettingType_e;
|
||||
|
||||
typedef enum {
|
||||
RCDEVICE_SUCCEED = 0,
|
||||
RCDEVICE_INVALID = 1,
|
||||
RCDEVICE_NODEV = 2,
|
||||
RCDEVICE_DEVBUSY = 3,
|
||||
} rcdeviceErrorCode_e;
|
||||
|
||||
// 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 runcamDeviceSetting_s {
|
||||
uint8_t id;
|
||||
char name[RCDEVICE_PROTOCOL_MAX_SETTING_NAME_LENGTH];
|
||||
char value[RCDEVICE_PROTOCOL_MAX_SETTING_VALUE_LENGTH];
|
||||
} runcamDeviceSetting_t;
|
||||
|
||||
typedef struct runcamDeviceSettingTextSelection_s {
|
||||
char text[RCDEVICE_PROTOCOL_MAX_SETTING_VALUE_LENGTH];
|
||||
} runcamDeviceSettingTextSelection_t;
|
||||
|
||||
typedef struct runcamDeviceSettingDetail_s {
|
||||
uint8_t type;
|
||||
uint32_t value;
|
||||
uint32_t minValue;
|
||||
uint32_t maxValue;
|
||||
uint8_t decimalPoint;
|
||||
uint32_t stepSize;
|
||||
uint8_t maxStringSize;
|
||||
char stringValue[RCDEVICE_PROTOCOL_MAX_STRING_LENGTH]; // when settingType is RCDEVICE_PROTOCOL_SETTINGTYPE_INFO or RCDEVICE_PROTOCOL_SETTINGTYPE_STRING, this field store the string/info value;
|
||||
runcamDeviceSettingTextSelection_t textSelections[RCDEVICE_PROTOCOL_MAX_TEXT_SELECTIONS];
|
||||
} runcamDeviceSettingDetail_t;
|
||||
|
||||
typedef struct runcamDeviceWriteSettingResponse_s {
|
||||
uint8_t resultCode;
|
||||
uint8_t needUpdateMenuItems;
|
||||
} runcamDeviceWriteSettingResponse_t;
|
||||
|
||||
typedef struct runcamDevice_s {
|
||||
serialPort_t *serialPort;
|
||||
uint8_t buffer[RCDEVICE_PROTOCOL_MAX_PACKET_SIZE];
|
||||
runcamDeviceInfo_t info;
|
||||
bool isReady;
|
||||
} runcamDevice_t;
|
||||
|
||||
bool runcamDeviceInit(runcamDevice_t *device);
|
||||
#define MAX_WAITING_RESPONSES 20
|
||||
|
||||
typedef enum {
|
||||
RCDEVICE_RESP_SUCCESS = 0,
|
||||
RCDEVICE_RESP_INCORRECT_CRC = 1,
|
||||
RCDEVICE_RESP_TIMEOUT = 2
|
||||
} rcdeviceResponseStatus_e;
|
||||
|
||||
typedef struct rcdeviceResponseParseContext_s rcdeviceResponseParseContext_t;
|
||||
typedef void(*rcdeviceRespParseFunc)(rcdeviceResponseParseContext_t*);
|
||||
struct rcdeviceResponseParseContext_s {
|
||||
uint8_t command;
|
||||
uint8_t expectedRespLen; // total length of response data
|
||||
uint8_t recvRespLen; // length of the data received
|
||||
uint8_t recvBuf[RCDEVICE_PROTOCOL_MAX_PACKET_SIZE]; // response data buffer
|
||||
timeUs_t timeout;
|
||||
timeUs_t timeoutTimestamp; // if zero, it's means keep waiting for the response
|
||||
rcdeviceRespParseFunc parserFunc;
|
||||
runcamDevice_t *device;
|
||||
uint8_t paramData[RCDEVICE_PROTOCOL_MAX_DATA_SIZE];
|
||||
uint8_t paramDataLen;
|
||||
uint8_t protocolVer;
|
||||
int maxRetryTimes;
|
||||
void *userInfo;
|
||||
rcdeviceResponseStatus_e result;
|
||||
};
|
||||
|
||||
typedef struct {
|
||||
uint8_t headPos; // current head position of the queue
|
||||
uint8_t tailPos;
|
||||
uint8_t itemCount; // the item count in the queue
|
||||
rcdeviceResponseParseContext_t buffer[MAX_WAITING_RESPONSES];
|
||||
rcdeviceRespParseFunc parseFunc;
|
||||
} rcdeviceWaitingResponseQueue;
|
||||
|
||||
void runcamDeviceInit(runcamDevice_t *device);
|
||||
void rcdeviceReceive(timeUs_t currentTimeUs);
|
||||
|
||||
// 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, uint8_t *resultCode);
|
||||
bool runcamDeviceSimulate5KeyOSDCableButtonPress(runcamDevice_t *device, uint8_t operation);
|
||||
bool runcamDeviceSimulate5KeyOSDCableButtonRelease(runcamDevice_t *device);
|
||||
void runcamDeviceOpen5KeyOSDCableConnection(runcamDevice_t *device, rcdeviceRespParseFunc parseFunc);
|
||||
void runcamDeviceClose5KeyOSDCableConnection(runcamDevice_t *device, rcdeviceRespParseFunc parseFunc);
|
||||
void runcamDeviceSimulate5KeyOSDCableButtonPress(runcamDevice_t *device, uint8_t operation, rcdeviceRespParseFunc parseFunc);
|
||||
void runcamDeviceSimulate5KeyOSDCableButtonRelease(runcamDevice_t *device, rcdeviceRespParseFunc parseFunc);
|
||||
|
||||
// DisplayPort feature support
|
||||
void runcamDeviceDispFillRegion(runcamDevice_t *device, uint8_t x, uint8_t y, uint8_t width, uint8_t height, uint8_t c);
|
||||
void runcamDeviceDispWriteChar(runcamDevice_t *device, uint8_t x, uint8_t y, uint8_t c);
|
||||
void runcamDeviceDispWriteHorizontalString(runcamDevice_t *device, uint8_t x, uint8_t y, const char *text);
|
||||
void runcamDeviceDispWriteVerticalString(runcamDevice_t *device, uint8_t x, uint8_t y, const char *text);
|
||||
void runcamDeviceDispWriteChars(runcamDevice_t *device, uint8_t *data, uint8_t datalen);
|
||||
|
||||
// Device Setting Access
|
||||
bool runcamDeviceGetSettings(runcamDevice_t *device, uint8_t parentSettingID, runcamDeviceSetting_t *outSettingList, int maxSettingItemCount);
|
||||
bool runcamDeviceGetSettingDetail(runcamDevice_t *device, uint8_t settingID, runcamDeviceSettingDetail_t *outSettingDetail);
|
||||
bool runcamDeviceWriteSetting(runcamDevice_t *device, uint8_t settingID, uint8_t *data, uint8_t dataLen, runcamDeviceWriteSettingResponse_t *response);
|
||||
void rcdeviceReceive(timeUs_t currentTimeUs);
|
|
@ -34,21 +34,28 @@
|
|||
|
||||
#include "io/beeper.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/osd.h"
|
||||
#include "io/rcdevice_cam.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#ifdef USE_RCDEVICE
|
||||
|
||||
#define IS_HI(X) (rcData[X] > FIVE_KEY_CABLE_JOYSTICK_MAX)
|
||||
#define IS_LO(X) (rcData[X] < FIVE_KEY_CABLE_JOYSTICK_MIN)
|
||||
#define IS_MID(X) (rcData[X] > FIVE_KEY_CABLE_JOYSTICK_MID_START && rcData[X] < FIVE_KEY_CABLE_JOYSTICK_MID_END)
|
||||
|
||||
|
||||
static runcamDevice_t runcamDevice;
|
||||
runcamDevice_t *camDevice = &runcamDevice;
|
||||
rcdeviceSwitchState_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1];
|
||||
bool rcdeviceInMenu;
|
||||
bool needRelease = false;
|
||||
bool rcdeviceInMenu = false;
|
||||
bool isButtonPressed = false;
|
||||
bool waitingDeviceResponse = false;
|
||||
|
||||
|
||||
static bool isFeatureSupported(uint8_t feature)
|
||||
{
|
||||
|
@ -59,21 +66,6 @@ static bool isFeatureSupported(uint8_t feature)
|
|||
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);
|
||||
bool isStartRecordingSupported = isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_START_RECORDING);
|
||||
bool isStopRecordingSupported = isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_STOP_RECORDING);
|
||||
|
||||
if (camDevice->serialPort != NULL && (isPowerSimulationSupported || isWiFiSimulationSupported || isChangeModeSupported || isStartRecordingSupported || isStopRecordingSupported)) {
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool rcdeviceIsEnabled(void)
|
||||
{
|
||||
return camDevice->serialPort != NULL;
|
||||
|
@ -88,38 +80,12 @@ static bool rcdeviceIs5KeyEnabled(void)
|
|||
return false;
|
||||
}
|
||||
|
||||
static bool reInitializeDevice() {
|
||||
#define MAX_RETRY_COUNT 4
|
||||
#define RETRY_INTERVAL_MS 500
|
||||
static timeMs_t lastInitializeTime = 0;
|
||||
static int tryInitCount = 0;
|
||||
bool result = false;
|
||||
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (tryInitCount < MAX_RETRY_COUNT) {
|
||||
timeMs_t nextRetryTime = lastInitializeTime + RETRY_INTERVAL_MS;
|
||||
if (millis() >= nextRetryTime) {
|
||||
result = rcdeviceInit();
|
||||
tryInitCount++;
|
||||
lastInitializeTime = millis();
|
||||
}
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
static void rcdeviceCameraControlProcess(void)
|
||||
{
|
||||
for (boxId_e i = BOXCAMERA1; i <= BOXCAMERA3; i++) {
|
||||
uint8_t switchIndex = i - BOXCAMERA1;
|
||||
|
||||
if (IS_RC_MODE_ACTIVE(i)) {
|
||||
if (!rcdeviceIsCameraControlEnabled()) {
|
||||
reInitializeDevice();
|
||||
}
|
||||
|
||||
// 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
|
||||
|
@ -157,7 +123,69 @@ static void rcdeviceCameraControlProcess(void)
|
|||
}
|
||||
}
|
||||
|
||||
static bool rcdeviceCamSimulate5KeyCablePress(rcdeviceCamSimulationKeyEvent_e key)
|
||||
static void rcdeviceSimulationOSDCableFailed(rcdeviceResponseParseContext_t *ctx)
|
||||
{
|
||||
if (ctx->command == RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION) {
|
||||
uint8_t operationID = ctx->paramData[0];
|
||||
if (operationID == RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE) {
|
||||
waitingDeviceResponse = false;
|
||||
return;
|
||||
}
|
||||
} else {
|
||||
rcdeviceInMenu = false;
|
||||
waitingDeviceResponse = false;
|
||||
}
|
||||
}
|
||||
|
||||
static void rcdeviceSimulationRespHandle(rcdeviceResponseParseContext_t *ctx)
|
||||
{
|
||||
if (ctx->result != RCDEVICE_RESP_SUCCESS) {
|
||||
rcdeviceSimulationOSDCableFailed(ctx);
|
||||
return ;
|
||||
}
|
||||
|
||||
switch (ctx->command) {
|
||||
case RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_RELEASE:
|
||||
{
|
||||
UNUSED(ctx);
|
||||
isButtonPressed = false;
|
||||
}
|
||||
break;
|
||||
case RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION:
|
||||
{
|
||||
// the high 4 bits is the operationID that we sent
|
||||
// the low 4 bits is the result code
|
||||
uint8_t operationID = ctx->paramData[0];
|
||||
bool errorCode = (ctx->recvBuf[1] & 0x0F);
|
||||
if (operationID == RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN) {
|
||||
if (errorCode == 1) {
|
||||
rcdeviceInMenu = true;
|
||||
beeper(BEEPER_CAM_CONNECTION_OPEN);
|
||||
} else {
|
||||
rcdeviceInMenu = false;
|
||||
beeper(BEEPER_CAM_CONNECTION_CLOSE);
|
||||
}
|
||||
} else if (operationID == RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE) {
|
||||
if (errorCode == 1) {
|
||||
rcdeviceInMenu = false;
|
||||
beeper(BEEPER_CAM_CONNECTION_CLOSE);
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
case RCDEVICE_PROTOCOL_COMMAND_5KEY_SIMULATION_PRESS:
|
||||
{
|
||||
isButtonPressed = true;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
waitingDeviceResponse = false;
|
||||
|
||||
return ;
|
||||
}
|
||||
|
||||
static void rcdeviceCamSimulate5KeyCablePress(rcdeviceCamSimulationKeyEvent_e key)
|
||||
{
|
||||
uint8_t operation = RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE;
|
||||
switch (key) {
|
||||
|
@ -176,32 +204,23 @@ static bool rcdeviceCamSimulate5KeyCablePress(rcdeviceCamSimulationKeyEvent_e ke
|
|||
case RCDEVICE_CAM_KEY_ENTER:
|
||||
operation = RCDEVICE_PROTOCOL_5KEY_SIMULATION_SET;
|
||||
break;
|
||||
case RCDEVICE_CAM_KEY_NONE:
|
||||
default:
|
||||
operation = RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE;
|
||||
break;
|
||||
}
|
||||
|
||||
return runcamDeviceSimulate5KeyOSDCableButtonPress(camDevice, operation);
|
||||
runcamDeviceSimulate5KeyOSDCableButtonPress(camDevice, operation, rcdeviceSimulationRespHandle);
|
||||
}
|
||||
|
||||
static bool rcdeviceSend5KeyOSDCableSimualtionEvent(rcdeviceCamSimulationKeyEvent_e key)
|
||||
void 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);
|
||||
}
|
||||
runcamDeviceOpen5KeyOSDCableConnection(camDevice, rcdeviceSimulationRespHandle);
|
||||
break;
|
||||
case RCDEVICE_CAM_KEY_CONNECTION_CLOSE: {
|
||||
uint8_t resultCode = 0;
|
||||
reqResult = runcamDeviceClose5KeyOSDCableConnection(camDevice, &resultCode);
|
||||
if (resultCode == 1) {
|
||||
rcdeviceInMenu = false;
|
||||
beeper(BEEPER_CAM_CONNECTION_CLOSE);
|
||||
}
|
||||
runcamDeviceClose5KeyOSDCableConnection(camDevice, rcdeviceSimulationRespHandle);
|
||||
}
|
||||
break;
|
||||
case RCDEVICE_CAM_KEY_ENTER:
|
||||
|
@ -209,17 +228,17 @@ static bool rcdeviceSend5KeyOSDCableSimualtionEvent(rcdeviceCamSimulationKeyEven
|
|||
case RCDEVICE_CAM_KEY_UP:
|
||||
case RCDEVICE_CAM_KEY_RIGHT:
|
||||
case RCDEVICE_CAM_KEY_DOWN:
|
||||
reqResult = rcdeviceCamSimulate5KeyCablePress(key);
|
||||
rcdeviceCamSimulate5KeyCablePress(key);
|
||||
break;
|
||||
case RCDEVICE_CAM_KEY_RELEASE:
|
||||
reqResult = runcamDeviceSimulate5KeyOSDCableButtonRelease(camDevice);
|
||||
runcamDeviceSimulate5KeyOSDCableButtonRelease(camDevice, rcdeviceSimulationRespHandle);
|
||||
break;
|
||||
case RCDEVICE_CAM_KEY_NONE:
|
||||
default:
|
||||
reqResult = false;
|
||||
break;
|
||||
}
|
||||
|
||||
return reqResult;
|
||||
return;
|
||||
}
|
||||
|
||||
static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs)
|
||||
|
@ -236,21 +255,20 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs)
|
|||
return;
|
||||
}
|
||||
|
||||
if (waitingDeviceResponse) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (isButtonPressed) {
|
||||
if (IS_MID(YAW) && IS_MID(PITCH) && IS_MID(ROLL)) {
|
||||
if (rcdeviceIs5KeyEnabled()) {
|
||||
rcdeviceSend5KeyOSDCableSimualtionEvent(RCDEVICE_CAM_KEY_RELEASE);
|
||||
waitingDeviceResponse = true;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
rcdeviceCamSimulationKeyEvent_e key = RCDEVICE_CAM_KEY_NONE;
|
||||
|
||||
if (needRelease) {
|
||||
if (IS_MID(YAW) && IS_MID(PITCH) && IS_MID(ROLL)) {
|
||||
if ((camDevice->serialPort != NULL || reInitializeDevice()) && rcdeviceIs5KeyEnabled()) {
|
||||
key = RCDEVICE_CAM_KEY_RELEASE;
|
||||
if (rcdeviceSend5KeyOSDCableSimualtionEvent(key)) {
|
||||
needRelease = false;
|
||||
} else {
|
||||
rcdeviceInMenu = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
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;
|
||||
|
@ -274,14 +292,11 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs)
|
|||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (key != RCDEVICE_CAM_KEY_NONE) {
|
||||
if ((camDevice->serialPort != NULL || reInitializeDevice()) && rcdeviceIs5KeyEnabled()) {
|
||||
if (rcdeviceSend5KeyOSDCableSimualtionEvent(key)) {
|
||||
needRelease = true;
|
||||
} else {
|
||||
rcdeviceInMenu = false;
|
||||
if (rcdeviceIs5KeyEnabled()) {
|
||||
rcdeviceSend5KeyOSDCableSimualtionEvent(key);
|
||||
waitingDeviceResponse = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -289,23 +304,23 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs)
|
|||
|
||||
void rcdeviceUpdate(timeUs_t currentTimeUs)
|
||||
{
|
||||
rcdeviceReceive(currentTimeUs);
|
||||
|
||||
rcdeviceCameraControlProcess();
|
||||
rcdevice5KeySimulationProcess(currentTimeUs);
|
||||
}
|
||||
|
||||
bool rcdeviceInit(void)
|
||||
void rcdeviceInit(void)
|
||||
{
|
||||
// open serial port
|
||||
if (!runcamDeviceInit(camDevice)) {
|
||||
return false;
|
||||
}
|
||||
runcamDeviceInit(camDevice);
|
||||
|
||||
for (boxId_e i = BOXCAMERA1; i <= BOXCAMERA3; i++) {
|
||||
uint8_t switchIndex = i - BOXCAMERA1;
|
||||
switchStates[switchIndex].isActivated = true;
|
||||
}
|
||||
|
||||
return true;
|
||||
return;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -39,10 +39,12 @@ typedef struct rcdeviceSwitchState_s {
|
|||
extern runcamDevice_t *camDevice;
|
||||
extern bool rcdeviceInMenu;
|
||||
|
||||
bool rcdeviceInit(void);
|
||||
void rcdeviceInit(void);
|
||||
void rcdeviceUpdate(timeUs_t currentTimeUs);
|
||||
|
||||
bool rcdeviceIsEnabled(void);
|
||||
|
||||
// used for unit test
|
||||
rcdeviceSwitchState_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1];
|
||||
|
||||
void rcdeviceSend5KeyOSDCableSimualtionEvent(rcdeviceCamSimulationKeyEvent_e key);
|
||||
|
|
|
@ -1,247 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software 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 and Betaflight are distributed in the hope that they
|
||||
* 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 this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_RCDEVICE
|
||||
|
||||
#include "io/rcdevice.h"
|
||||
|
||||
#include "pg/vcd.h"
|
||||
|
||||
#include "rcdevice_osd.h"
|
||||
|
||||
#define VIDEO_BUFFER_CHARS_PAL 480
|
||||
|
||||
static uint8_t columnCount = 30;
|
||||
|
||||
static runcamDevice_t runcamOSDDevice;
|
||||
runcamDevice_t *osdDevice = &runcamOSDDevice;
|
||||
|
||||
static uint8_t video_system;
|
||||
static uint16_t maxScreenSize = VIDEO_BUFFER_CHARS_PAL;
|
||||
|
||||
#ifdef USE_PARTICLE_DRAW
|
||||
#define MAX_CHARS2UPDATE 20
|
||||
static uint8_t screenBuffer[VIDEO_BUFFER_CHARS_PAL + 40]; // For faster writes
|
||||
// we use memcpy so we
|
||||
// need some space to
|
||||
// don't overwrite
|
||||
// buffer
|
||||
static uint8_t shadowBuffer[VIDEO_BUFFER_CHARS_PAL];
|
||||
static bool rcdeviceOSDLock = false;
|
||||
#endif
|
||||
|
||||
bool rcdeviceOSDInit(const vcdProfile_t *vcdProfile)
|
||||
{
|
||||
if (!runcamDeviceInit(osdDevice)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if ((osdDevice->info.features & RCDEVICE_PROTOCOL_FEATURE_DISPLAYP_PORT) == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// get screen column count
|
||||
runcamDeviceSettingDetail_t settingDetail;
|
||||
if (!runcamDeviceGetSettingDetail(osdDevice, RCDEVICE_PROTOCOL_SETTINGID_DISP_COLUMNS, &settingDetail)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
columnCount = settingDetail.value;
|
||||
|
||||
video_system = vcdProfile->video_system;
|
||||
if (video_system == VIDEO_SYSTEM_AUTO) {
|
||||
// fetch current video mode from device
|
||||
runcamDeviceSettingDetail_t settingDetail;
|
||||
if (!runcamDeviceGetSettingDetail(osdDevice, RCDEVICE_PROTOCOL_SETTINGID_DISP_TV_MODE, &settingDetail)) {
|
||||
return false;
|
||||
}
|
||||
video_system = settingDetail.value;
|
||||
} else {
|
||||
// set video system
|
||||
runcamDeviceWriteSettingResponse_t response;
|
||||
uint8_t tvMode = 0;
|
||||
if (video_system == VIDEO_SYSTEM_NTSC) {
|
||||
tvMode = 0;
|
||||
} else if (video_system == VIDEO_SYSTEM_PAL) {
|
||||
tvMode = 1;
|
||||
}
|
||||
|
||||
if (!runcamDeviceWriteSetting(osdDevice, RCDEVICE_PROTOCOL_SETTINGID_DISP_TV_MODE, &tvMode, sizeof(uint8_t), &response)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (response.resultCode) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// user bf charset
|
||||
uint8_t charsetID = 0;
|
||||
runcamDeviceWriteSettingResponse_t updateCharsetResp;
|
||||
if (!runcamDeviceWriteSetting(osdDevice, RCDEVICE_PROTOCOL_SETTINGID_DISP_CHARSET, &charsetID, sizeof(uint8_t), &updateCharsetResp) || updateCharsetResp.resultCode != 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
#ifdef USE_PARTICLE_DRAW
|
||||
memset(shadowBuffer, 2, VIDEO_BUFFER_CHARS_PAL);
|
||||
#endif
|
||||
|
||||
// fill screen with ' '
|
||||
rcdeviceOSDClearScreen(NULL);
|
||||
return true;
|
||||
}
|
||||
|
||||
int rcdeviceOSDGrab(displayPort_t *displayPort)
|
||||
{
|
||||
UNUSED(displayPort);
|
||||
// osdResetAlarms();
|
||||
// resumeRefreshAt = 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int rcdeviceOSDRelease(displayPort_t *displayPort)
|
||||
{
|
||||
UNUSED(displayPort);
|
||||
return 0;
|
||||
}
|
||||
|
||||
int rcdeviceOSDDrawScreen(displayPort_t *displayPort)
|
||||
{
|
||||
UNUSED(displayPort);
|
||||
|
||||
#ifdef USE_PARTICLE_DRAW
|
||||
static uint16_t pos = 0;
|
||||
int k = 0;
|
||||
|
||||
if (!rcdeviceOSDLock) {
|
||||
rcdeviceOSDLock = true;
|
||||
|
||||
uint8_t data[60];
|
||||
uint8_t dataLen = 0;
|
||||
for (k = 0; k < MAX_CHARS2UPDATE; k++) {
|
||||
if (screenBuffer[pos] != shadowBuffer[pos]) {
|
||||
shadowBuffer[pos] = screenBuffer[pos];
|
||||
uint8_t x = pos % columnCount;
|
||||
uint8_t y = pos / columnCount;
|
||||
data[dataLen++] = x;
|
||||
data[dataLen++] = y;
|
||||
data[dataLen++] = screenBuffer[pos];
|
||||
}
|
||||
|
||||
if (++pos >= maxScreenSize) {
|
||||
pos = 0;
|
||||
break;
|
||||
}
|
||||
}
|
||||
runcamDeviceDispWriteChars(osdDevice, data, dataLen);
|
||||
|
||||
rcdeviceOSDLock = false;
|
||||
}
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
int rcdeviceOSDWriteString(displayPort_t *displayPort, uint8_t x, uint8_t y, const char *buff)
|
||||
{
|
||||
UNUSED(displayPort);
|
||||
#if !defined(USE_PARTICLE_DRAW)
|
||||
runcamDeviceDispWriteHorizontalString(osdDevice, x, y, buff);
|
||||
#else
|
||||
for (int xpos = x; *buff && xpos < columnCount; xpos++) {
|
||||
screenBuffer[y * columnCount + xpos] = *buff++;
|
||||
}
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
int rcdeviceOSDWriteChar(displayPort_t *displayPort, uint8_t x, uint8_t y, uint8_t c)
|
||||
{
|
||||
UNUSED(displayPort);
|
||||
#if !defined(USE_PARTICLE_DRAW)
|
||||
runcamDeviceDispWriteChar(osdDevice, x, y, c);
|
||||
#else
|
||||
screenBuffer[y * columnCount + x] = c;
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int rcdeviceOSDClearScreen(displayPort_t *displayPort)
|
||||
{
|
||||
UNUSED(displayPort);
|
||||
|
||||
#if defined(USE_PARTICLE_DRAW)
|
||||
memset(screenBuffer, 0x20, sizeof(screenBuffer));
|
||||
#else
|
||||
runcamDeviceDispFillRegion(osdDevice, 0, 0, 255, 255, ' ');
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
bool rcdeviceOSDIsTransferInProgress(const displayPort_t *displayPort)
|
||||
{
|
||||
UNUSED(displayPort);
|
||||
return false;
|
||||
}
|
||||
|
||||
bool rcdeviceOSDIsSynced(const displayPort_t *displayPort)
|
||||
{
|
||||
UNUSED(displayPort);
|
||||
return true;
|
||||
}
|
||||
|
||||
int rcdeviceOSDHeartbeat(displayPort_t *displayPort)
|
||||
{
|
||||
UNUSED(displayPort);
|
||||
return 0;
|
||||
}
|
||||
|
||||
void rcdeviceOSDResync(displayPort_t *displayPort)
|
||||
{
|
||||
UNUSED(displayPort);
|
||||
|
||||
if (video_system == VIDEO_SYSTEM_PAL) {
|
||||
displayPort->rows = RCDEVICE_PROTOCOL_OSD_VIDEO_LINES_PAL;
|
||||
} else {
|
||||
displayPort->rows = RCDEVICE_PROTOCOL_OSD_VIDEO_LINES_NTSC;
|
||||
}
|
||||
|
||||
displayPort->cols = columnCount;
|
||||
maxScreenSize = displayPort->rows * displayPort->cols;
|
||||
}
|
||||
|
||||
uint32_t rcdeviceOSDTxBytesFree(const displayPort_t *displayPort)
|
||||
{
|
||||
UNUSED(displayPort);
|
||||
return INT32_MAX;
|
||||
}
|
||||
|
||||
int rcdeviceScreenSize(const displayPort_t *displayPort)
|
||||
{
|
||||
return displayPort->rows * displayPort->cols;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,43 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software 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 and Betaflight are distributed in the hope that they
|
||||
* 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 this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "drivers/display.h"
|
||||
|
||||
#define RCDEVICE_PROTOCOL_OSD_VIDEO_LINES_NTSC 13
|
||||
#define RCDEVICE_PROTOCOL_OSD_VIDEO_LINES_PAL 16
|
||||
|
||||
struct vcdProfile_s;
|
||||
|
||||
bool rcdeviceOSDInit(const struct vcdProfile_s *vcdProfile);
|
||||
int rcdeviceOSDGrab(displayPort_t *displayPort);
|
||||
int rcdeviceOSDRelease(displayPort_t *displayPort);
|
||||
|
||||
int rcdeviceOSDDrawScreen(displayPort_t *);
|
||||
|
||||
int rcdeviceOSDWriteString(displayPort_t *, uint8_t x, uint8_t y, const char *buff);
|
||||
int rcdeviceOSDWriteChar(displayPort_t *, uint8_t x, uint8_t y, uint8_t c);
|
||||
int rcdeviceOSDReloadProfile(displayPort_t *);
|
||||
int rcdeviceOSDClearScreen(displayPort_t *);
|
||||
bool rcdeviceOSDIsTransferInProgress(const displayPort_t *);
|
||||
int rcdeviceOSDHeartbeat(displayPort_t *displayPort);
|
||||
void rcdeviceOSDResync(displayPort_t *displayPort);
|
||||
bool rcdeviceOSDIsSynced(const displayPort_t *displayPort);
|
||||
uint32_t rcdeviceOSDTxBytesFree(const displayPort_t *displayPort);
|
||||
int rcdeviceScreenSize(const displayPort_t *displayPort);
|
|
@ -289,7 +289,6 @@ rcdevice_unittest_SRC := \
|
|||
$(USER_DIR)/common/bitarray.c \
|
||||
$(USER_DIR)/fc/rc_modes.c \
|
||||
$(USER_DIR)/io/rcdevice.c \
|
||||
$(USER_DIR)/io/rcdevice_osd.c \
|
||||
$(USER_DIR)/io/rcdevice_cam.c \
|
||||
|
||||
pid_unittest_SRC := \
|
||||
|
|
File diff suppressed because it is too large
Load diff
Loading…
Add table
Add a link
Reference in a new issue