Skip to content

Commit

Permalink
AP_RCProtocol: add support for MAVLink receiver, handle RADIO_RC_CHAN…
Browse files Browse the repository at this point in the history
…NELS message
  • Loading branch information
olliw42 committed Feb 29, 2024
1 parent d437991 commit c8172a2
Show file tree
Hide file tree
Showing 6 changed files with 95 additions and 0 deletions.
26 changes: 26 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include "AP_RCProtocol_FPort2.h"
#include "AP_RCProtocol_DroneCAN.h"
#include "AP_RCProtocol_GHST.h"
#include "AP_RCProtocol_MAVLinkRadio.h"
#include <AP_Math/AP_Math.h>
#include <RC_Channel/RC_Channel.h>

Expand Down Expand Up @@ -88,6 +89,9 @@ void AP_RCProtocol::init()
#if AP_RCPROTOCOL_GHST_ENABLED
backend[AP_RCProtocol::GHST] = new AP_RCProtocol_GHST(*this);
#endif
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
backend[AP_RCProtocol::MAVLINK_RADIO] = new AP_RCProtocol_MAVLinkRadio(*this);
#endif
}

AP_RCProtocol::~AP_RCProtocol()
Expand Down Expand Up @@ -422,6 +426,9 @@ bool AP_RCProtocol::new_input()
const rcprotocol_t pollable[] {
#if AP_RCPROTOCOL_DRONECAN_ENABLED
AP_RCProtocol::DRONECAN,
#endif
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
AP_RCProtocol::MAVLINK_RADIO,
#endif
};
for (const auto protocol : pollable) {
Expand Down Expand Up @@ -554,6 +561,10 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
#if AP_RCPROTOCOL_GHST_ENABLED
case GHST:
return "GHST";
#endif
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
case MAVLINK_RADIO:
return "MAVRadio";
#endif
case NONE:
break;
Expand Down Expand Up @@ -589,6 +600,21 @@ bool AP_RCProtocol::protocol_enabled(rcprotocol_t protocol) const
return ((1U<<(uint8_t(protocol)+1)) & rc_protocols_mask) != 0;
}

void AP_RCProtocol::handle_radio_rc_channels(const mavlink_radio_rc_channels_t* packet)
{
// take a shortcut if protocol is known to be MAVLINK_RADIO
if (_detected_protocol == AP_RCProtocol::MAVLINK_RADIO) {
backend[_detected_protocol]->update_radio_rc_channels(packet);
return;
}

for (uint8_t i = 0; i < ARRAY_SIZE(backend); i++) {
if (backend[i] != nullptr) {
backend[i]->update_radio_rc_channels(packet);
}
}
};

namespace AP {
AP_RCProtocol &RC()
{
Expand Down
10 changes: 10 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@

#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <GCS_MAVLink/GCS_MAVLink.h>

#define MAX_RCIN_CHANNELS 18
#define MIN_RCIN_CHANNELS 5
Expand Down Expand Up @@ -74,6 +75,9 @@ class AP_RCProtocol {
#endif
#if AP_RCPROTOCOL_GHST_ENABLED
GHST = 14,
#endif
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
MAVLINK_RADIO = 15,
#endif
NONE //last enum always is None
};
Expand Down Expand Up @@ -158,6 +162,9 @@ class AP_RCProtocol {
#endif
#if AP_RCPROTOCOL_DRONECAN_ENABLED
case DRONECAN:
#endif
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
case MAVLINK_RADIO:
#endif
case NONE:
return false;
Expand Down Expand Up @@ -205,6 +212,9 @@ class AP_RCProtocol {
return _detected_with_bytes;
}

// handle mavlink radio
void handle_radio_rc_channels(const mavlink_radio_rc_channels_t* packet);

private:
void check_added_uart(void);

Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,9 @@ class AP_RCProtocol_Backend {
// allow for backends that need regular polling
virtual void update(void) {}

// update from mavlink messages
virtual void update_radio_rc_channels(const mavlink_radio_rc_channels_t* packet) {}

// get number of frames, ignoring failsafe
uint32_t get_rc_frame_count(void) const {
return rc_frame_count;
Expand Down
31 changes: 31 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol_MavlinkRadio.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@

#include "AP_RCProtocol_config.h"

#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED

#include "AP_RCProtocol_MAVLinkRadio.h"

// constructor
AP_RCProtocol_MAVLinkRadio::AP_RCProtocol_MAVLinkRadio(AP_RCProtocol &_frontend) :
AP_RCProtocol_Backend(_frontend)
{}

void AP_RCProtocol_MAVLinkRadio::update_radio_rc_channels(const mavlink_radio_rc_channels_t* packet)
{
uint8_t count = packet->count;
if (count >= MAX_RCIN_CHANNELS) count = MAX_RCIN_CHANNELS;

uint16_t rc_chan[MAX_RCIN_CHANNELS];
for (uint8_t i = 0; i < count; i++) {
// The channel values are in centered 13 bit format. Range is [-4096,4096], center is 0.
// According to specification, the conversion to PWM is x * 5/32 + 1500.
rc_chan[i] = ((int32_t)packet->channels[i] * 5) / 32 + 1500;
}

bool failsafe = (packet->flags & RADIO_RC_CHANNELS_FLAGS_FAILSAFE);

add_input(count, rc_chan, failsafe);
}

#endif // AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED

21 changes: 21 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol_MavlinkRadio.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@

#pragma once

#include "AP_RCProtocol_config.h"

#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED

#include "AP_RCProtocol.h"


class AP_RCProtocol_MAVLinkRadio : public AP_RCProtocol_Backend {
public:

AP_RCProtocol_MAVLinkRadio(AP_RCProtocol &_frontend);

// update from mavlink messages
void update_radio_rc_channels(const mavlink_radio_rc_channels_t* packet) override;
};

#endif // AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED

4 changes: 4 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,3 +69,7 @@
#ifndef AP_RCPROTOCOL_GHST_ENABLED
#define AP_RCPROTOCOL_GHST_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED
#endif

#ifndef AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
#define AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024
#endif

0 comments on commit c8172a2

Please sign in to comment.