Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

DroneCAN: Add support for few more statistics to DroneCAN RC #28390

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 5 additions & 5 deletions libraries/AP_OSD/AP_OSD_Screen.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2064,7 +2064,7 @@ bool AP_OSD_Screen::is_btfl_fonts()

void AP_OSD_Screen::draw_rc_tx_power(uint8_t x, uint8_t y)
{
const int16_t tx_power = AP::crsf()->get_link_status().tx_power;
const int16_t tx_power = AP::RC().get_link_status().tx_power;
bool btfl = is_btfl_fonts();
if (tx_power > 0) {
if (tx_power < 1000) {
Expand Down Expand Up @@ -2092,7 +2092,7 @@ void AP_OSD_Screen::draw_rc_tx_power(uint8_t x, uint8_t y)

void AP_OSD_Screen::draw_rc_rssi_dbm(uint8_t x, uint8_t y)
{
const int8_t rssidbm = AP::crsf()->get_link_status().rssi_dbm;
const int8_t rssidbm = AP::RC().get_link_status().rssi_dbm;
const bool blink = -rssidbm < osd->warn_rssi;
bool btfl = is_btfl_fonts();

Expand All @@ -2115,7 +2115,7 @@ void AP_OSD_Screen::draw_rc_rssi_dbm(uint8_t x, uint8_t y)

void AP_OSD_Screen::draw_rc_snr(uint8_t x, uint8_t y)
{
const int8_t snr = AP::crsf()->get_link_status().snr;
const int8_t snr = AP::RC().get_link_status().snr;
const bool blink = snr < osd->warn_snr;
bool btfl = is_btfl_fonts();
if (snr == INT8_MIN) {
Expand All @@ -2135,7 +2135,7 @@ void AP_OSD_Screen::draw_rc_snr(uint8_t x, uint8_t y)

void AP_OSD_Screen::draw_rc_active_antenna(uint8_t x, uint8_t y)
{
const int8_t active_antenna = AP::crsf()->get_link_status().active_antenna;
const int8_t active_antenna = AP::RC().get_link_status().active_antenna;
bool btfl = is_btfl_fonts();
if (active_antenna < 0) {
if (btfl) {
Expand All @@ -2154,7 +2154,7 @@ void AP_OSD_Screen::draw_rc_active_antenna(uint8_t x, uint8_t y)

void AP_OSD_Screen::draw_rc_lq(uint8_t x, uint8_t y)
{
const int16_t lqv = AP::crsf()->get_link_status().link_quality;
const int16_t lqv = AP::RC().get_link_status().link_quality;
const bool blink = lqv < osd->warn_lq;
bool btfl = is_btfl_fonts();
bool prefix_rf = check_option(AP_OSD::OPTION_RF_MODE_ALONG_WITH_LQ);
Expand Down
12 changes: 12 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -250,6 +250,18 @@ class AP_RCProtocol {
void handle_radio_rc_channels(const mavlink_radio_rc_channels_t* packet);
#endif

// some backends have a struct LinkStatus and a field _link_status, avoid name clash
struct RcLinkStatus {
int16_t link_quality = -1;
int16_t tx_power = -1;
int8_t rssi_dbm = -1;
int8_t snr = INT8_MIN;
int8_t active_antenna = -1;
};
volatile struct RcLinkStatus _rc_link_status;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
volatile struct RcLinkStatus _rc_link_status;
volatile struct RCLinkStatus _rc_link_status;

Why volatile?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this I didn't understand too ... so I was just closily following what is done for the CRSF class
https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h#L310-L314
https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h#L361
assuming that someone had a good reason which is above my paygrade

pl say clear "yes volatile" or "no voloatile" and I will do

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

has the "volatile" thing been sorted out? It should stay?


const volatile RcLinkStatus& get_link_status() const { return _rc_link_status; }

private:
void check_added_uart(void);

Expand Down
9 changes: 9 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -632,6 +632,15 @@ void AP_RCProtocol_CRSF::process_link_stats_frame(const void* data)
_link_status.active_antenna = -1;
}
#endif

// Report to frontend
frontend._rc_link_status.link_quality = _link_status.link_quality;
#if AP_OSD_LINK_STATS_EXTENSIONS_ENABLED
frontend._rc_link_status.rssi_dbm = _link_status.rssi_dbm;
frontend._rc_link_status.snr = _link_status.snr;
frontend._rc_link_status.tx_power = _link_status.tx_power;
frontend._rc_link_status.active_antenna = _link_status.active_antenna;
#endif
}

// process link statistics to get RX RSSI
Expand Down
44 changes: 42 additions & 2 deletions libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,12 +90,52 @@ void AP_RCProtocol_DroneCAN::update()
}
last_receive_ms = rcin.last_sample_time_ms;

if (rcin.bits.QUALITY_VALID) {
switch (rcin.bits.QUALITY_TYPE) {
case QualityType::RSSI:
rssi = rcin.quality;
break;
case QualityType::LQ_ACTIVE_ANTENNA:
// highest bit carries active antenna data
frontend._rc_link_status.link_quality = (rcin.quality & 0x7F);
frontend._rc_link_status.active_antenna = (rcin.quality & 0x80) ? 1 : 0;
break;
case QualityType::RSSI_DBM:
frontend._rc_link_status.rssi_dbm = rcin.quality;
// also set the rssi field, this avoids having to waste a slot for sending both
// AP rssi: -1 for unknown, 0 for no link, 255 for maximum link
if (rcin.quality < 50) {
rssi = 255;
} else if (rcin.quality > 120) {
rssi = 0;
} else {
rssi = int16_t(roundf((120.0f - rcin.quality) * (255.0f / 70.0f)));
}
break;
case QualityType::SNR:
// SNR is shifted by 128 to support negative values
frontend._rc_link_status.snr = (int8_t)rcin.quality - 128;
break;
case QualityType::TX_POWER:
// carries tx power in units of 5 mW, thus can't support higher than 255*5 = 1275 mW
frontend._rc_link_status.tx_power = (int16_t)rcin.quality * 5;
break;
}
} else {
rssi = -1;
frontend._rc_link_status.link_quality = -1;
frontend._rc_link_status.rssi_dbm = -1;
frontend._rc_link_status.snr = INT8_MIN;
frontend._rc_link_status.tx_power = -1;
frontend._rc_link_status.active_antenna = -1;
}

add_input(
rcin.num_channels,
rcin.channels,
rcin.bits.FAILSAFE,
rcin.bits.QUALITY_VALID ? rcin.quality : 0, // CHECK ME
0 // link quality
rssi,
frontend._rc_link_status.link_quality
);
}
}
Expand Down
11 changes: 11 additions & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,22 @@ class AP_RCProtocol_DroneCAN : public AP_RCProtocol_Backend {

static AP_RCProtocol_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id);

enum QualityType {
RSSI = 0,
LQ_ACTIVE_ANTENNA = 1,
RSSI_DBM = 2,
SNR = 3,
TX_POWER = 4
};

struct {
uint8_t quality;
union {
uint16_t status;
struct {
uint8_t QUALITY_VALID : 1;
uint8_t FAILSAFE : 1;
uint8_t QUALITY_TYPE : 3;
} bits;
};
uint8_t num_channels;
Expand All @@ -46,6 +55,8 @@ class AP_RCProtocol_DroneCAN : public AP_RCProtocol_Backend {
HAL_Semaphore sem;
} rcin;

int16_t rssi = -1;

// Module Detection Registry
static struct Registry {
struct DetectedDevice {
Expand Down
Loading