inav icon indicating copy to clipboard operation
inav copied to clipboard

Servo Mixer - Logic Condition

Open kolabuzlu opened this issue 2 months ago • 5 comments

Current Behavior

I’ve setup a servo mixing which is working absolutely fine. But instead of Always, I selected a logic condition to activate this mix. Setup a logic condition and verified it is working. I can see blue dot when it is true and no dot when it is false. But servo mixing stays active all the time. It does not follow logic condition.

Steps to reproduce

  1. Create a logic condition.
  2. Create a servo mix.
  3. Select that logic condition as activation parameter of the mix.
  4. Mix is always active if logic condition has been met or not.

Expected behavior

If logic condition is false, mix should be ignored.

Suggested solution(s)

Check everything related. Maybe I’m missing something.

Additional context

None


  • FC Board name and vendor: Matek H743 V3
  • INAV version string: INAV 8.0.1

kolabuzlu avatar Oct 15 '25 10:10 kolabuzlu

This used to be working. Can you please provide a diff all and video (if possible) of the problem.

MrD-RC avatar Oct 15 '25 10:10 MrD-RC

I have a pusher, T tail plane. When I increase throttle, a strong left yaw movement occurs (in manual, acro, horizon modes) with increasing throttle. So I decided to create a servo mix applying right rudder proportional to throttle. I did not do this in the radio not to confuse autopilot. Did it in mixer tab. Mixed rudder servo with Stabilized Throttle (to use it in every flight modes with auto throttle) Works like a charm. But, when disarmed, rudder output becomes 1000 and deflects fully to left and stays like that. To prevent this, I tried to activate this mix only when armed. Because without this mix, rudder stays in the middle as usual. And armed, stays perfectly fine again. I wanted to ignore this mix when the plane is disarmed.

(I think a guy created a topic here with the same issue by the way.)

Here is my diff all :

diff all

version

INAV/MATEKH743 8.0.1 Mar 28 2025 / 09:55:33 (ae47bcba)

GCC-13.2.1 20231009

start the command batch

batch start

reset configuration to default settings

defaults noreboot

resources

Timer overrides

Outputs [servo]

servo 1 1000 2000 1515 -100 servo 2 1000 2000 1465 -100 servo 3 1000 2000 1543 -100

safehome

Fixed Wing Approach

fwapproach 8 12400 6900 0 0 0 1

geozone

geozone vertices

features

feature GPS feature PWM_OUTPUT_ENABLE feature FW_LAUNCH feature FW_AUTOTRIM

beeper

blackbox

blackbox -NAV_ACC blackbox NAV_POS blackbox NAV_PID blackbox MAG blackbox ACC blackbox ATTI blackbox RC_DATA blackbox RC_COMMAND blackbox MOTORS blackbox -GYRO_RAW blackbox -PEAKS_R blackbox -PEAKS_P blackbox -PEAKS_Y blackbox SERVOS

Receiver: Channel map

Ports

serial 1 2 115200 115200 0 115200 serial 2 33554432 115200 115200 0 115200

LEDs

LED color

LED mode_color

Modes [aux]

aux 0 0 2 900 1800 aux 1 2 1 900 1200 aux 2 12 1 1800 2100 aux 3 53 0 1200 1800 aux 4 10 0 1800 2100 aux 5 21 3 1800 2100 aux 6 54 3 900 1200

Adjustments [adjrange]

Receiver rxrange

temp_sensor

Mission Control Waypoints [wp]

#wp 0 invalid

OSD [osd_layout]

osd_layout 0 0 56 11 V osd_layout 0 1 1 11 V osd_layout 0 3 8 6 V osd_layout 0 4 8 6 V osd_layout 0 7 16 21 V osd_layout 0 8 28 21 V osd_layout 0 9 1 5 V osd_layout 0 11 2 6 V osd_layout 0 12 1 7 V osd_layout 0 14 9 0 V osd_layout 0 15 38 11 V osd_layout 0 16 21 17 V osd_layout 0 17 21 18 V osd_layout 0 18 21 19 V osd_layout 0 20 33 0 V osd_layout 0 21 19 0 V osd_layout 0 22 30 1 V osd_layout 0 23 19 1 V osd_layout 0 24 38 1 V osd_layout 0 28 48 0 V osd_layout 0 30 17 16 V osd_layout 0 32 1 12 V osd_layout 0 34 26 3 V osd_layout 0 38 28 20 V osd_layout 0 41 55 15 V osd_layout 0 42 55 14 V osd_layout 0 62 42 17 V osd_layout 0 63 42 18 V osd_layout 0 67 10 18 V osd_layout 0 68 10 17 V osd_layout 0 69 10 19 V osd_layout 0 85 17 11 V osd_layout 0 135 45 6 V osd_layout 0 140 38 1 H

