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

class RCUpdate More...

#include <rc_update.h>

Inheritance diagram for RCUpdate::RCUpdate:
Collaboration diagram for RCUpdate::RCUpdate:

Public Member Functions

 RCUpdate ()
 
 ~RCUpdate () override
 
void Run () override
 
bool init ()
 
int print_status () override
 

Static Public Member Functions

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

Private Member Functions

void rc_parameter_map_poll (bool forced=false)
 Check for changes in rc_parameter_map. More...
 
void update_rc_functions ()
 update the RC functions. More...
 
void parameters_updated ()
 Update our local parameter cache. More...
 
float get_rc_value (uint8_t func, float min_value, float max_value)
 Get and limit value for specified RC function. More...
 
switch_pos_t get_rc_sw3pos_position (uint8_t func, float on_th, bool on_inv, float mid_th, bool mid_inv)
 Get switch position for specified function. More...
 
switch_pos_t get_rc_sw2pos_position (uint8_t func, float on_th, bool on_inv)
 
void set_params_from_rc ()
 Update parameters from RC channels if the functionality is activated and the input has changed since the last update. More...
 

Private Attributes

perf_counter_t _loop_perf
 loop performance counter More...
 
Parameters _parameters {}
 local copies of interesting parameters More...
 
ParameterHandles _parameter_handles {}
 handles for interesting parameters More...
 
uORB::SubscriptionCallbackWorkItem _input_rc_sub {this, ORB_ID(input_rc)}
 
uORB::Subscription _parameter_update_sub {ORB_ID(parameter_update)}
 notification of parameter updates More...
 
uORB::Subscription _rc_parameter_map_sub {ORB_ID(rc_parameter_map)}
 rc parameter map subscription More...
 
uORB::Publication< rc_channels_s_rc_pub {ORB_ID(rc_channels)}
 raw r/c control topic More...
 
uORB::Publication< actuator_controls_s_actuator_group_3_pub {ORB_ID(actuator_controls_3)}
 manual control as actuator topic More...
 
uORB::PublicationMulti< manual_control_setpoint_s_manual_control_pub {ORB_ID(manual_control_setpoint), ORB_PRIO_HIGH}
 manual control signal topic More...
 
rc_channels_s _rc {}
 r/c channel data More...
 
rc_parameter_map_s _rc_parameter_map {}
 
float _param_rc_values [rc_parameter_map_s::RC_PARAM_MAP_NCHAN] {}
 parameter values for RC control More...
 
hrt_abstime _last_rc_to_param_map_time = 0
 
math::LowPassFilter2p _filter_roll
 filters for the main 4 stick inputs More...
 
math::LowPassFilter2p _filter_pitch
 
math::LowPassFilter2p _filter_yaw
 we want smooth setpoints as inputs to the controllers More...
 
math::LowPassFilter2p _filter_throttle
 

Detailed Description

class RCUpdate

Handling of RC updates

Definition at line 72 of file rc_update.h.

Constructor & Destructor Documentation

◆ RCUpdate()

RCUpdate::RCUpdate::RCUpdate ( )

Definition at line 47 of file rc_update.cpp.

References uart_esc::_parameter_handles, and RCUpdate::initialize_parameter_handles().

Here is the call graph for this function:

◆ ~RCUpdate()

RCUpdate::RCUpdate::~RCUpdate ( )
override

Definition at line 62 of file rc_update.cpp.

References perf_free().

Here is the call graph for this function:

Member Function Documentation

◆ custom_command()

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

Definition at line 524 of file rc_update.cpp.

References print_usage().

Here is the call graph for this function:

◆ get_rc_sw2pos_position()

switch_pos_t RCUpdate::RCUpdate::get_rc_sw2pos_position ( uint8_t  func,
float  on_th,
bool  on_inv 
)
private

Definition at line 208 of file rc_update.cpp.

◆ get_rc_sw3pos_position()

switch_pos_t RCUpdate::RCUpdate::get_rc_sw3pos_position ( uint8_t  func,
float  on_th,
bool  on_inv,
float  mid_th,
bool  mid_inv 
)
private

Get switch position for specified function.

Definition at line 187 of file rc_update.cpp.

◆ get_rc_value()

float RCUpdate::RCUpdate::get_rc_value ( uint8_t  func,
float  min_value,
float  max_value 
)
private

Get and limit value for specified RC function.

Returns NAN if not mapped.

Definition at line 175 of file rc_update.cpp.

References math::constrain().

Here is the call graph for this function:

◆ init()

bool RCUpdate::RCUpdate::init ( )

Definition at line 68 of file rc_update.cpp.

◆ parameters_updated()

void RCUpdate::RCUpdate::parameters_updated ( )
private

Update our local parameter cache.

Definition at line 79 of file rc_update.cpp.

References uart_esc::_parameter_handles, uart_esc::_parameters, and RCUpdate::update_parameters().

