PX4 Firmware
PX4 Autopilot Software http://px4.io
uart_esc Namespace Reference

Functions

void uart_esc_rotate_motors (int16_t *motor_rpm, int num_rotors)
 Rotate the motor rpm values based on the motor mappings configuration stored in motor_mapping. More...
 
static void usage ()
 Print out the usage information. More...
 
static void start (const char *device) __attribute__((unused))
 uart_esc start More...
 
static void stop ()
 uart_esc stop More...
 
static void task_main_trampoline (int argc, char *argv[])
 task main trampoline function More...
 
static void task_main (int argc, char *argv[])
 uart_esc thread primary entry point More...
 
static int initialize_mixer (const char *mixer_filename)
 
static int mixer_control_callback (uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input)
 
static void parameters_init ()
 
static void parameters_update ()
 
void start ()
 Attempt to start driver on all available I2C busses. More...
 

Variables

volatile bool _task_should_exit = false
 
static char _device [MAX_LEN_DEV_PATH]
 
static bool _is_running = false
 
static px4_task_t _task_handle = -1
 
UartEsc * esc
 
int _controls_sub
 
int _armed_sub
 
int _param_sub
 
static const char * MIXER_FILENAME = "/dev/fs/mixer_config.mix"
 
orb_advert_t _outputs_pub
 
actuator_controls_s _controls
 
actuator_armed_s _armed
 
parameter_update_s _param_update
 
actuator_outputs_s _outputs
 
static MultirotorMixermixer
 mixer initialization More...
 
struct {
   int   uart_esc::model
 
   int   uart_esc::baudrate
 
   int   uart_esc::px4_motor_mapping [UART_ESC_MAX_MOTORS]
 
_parameters
 
struct {
   param_t   uart_esc::model
 
   param_t   uart_esc::baudrate
 
