PX4 Firmware
PX4 Autopilot Software http://px4.io
mixer.cpp File Reference
#include <px4_platform_common/px4_config.h>
#include <syslog.h>
#include <sys/types.h>
#include <stdbool.h>
#include <float.h>
#include <string.h>
#include <math.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_hrt.h>
#include <lib/mixer/MixerGroup.hpp>
#include <output_limit/output_limit.h>
#include <rc/sbus.h>
#include <uORB/topics/actuator_controls.h>
#include "mixer.h"
#include "px4io.h"
Include dependency graph for mixer.cpp:

Go to the source code of this file.

Macros

#define FMU_INPUT_DROP_LIMIT_US   500000
 

Enumerations

enum  mixer_source {
  MIX_NONE, MIX_DISARMED, MIX_FMU, MIX_OVERRIDE,
  MIX_FAILSAFE, MIX_OVERRIDE_FMU_OK
}
 

Functions

static int mixer_callback (uintptr_t handle, uint8_t control_group, uint8_t control_index, float &control)
 
static int mixer_mix_threadsafe (float *outputs, volatile uint16_t *limits)
 
void mixer_tick ()
 
int mixer_handle_text_create_mixer ()
 
int mixer_handle_text (const void *buffer, size_t length)
 
void mixer_set_failsafe ()
 

Variables

static volatile bool mixer_servos_armed = false
 
static volatile bool should_arm = false
 
static volatile bool should_arm_nothrottle = false
 
static volatile bool should_always_enable_pwm = false
 
static volatile bool in_mixer = false
 
static bool new_fmu_data = false
 
static uint64_t last_fmu_update = 0
 
int _sbus_fd
 
static volatile mixer_source source
 
static MixerGroup mixer_group
 
static char mixer_text [PX4IO_MAX_MIXER_LENGTH]
 
static unsigned mixer_text_length = 0
 
static bool mixer_update_pending = false
 

Macro Definition Documentation

◆ FMU_INPUT_DROP_LIMIT_US

#define FMU_INPUT_DROP_LIMIT_US   500000

Definition at line 70 of file mixer.cpp.

Referenced by mixer_tick().

Enumeration Type Documentation

◆ mixer_source

Enumerator
MIX_NONE 
MIX_DISARMED 
MIX_FMU 
MIX_OVERRIDE 
MIX_FAILSAFE 
MIX_OVERRIDE_FMU_OK 

Definition at line 85 of file mixer.cpp.

Function Documentation

◆ mixer_callback()

static int mixer_callback ( uintptr_t  handle,
uint8_t  control_group,
uint8_t  control_index,
float &  control 
)
static

Definition at line 404 of file mixer.cpp.

References CONTROL_PAGE_INDEX, f(), MIX_DISARMED, MIX_FAILSAFE, MIX_FMU, MIX_NONE, MIX_OVERRIDE, MIX_OVERRIDE_FMU_OK, OUTPUT_LIMIT_STATE_RAMP, pwm_limit, PX4IO_CONTROL_CHANNELS, PX4IO_CONTROL_GROUPS, PX4IO_P_RC_BASE, PX4IO_P_RC_VALID, r_page_controls, r_page_rc_input, r_setup_scale_pitch, r_setup_scale_roll, r_setup_scale_yaw, r_setup_trim_pitch, r_setup_trim_roll, r_setup_trim_yaw, REG_TO_FLOAT, should_arm, should_arm_nothrottle, source, and output_limit_t::state.

Referenced by mixer_handle_text_create_mixer().

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

◆ mixer_handle_text()

int mixer_handle_text ( const void *  buffer,
size_t  length 
)

Definition at line 566 of file mixer.cpp.

References px4io_mixdata::action, atomic_modify_clear(), F2I_MIXER_ACTION_APPEND, F2I_MIXER_ACTION_RESET, in_mixer, isr_debug(), mixer_text, mixer_text_length, mixer_update_pending, msg, PX4IO_P_SETUP_ARMING_FMU_ARMED, PX4IO_P_STATUS_FLAGS_MIXER_OK, PX4IO_P_STATUS_FLAGS_SAFETY_OFF, r_setup_arming, r_status_flags, MixerGroup::reset(), px4io_mixdata::text, update_mc_thrust_param, and update_trims.

Referenced by registers_set().

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

◆ mixer_handle_text_create_mixer()

int mixer_handle_text_create_mixer ( void  )

Definition at line 523 of file mixer.cpp.

References in_mixer, isr_debug(), MixerGroup::load_from_buf(), mixer_callback(), mixer_text, mixer_text_length, mixer_update_pending, PX4IO_P_SETUP_ARMING_FMU_ARMED, PX4IO_P_STATUS_FLAGS_SAFETY_OFF, r_setup_arming, and r_status_flags.

Referenced by mixer_tick().

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

◆ mixer_mix_threadsafe()

int mixer_mix_threadsafe ( float *  outputs,
volatile uint16_t *  limits 
)
static

Definition at line 101 of file mixer.cpp.

References MixerGroup::get_saturation_status(), in_mixer, MixerGroup::mix(), PX4IO_P_STATUS_FLAGS_MIXER_OK, PX4IO_SERVO_COUNT, and r_status_flags.

Referenced by mixer_set_failsafe(), and mixer_tick().

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

