From b9face97660482faa6d41aac8c7d7197ca6155ef Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 20 Aug 2015 10:47:24 +0200 Subject: [PATCH] PWM in / RC in driver: Move to generated uORB topic --- msg/input_rc.msg | 21 +++++++++ src/drivers/drv_rc_input.h | 91 ++------------------------------------ 2 files changed, 24 insertions(+), 88 deletions(-) create mode 100644 msg/input_rc.msg diff --git a/msg/input_rc.msg b/msg/input_rc.msg new file mode 100644 index 0000000000..c07d229503 --- /dev/null +++ b/msg/input_rc.msg @@ -0,0 +1,21 @@ +uint8 RC_INPUT_SOURCE_UNKNOWN = 0 +uint8 RC_INPUT_SOURCE_PX4FMU_PPM = 1 +uint8 RC_INPUT_SOURCE_PX4IO_PPM = 2 +uint8 RC_INPUT_SOURCE_PX4IO_SPEKTRUM = 3 +uint8 RC_INPUT_SOURCE_PX4IO_SBUS = 4 +uint8 RC_INPUT_SOURCE_PX4IO_ST24 = 5 +uint8 RC_INPUT_SOURCE_MAVLINK = 6 + +uint8 RC_INPUT_MAX_CHANNELS = 18 # Maximum number of R/C input channels in the system. S.Bus has up to 18 channels. + +uint64 timestamp_publication # publication time +uint64 timestamp_last_signal # last valid reception time +uint32 channel_count # number of channels actually being seen +int32 rssi # receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception +bool rc_failsafe # explicit failsafe flag: true on TX failure or TX out of range , false otherwise. Only the true state is reliable, as there are some (PPM) receivers on the market going into failsafe without telling us explicitly. +bool rc_lost # RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise. True usally means that the receiver has been disconnected, but can also indicate a radio link loss on "stupid" systems. Will remain false, if a RX with failsafe option continues to transmit frames after a link loss. +uint16 rc_lost_frame_count # Number of lost RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike funtionality. +uint16 rc_total_frame_count # Number of total RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike funtionality. +uint16 rc_ppm_frame_length # Length of a single PPM frame. Zero for non-PPM systems +uint8 input_source # Input source +uint16[18] values # measured pulse widths for each of the supported channels diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h index b82ced3845..b08f10d465 100644 --- a/src/drivers/drv_rc_input.h +++ b/src/drivers/drv_rc_input.h @@ -57,11 +57,6 @@ */ #define RC_INPUT0_DEVICE_PATH "/dev/input_rc0" -/** - * Maximum number of R/C input channels in the system. S.Bus has up to 18 channels. - */ -#define RC_INPUT_MAX_CHANNELS 18 - /** * Maximum RSSI value */ @@ -82,10 +77,9 @@ */ #define RC_INPUT_MAX_DEADZONE_US 500 -/** - * @addtogroup topics - * @{ - */ +#include +#define pwm_output_values output_pwm_s +#define rc_input_values input_rc_s /** * Input signal type, value is a control position from zero to 100 @@ -93,85 +87,6 @@ */ typedef uint16_t rc_input_t; -enum RC_INPUT_SOURCE { - RC_INPUT_SOURCE_UNKNOWN = 0, - RC_INPUT_SOURCE_PX4FMU_PPM, - RC_INPUT_SOURCE_PX4IO_PPM, - RC_INPUT_SOURCE_PX4IO_SPEKTRUM, - RC_INPUT_SOURCE_PX4IO_SBUS, - RC_INPUT_SOURCE_PX4IO_ST24, - RC_INPUT_SOURCE_MAVLINK -}; - -/** - * R/C input status structure. - * - * Published to input_rc, may also be published to other names depending - * on the board involved. - */ -struct rc_input_values { - /** publication time */ - uint64_t timestamp_publication; - - /** last valid reception time */ - uint64_t timestamp_last_signal; - - /** number of channels actually being seen */ - uint32_t channel_count; - - /** receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception */ - int32_t rssi; - - /** - * explicit failsafe flag: true on TX failure or TX out of range , false otherwise. - * Only the true state is reliable, as there are some (PPM) receivers on the market going - * into failsafe without telling us explicitly. - * */ - bool rc_failsafe; - - /** - * RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise. - * True usally means that the receiver has been disconnected, but can also indicate a radio link loss on "stupid" systems. - * Will remain false, if a RX with failsafe option continues to transmit frames after a link loss. - * */ - bool rc_lost; - - /** - * Number of lost RC frames. - * Note: intended purpose: observe the radio link quality if RSSI is not available - * This value must not be used to trigger any failsafe-alike funtionality. - * */ - uint16_t rc_lost_frame_count; - - /** - * Number of total RC frames. - * Note: intended purpose: observe the radio link quality if RSSI is not available - * This value must not be used to trigger any failsafe-alike funtionality. - * */ - uint16_t rc_total_frame_count; - - /** - * Length of a single PPM frame. - * Zero for non-PPM systems - */ - uint16_t rc_ppm_frame_length; - - /** Input source */ - enum RC_INPUT_SOURCE input_source; - - /** measured pulse widths for each of the supported channels */ - rc_input_t values[RC_INPUT_MAX_CHANNELS]; -}; - -/** - * @} - */ - -/* - * ObjDev tag for R/C inputs. - */ -ORB_DECLARE(input_rc); - #define _RC_INPUT_BASE 0x2b00 /** Fetch R/C input values into (rc_input_values *)arg */