mirror of https://github.com/ArduPilot/ardupilot
AP_MSP: added a new backend for msp displayport aka canvas mode support
This commit is contained in:
parent
05686f3c60
commit
188b7a50a9
|
@ -19,6 +19,7 @@
|
|||
#include "AP_MSP.h"
|
||||
#include "AP_MSP_Telem_Generic.h"
|
||||
#include "AP_MSP_Telem_DJI.h"
|
||||
#include "AP_MSP_Telem_DisplayPort.h"
|
||||
|
||||
#include <ctype.h>
|
||||
#include <stdio.h>
|
||||
|
@ -44,7 +45,7 @@ const AP_Param::GroupInfo AP_MSP::var_info[] = {
|
|||
// @Description: A bitmask to set some MSP specific options
|
||||
// @Bitmask: 0:EnableTelemetryMode, 1: DJIWorkarounds
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_OPTIONS", 2, AP_MSP, _options, OPTION_TELEMETRY_DJI_WORKAROUNDS),
|
||||
AP_GROUPINFO("_OPTIONS", 2, AP_MSP, _options, (uint8_t)MspOption::OPTION_TELEMETRY_DJI_WORKAROUNDS),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -63,6 +64,10 @@ bool AP_MSP::init_backend(uint8_t backend_idx, AP_HAL::UARTDriver *uart, AP_Seri
|
|||
_backends[backend_idx] = new AP_MSP_Telem_Generic(uart);
|
||||
} else if (protocol == AP_SerialManager::SerialProtocol_DJI_FPV) {
|
||||
_backends[backend_idx] = new AP_MSP_Telem_DJI(uart);
|
||||
#if HAL_WITH_MSP_DISPLAYPORT
|
||||
} else if (protocol == AP_SerialManager::SerialProtocol_MSP_DisplayPort) {
|
||||
_backends[backend_idx] = new AP_MSP_Telem_DisplayPort(uart);
|
||||
#endif
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
|
@ -80,7 +85,7 @@ void AP_MSP::init()
|
|||
{
|
||||
const AP_SerialManager &serial_manager = AP::serialmanager();
|
||||
AP_HAL::UARTDriver *uart = nullptr;
|
||||
|
||||
uint8_t backends_using_msp_thread = 0;
|
||||
// DJI FPV backends
|
||||
for (uint8_t protocol_instance=0; protocol_instance<MSP_MAX_INSTANCES; protocol_instance++) {
|
||||
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_DJI_FPV, protocol_instance);
|
||||
|
@ -92,6 +97,9 @@ void AP_MSP::init()
|
|||
if (!_msp_status.osd_initialized) {
|
||||
init_osd();
|
||||
}
|
||||
if (_backends[_msp_status.backend_count]->use_msp_thread()) {
|
||||
backends_using_msp_thread++;
|
||||
}
|
||||
_msp_status.backend_count++;
|
||||
}
|
||||
}
|
||||
|
@ -102,11 +110,28 @@ void AP_MSP::init()
|
|||
if (!init_backend(_msp_status.backend_count, uart, AP_SerialManager::SerialProtocol_MSP)) {
|
||||
break;
|
||||
}
|
||||
if (_backends[_msp_status.backend_count]->use_msp_thread()) {
|
||||
backends_using_msp_thread++;
|
||||
}
|
||||
_msp_status.backend_count++;
|
||||
}
|
||||
}
|
||||
|
||||
if (_msp_status.backend_count > 0) {
|
||||
#if HAL_WITH_MSP_DISPLAYPORT
|
||||
// MSP DisplayPort backends
|
||||
for (uint8_t protocol_instance=0; protocol_instance<MSP_MAX_INSTANCES-_msp_status.backend_count; protocol_instance++) {
|
||||
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_MSP_DisplayPort, protocol_instance);
|
||||
if (uart != nullptr) {
|
||||
if (!init_backend(_msp_status.backend_count, uart, AP_SerialManager::SerialProtocol_MSP_DisplayPort)) {
|
||||
break;
|
||||
}
|
||||
if (_backends[_msp_status.backend_count]->use_msp_thread()) {
|
||||
backends_using_msp_thread++;
|
||||
}
|
||||
_msp_status.backend_count++;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
if (backends_using_msp_thread > 0) {
|
||||
// we've found at least 1 msp backend, start protocol handler
|
||||
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_MSP::loop, void),
|
||||
"MSP",
|
||||
|
@ -161,7 +186,8 @@ void AP_MSP::loop(void)
|
|||
{
|
||||
for (uint8_t i=0; i<_msp_status.backend_count; i++) {
|
||||
// one time uart init
|
||||
if (_backends[i] != nullptr) {
|
||||
// note: we do not access a uart for a backend handled by another thread
|
||||
if (_backends[i] != nullptr && _backends[i]->use_msp_thread()) {
|
||||
_backends[i]->init_uart();
|
||||
}
|
||||
}
|
||||
|
@ -185,7 +211,8 @@ void AP_MSP::loop(void)
|
|||
}
|
||||
|
||||
for (uint8_t i=0; i< _msp_status.backend_count; i++) {
|
||||
if (_backends[i] != nullptr) {
|
||||
// note: we do not access a uart for a backend handled by another thread
|
||||
if (_backends[i] != nullptr && _backends[i]->use_msp_thread()) {
|
||||
// dynamically hide/unhide
|
||||
_backends[i]->hide_osd_items();
|
||||
// process incoming MSP frames (and reply if needed)
|
||||
|
@ -197,9 +224,13 @@ void AP_MSP::loop(void)
|
|||
}
|
||||
}
|
||||
|
||||
bool AP_MSP::check_option(msp_option_e option)
|
||||
{
|
||||
return (_options & option) != 0;
|
||||
AP_MSP_Telem_Backend* AP_MSP::find_protocol(const AP_SerialManager::SerialProtocol protocol) const {
|
||||
for (uint8_t i=0; i< _msp_status.backend_count; i++) {
|
||||
if (_backends[i] != nullptr && _backends[i]->get_serial_protocol() == protocol) {
|
||||
return _backends[i];
|
||||
}
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
namespace AP
|
||||
|
|
|
@ -36,7 +36,10 @@ class AP_MSP
|
|||
friend class AP_MSP_Telem_Generic;
|
||||
friend class AP_MSP_Telem_DJI;
|
||||
friend class AP_MSP_Telem_Backend;
|
||||
|
||||
#if HAL_WITH_MSP_DISPLAYPORT
|
||||
friend class AP_MSP_Telem_DisplayPort;
|
||||
friend class AP_OSD_MSP_DisplayPort;
|
||||
#endif
|
||||
public:
|
||||
AP_MSP();
|
||||
|
||||
|
@ -50,6 +53,14 @@ public:
|
|||
// init - perform required initialisation
|
||||
void init();
|
||||
|
||||
enum class MspOption : uint8_t {
|
||||
OPTION_TELEMETRY_MODE = 1U<<0,
|
||||
OPTION_TELEMETRY_DJI_WORKAROUNDS = 1U<<1,
|
||||
OPTION_DISPLAYPORT_BTFL_SYMBOLS = 1U<<2,
|
||||
};
|
||||
|
||||
bool check_option(const MspOption option) const { return (_options & (uint8_t)option) != 0; };
|
||||
|
||||
static AP_MSP *get_singleton(void)
|
||||
{
|
||||
return _singleton;
|
||||
|
@ -57,11 +68,6 @@ public:
|
|||
|
||||
private:
|
||||
|
||||
enum msp_option_e : uint8_t {
|
||||
OPTION_TELEMETRY_MODE = 1U<<0,
|
||||
OPTION_TELEMETRY_DJI_WORKAROUNDS = 1U<<1
|
||||
};
|
||||
|
||||
AP_MSP_Telem_Backend *_backends[MSP_MAX_INSTANCES];
|
||||
|
||||
AP_Int8 _options;
|
||||
|
@ -83,7 +89,7 @@ private:
|
|||
bool init_backend(uint8_t backend_idx, AP_HAL::UARTDriver *uart, AP_SerialManager::SerialProtocol protocol);
|
||||
void init_osd();
|
||||
void loop(void);
|
||||
bool check_option(const msp_option_e option);
|
||||
AP_MSP_Telem_Backend* find_protocol(const AP_SerialManager::SerialProtocol protocol) const;
|
||||
|
||||
static AP_MSP *_singleton;
|
||||
};
|
||||
|
|
|
@ -357,6 +357,25 @@ void AP_MSP_Telem_Backend::process_incoming_data()
|
|||
}
|
||||
}
|
||||
|
||||
/*
|
||||
send an MSP packet
|
||||
*/
|
||||
void AP_MSP_Telem_Backend::msp_send_packet(uint16_t cmd, MSP::msp_version_e msp_version, const void *p, uint16_t size, bool is_request)
|
||||
{
|
||||
uint8_t out_buf[MSP_PORT_OUTBUF_SIZE];
|
||||
|
||||
msp_packet_t pkt = {
|
||||
.buf = { .ptr = out_buf, .end = MSP_ARRAYEND(out_buf), },
|
||||
.cmd = (int16_t)cmd,
|
||||
.flags = 0,
|
||||
.result = 0,
|
||||
};
|
||||
|
||||
sbuf_write_data(&pkt.buf, p, size);
|
||||
sbuf_switch_to_reader(&pkt.buf, &out_buf[0]);
|
||||
msp_serial_encode(&_msp_port, &pkt, msp_version, is_request);
|
||||
}
|
||||
|
||||
/*
|
||||
ported from betaflight/src/main/msp/msp_serial.c
|
||||
*/
|
||||
|
@ -1059,4 +1078,67 @@ void AP_MSP_Telem_Backend::hide_osd_items(void)
|
|||
}
|
||||
}
|
||||
|
||||
#if HAL_WITH_MSP_DISPLAYPORT
|
||||
// ported from betaflight/src/main/io/displayport_msp.c
|
||||
void AP_MSP_Telem_Backend::msp_displayport_heartbeat()
|
||||
{
|
||||
const uint8_t subcmd[] = { msp_displayport_subcmd_e::MSP_DISPLAYPORT_HEARTBEAT };
|
||||
|
||||
// heartbeat is used to:
|
||||
// a) ensure display is not released by remote OSD software
|
||||
// b) prevent OSD Slave boards from displaying a 'disconnected' status.
|
||||
msp_send_packet(MSP_DISPLAYPORT, MSP::MSP_V1, subcmd, sizeof(subcmd), false);
|
||||
}
|
||||
|
||||
void AP_MSP_Telem_Backend::msp_displayport_grab()
|
||||
{
|
||||
msp_displayport_heartbeat();
|
||||
}
|
||||
|
||||
void AP_MSP_Telem_Backend::msp_displayport_release()
|
||||
{
|
||||
const uint8_t subcmd[] = { msp_displayport_subcmd_e::MSP_DISPLAYPORT_RELEASE };
|
||||
|
||||
msp_send_packet(MSP_DISPLAYPORT, MSP::MSP_V1, subcmd, sizeof(subcmd), false);
|
||||
}
|
||||
|
||||
void AP_MSP_Telem_Backend::msp_displayport_clear_screen()
|
||||
{
|
||||
const uint8_t subcmd[] = { msp_displayport_subcmd_e::MSP_DISPLAYPORT_CLEAR_SCREEN };
|
||||
|
||||
msp_send_packet(MSP_DISPLAYPORT, MSP::MSP_V1, subcmd, sizeof(subcmd), false);
|
||||
}
|
||||
|
||||
void AP_MSP_Telem_Backend::msp_displayport_draw_screen()
|
||||
{
|
||||
const uint8_t subcmd[] = { msp_displayport_subcmd_e::MSP_DISPLAYPORT_DRAW_SCREEN };
|
||||
msp_send_packet(MSP_DISPLAYPORT, MSP::MSP_V1, subcmd, sizeof(subcmd), false);
|
||||
}
|
||||
|
||||
void AP_MSP_Telem_Backend::msp_displayport_write_string(uint8_t col, uint8_t row, bool blink, const char *string)
|
||||
{
|
||||
int len = strlen(string);
|
||||
if (len >= OSD_MSP_DISPLAYPORT_MAX_STRING_LENGTH) {
|
||||
len = OSD_MSP_DISPLAYPORT_MAX_STRING_LENGTH;
|
||||
}
|
||||
|
||||
struct PACKED {
|
||||
uint8_t sub_cmd;
|
||||
uint8_t row;
|
||||
uint8_t col;
|
||||
uint8_t attr;
|
||||
uint8_t text[OSD_MSP_DISPLAYPORT_MAX_STRING_LENGTH];
|
||||
} packet {};
|
||||
|
||||
packet.sub_cmd = msp_displayport_subcmd_e::MSP_DISPLAYPORT_WRITE_STRING;
|
||||
packet.row = row;
|
||||
packet.col = col;
|
||||
if (blink) {
|
||||
packet.attr |= DISPLAYPORT_MSP_ATTR_BLINK;
|
||||
}
|
||||
memcpy(packet.text, string, len);
|
||||
|
||||
msp_send_packet(MSP_DISPLAYPORT, MSP::MSP_V1, &packet, 4 + len, false);
|
||||
}
|
||||
#endif //HAL_WITH_MSP_DISPLAYPORT
|
||||
#endif //HAL_MSP_ENABLED
|
||||
|
|
|
@ -17,7 +17,6 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_RCTelemetry/AP_RCTelemetry.h>
|
||||
|
||||
#include "msp.h"
|
||||
|
||||
#include <time.h>
|
||||
|
@ -33,6 +32,7 @@ class AP_MSP;
|
|||
|
||||
class AP_MSP_Telem_Backend : AP_RCTelemetry
|
||||
{
|
||||
friend AP_MSP;
|
||||
public:
|
||||
AP_MSP_Telem_Backend(AP_HAL::UARTDriver *uart);
|
||||
|
||||
|
@ -77,6 +77,16 @@ public:
|
|||
void process_incoming_data(); // incoming data
|
||||
void process_outgoing_data(); // push outgoing data
|
||||
|
||||
#if HAL_WITH_MSP_DISPLAYPORT
|
||||
// displayport commands
|
||||
// betaflight/src/main/io/displayport_msp.c
|
||||
virtual void msp_displayport_heartbeat();
|
||||
virtual void msp_displayport_grab();
|
||||
virtual void msp_displayport_release();
|
||||
virtual void msp_displayport_clear_screen();
|
||||
virtual void msp_displayport_draw_screen();
|
||||
virtual void msp_displayport_write_string(uint8_t col, uint8_t row, bool blink, const char *string);
|
||||
#endif
|
||||
protected:
|
||||
enum msp_packet_type : uint8_t {
|
||||
EMPTY_SLOT = 0,
|
||||
|
@ -158,6 +168,9 @@ protected:
|
|||
MSP::MSPCommandResult msp_process_sensor_command(uint16_t cmd_msp, MSP::sbuf_t *src);
|
||||
MSP::MSPCommandResult msp_process_out_command(uint16_t cmd_msp, MSP::sbuf_t *dst);
|
||||
|
||||
// MSP send
|
||||
void msp_send_packet(uint16_t cmd, MSP::msp_version_e msp_version, const void *p, uint16_t size, bool is_request);
|
||||
|
||||
// MSP sensor command processing
|
||||
void msp_handle_opflow(const MSP::msp_opflow_data_message_t &pkt);
|
||||
void msp_handle_rangefinder(const MSP::msp_rangefinder_data_message_t &pkt);
|
||||
|
@ -173,7 +186,9 @@ protected:
|
|||
return 0;
|
||||
}
|
||||
|
||||
virtual bool is_scheduler_enabled() = 0; // only osd backends should allow a push type telemetry
|
||||
virtual bool is_scheduler_enabled() const = 0; // only osd backends should allow a push type telemetry
|
||||
virtual bool use_msp_thread() const {return true;}; // is this backend hanlded by the MSP thread?
|
||||
virtual AP_SerialManager::SerialProtocol get_serial_protocol() const = 0;
|
||||
|
||||
// implementation specific MSP out command processing
|
||||
virtual MSP::MSPCommandResult msp_process_out_api_version(MSP::sbuf_t *dst) = 0;
|
||||
|
|
|
@ -34,18 +34,18 @@ bool AP_MSP_Telem_DJI::init_uart()
|
|||
return false;
|
||||
}
|
||||
|
||||
bool AP_MSP_Telem_DJI::is_scheduler_enabled()
|
||||
bool AP_MSP_Telem_DJI::is_scheduler_enabled() const
|
||||
{
|
||||
AP_MSP *msp = AP::msp();
|
||||
const AP_MSP *msp = AP::msp();
|
||||
if (msp == nullptr) {
|
||||
return false;
|
||||
}
|
||||
return msp->check_option(AP_MSP::OPTION_TELEMETRY_MODE);
|
||||
return msp->check_option(AP_MSP::MspOption::OPTION_TELEMETRY_MODE);
|
||||
}
|
||||
|
||||
void AP_MSP_Telem_DJI::hide_osd_items(void)
|
||||
{
|
||||
AP_MSP *msp = AP::msp();
|
||||
const AP_MSP *msp = AP::msp();
|
||||
if (msp == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
@ -84,17 +84,33 @@ uint32_t AP_MSP_Telem_DJI::get_osd_flight_mode_bitmask(void)
|
|||
|
||||
MSPCommandResult AP_MSP_Telem_DJI::msp_process_out_api_version(sbuf_t *dst)
|
||||
{
|
||||
sbuf_write_u8(dst, MSP_PROTOCOL_VERSION);
|
||||
sbuf_write_u8(dst, API_VERSION_MAJOR);
|
||||
sbuf_write_u8(dst, API_VERSION_MINOR);
|
||||
struct {
|
||||
uint8_t proto;
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
} api_version;
|
||||
|
||||
api_version.proto = MSP_PROTOCOL_VERSION;
|
||||
api_version.major = API_VERSION_MAJOR;
|
||||
api_version.minor = API_VERSION_MINOR;
|
||||
|
||||
sbuf_write_data(dst, &api_version, sizeof(api_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_DJI::msp_process_out_fc_version(sbuf_t *dst)
|
||||
{
|
||||
sbuf_write_u8(dst, FC_VERSION_MAJOR);
|
||||
sbuf_write_u8(dst, FC_VERSION_MINOR);
|
||||
sbuf_write_u8(dst, FC_VERSION_PATCH_LEVEL);
|
||||
struct {
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
uint8_t patch;
|
||||
} fc_version;
|
||||
|
||||
fc_version.major = FC_VERSION_MAJOR;
|
||||
fc_version.minor = FC_VERSION_MINOR;
|
||||
fc_version.patch = FC_VERSION_PATCH_LEVEL;
|
||||
|
||||
sbuf_write_data(dst, &fc_version, sizeof(fc_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
|
@ -108,7 +124,7 @@ MSPCommandResult AP_MSP_Telem_DJI::msp_process_out_esc_sensor_data(sbuf_t *dst)
|
|||
{
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
const auto msp = AP::msp();
|
||||
if (msp && (msp->_options & AP_MSP::OPTION_TELEMETRY_DJI_WORKAROUNDS)) {
|
||||
if (msp && msp->check_option(AP_MSP::MspOption::OPTION_TELEMETRY_DJI_WORKAROUNDS)) {
|
||||
AP_ESC_Telem& telem = AP::esc_telem();
|
||||
int16_t highest_temperature = 0;
|
||||
telem.get_highest_motor_temperature(highest_temperature);
|
||||
|
|
|
@ -51,7 +51,8 @@ class AP_MSP_Telem_DJI : public AP_MSP_Telem_Backend
|
|||
public:
|
||||
bool init_uart() override;
|
||||
// implementation specific helpers
|
||||
bool is_scheduler_enabled() override;
|
||||
bool is_scheduler_enabled() const override;
|
||||
AP_SerialManager::SerialProtocol get_serial_protocol() const override { return AP_SerialManager::SerialProtocol::SerialProtocol_DJI_FPV; };
|
||||
uint32_t get_osd_flight_mode_bitmask(void) override;
|
||||
void hide_osd_items(void) override;
|
||||
MSP::MSPCommandResult msp_process_out_api_version(MSP::sbuf_t *dst) override;
|
||||
|
|
|
@ -0,0 +1,76 @@
|
|||
/*
|
||||
This program 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.
|
||||
|
||||
This program 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 this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <AP_Common/AP_FWVersion.h>
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
||||
#include "AP_MSP.h"
|
||||
#include "AP_MSP_Telem_DisplayPort.h"
|
||||
|
||||
#if HAL_WITH_MSP_DISPLAYPORT
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace MSP;
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_DisplayPort::msp_process_out_api_version(sbuf_t *dst)
|
||||
{
|
||||
struct {
|
||||
uint8_t proto;
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
} api_version;
|
||||
|
||||
api_version.proto = MSP_PROTOCOL_VERSION;
|
||||
api_version.major = API_VERSION_MAJOR;
|
||||
api_version.minor = API_VERSION_MINOR;
|
||||
|
||||
sbuf_write_data(dst, &api_version, sizeof(api_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_DisplayPort::msp_process_out_fc_version(sbuf_t *dst)
|
||||
{
|
||||
struct {
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
uint8_t patch;
|
||||
} fc_version;
|
||||
|
||||
fc_version.major = FC_VERSION_MAJOR;
|
||||
fc_version.minor = FC_VERSION_MINOR;
|
||||
fc_version.patch = FC_VERSION_PATCH_LEVEL;
|
||||
|
||||
sbuf_write_data(dst, &fc_version, sizeof(fc_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_DisplayPort::msp_process_out_fc_variant(sbuf_t *dst)
|
||||
{
|
||||
const AP_MSP *msp = AP::msp();
|
||||
if (msp == nullptr) {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
// do we use backend specific symbols table?
|
||||
if (msp->check_option(AP_MSP::MspOption::OPTION_DISPLAYPORT_BTFL_SYMBOLS)) {
|
||||
sbuf_write_data(dst, BETAFLIGHT_IDENTIFIER, FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
|
||||
} else {
|
||||
sbuf_write_data(dst, ARDUPILOT_IDENTIFIER, FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
|
||||
}
|
||||
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
#endif //HAL_WITH_MSP_DISPLAYPORT
|
|
@ -0,0 +1,36 @@
|
|||
/*
|
||||
This program 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.
|
||||
|
||||
This program 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 this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
MSP generic telemetry library backend
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "AP_MSP_Telem_Backend.h"
|
||||
|
||||
#if HAL_WITH_MSP_DISPLAYPORT
|
||||
|
||||
class AP_MSP_Telem_DisplayPort : public AP_MSP_Telem_Backend
|
||||
{
|
||||
using AP_MSP_Telem_Backend::AP_MSP_Telem_Backend;
|
||||
public:
|
||||
bool is_scheduler_enabled() const override { return false; }
|
||||
bool use_msp_thread() const override { return false; }
|
||||
AP_SerialManager::SerialProtocol get_serial_protocol() const override { return AP_SerialManager::SerialProtocol::SerialProtocol_MSP_DisplayPort; };
|
||||
|
||||
MSP::MSPCommandResult msp_process_out_api_version(MSP::sbuf_t *dst) override;
|
||||
MSP::MSPCommandResult msp_process_out_fc_version(MSP::sbuf_t *dst) override;
|
||||
MSP::MSPCommandResult msp_process_out_fc_variant(MSP::sbuf_t *dst) override;
|
||||
};
|
||||
|
||||
#endif //HAL_WITH_MSP_DISPLAYPORT
|
|
@ -27,17 +27,33 @@ using namespace MSP;
|
|||
|
||||
MSPCommandResult AP_MSP_Telem_Generic::msp_process_out_api_version(sbuf_t *dst)
|
||||
{
|
||||
sbuf_write_u8(dst, MSP_PROTOCOL_VERSION);
|
||||
sbuf_write_u8(dst, API_VERSION_MAJOR);
|
||||
sbuf_write_u8(dst, API_VERSION_MINOR);
|
||||
struct {
|
||||
uint8_t proto;
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
} api_version;
|
||||
|
||||
api_version.proto = MSP_PROTOCOL_VERSION;
|
||||
api_version.major = API_VERSION_MAJOR;
|
||||
api_version.minor = API_VERSION_MINOR;
|
||||
|
||||
sbuf_write_data(dst, &api_version, sizeof(api_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
MSPCommandResult AP_MSP_Telem_Generic::msp_process_out_fc_version(sbuf_t *dst)
|
||||
{
|
||||
sbuf_write_u8(dst, FC_VERSION_MAJOR);
|
||||
sbuf_write_u8(dst, FC_VERSION_MINOR);
|
||||
sbuf_write_u8(dst, FC_VERSION_PATCH_LEVEL);
|
||||
struct {
|
||||
uint8_t major;
|
||||
uint8_t minor;
|
||||
uint8_t patch;
|
||||
} fc_version;
|
||||
|
||||
fc_version.major = FC_VERSION_MAJOR;
|
||||
fc_version.minor = FC_VERSION_MINOR;
|
||||
fc_version.patch = FC_VERSION_PATCH_LEVEL;
|
||||
|
||||
sbuf_write_data(dst, &fc_version, sizeof(fc_version));
|
||||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
|
|
|
@ -24,10 +24,8 @@ class AP_MSP_Telem_Generic : public AP_MSP_Telem_Backend
|
|||
{
|
||||
using AP_MSP_Telem_Backend::AP_MSP_Telem_Backend;
|
||||
public:
|
||||
bool is_scheduler_enabled() override
|
||||
{
|
||||
return false;
|
||||
}
|
||||
bool is_scheduler_enabled() const override { return false; }
|
||||
AP_SerialManager::SerialProtocol get_serial_protocol() const override { return AP_SerialManager::SerialProtocol::SerialProtocol_MSP; };
|
||||
MSP::MSPCommandResult msp_process_out_api_version(MSP::sbuf_t *dst) override;
|
||||
MSP::MSPCommandResult msp_process_out_fc_version(MSP::sbuf_t *dst) override;
|
||||
MSP::MSPCommandResult msp_process_out_fc_variant(MSP::sbuf_t *dst) override;
|
||||
|
|
|
@ -11,6 +11,11 @@
|
|||
#define HAL_MSP_SENSORS_ENABLED defined(HAL_MSP_ENABLED) && !HAL_MINIMIZE_FEATURES && !defined(HAL_BUILD_AP_PERIPH)
|
||||
#endif
|
||||
|
||||
// define for enabling MSP DisplayPort
|
||||
#ifndef HAL_WITH_MSP_DISPLAYPORT
|
||||
#define HAL_WITH_MSP_DISPLAYPORT defined(HAL_MSP_ENABLED) && !HAL_MINIMIZE_FEATURES && !defined(HAL_BUILD_AP_PERIPH)
|
||||
#endif
|
||||
|
||||
#include <AP_HAL/UARTDriver.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
|
||||
|
@ -35,6 +40,13 @@
|
|||
#define MSP_MAX_HEADER_SIZE 9
|
||||
// inav/src/main/msp/msp_protocol_v2_sensor.h
|
||||
#define MSP2_IS_SENSOR_MESSAGE(x) ((x) >= 0x1F00U && (x) <= 0x1FFFU)
|
||||
// betaflight/src/main/io/displayport_msp.h
|
||||
// MSP displayport V2 attribute byte bit functions
|
||||
#define DISPLAYPORT_MSP_ATTR_VERSION 1U<<7 // Format indicator; must be zero for V2 (and V1)
|
||||
#define DISPLAYPORT_MSP_ATTR_BLINK 1U<<6 // Device local blink
|
||||
#define DISPLAYPORT_MSP_ATTR_MASK (~(DISPLAYPORT_MSP_ATTR_VERSION|DISPLAYPORT_MSP_ATTR_BLINK))
|
||||
// betaflight/src/main/io/displayport_msp.c
|
||||
#define OSD_MSP_DISPLAYPORT_MAX_STRING_LENGTH 30
|
||||
|
||||
class AP_MSP_Telem_Backend;
|
||||
|
||||
|
@ -86,6 +98,14 @@ typedef enum {
|
|||
MSP_COMMAND_RECEIVED
|
||||
} msp_state_e;
|
||||
|
||||
typedef enum : uint8_t {
|
||||
MSP_DISPLAYPORT_HEARTBEAT = 0,
|
||||
MSP_DISPLAYPORT_RELEASE = 1,
|
||||
MSP_DISPLAYPORT_CLEAR_SCREEN = 2,
|
||||
MSP_DISPLAYPORT_WRITE_STRING = 3,
|
||||
MSP_DISPLAYPORT_DRAW_SCREEN = 4,
|
||||
} msp_displayport_subcmd_e;
|
||||
|
||||
typedef struct PACKED {
|
||||
uint8_t size;
|
||||
uint8_t cmd;
|
||||
|
|
Loading…
Reference in New Issue