PX4 Firmware
PX4 Autopilot Software http://px4.io
RCInput Class Reference

#include <RCInput.hpp>

Inheritance diagram for RCInput:
Collaboration diagram for RCInput:

Public Member Functions

 RCInput (bool run_as_task, char *device)
 
virtual ~RCInput ()
 
void run () override
 
void cycle ()
 run the main loop: if running as task, continuously iterate, otherwise execute only one single cycle More...
 
int print_status () override
 
int init ()
 

Static Public Member Functions

static int task_spawn (int argc, char *argv[])
 
static RCInputinstantiate (int argc, char *argv[])
 
static int custom_command (int argc, char *argv[])
 
static int print_usage (const char *reason=nullptr)
 

Private Types

enum  RC_SCAN {
  RC_SCAN_PPM = 0, RC_SCAN_SBUS, RC_SCAN_DSM, RC_SCAN_SUMD,
  RC_SCAN_ST24, RC_SCAN_CRSF
}
 

Private Member Functions

int start ()
 
void fill_rc_in (uint16_t raw_rc_count_local, uint16_t raw_rc_values_local[input_rc_s::RC_INPUT_MAX_CHANNELS], hrt_abstime now, bool frame_drop, bool failsafe, unsigned frame_drops, int rssi)
 
void set_rc_scan_state (RC_SCAN _rc_scan_state)
 
void rc_io_invert (bool invert)
 

Static Private Member Functions

static void cycle_trampoline (void *arg)
 
static void cycle_trampoline_init (void *arg)
 

Private Attributes

enum RCInput::RC_SCAN RC_SCAN_SBUS
 
hrt_abstime _rc_scan_begin {0}
 
bool _rc_scan_locked {false}
 
bool _report_lock {true}
 
unsigned _current_update_interval {4000}
 
bool _run_as_task {false}
 
uORB::Subscription _vehicle_cmd_sub {ORB_ID(vehicle_command)}
 
uORB::Subscription _adc_sub {ORB_ID(adc_report)}
 
input_rc_s _rc_in {}
 
float _analog_rc_rssi_volt {-1.0f}
 
bool _analog_rc_rssi_stable {false}
 
uORB::PublicationMulti< input_rc_s_to_input_rc {ORB_ID(input_rc)}
 
int _rcs_fd {-1}
 
char _device [20] {}
 device / serial port path More...
 
uint8_t _rcs_buf [SBUS_BUFFER_SIZE] {}
 
uint16_t _raw_rc_values [input_rc_s::RC_INPUT_MAX_CHANNELS] {}
 
uint16_t _raw_rc_count {}
 
CRSFTelemetry_crsf_telemetry {nullptr}
 
perf_counter_t _cycle_perf
 
perf_counter_t _publish_interval_perf
 

Static Private Attributes

static constexpr char const * RC_SCAN_STRING [6]
 
static struct work_s _work = {}
 

Detailed Description

Definition at line 64 of file RCInput.hpp.

Member Enumeration Documentation

◆ RC_SCAN

enum RCInput::RC_SCAN
private
Enumerator
RC_SCAN_PPM 
RC_SCAN_SBUS 
RC_SCAN_DSM 
RC_SCAN_SUMD 
RC_SCAN_ST24 
RC_SCAN_CRSF 

Definition at line 97 of file RCInput.hpp.

Constructor & Destructor Documentation

◆ RCInput()

RCInput::RCInput ( bool  run_as_task,
char *  device 
)

Definition at line 47 of file RCInput.cpp.

References _device, _raw_rc_values, _rc_in, input_rc_s::input_source, and input_rc_s::rc_lost.

Referenced by cycle_trampoline_init(), and instantiate().

Here is the caller graph for this function:

◆ ~RCInput()

RCInput::~RCInput ( )
virtual

Definition at line 72 of file RCInput.cpp.

References _crsf_telemetry, _cycle_perf, _publish_interval_perf, dsm_deinit(), and perf_free().

Here is the call graph for this function:

Member Function Documentation

◆ custom_command()

int RCInput::custom_command ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 747 of file RCInput.cpp.

References DSMX8_BIND_PULSES, is_running(), print_usage(), and task_spawn().

Here is the call graph for this function:

◆ cycle()

void RCInput::cycle ( )

run the main loop: if running as task, continuously iterate, otherwise execute only one single cycle

Definition at line 319 of file RCInput.cpp.