Here is the call graph for this function:

◆ print_status()

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

Definition at line 515 of file rc_update.cpp.

References perf_print_counter().

Here is the call graph for this function:

◆ print_usage()

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

Definition at line 530 of file rc_update.cpp.

◆ rc_parameter_map_poll()

void RCUpdate::RCUpdate::rc_parameter_map_poll ( bool  forced = false)
private

Check for changes in rc_parameter_map.

Definition at line 135 of file rc_update.cpp.

References uart_esc::_parameter_handles, param_find(), and param_for_used_index().

Here is the call graph for this function:

◆ Run()

◆ set_params_from_rc()

void RCUpdate::RCUpdate::set_params_from_rc ( )
private

Update parameters from RC channels if the functionality is activated and the input has changed since the last update.

Parameters

Definition at line 226 of file rc_update.cpp.

References uart_esc::_parameter_handles, math::constrain(), FLT_EPSILON, and param_set().

Here is the call graph for this function:

◆ task_spawn()

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

Definition at line 491 of file rc_update.cpp.

References ll40ls::instance.

◆ update_rc_functions()

void RCUpdate::RCUpdate::update_rc_functions ( )
private

update the RC functions.

Call this when the parameters change.

Definition at line 88 of file rc_update.cpp.

References uart_esc::_parameters, and f().

Here is the call graph for this function:

Member Data Documentation

◆ _actuator_group_3_pub

uORB::Publication<actuator_controls_s> RCUpdate::RCUpdate::_actuator_group_3_pub {ORB_ID(actuator_controls_3)}
private

manual control as actuator topic

Definition at line 140 of file rc_update.h.

◆ _filter_pitch

math::LowPassFilter2p RCUpdate::RCUpdate::_filter_pitch
private

Definition at line 152 of file rc_update.h.

◆ _filter_roll

math::LowPassFilter2p RCUpdate::RCUpdate::_filter_roll
private

filters for the main 4 stick inputs

Definition at line 151 of file rc_update.h.

◆ _filter_throttle

math::LowPassFilter2p RCUpdate::RCUpdate::_filter_throttle
private

Definition at line 154 of file rc_update.h.

◆ _filter_yaw

math::LowPassFilter2p RCUpdate::RCUpdate::_filter_yaw
private

we want smooth setpoints as inputs to the controllers

Definition at line 153 of file rc_update.h.

◆ _input_rc_sub

uORB::SubscriptionCallbackWorkItem RCUpdate::RCUpdate::_input_rc_sub {this, ORB_ID(input_rc)}
private

Definition at line 134 of file rc_update.h.

◆ _last_rc_to_param_map_time

hrt_abstime RCUpdate::RCUpdate::_last_rc_to_param_map_time = 0
private

Definition at line 149 of file rc_update.h.

◆ _loop_perf

perf_counter_t RCUpdate::RCUpdate::_loop_perf
private

loop performance counter

Definition at line 129 of file rc_update.h.

◆ _manual_control_pub

uORB::PublicationMulti<manual_control_setpoint_s> RCUpdate::RCUpdate::_manual_control_pub {ORB_ID(manual_control_setpoint), ORB_PRIO_HIGH}
private

manual control signal topic

Definition at line 142 of file rc_update.h.

◆ _param_rc_values

float RCUpdate::RCUpdate::_param_rc_values[rc_parameter_map_s::RC_PARAM_MAP_NCHAN] {}
private

parameter values for RC control

Definition at line 147 of file rc_update.h.

◆ _parameter_handles

ParameterHandles RCUpdate::RCUpdate::_parameter_handles {}
private

handles for interesting parameters

Definition at line 132 of file rc_update.h.

◆ _parameter_update_sub

uORB::Subscription RCUpdate::RCUpdate::_parameter_update_sub {ORB_ID(parameter_update)}
private

notification of parameter updates

Definition at line 136 of file rc_update.h.

◆ _parameters

Parameters RCUpdate::RCUpdate::_parameters {}
private

local copies of interesting parameters

Definition at line 131 of file rc_update.h.

◆ _rc

rc_channels_s RCUpdate::RCUpdate::_rc {}
private

r/c channel data

Definition at line 144 of file rc_update.h.

◆ _rc_parameter_map

rc_parameter_map_s RCUpdate::RCUpdate::_rc_parameter_map {}
private

Definition at line 146 of file rc_update.h.

◆ _rc_parameter_map_sub

uORB::Subscription RCUpdate::RCUpdate::_rc_parameter_map_sub {ORB_ID(rc_parameter_map)}
private

rc parameter map subscription

Definition at line 137 of file rc_update.h.

◆ _rc_pub

uORB::Publication<rc_channels_s> RCUpdate::RCUpdate::_rc_pub {ORB_ID(rc_channels)}
private

raw r/c control topic

Definition at line 139 of file rc_update.h.


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