Programming: logic

logic 0 1 -1 2 2 8 0 12 0 logic 1 1 0 18 0 0 0 2000 0 logic 2 1 -1 3 2 8 0 10 0 logic 3 1 2 18 0 0 0 0 0 logic 4 1 -1 1 2 17 0 1 0

Programming: global variables

Programming: PID controllers

OSD: custom elements

master

set gyro_main_lpf_hz = 25 set dynamic_gyro_notch_q = 250 set dynamic_gyro_notch_min_hz = 30 set gyro_zero_x = -14 set gyro_zero_y = -12 set gyro_zero_z = 4 set ins_gravity_cmss = 976.742 set gyro_adaptive_filter_min_hz = 20 set acc_hardware = ICM42605 set acczero_x = 14 set acczero_y = -6 set acczero_z = -8 set accgain_x = 4045 set accgain_y = 4094 set accgain_z = 4100 set align_mag = CW270FLIP set mag_hardware = QMC5883 set magzero_x = -791 set magzero_y = 11557 set magzero_z = 11484 set maggain_x = 1380 set maggain_y = 1346 set maggain_z = 1493 set mag_calibration_time = 60 set align_mag_roll = 20 set align_mag_pitch = 1800 set align_mag_yaw = 2700 set baro_hardware = SPL06 set pitot_hardware = VIRTUAL set serialrx_provider = SBUS_FAST set blackbox_rate_denom = 2 set motor_pwm_protocol = STANDARD set failsafe_procedure = RTH set align_board_pitch = -70 set vbat_scale = 1096 set current_meter_scale = 159 set current_meter_offset = -16 set cruise_power = 62 set idle_power = 10 set rth_energy_margin = 10 set small_angle = 180 set applied_defaults = 3 set gps_sbas_mode = EGNOS set gps_auto_baud_max_supported = 115200 set gps_ublox_use_galileo = ON set airmode_type = STICK_CENTER_ONCE set inav_w_z_baro_p = 0.350 set nav_wp_radius = 1000 set nav_wp_max_safe_distance = 1500 set nav_fw_wp_tracking_accuracy = 4 set nav_fw_wp_turn_smoothing = ON-CUT set nav_land_minalt_vspd = 500 set nav_land_maxalt_vspd = 700 set nav_emerg_landing_speed = 700 set nav_rth_allow_landing = NEVER set nav_rth_altitude = 7500 set nav_rth_home_altitude = 7500 set nav_fw_cruise_speed = 1250 set nav_fw_control_smoothness = 2 set nav_fw_launch_velocity = 150 set nav_fw_launch_accel = 1500 set nav_fw_launch_max_angle = 90 set nav_fw_launch_motor_delay = 100 set nav_fw_launch_timeout = 10000 set nav_fw_launch_max_altitude = 7500 set nav_fw_launch_climb_angle = 27 set osd_video_system = DJIWTF set osd_coordinate_digits = 8 set name = DHKUAV set pilot_name = DHK set tz_offset = 180

control_profile

control_profile 1

set fw_p_pitch = 15 set fw_i_pitch = 5 set fw_d_pitch = 5 set fw_ff_pitch = 115 set fw_p_roll = 15 set fw_i_roll = 3 set fw_d_roll = 7 set fw_ff_roll = 73 set fw_p_yaw = 18 set fw_i_yaw = 4 set fw_d_yaw = 12 set fw_ff_yaw = 160 set dterm_lpf_hz = 10 set fw_turn_assist_pitch_gain = 0.400 set nav_fw_pos_z_p = 25 set nav_fw_pos_z_d = 8 set nav_fw_pos_xy_p = 55 set d_boost_min = 1.000 set d_boost_max = 1.000 set fw_level_pitch_trim = -1.000 set rc_expo = 30 set rc_yaw_expo = 30 set roll_rate = 19 set pitch_rate = 12 set yaw_rate = 4