◆ mixer_set_failsafe()

void mixer_set_failsafe ( void  )

Definition at line 635 of file mixer.cpp.

References dt, FLT_EPSILON, mixer_mix_threadsafe(), PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM, PX4IO_P_STATUS_FLAGS_MIXER_OK, PX4IO_SERVO_COUNT, r_mixer_limits, r_page_servo_control_max, r_page_servo_control_min, r_page_servo_failsafe, r_setup_arming, r_setup_slew_max, r_setup_thr_fac, r_status_flags, REG_TO_FLOAT, MixerGroup::set_max_delta_out_once(), MixerGroup::set_thrust_factor(), and update_mc_thrust_param.

Referenced by registers_set_one().

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

◆ mixer_tick()

void mixer_tick ( void  )

Definition at line 117 of file mixer.cpp.

References _sbus_fd, atomic_modify_clear(), atomic_modify_or(), dt, f(), FLOAT_TO_REG, FLT_EPSILON, sys_state_s::fmu_data_received_time, FMU_INPUT_DROP_LIMIT_US, hrt_abstime, hrt_elapsed_time(), isr_debug(), last_fmu_update, MIX_DISARMED, MIX_FAILSAFE, MIX_FMU, MIX_NONE, MIX_OVERRIDE, MIX_OVERRIDE_FMU_OK, mixer_handle_text_create_mixer(), mixer_mix_threadsafe(), mixer_servos_armed, new_fmu_data, output_limit_calc(), pwm_limit, PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE, PX4IO_P_SETUP_ARMING_FMU_ARMED, PX4IO_P_SETUP_ARMING_FMU_PREARMED, PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE, PX4IO_P_SETUP_ARMING_LOCKDOWN, PX4IO_P_SETUP_FEATURES_SBUS1_OUT, PX4IO_P_SETUP_FEATURES_SBUS2_OUT, PX4IO_P_STATUS_ALARMS_FMU_LOST, PX4IO_P_STATUS_FLAGS_FAILSAFE, PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED, PX4IO_P_STATUS_FLAGS_FMU_OK, PX4IO_P_STATUS_FLAGS_INIT_OK, PX4IO_P_STATUS_FLAGS_MIXER_OK, PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED, PX4IO_P_STATUS_FLAGS_OVERRIDE, PX4IO_P_STATUS_FLAGS_RAW_PWM, PX4IO_P_STATUS_FLAGS_SAFETY_OFF, PX4IO_SERVO_COUNT, r_mixer_limits, r_page_actuators, r_page_direct_pwm, r_page_servo_control_max, r_page_servo_control_min, r_page_servo_control_trim, r_page_servo_disarmed, r_page_servo_failsafe, r_page_servos, r_setup_airmode, r_setup_arming, r_setup_features, r_setup_flighttermination, r_setup_pwm_reverse, r_setup_slew_max, r_setup_thr_fac, r_status_alarms, r_status_flags, REG_TO_BOOL, REG_TO_FLOAT, REG_TO_SIGNED, sbus1_output(), sbus2_output(), MixerGroup::set_airmode(), MixerGroup::set_max_delta_out_once(), MixerGroup::set_thrust_factor(), MixerGroup::set_trims(), should_always_enable_pwm, should_arm, should_arm_nothrottle, source, system_state, up_pwm_servo_arm(), up_pwm_servo_set(), up_pwm_update(), update_mc_thrust_param, and update_trims.

Referenced by user_start().

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

Variable Documentation

◆ _sbus_fd

int _sbus_fd

Definition at line 67 of file controls.c.

Referenced by controls_init(), controls_tick(), and mixer_tick().

◆ in_mixer

volatile bool in_mixer = false
static

◆ last_fmu_update

uint64_t last_fmu_update = 0
static

Definition at line 80 of file mixer.cpp.

Referenced by mixer_tick().

◆ mixer_group

MixerGroup mixer_group
static

Definition at line 99 of file mixer.cpp.

◆ mixer_servos_armed

volatile bool mixer_servos_armed = false
static

Definition at line 73 of file mixer.cpp.

Referenced by mixer_tick().

◆ mixer_text

char mixer_text[PX4IO_MAX_MIXER_LENGTH]
static

◆ mixer_text_length

unsigned mixer_text_length = 0
static

◆ mixer_update_pending

bool mixer_update_pending = false
static

Definition at line 520 of file mixer.cpp.

Referenced by mixer_handle_text(), and mixer_handle_text_create_mixer().

◆ new_fmu_data

bool new_fmu_data = false
static

Definition at line 79 of file mixer.cpp.

Referenced by mixer_tick().

◆ should_always_enable_pwm

volatile bool should_always_enable_pwm = false
static

Definition at line 76 of file mixer.cpp.

Referenced by mixer_tick().

◆ should_arm

volatile bool should_arm = false
static

Definition at line 74 of file mixer.cpp.

Referenced by mixer_callback(), mixer_tick(), and MixerTest::mixerTest().

◆ should_arm_nothrottle

volatile bool should_arm_nothrottle = false
static

Definition at line 75 of file mixer.cpp.

Referenced by mixer_callback(), and mixer_tick().

◆ source

volatile mixer_source source
static

Definition at line 94 of file mixer.cpp.

Referenced by mixer_callback(), and mixer_tick().