Skip to content

Commit

Permalink
AP_RCProtocol: add support for RC input from SITL FDM data
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Mar 15, 2024
1 parent 8ae8c65 commit c0f4454
Show file tree
Hide file tree
Showing 7 changed files with 131 additions and 1 deletion.
27 changes: 26 additions & 1 deletion libraries/AP_RCProtocol/AP_RCProtocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#include "AP_RCProtocol_MAVLinkRadio.h"
#include "AP_RCProtocol_Joystick_SFML.h"
#include "AP_RCProtocol_UDP_Packed16BitValues.h"
#include "AP_RCProtocol_FDM.h"
#include <AP_Math/AP_Math.h>
#include <RC_Channel/RC_Channel.h>

Expand Down Expand Up @@ -98,8 +99,18 @@ void AP_RCProtocol::init()
backend[AP_RCProtocol::JOYSTICK_SFML] = new AP_RCProtocol_Joystick_SFML(*this);
#endif
#if AP_RCPROTOCOL_UDP_PACKED16BITVALUES_ENABLED
backend[AP_RCProtocol::UDP_PACKED16BITVALUES] = new AP_RCProtocol_UDP_Packed16BitValues(*this);
const auto UDP_Packed16BitValues_backend = new AP_RCProtocol_UDP_Packed16BitValues(*this);
backend[AP_RCProtocol::UDP_PACKED16BITVALUES] = UDP_Packed16BitValues_backend;
#endif
#if AP_RCPROTOCOL_FDM_ENABLED
const auto FDM_backend = new AP_RCProtocol_FDM(*this);;
backend[AP_RCProtocol::FDM] = FDM_backend;
#if AP_RCPROTOCOL_UDP_PACKED16BITVALUES_ENABLED
// the UDP-Packed16Bit backend gives way to the FDM backend:
UDP_Packed16BitValues_backend->set_fdm_backend(FDM_backend);
#endif // AP_RCPROTOCOL_UDP_PACKED16BITVALUES_ENABLED
#endif // AP_RCPROTOCOL_FDM_ENABLED

}

AP_RCProtocol::~AP_RCProtocol()
Expand All @@ -114,6 +125,13 @@ AP_RCProtocol::~AP_RCProtocol()