control_profile

control_profile 2

set fw_i_pitch = 0 set fw_ff_pitch = 80 set fw_i_roll = 0 set fw_p_yaw = 5 set fw_i_yaw = 0 set fw_ff_yaw = 80 set dterm_lpf_hz = 10 set fw_turn_assist_pitch_gain = 0.400 set nav_fw_pos_z_p = 25 set nav_fw_pos_z_d = 8 set nav_fw_pos_xy_p = 55 set d_boost_min = 1.000 set d_boost_max = 1.000 set rc_expo = 30 set rc_yaw_expo = 30 set roll_rate = 18 set pitch_rate = 9 set yaw_rate = 4

control_profile

control_profile 3

set fw_p_pitch = 25 set fw_i_pitch = 5 set fw_d_pitch = 5 set fw_ff_pitch = 80 set fw_p_roll = 25 set fw_i_roll = 3 set fw_d_roll = 7 set fw_p_yaw = 25 set fw_i_yaw = 0 set fw_d_yaw = 5 set fw_ff_yaw = 80 set dterm_lpf_hz = 10 set fw_turn_assist_pitch_gain = 0.400 set nav_fw_pos_z_p = 25 set nav_fw_pos_z_d = 8 set nav_fw_pos_xy_p = 55 set d_boost_min = 1.000 set d_boost_max = 1.000 set rc_expo = 30 set rc_yaw_expo = 30 set roll_rate = 18 set pitch_rate = 9 set yaw_rate = 4

mixer_profile

mixer_profile 1

set platform_type = AIRPLANE set has_flaps = ON set model_preview_type = 14

Mixer: motor mixer

mmix reset

mmix 0 1.000 0.000 0.000 0.000

Mixer: servo mixer

smix reset

smix 0 1 0 100 0 -1 smix 1 2 1 100 0 -1 smix 2 3 2 92 0 -1 smix 3 4 30 100 0 -1 smix 4 3 3 -8 0 4

mixer_profile

mixer_profile 2

set platform_type = AIRPLANE set has_flaps = ON set model_preview_type = 14

Mixer: motor mixer

mmix reset

mmix 0 1.000 0.000 0.000 0.000

Mixer: servo mixer

smix reset

smix 0 1 0 100 0 -1 smix 1 2 1 100 0 -1 smix 2 3 2 100 0 -1 smix 3 4 30 100 0 -1

battery_profile

battery_profile 1

set bat_cells = 3 set battery_capacity = 2200 set battery_capacity_warning = 660 set battery_capacity_critical = 330 set throttle_idle = 0.000 set nav_fw_cruise_thr = 1480 set nav_fw_min_thr = 1150 set nav_fw_max_thr = 1850 set nav_fw_launch_thr = 1900

battery_profile

battery_profile 2

set throttle_idle = 5.000

battery_profile

battery_profile 3

set throttle_idle = 5.000

restore original profile selection

control_profile 1 mixer_profile 1 battery_profile 1

save configuration

save

Best regards.

kolabuzlu avatar Oct 15 '25 18:10 kolabuzlu

A workaround for the moment is to use the Programming tab to set a global variable equal to throttle. Then use that global variable in the mixer.

The issue is, when a servo has throttle in its mix, the assumption is it may well be controlling a motor / engine. So disarming the motors should zero out those servos.

That check probably doesn't look at the condition on the mixer rule.

sensei-hacker avatar Oct 15 '25 19:10 sensei-hacker

A workaround for the moment is to use the Programming tab to set a global variable equal to throttle. Then use that global variable in the mixer.

The issue is, when a servo has throttle in its mix, the assumption is it may well be controlling a motor / engine. So disarming the motors should zero out those servos.

That check probably doesn't look at the condition on the mixer rule.

I’ve just tried this but rudder servo moves jittery if I do this way, not smooth operation as setting the mixing as usual.

kolabuzlu avatar Oct 15 '25 21:10 kolabuzlu

Ah true. The PLC only runs at 10 Hz. A better way would be to use Mixer Profile 2. At the top of Configurator, you can select between mixer profile 1 and mixer profile 2.

Then on the Modes tab, set the profile 2 mode to be the same channel as your arm channel. When you arm and disarm, it will switch between the two mixers.

sensei-hacker avatar Oct 15 '25 21:10 sensei-hacker