mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: add support for MAVLink receiver, handle RADIO_RC_CHANNELS message
This commit is contained in:
parent
0bb98c3db5
commit
fba1e68ef4
|
@ -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>
|
||||
|
||||
|
@ -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()
|
||||
|
@ -430,6 +434,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) {
|
||||
|
@ -562,6 +569,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;
|
||||
|
@ -597,6 +608,17 @@ bool AP_RCProtocol::protocol_enabled(rcprotocol_t protocol) const
|
|||
return ((1U<<(uint8_t(protocol)+1)) & rc_protocols_mask) != 0;
|
||||
}
|
||||
|
||||
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
||||
void AP_RCProtocol::handle_radio_rc_channels(const mavlink_radio_rc_channels_t* packet)
|
||||
{
|
||||
if (backend[AP_RCProtocol::MAVLINK_RADIO] == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
||||
backend[AP_RCProtocol::MAVLINK_RADIO]->update_radio_rc_channels(packet);
|
||||
};
|
||||
#endif // AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
||||
|
||||
namespace AP {
|
||||
AP_RCProtocol &RC()
|
||||
{
|
||||
|
|
|
@ -20,6 +20,9 @@
|
|||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#endif
|
||||
|
||||
#define MAX_RCIN_CHANNELS 18
|
||||
#define MIN_RCIN_CHANNELS 5
|
||||
|
@ -74,6 +77,9 @@ public:
|
|||
#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
|
||||
};
|
||||
|
@ -158,6 +164,9 @@ public:
|
|||
#endif
|
||||
#if AP_RCPROTOCOL_DRONECAN_ENABLED
|
||||
case DRONECAN:
|
||||
#endif
|
||||
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
||||
case MAVLINK_RADIO:
|
||||
#endif
|
||||
case NONE:
|
||||
return false;
|
||||
|
@ -205,6 +214,11 @@ public:
|
|||
return _detected_with_bytes;
|
||||
}
|
||||
|
||||
// handle mavlink radio
|
||||
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
||||
void handle_radio_rc_channels(const mavlink_radio_rc_channels_t* packet);
|
||||
#endif
|
||||
|
||||
private:
|
||||
void check_added_uart(void);
|
||||
|
||||
|
|
|
@ -44,6 +44,11 @@ public:
|
|||
// allow for backends that need regular polling
|
||||
virtual void update(void) {}
|
||||
|
||||
// update from mavlink messages
|
||||
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
||||
virtual void update_radio_rc_channels(const mavlink_radio_rc_channels_t* packet) {}
|
||||
#endif
|
||||
|
||||
// get number of frames, ignoring failsafe
|
||||
uint32_t get_rc_frame_count(void) const {
|
||||
return rc_frame_count;
|
||||
|
|
|
@ -0,0 +1,25 @@
|
|||
|
||||
#include "AP_RCProtocol_config.h"
|
||||
|
||||
#if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
||||
|
||||
#include "AP_RCProtocol_MAVLinkRadio.h"
|
||||
|
||||
void AP_RCProtocol_MAVLinkRadio::update_radio_rc_channels(const mavlink_radio_rc_channels_t* packet)
|
||||
{
|
||||
const uint8_t count = MIN(packet->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
|
||||
|
|
@ -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:
|
||||
|
||||
using AP_RCProtocol_Backend::AP_RCProtocol_Backend;
|
||||
|
||||
// update from mavlink messages
|
||||
void update_radio_rc_channels(const mavlink_radio_rc_channels_t* packet) override;
|
||||
};
|
||||
|
||||
#endif // AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
|
||||
|
|
@ -2,6 +2,7 @@
|
|||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
#include <AP_Frsky_Telem/AP_Frsky_config.h>
|
||||
#include <GCS_MAVLink/GCS_config.h>
|
||||
|
||||
#ifndef AP_RCPROTOCOL_ENABLED
|
||||
#define AP_RCPROTOCOL_ENABLED 1
|
||||
|
@ -69,3 +70,8 @@
|
|||
#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 && HAL_GCS_ENABLED
|
||||
#endif
|
||||
|
||||
|
|
Loading…
Reference in New Issue