pub struct RADIO_RC_CHANNELS_DATA {
pub time_last_update_ms: u32,
pub flags: RadioRcChannelsFlags,
pub target_system: u8,
pub target_component: u8,
pub count: u8,
pub channels: [i16; 32],
}
development
only.Expand description
id: 420 RC channel outputs from a MAVLink RC receiver for input to a flight controller or other components (allows an RC receiver to connect via MAVLink instead of some other protocol such as PPM-Sum or S.BUS). Note that this is not intended to be an over-the-air format, and does not replace RC_CHANNELS and similar messages reported by the flight controller. The target_system field should normally be set to the system id of the system to control, typically the flight controller. The target_component field can normally be set to 0, so that all components of the system can receive the message. The channels array field can publish up to 32 channels; the number of channel items used in the array is specified in the count field. The time_last_update_ms field contains the timestamp of the last received valid channels data in the receiver’s time domain. The count field indicates the first index of the channel array that is not used for channel data (this and later indexes are zero-filled). The RADIO_RC_CHANNELS_FLAGS_OUTDATED flag is set by the receiver if the channels data is not up-to-date (for example, if new data from the transmitter could not be validated so the last valid data is resent). The RADIO_RC_CHANNELS_FLAGS_FAILSAFE failsafe flag is set by the receiver if the receiver’s failsafe condition is met (implementation dependent, e.g., connection to the RC radio is lost). In this case time_last_update_ms still contains the timestamp of the last valid channels data, but the content of the channels data is not defined by the protocol (it is up to the implementation of the receiver). For instance, the channels data could contain failsafe values configured in the receiver; the default is to carry the last valid data. Note: The RC channels fields are extensions to ensure that they are located at the end of the serialized payload and subject to MAVLink’s trailing-zero trimming.
Fields§
§time_last_update_ms: u32
Time when the data in the channels field were last updated (time since boot in the receiver’s time domain).
flags: RadioRcChannelsFlags
Radio RC channels status flags.
target_system: u8
System ID (ID of target system, normally flight controller).
target_component: u8
Component ID (normally 0 for broadcast).
count: u8
Total number of RC channels being received. This can be larger than 32, indicating that more channels are available but not given in this message.
channels: [i16; 32]
RC channels. Channel values are in centered 13 bit format. Range is -4096 to 4096, center is 0. Conversion to PWM is x * 5/32 + 1500. Channels with indexes equal or above count should be set to 0, to benefit from MAVLink’s trailing-zero trimming.
Implementations§
Source§impl RADIO_RC_CHANNELS_DATA
impl RADIO_RC_CHANNELS_DATA
pub const ENCODED_LEN: usize = 73usize
pub const DEFAULT: Self
Trait Implementations§
Source§impl Clone for RADIO_RC_CHANNELS_DATA
impl Clone for RADIO_RC_CHANNELS_DATA
Source§fn clone(&self) -> RADIO_RC_CHANNELS_DATA
fn clone(&self) -> RADIO_RC_CHANNELS_DATA
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read more