APM:Libraries
|
Go to the source code of this file.
Macros | |
#define | SRXL_MIN_FRAMESPACE_US 8000U /* Minumum space between srxl frames in us (applies to all variants) */ |
#define | SRXL_MAX_CHANNELS 20U /* Maximum number of channels from srxl datastream */ |
#define | STATE_IDLE 0x00U /* do nothing */ |
#define | STATE_NEW 0x01U /* get header of frame + prepare for frame reception + begin new crc cycle */ |
#define | STATE_COLLECT 0x02U /* collect RC channel data from frame + concurrently calc crc over payload data + extract channel information */ |
#define | SRXL_FRAMELEN_V1 27U /* Framelength with header in byte for: Mpx SRXLv1 or XBUS Mode B */ |
#define | SRXL_FRAMELEN_V2 35U /* Framelength with header in byte for: Mpx SRXLv2 */ |
#define | SRXL_FRAMELEN_V5 18U /* Framelength with header in byte for Spk AR7700 etc. */ |
#define | SRXL_FRAMELEN_MAX 35U /* maximum possible framelengh */ |
#define | SRXL_HEADER_V1 0xA1U /* Headerbyte for: Mpx SRXLv1 or XBUS Mode B */ |
#define | SRXL_HEADER_V2 0xA2U /* Headerbyte for: Mpx SRXLv2 */ |
#define | SRXL_HEADER_V5 0xA5U /* Headerbyte for: Spk AR7700 etc. */ |
#define | SRXL_HEADER_NOT_IMPL 0xFFU /* Headerbyte for non impemented srxl header*/ |
Functions | |
static uint16_t | srxl_crc16 (uint16_t crc, uint8_t new_byte) |
static int | srxl_channels_get_v1v2 (uint16_t max_values, uint8_t *num_values, uint16_t *values, bool *failsafe_state) |
static int | srxl_channels_get_v5 (uint16_t max_values, uint8_t *num_values, uint16_t *values, bool *failsafe_state) |
int | srxl_decode (uint64_t timestamp_us, uint8_t byte, uint8_t *num_values, uint16_t *values, uint16_t max_values, bool *failsafe_state) |
Variables | |
static uint8_t | buffer [SRXL_FRAMELEN_MAX] |
static uint8_t | buflen |
static uint64_t | last_data_us |
static uint16_t | channels [SRXL_MAX_CHANNELS] |
static uint8_t | frame_header = 0U |
static uint8_t | frame_len_full = 0U |
static uint8_t | decode_state = STATE_IDLE |
static uint8_t | decode_state_next = STATE_IDLE |
static uint16_t | crc_fmu = 0U |
static uint16_t | crc_receiver = 0U |
static uint16_t | max_channels |
#define SRXL_FRAMELEN_MAX 35U /* maximum possible framelengh */ |
#define SRXL_FRAMELEN_V1 27U /* Framelength with header in byte for: Mpx SRXLv1 or XBUS Mode B */ |
Definition at line 42 of file srxl.cpp.
Referenced by srxl_decode().
#define SRXL_FRAMELEN_V2 35U /* Framelength with header in byte for: Mpx SRXLv2 */ |
Definition at line 43 of file srxl.cpp.
Referenced by srxl_decode().
#define SRXL_FRAMELEN_V5 18U /* Framelength with header in byte for Spk AR7700 etc. */ |
Definition at line 44 of file srxl.cpp.
Referenced by srxl_decode().
#define SRXL_HEADER_NOT_IMPL 0xFFU /* Headerbyte for non impemented srxl header*/ |
Definition at line 51 of file srxl.cpp.
Referenced by srxl_decode().
#define SRXL_HEADER_V1 0xA1U /* Headerbyte for: Mpx SRXLv1 or XBUS Mode B */ |
Definition at line 48 of file srxl.cpp.
Referenced by srxl_decode().
#define SRXL_HEADER_V2 0xA2U /* Headerbyte for: Mpx SRXLv2 */ |
Definition at line 49 of file srxl.cpp.
Referenced by srxl_decode().
#define SRXL_HEADER_V5 0xA5U /* Headerbyte for: Spk AR7700 etc. */ |
Definition at line 50 of file srxl.cpp.
Referenced by srxl_decode().
#define SRXL_MAX_CHANNELS 20U /* Maximum number of channels from srxl datastream */ |
Definition at line 32 of file srxl.cpp.
Referenced by srxl_channels_get_v5().
#define SRXL_MIN_FRAMESPACE_US 8000U /* Minumum space between srxl frames in us (applies to all variants) */ |
Definition at line 31 of file srxl.cpp.
Referenced by srxl_decode().
#define STATE_COLLECT 0x02U /* collect RC channel data from frame + concurrently calc crc over payload data + extract channel information */ |
Definition at line 37 of file srxl.cpp.
Referenced by srxl_decode().
#define STATE_IDLE 0x00U /* do nothing */ |
Definition at line 35 of file srxl.cpp.
Referenced by srxl_decode().
#define STATE_NEW 0x01U /* get header of frame + prepare for frame reception + begin new crc cycle */ |
Definition at line 36 of file srxl.cpp.
Referenced by srxl_decode().
|
static |
Get RC channel information as microsecond pulsewidth representation from srxl version 1 and 2
This function extracts RC channel information from srxl dataframe. The function expects the whole dataframe in correct order in static array "buffer[SRXL_FRAMELEN_MAX]". After extracting all RC channel information, the data is transferred to "values" array from parameter list. If the pixhawk does not support all channels from srxl datastream, only supported number of channels will be refreshed.
IMPORTANT SAFETY NOTICE: This function shall only be used after CRC has been successful.
Structure of SRXL v1 dataframe –> 12 channels, 12 Bit per channel Byte0: Header 0xA1 Byte1: Bits7-4:Empty Bits3-0:Channel1 MSB Byte2: Bits7-0: Channel1 LSB (....) Byte23: Bits7-4:Empty Bits3-0:Channel12 MSB Byte24: Bits7-0: Channel12 LSB Byte25: CRC16 MSB Byte26: CRC16 LSB
Structure of SRXL v2 dataframe –> 16 channels, 12 Bit per channel Byte0: Header 0xA2 Byte1: Bits7-4:Empty Bits3-0:Channel1 MSB Byte2: Bits7-0: Channel1 LSB (....) Byte31: Bits7-4:Empty Bits3-0:Channel16 MSB Byte32: Bits7-0: Channel16 LSB Byte33: CRC16 MSB Byte34: CRC16 LSB
[in] | max_values | - maximum number of values supported by the pixhawk |
[out] | num_values | - number of RC channels extracted from srxl frame |
[out] | values | - array of RC channels with refreshed information as pulsewidth in microseconds Range: 800us - 2200us |
[out] | failsafe_state | - true: RC-receiver is in failsafe state, false: RC-receiver is not in failsafe state |
0 | success |
Definition at line 133 of file srxl.cpp.
Referenced by srxl_decode().
|
static |
Get RC channel information as microsecond pulsewidth representation from srxl version 5
This function extracts RC channel information from srxl dataframe. The function expects the whole dataframe in correct order in static array "buffer[SRXL_FRAMELEN_MAX]". After extracting all RC channel information, the data is transferred to "values" array from parameter list. If the pixhawk does not support all channels from srxl datastream, only supported number of channels will be refreshed.
IMPORTANT SAFETY NOTICE: This function shall only be used after CRC has been successful.
Structure of SRXL v5 dataframe Byte0: Header 0xA5 Byte1 - Byte16: Payload Byte17: CRC16 MSB Byte18: CRC16 LSB
[in] | max_values | - maximum number of values supported by the pixhawk |
[out] | num_values | - number of RC channels extracted from srxl frame |
[out] | values | - array of RC channels with refreshed information as pulsewidth in microseconds Range: 800us - 2200us |
[out] | failsafe_state | - true: RC-receiver is in failsafe state, false: RC-receiver is not in failsafe state |
0 | success |
Definition at line 179 of file srxl.cpp.
Referenced by srxl_decode().
|
static |
This function calculates the 16bit crc as used throughout the srxl protocol variants
This function is intended to be called whenever a new byte shall be added to the crc. Simply provide the old crc and the new data byte and the function return the new crc value.
To start a new crc calculation for a new srxl frame, provide parameter crc=0 and the first byte of the frame.
[in] | crc | - start value for crc |
[in] | new_byte | - byte that shall be included in crc calculation |
Definition at line 86 of file srxl.cpp.
Referenced by srxl_decode().
int srxl_decode | ( | uint64_t | timestamp_us, |
uint8_t | byte, | ||
uint8_t * | num_values, | ||
uint16_t * | values, | ||
uint16_t | max_values, | ||
bool * | failsafe_state | ||
) |
Decode SRXL frames
Structure of all SRXL frames Byte[0]: Header 0xA<VARIANT> –> Variant specific header. Variant is encoded in bits 3-0 of header byte. Byte[1] - Byte[N-2]: SRXL variant specific payload Byte[N-1] - Byte[N]: CRC16 over payload and header
[in] | timestamp_us | - timestamp in microseconds |
[in] | received | byte in microseconds |
[out] | num_values | - number of RC channels extracted from srxl frame |
[out] | values | - array of RC channels with refreshed information as pulsewidth in microseconds Range: 800us - 2200us |
[in] | maximum | number of values supported by pixhawk |
[out] | failsafe_state | - true: RC-receiver is in failsafe state, false: RC-receiver is not in failsafe state |
0 | success (a decoded packet) |
1 | no packet yet (accumulating) |
2 | unknown packet |
4 | checksum error |
Definition at line 262 of file srxl.cpp.
Referenced by Linux::RCInput::add_srxl_input(), and srxl_decode().
|
static |
Definition at line 56 of file srxl.cpp.
Referenced by AP_InertialSensor_L3G4200D::_accumulate(), Linux::RCInput_Navio2::_timer_tick(), F4Light::SPIDevice::apply_speed(), ObjectBuffer< GCS_MAVLINK::pending_param_request >::available(), BM_Crop8bpp(), BM_YuyvToGrey(), AP_GPS_Backend::broadcast_gps_type(), ObjectBuffer< GCS_MAVLINK::pending_param_request >::clear(), ObjectBuffer< GCS_MAVLINK::pending_param_request >::empty(), F4Light::USBDriver::flush(), DataFlash_Backend::Log_Write(), AP_GPS_NOVA::name(), ObjectBuffer< GCS_MAVLINK::pending_param_request >::ObjectBuffer(), ObjectBuffer< GCS_MAVLINK::pending_param_request >::peek(), ObjectBuffer< GCS_MAVLINK::pending_param_request >::pop(), ChibiOS::AnalogIn::power_status_flags(), AP_HAL::BetterStream::println(), ObjectBuffer< GCS_MAVLINK::pending_param_request >::push(), ObjectBuffer< GCS_MAVLINK::pending_param_request >::push_force(), AP_GPS_GSOF::requestBaud(), AP_GPS_GSOF::requestGSOF(), ChibiOS::RCOutput::scale_esc_to_unity(), ObjectBuffer< GCS_MAVLINK::pending_param_request >::space(), srxl_channels_get_v1v2(), srxl_channels_get_v5(), srxl_decode(), AP_Compass_IST8310::timer(), AP_Compass_QMC5883L::timer(), F4Light::UART_OSD::tx_pending(), HALSITL::UARTDriver::tx_pending(), F4Light::UARTDriver::txspace(), AP_SBusOut::update(), ObjectBuffer< GCS_MAVLINK::pending_param_request >::update(), AnalogSource_Navio2::voltage_average(), AP_GPS_Backend::Write_DataFlash_Log_Startup_messages(), and ObjectBuffer< GCS_MAVLINK::pending_param_request >::~ObjectBuffer().
|
static |
Definition at line 57 of file srxl.cpp.
Referenced by SITL::JSBSim::drain_control_socket(), SITL::Gazebo::drain_sockets(), SITL::JSBSim::send_servos(), and srxl_decode().
|
static |
Definition at line 59 of file srxl.cpp.
Referenced by Linux::RCInput_SoloLink::_timer_tick(), SRV_Channels::adjust_trim(), SRV_Channels::channel_function(), SRV_Channels::constrain_pwm(), SRV_Channels::copy_radio_in_out(), SRV_Channels::copy_radio_in_out_mask(), SRV_Channels::enable_aux_servos(), SRV_Channels::find_channel(), SRV_Channels::get_channel_for(), SRV_Channels::get_output_norm(), SRV_Channels::get_output_pwm(), SRV_Channels::limit_slew_rate(), SRV_Channels::move_servo(), SRV_Channels::output_ch_all(), RC_Channels::rc_channel(), SRV_Channels::set_angle(), SRV_Channels::set_aux_channel_default(), SRV_Channels::set_default_function(), SRV_Channels::set_esc_scaling_for(), SRV_Channels::set_failsafe_limit(), SRV_Channels::set_failsafe_pwm(), SRV_Channels::set_output_limit(), SRV_Channels::set_output_pwm(), SRV_Channels::set_output_pwm_first(), SRV_Channels::set_output_pwm_trimmed(), SRV_Channels::set_output_to_trim(), SRV_Channels::set_range(), SRV_Channels::set_rc_frequency(), SRV_Channels::set_safety_limit(), SRV_Channels::set_trim_to_min_for(), SRV_Channels::set_trim_to_pwm_for(), SRV_Channels::set_trim_to_servo_out_for(), SRV_Channels::srv_channel(), srxl_channels_get_v1v2(), srxl_channels_get_v5(), SRV_Channels::update_aux_servo_function(), SRV_Channels::upgrade_motors_servo(), and SRV_Channels::upgrade_parameters().
|
static |
Definition at line 65 of file srxl.cpp.
Referenced by srxl_decode().
|
static |
Definition at line 66 of file srxl.cpp.
Referenced by srxl_decode().
|
static |
Definition at line 63 of file srxl.cpp.
Referenced by srxl_decode().
|
static |
Definition at line 64 of file srxl.cpp.
Referenced by srxl_decode().
|
static |
Definition at line 61 of file srxl.cpp.
Referenced by srxl_decode().
|
static |
Definition at line 62 of file srxl.cpp.
Referenced by srxl_channels_get_v1v2(), and srxl_decode().
|
static |
Definition at line 58 of file srxl.cpp.
Referenced by srxl_decode().
|
static |
Definition at line 69 of file srxl.cpp.
Referenced by srxl_channels_get_v5().