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

Added link stats packet #33

Open
wants to merge 8 commits into
base: master
Choose a base branch
from
Open
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
40 changes: 40 additions & 0 deletions dronecan/sensors/rc/1141.RCLinkStats.uavcan
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
#
# This definition describes metadata and statistics for a RF control link.
# It provides information regarding a link's signal quality, as well as transmitter
# power, and antenna information. It accomodates single-radio, and dual-radio
# link architectures. It provides information for both uplink (control unit to airborne
# receiver), and downlink (airborne receiver to control unit) data.
#

uint8 STATUS_RSSI_VALID = 1 # RSSI field is valid

# Uplink - received signal strength, in decibel-milliwatts (RSSI dBm) for antennas 1 and 2 respectively.
# Ranges from # -255 to 0. (An integer value of 100 means RSSI is -100dBm)
uint8 uplink_rssi_1
uint8 uplink_rssi_2

# Link quality, on a scale from 1 to 255. Is a proxy for packet loss. 0 means data is unavailable. 1 and 255 are mapped to 0% and 100% of packets received.
uint8 uplink_link_quality
Comment on lines +16 to +17
Copy link

@hamishwillee hamishwillee Jun 22, 2023

Choose a reason for hiding this comment

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

This version would align with MAVLink better.

  • MAVLink uses 0 as a proxy for invalid by preference, and max field values if "0" is meaningful number for the field., In this case 0 is valid, so suggest we swap around.
  • Usually it is easier for users parsing the data to supply percentage data as a 0..100 range. The only reason to use the full range is if you need finer resolution, which I do not believe is the case here.
  • Have no discussed the words with OllieW yet.
Suggested change
# Link quality, on a scale from 1 to 255. Is a proxy for packet loss. 0 means data is unavailable. 1 and 255 are mapped to 0% and 100% of packets received.
uint8 uplink_link_quality
# Link quality, as a percentage of valid packets received over some time period [0..100]. 256 means data is unavailable.
uint8 uplink_link_quality

Choose a reason for hiding this comment

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

@David-OConnor Can we swap to this pattern?


David-OConnor marked this conversation as resolved.
Show resolved Hide resolved
# Signal-to-noise ratio.
int8 uplink_snr

# This is an implementation-specific enum. May represent the OTA protocol used,
# and transmission rate.
uint8 rf_mode

# This is an implementation-specific enum describing the current transmitter nominal
# power level.
uint8 uplink_tx_power

# Statistics for downlink data, ie telemetry. See their respective `uplink` fields for
# descriptions.
uint8 downlink_rssi_1
uint8 downlink_rssi_2
uint8 downlink_link_quality
int8 downlink_snr

# Active antenna on transmitter and receiver. Example: 1 for antenna 1, and 2 for antenna 2.
# Not applicable for single-antenna links.
uint8 tx_active_antenna
uint8 rx_active_antenna
Comment on lines +37 to +40

Choose a reason for hiding this comment

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

Is this the uplink or the downlink? Or is this a typo - ie. do you mean uplink_tx_active_antenna and uplink_rx_active_antenna or something else?

From discussion on MAVLink issue:

a unit which has two antenna may or may not split them into one is for Tx and the other one for Rx.
Usually, at least in nearly all cases I'm aware of, they both would be used to e.g. receive, which is when called receive diversity. Note that many bidirectional units are half-duplex, i.e. work as transmit-receive-transmit-receive-.... so that both antenna can be used for receiving one frame at the same time.
I guess the system you have in mind is a system there two over-the-air channels/frequencies are used in parallel, in a full-duplex sense, there one channel/frequency is for transmission in one direction and the other for transmission in the other direction. As said, essentially all systems I'm aware of are of the half-duplex nature.
Anyway, also the full-duplex case can be represented by the suggested fields.

My assumption is therefore that you need to be able to get info for antenna usage on both uplink and downlink.
(Note, Ollie uses Rx for air unit, and Tx for ground unit).

I'm still confused by the intent here - i.e. if you have bidirectional data, and the antenna both receive and both send in a cycle how would you represent it. I mean you'd have to show "no rx antenna and both 1 and 2 on the tx, then visa versa).
Also if it is switching, how useful is that?