bool AP_RCProtocol::should_search(uint32_t now_ms) const
{
#if AP_RCPROTOCOL_FDM_ENABLED && AP_RCPROTOCOL_UDP_PACKED16BITVALUES_ENABLED
// force re-detection when FDM is active and active backend is UDP values
if (_detected_protocol == AP_RCProtocol::UDP_PACKED16BITVALUES &&
((AP_RCProtocol_FDM*)backend[AP_RCProtocol::FDM])->active()) {
return true;
}
#endif // AP_RCPROTOCOL_FDM_ENABLED && AP_RCPROTOCOL_UDP_PACKED16BITVALUES_ENABLED
#if AP_RC_CHANNEL_ENABLED && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
if (_detected_protocol != AP_RCProtocol::NONE && !rc().option_is_enabled(RC_Channels::Option::MULTI_RECEIVER_SUPPORT)) {
return false;
Expand Down Expand Up @@ -451,6 +469,9 @@ bool AP_RCProtocol::new_input()
#endif
#if AP_RCPROTOCOL_UDP_PACKED16BITVALUES_ENABLED
AP_RCProtocol::UDP_PACKED16BITVALUES,
#endif
#if AP_RCPROTOCOL_FDM_ENABLED
AP_RCProtocol::FDM,
#endif
};
for (const auto protocol : pollable) {
Expand Down Expand Up @@ -595,6 +616,10 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol)
#if AP_RCPROTOCOL_UDP_PACKED16BITVALUES_ENABLED
case UDP_PACKED16BITVALUES:
return "UDP-Packed16BitValues";
#endif
#if AP_RCPROTOCOL_FDM_ENABLED
case FDM:
return "FDM";
#endif
case NONE:
break;
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,9 @@ class AP_RCProtocol {
#endif
#if AP_RCPROTOCOL_UDP_PACKED16BITVALUES_ENABLED
UDP_PACKED16BITVALUES = 17,
#endif
#if AP_RCPROTOCOL_FDM_ENABLED
FDM = 18,
#endif
NONE //last enum always is None
};
Expand Down Expand Up @@ -179,6 +182,9 @@ class AP_RCProtocol {
#endif
#if AP_RCPROTOCOL_UDP_PACKED16BITVALUES_ENABLED
case UDP_PACKED16BITVALUES:
#endif
#if AP_RCPROTOCOL_FDM_ENABLED
case FDM:
#endif
case NONE:
return false;
Expand Down
50 changes: 50 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol_FDM.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
#include "AP_RCProtocol_config.h"

#if AP_RCPROTOCOL_FDM_ENABLED

#include "AP_RCProtocol_FDM.h"

#include <AP_HAL/AP_HAL.h>
#include <SITL/SITL.h>

extern const AP_HAL::HAL& hal;

void AP_RCProtocol_FDM::update()
{
const auto sitl = AP::sitl();
if (sitl == nullptr) {
return;
}

const auto &fdm = sitl->state;

// see if there's fresh input. Until timestamps are worked out,
// just check for non-zero values:
if (fdm.rcin_chan_count == 0) {
return;
}

// simulate RC input at 50Hz
if (AP_HAL::millis() - last_input_ms < 20) {
return;
}

last_input_ms = AP_HAL::millis();

// scale from FDM 0-1 floats to PWM values
// these are the values that will be fed into the autopilot.
uint16_t pwm_input[16];
const uint8_t count = MIN(ARRAY_SIZE(pwm_input), fdm.rcin_chan_count);
for (uint8_t i=0; i<count; i++) {
pwm_input[i] = 1000 + fdm.rcin[i] * 1000;
}
add_input(
count,
pwm_input,
false, // failsafe
0, // check me
0 // link quality
);
}

#endif // AP_RCPROTOCOL_FDM_ENABLED
24 changes: 24 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol_FDM.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
#pragma once

#include "AP_RCProtocol_config.h"

#if AP_RCPROTOCOL_FDM_ENABLED

#include "AP_RCProtocol_Backend.h"

class AP_RCProtocol_FDM : public AP_RCProtocol_Backend {
public:

using AP_RCProtocol_Backend::AP_RCProtocol_Backend;

void update() override;

bool active() const { return last_input_ms > 0; }

private:

uint32_t last_input_ms;
};


#endif // AP_RCPROTOCOL_FDM_ENABLED
11 changes: 11 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol_UDP_Packed16BitValues.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,10 @@
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <SITL/SITL.h>

#if AP_RCPROTOCOL_FDM_ENABLED
#include "AP_RCProtocol_FDM.h"
#endif

extern const AP_HAL::HAL& hal;

void AP_RCProtocol_UDP_Packed16BitValues::set_default_pwm_input_values()
Expand Down Expand Up @@ -59,6 +63,13 @@ bool AP_RCProtocol_UDP_Packed16BitValues::init()

void AP_RCProtocol_UDP_Packed16BitValues::update()
{
#if AP_RCPROTOCOL_FDM_ENABLED
// yield to the FDM backend if it is getting data
if (fdm_backend->active()) {
return;
}
#endif

if (!init_done) {
if (!init()) {
return;
Expand Down
10 changes: 10 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol_UDP_Packed16BitValues.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,12 @@ class AP_RCProtocol_UDP_Packed16BitValues : public AP_RCProtocol_Backend {

void update() override;

#if AP_RCPROTOCOL_FDM_ENABLED
void set_fdm_backend(class AP_RCProtocol_FDM *_fdm_backend) {
fdm_backend = _fdm_backend;
}
#endif

private:

bool init();
Expand All @@ -33,6 +39,10 @@ class AP_RCProtocol_UDP_Packed16BitValues : public AP_RCProtocol_Backend {
uint8_t num_channels;

void set_default_pwm_input_values();

#if AP_RCPROTOCOL_FDM_ENABLED
AP_RCProtocol_FDM *fdm_backend;
#endif
};


Expand Down
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 @@ -82,3 +82,7 @@
#ifndef AP_RCPROTOCOL_UDP_PACKED16BITVALUES_ENABLED
#define AP_RCPROTOCOL_UDP_PACKED16BITVALUES_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#endif

#ifndef AP_RCPROTOCOL_FDM_ENABLED
#define AP_RCPROTOCOL_FDM_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#endif

0 comments on commit c0f4454

Please sign in to comment.