40 #if defined(SPEKTRUM_POWER)    41 static bool bind_spektrum(
int arg);
    58     for (
unsigned i = 0; i < input_rc_s::RC_INPUT_MAX_CHANNELS; i++) {
    91 #  ifdef RF_RADIO_POWER_CONTROL    93     RF_RADIO_POWER_CONTROL(
true);
   103     if (board_rc_swap_rxtx(
_device)) {
   104         ioctl(
_rcs_fd, TIOCSSWAP, SER_SWAP_ENABLED);
   113     px4_arch_unconfiggpio(GPIO_PPM_IN);
   123     bool run_as_task = 
false;
   124     bool error_flag = 
false;
   128     const char *myoptarg = 
nullptr;
   129     const char *
device = RC_SERIAL_PORT;
   131     while ((ch = px4_getopt(argc, argv, 
"td:", &myoptind, &myoptarg)) != EOF) {
   146             PX4_WARN(
"unrecognized flag");
   167         wait_until_running();
   169         _task_id = task_id_is_work_queue;
   175         const char *
const args[] = { device, 
nullptr };
   176         _task_id = px4_task_spawn_cmd(
"rc_input",
   178                           SCHED_PRIORITY_SLOW_DRIVER,
   180                           (px4_main_t)&run_trampoline,
   181                           (
char *
const *)args);
   198         PX4_ERR(
"alloc failed");
   202     int ret = dev->
init();
   205         PX4_ERR(
"init failed (%i)", ret);
   223             uint16_t raw_rc_values_local[input_rc_s::RC_INPUT_MAX_CHANNELS],
   225             unsigned frame_drops, 
int rssi = -1)
   234     unsigned valid_chans = 0;
   239         if (raw_rc_values_local[i] != UINT16_MAX) {
   258             if (rssi_analog > 100.0
f) {
   259                 rssi_analog = 100.0f;
   262             if (rssi_analog < 0.0
f) {
   276     if (valid_chans == 0) {
   286 #ifdef RC_SERIAL_PORT   291     _rc_scan_state = newState;
   298     if (!board_rc_invert_input(
_device, invert)) {
   299         ioctl(
_rcs_fd, TIOCSINVERT, invert ? (SER_INVERT_ENABLED_RX | SER_INVERT_ENABLED_TX) : 0);
   310         PX4_ERR(
"init failed (%i)", ret);
   327 #if defined(SPEKTRUM_POWER)   333             if ((
unsigned int)vcmd.
command == vehicle_command_s::VEHICLE_CMD_START_RX_PAIR) {
   335                     if ((
int)vcmd.
param1 == 0) {
   337                         int dsm_bind_mode = (int)vcmd.
param2;
   339                         int dsm_bind_pulses = 0;
   341                         if (dsm_bind_mode == 0) {
   344                         } 
else if (dsm_bind_mode == 1) {
   351                         bind_spektrum(dsm_bind_pulses);
   355                     PX4_WARN(
"system armed, bind request rejected");
   363 #ifdef ADC_RC_RSSI_CHANNEL   369             for (
unsigned i = 0; i < adc_chans; i++) {
   370                 if (adc.
channel_id[i] == ADC_RC_RSSI_CHANNEL) {
   388         bool rc_updated = 
false;
   390 #ifdef RC_SERIAL_PORT   395         bool sbus_failsafe, sbus_frame_drop;
   396         unsigned frame_drops;
   418         switch (_rc_scan_state) {
   432                                 &sbus_frame_drop, &frame_drops, input_rc_s::RC_INPUT_MAX_CHANNELS);
   438                                sbus_frame_drop, sbus_failsafe, frame_drops);
   465                                    &dsm_11_bit, &frame_drops, &dsm_rssi, input_rc_s::RC_INPUT_MAX_CHANNELS);
   471                                false, 
false, frame_drops, dsm_rssi);
   495                     uint8_t st24_rssi, lost_count;
   499                     for (
unsigned i = 0; i < (unsigned)newBytes; i++) {
   510                         if (lost_count == 0) {
   514                                    false, 
false, frame_drops, st24_rssi);
   543                     uint8_t sumd_rssi, rx_count;
   548                     for (
unsigned i = 0; i < (unsigned)newBytes; i++) {
   559                                false, sumd_failsafe, frame_drops, sumd_rssi);
   573 #ifdef HRT_PPM_CHANNEL   577                 px4_arch_configgpio(GPIO_PPM_IN);
   579                 ioctl(
_rcs_fd, TIOCSINVERT, 0);
   596                 px4_arch_unconfiggpio(GPIO_PPM_IN);
   601 #else   // skip PPM if it's not supported   604 #endif  // HRT_PPM_CHANNEL   621                                 input_rc_s::RC_INPUT_MAX_CHANNELS);
   631 #ifdef CONFIG_ARCH_BOARD_OMNIBUS_F4SD   655 #else  // RC_SERIAL_PORT not defined   656 #ifdef HRT_PPM_CHANNEL   667 #endif  // HRT_PPM_CHANNEL   668 #endif  // RC_SERIAL_PORT   700 #if defined(SPEKTRUM_POWER)   701 bool bind_spektrum(
int arg)
   708     PX4_INFO(
"DSM_BIND_START: DSM%s RX", (arg == 0) ? 
"2" : ((arg == 1) ? 
"-X" : 
"-X8"));
   722         irqstate_t flags = px4_enter_critical_section();
   724         px4_leave_critical_section(flags);
   733         PX4_ERR(
"DSM bind failed");
   737     return (ret == PX4_OK);
   744     return new RCInput(
true, argv[0]);
   749 #if defined(SPEKTRUM_POWER)   750     const char *verb = argv[0];
   752     if (!strcmp(verb, 
"bind")) {
   773     PX4_INFO(
"Running %s", (
_run_as_task ? 
"as task" : 
"on work queue"));
   780         PX4_INFO(
"Serial device: %s", 
_device);
   787 #if ADC_RC_RSSI_CHANNEL   805         PX4_WARN(
"%s\n", reason);
   808     PRINT_MODULE_DESCRIPTION(
   811 This module does the RC input parsing and auto-selecting the method. Supported methods are:   817 - TBS Crossfire (CRSF)   820 By default the module runs on the work queue, to reduce RAM usage. It can also be run in its own thread,   821 specified via start flag -t, to reduce latency.   822 When running on the work queue, it schedules at a fixed frequency.   825     PRINT_MODULE_USAGE_NAME("rc_input", 
"driver");
   826     PRINT_MODULE_USAGE_COMMAND_DESCR(
"start", 
"Start the task (without any mode set, use any of the mode_* cmds)");
   827     PRINT_MODULE_USAGE_PARAM_FLAG(
't', 
"Run as separate task instead of the work queue", 
true);
   828     PRINT_MODULE_USAGE_PARAM_STRING(
'd', 
"/dev/ttyS3", 
"<file:dev>", 
"RC device", 
true);
   830 #if defined(SPEKTRUM_POWER)   831     PRINT_MODULE_USAGE_COMMAND_DESCR(
"bind", 
"Send a DSM bind command (module must be running)");
   834     PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
 
int sumd_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels, uint16_t max_chan_count, bool *failsafe)
Decoder for SUMD/SUMH protocol. 
measure the time elapsed performing an event 
__EXPORT uint16_t ppm_frame_length
length of the decoded PPM frame (includes gap) 
int main(int argc, char **argv)
bool crsf_parse(const uint64_t now, const uint8_t *frame, unsigned len, uint16_t *values, uint16_t *num_values, uint16_t max_channels)
Parse the CRSF protocol and extract RC channel data. 
Namespace encapsulating all device framework classes, functions and data. 
unsigned sbus_dropped_frames()
The number of incomplete frames we encountered. 
static void read(bootloader_app_shared_t *pshared)
int crsf_config(int uart_fd)
Configure an UART port to be used for CRSF. 
__EXPORT hrt_abstime ppm_last_valid_decode
timestamp of the last valid decode 
void perf_count(perf_counter_t handle)
Count a performance event. 
void perf_free(perf_counter_t handle)
Free a counter. 
bool update(const hrt_abstime &now)
Send telemetry data. 
#define DSMX8_BIND_PULSES
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
static hrt_abstime hrt_elapsed_time(const hrt_abstime *then)
Compute the delta between a timestamp taken in the past and now. 
High-level class that handles sending of CRSF telemetry data. 
void perf_end(perf_counter_t handle)
End a performance event. 
bool dsm_parse(const uint64_t now, const uint8_t *frame, const unsigned len, uint16_t *values, uint16_t *num_values, bool *dsm_11_bit, unsigned *frame_drops, int8_t *rssi_percent, uint16_t max_channels)
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units. 
__EXPORT unsigned ppm_decoded_channels
count of decoded channels 
int dsm_init(const char *device)
Initialize the DSM receive functionality. 
int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *lost_count, uint16_t *channel_count, uint16_t *channels, uint16_t max_chan_count)
Decoder for ST24 protocol. 
void perf_print_counter(perf_counter_t handle)
Print one performance counter to stdout. 
__BEGIN_DECLS __EXPORT uint16_t ppm_buffer[PPM_MAX_CHANNELS]
decoded PPM channel values 
bool sbus_parse(uint64_t now, uint8_t *frame, unsigned len, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, unsigned *frame_drops, uint16_t max_channels)
bool update(void *dst)
Update the struct. 
bool publish(const T &data)
Publish the struct. 
void perf_begin(perf_counter_t handle)
Begin a performance event. 
measure the interval between instances of an event 
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap). 
int sbus_config(int sbus_fd, bool singlewire)
Parse serial bytes on the S.BUS bus.