References _adc_sub, _analog_rc_rssi_stable, _analog_rc_rssi_volt, _crsf_telemetry, _current_update_interval, _cycle_perf, _device, _publish_interval_perf, _raw_rc_count, _raw_rc_values, _rc_in, _rc_scan_begin, _rc_scan_locked, _rcs_buf, _rcs_fd, _report_lock, _run_as_task, _to_input_rc, _vehicle_cmd_sub, adc_report_s::channel_id, adc_report_s::channel_value, vehicle_command_s::command, crsf_config(), crsf_parse(), cycle_trampoline(), DSM2_BIND_PULSES, DSM_CMD_BIND_POWER_DOWN, DSM_CMD_BIND_POWER_UP, DSM_CMD_BIND_REINIT_UART, DSM_CMD_BIND_SEND_PULSES, DSM_CMD_BIND_SET_RX_OUT, dsm_config(), dsm_parse(), DSMX8_BIND_PULSES, DSMX_BIND_PULSES, f(), fill_rc_in(), hrt_absolute_time(), hrt_abstime, input_rc_s::input_source, OK, vehicle_command_s::param1, vehicle_command_s::param2, perf_begin(), perf_count(), perf_end(), ppm_buffer, ppm_decoded_channels, ppm_frame_length, ppm_last_valid_decode, uORB::PublicationMulti< T >::publish(), RC_INPUT_RSSI_MAX, rc_io_invert(), input_rc_s::rc_lost, input_rc_s::rc_ppm_frame_length, RC_SCAN_CRSF, RC_SCAN_DSM, RC_SCAN_PPM, RC_SCAN_SBUS, RC_SCAN_ST24, RC_SCAN_SUMD, read(), SBUS_BUFFER_SIZE, sbus_config(), sbus_parse(), set_rc_scan_state(), st24_decode(), sumd_decode(), input_rc_s::timestamp_last_signal, CRSFTelemetry::update(), and uORB::Subscription::update().

Referenced by cycle_trampoline(), cycle_trampoline_init(), and run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ cycle_trampoline()

void RCInput::cycle_trampoline ( void *  arg)
staticprivate

Definition at line 215 of file RCInput.cpp.

References cycle().

Referenced by cycle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ cycle_trampoline_init()

void RCInput::cycle_trampoline_init ( void *  arg)
staticprivate

Definition at line 193 of file RCInput.cpp.

References cycle(), init(), and RCInput().

Referenced by task_spawn().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ fill_rc_in()

void RCInput::fill_rc_in ( uint16_t  raw_rc_count_local,
uint16_t  raw_rc_values_local[input_rc_s::RC_INPUT_MAX_CHANNELS],
hrt_abstime  now,
bool  frame_drop,
bool  failsafe,
unsigned  frame_drops,
int  rssi = -1 
)
private

Definition at line 222 of file RCInput.cpp.

References _analog_rc_rssi_stable, _analog_rc_rssi_volt, _device, _raw_rc_values, _rc_in, _rc_scan_begin, _rcs_fd, input_rc_s::channel_count, f(), input_rc_s::rc_failsafe, rc_io_invert(), input_rc_s::rc_lost, input_rc_s::rc_lost_frame_count, input_rc_s::rc_ppm_frame_length, input_rc_s::rc_total_frame_count, input_rc_s::rssi, set_rc_scan_state(), input_rc_s::timestamp, input_rc_s::timestamp_last_signal, and input_rc_s::values.

Referenced by cycle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init()

int RCInput::init ( )

Definition at line 87 of file RCInput.cpp.

References _device, _rcs_fd, dsm_init(), and sbus_config().

Referenced by cycle_trampoline_init(), and run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ instantiate()

RCInput * RCInput::instantiate ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 741 of file RCInput.cpp.

References RCInput().

Here is the call graph for this function:

◆ print_status()

int RCInput::print_status ( )
override
See also
ModuleBase::print_status()

Definition at line 771 of file RCInput.cpp.

References _analog_rc_rssi_volt, _crsf_telemetry, _current_update_interval, _cycle_perf, _device, _publish_interval_perf, _rc_in, _rc_scan_locked, _run_as_task, f(), hrt_elapsed_time(), perf_print_counter(), RC_SCAN_STRING, sbus_dropped_frames(), and input_rc_s::timestamp.

Here is the call graph for this function:

◆ print_usage()

int RCInput::print_usage ( const char *  reason = nullptr)
static
See also
ModuleBase

Definition at line 802 of file RCInput.cpp.

Referenced by custom_command().

Here is the caller graph for this function:

◆ rc_io_invert()

void RCInput::rc_io_invert ( bool  invert)
private

Referenced by cycle(), and fill_rc_in().

Here is the caller graph for this function:

◆ run()

void RCInput::run ( )
override
See also
ModuleBase::run()

Definition at line 305 of file RCInput.cpp.

References cycle(), and init().

Here is the call graph for this function:

◆ set_rc_scan_state()

void RCInput::set_rc_scan_state ( RC_SCAN  _rc_scan_state)
private