   param_t   uart_esc::px4_motor_mapping [UART_ESC_MAX_MOTORS]
 
_parameter_handles
 

Function Documentation

◆ initialize_mixer()

int uart_esc::initialize_mixer ( const char *  mixer_filename)
static

Definition at line 195 of file uart_esc_main.cpp.

References MultirotorMixer::from_text(), mixer_control_callback(), and read().

Referenced by task_main().

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

◆ mixer_control_callback()

int uart_esc::mixer_control_callback ( uintptr_t  handle,
uint8_t  control_group,
uint8_t  control_index,
float &  input 
)
static

Definition at line 171 of file uart_esc_main.cpp.

References actuator_controls_s::control.

Referenced by initialize_mixer().

Here is the caller graph for this function:

◆ parameters_init()

void uart_esc::parameters_init ( )
static

Definition at line 131 of file uart_esc_main.cpp.

References _parameter_handles, param_find(), parameters_update(), and UART_ESC_MAX_MOTORS.

Referenced by task_main().

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

◆ parameters_update()

void uart_esc::parameters_update ( )
static

Definition at line 148 of file uart_esc_main.cpp.

References _parameter_handles, _parameters, param_get(), and UART_ESC_MAX_MOTORS.

Referenced by parameters_init(), and task_main().

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

◆ start() [1/2]

static void uart_esc::start ( const char *  device)
static

uart_esc start

Referenced by uart_esc_main().

Here is the caller graph for this function:

◆ start() [2/2]

void uart_esc::start ( )

Attempt to start driver on all available I2C busses.

This function will return as soon as the first sensor is detected on one of the available busses or if no sensors are detected.

Attempt to start driver on all available I2C busses.

Definition at line 423 of file uart_esc_main.cpp.

References i2c_bus_options, NUM_I2C_BUS_OPTIONS, ets_airspeed::start_bus(), task_main_trampoline(), and warn.

Referenced by spektrum_rc_main().

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

◆ stop()

void uart_esc::stop ( )
static

uart_esc stop

Definition at line 443 of file uart_esc_main.cpp.

Referenced by uart_esc_main().

Here is the caller graph for this function:

◆ task_main()

void uart_esc::task_main ( int  argc,
char *  argv[] 
)
static

uart_esc thread primary entry point

Definition at line 275 of file uart_esc_main.cpp.

References _controls_sub, _parameters, actuator_armed_s::armed, esc, hrt_absolute_time(), initialize_mixer(), actuator_armed_s::lockdown, actuator_armed_s::manual_lockdown, MultirotorMixer::mix(), actuator_outputs_s::noutputs, orb_advertise(), orb_check(), orb_copy(), ORB_ID, orb_publish(), orb_subscribe(), actuator_outputs_s::output, parameters_init(), parameters_update(), px4_poll(), actuator_outputs_s::timestamp, UART_ESC_MAX_MOTORS, and uart_esc_rotate_motors().

Referenced by task_main_trampoline().

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

◆ task_main_trampoline()

void uart_esc::task_main_trampoline ( int  argc,
char *  argv[] 
)
static

task main trampoline function

uart_esc main entrance

Definition at line 417 of file uart_esc_main.cpp.

References task_main().

Referenced by start().

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

◆ uart_esc_rotate_motors()

void uart_esc::uart_esc_rotate_motors ( int16_t *  motor_rpm,
int  num_rotors 
)

Rotate the motor rpm values based on the motor mappings configuration stored in motor_mapping.

Definition at line 260 of file uart_esc_main.cpp.

References _parameters, and UART_ESC_MAX_MOTORS.

Referenced by task_main().

Here is the caller graph for this function:

◆ usage()

void uart_esc::usage ( void  )
static

Print out the usage information.

Definition at line 451 of file uart_esc_main.cpp.

Referenced by uart_esc_main().

Here is the caller graph for this function:

Variable Documentation

◆ _armed

actuator_armed_s uart_esc::_armed

Definition at line 92 of file uart_esc_main.cpp.

◆ _armed_sub

int uart_esc::_armed_sub

Definition at line 79 of file uart_esc_main.cpp.

◆ _controls

actuator_controls_s uart_esc::_controls

Definition at line 91 of file uart_esc_main.cpp.

◆ _controls_sub

int uart_esc::_controls_sub

Definition at line 78 of file uart_esc_main.cpp.

Referenced by task_main().

◆ _device

char uart_esc::_device[MAX_LEN_DEV_PATH]
static

Definition at line 71 of file uart_esc_main.cpp.

Referenced by uart_esc_main().

◆ _is_running

bool uart_esc::_is_running = false
static

Definition at line 72 of file uart_esc_main.cpp.

Referenced by uart_esc_main().

◆ _outputs

actuator_outputs_s uart_esc::_outputs

Definition at line 94 of file uart_esc_main.cpp.

◆ _outputs_pub

orb_advert_t uart_esc::_outputs_pub

Definition at line 88 of file uart_esc_main.cpp.

◆ _param_sub

int uart_esc::_param_sub

Definition at line 80 of file uart_esc_main.cpp.

◆ _param_update

parameter_update_s uart_esc::_param_update

Definition at line 93 of file uart_esc_main.cpp.

◆ _parameter_handles

◆ _parameters

◆ _task_handle

px4_task_t uart_esc::_task_handle = -1
static

Definition at line 73 of file uart_esc_main.cpp.

◆ _task_should_exit

volatile bool uart_esc::_task_should_exit = false

Definition at line 70 of file uart_esc_main.cpp.

◆ baudrate

param_t uart_esc::baudrate

Definition at line 121 of file uart_esc_main.cpp.

Referenced by GPSDriverUBX::configure(), and GPS::pollOrRead().

◆ esc

UartEsc* uart_esc::esc

Definition at line 74 of file uart_esc_main.cpp.

Referenced by task_main(), and MK::task_main().

◆ mixer

◆ MIXER_FILENAME

const char* uart_esc::MIXER_FILENAME = "/dev/fs/mixer_config.mix"
static

Definition at line 84 of file uart_esc_main.cpp.

◆ model

param_t uart_esc::model

Definition at line 120 of file uart_esc_main.cpp.

◆ px4_motor_mapping

param_t uart_esc::px4_motor_mapping[UART_ESC_MAX_MOTORS]

Definition at line 122 of file uart_esc_main.cpp.