Referenced by cycle(), and fill_rc_in().

Here is the caller graph for this function:

◆ start()

int RCInput::start ( )
private

◆ task_spawn()

int RCInput::task_spawn ( int  argc,
char *  argv[] 
)
static
See also
ModuleBase

Definition at line 121 of file RCInput.cpp.

References cycle_trampoline_init().

Referenced by custom_command().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _adc_sub

uORB::Subscription RCInput::_adc_sub {ORB_ID(adc_report)}
private

Definition at line 127 of file RCInput.hpp.

Referenced by cycle().

◆ _analog_rc_rssi_stable

bool RCInput::_analog_rc_rssi_stable {false}
private

Definition at line 132 of file RCInput.hpp.

Referenced by cycle(), and fill_rc_in().

◆ _analog_rc_rssi_volt

float RCInput::_analog_rc_rssi_volt {-1.0f}
private

Definition at line 131 of file RCInput.hpp.

Referenced by cycle(), fill_rc_in(), and print_status().

◆ _crsf_telemetry

CRSFTelemetry* RCInput::_crsf_telemetry {nullptr}
private

Definition at line 144 of file RCInput.hpp.

Referenced by cycle(), print_status(), and ~RCInput().

◆ _current_update_interval

unsigned RCInput::_current_update_interval {4000}
private

Definition at line 120 of file RCInput.hpp.

Referenced by cycle(), and print_status().

◆ _cycle_perf

perf_counter_t RCInput::_cycle_perf
private

Definition at line 146 of file RCInput.hpp.

Referenced by cycle(), print_status(), and ~RCInput().

◆ _device

char RCInput::_device[20] {}
private

device / serial port path

Definition at line 137 of file RCInput.hpp.

Referenced by cycle(), fill_rc_in(), init(), print_status(), and RCInput().

◆ _publish_interval_perf

perf_counter_t RCInput::_publish_interval_perf
private

Definition at line 147 of file RCInput.hpp.

Referenced by cycle(), print_status(), and ~RCInput().

◆ _raw_rc_count

uint16_t RCInput::_raw_rc_count {}
private

Definition at line 142 of file RCInput.hpp.

Referenced by cycle().

◆ _raw_rc_values

uint16_t RCInput::_raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS] {}
private

Definition at line 141 of file RCInput.hpp.

Referenced by cycle(), fill_rc_in(), and RCInput().

◆ _rc_in

input_rc_s RCInput::_rc_in {}
private

Definition at line 129 of file RCInput.hpp.

Referenced by cycle(), fill_rc_in(), print_status(), and RCInput().

◆ _rc_scan_begin

hrt_abstime RCInput::_rc_scan_begin {0}
private

Definition at line 115 of file RCInput.hpp.

Referenced by cycle(), and fill_rc_in().

◆ _rc_scan_locked

bool RCInput::_rc_scan_locked {false}
private

Definition at line 117 of file RCInput.hpp.

Referenced by cycle(), and print_status().

◆ _rcs_buf

uint8_t RCInput::_rcs_buf[SBUS_BUFFER_SIZE] {}
private

Definition at line 139 of file RCInput.hpp.

Referenced by cycle().

◆ _rcs_fd

int RCInput::_rcs_fd {-1}
private

Definition at line 136 of file RCInput.hpp.

Referenced by cycle(), fill_rc_in(), and init().

◆ _report_lock

bool RCInput::_report_lock {true}
private

Definition at line 118 of file RCInput.hpp.

Referenced by cycle().

◆ _run_as_task

bool RCInput::_run_as_task {false}
private

Definition at line 122 of file RCInput.hpp.

Referenced by cycle(), and print_status().

◆ _to_input_rc

uORB::PublicationMulti<input_rc_s> RCInput::_to_input_rc {ORB_ID(input_rc)}
private

Definition at line 134 of file RCInput.hpp.

Referenced by cycle().

◆ _vehicle_cmd_sub

uORB::Subscription RCInput::_vehicle_cmd_sub {ORB_ID(vehicle_command)}
private

Definition at line 126 of file RCInput.hpp.

Referenced by cycle().

◆ _work

work_s RCInput::_work = {}
staticprivate

Definition at line 124 of file RCInput.hpp.

◆ RC_SCAN_SBUS

enum RCInput::RC_SCAN RCInput::RC_SCAN_SBUS
private

Referenced by cycle().

◆ RC_SCAN_STRING

constexpr char const * RCInput::RC_SCAN_STRING
staticprivate
Initial value:
{
"PPM",
"SBUS",
"DSM",
"SUMD",
"ST24",
"CRSF"
}

Definition at line 106 of file RCInput.hpp.

Referenced by print_status().


The documentation for this class was generated from the following files: