Iris: set mixer to quad_wide

The geometry was previously quad_deadcat in which front motors are closer to CG and thus more loaded in hover.
quad_wide is the same geometry as quad_deadcat except the CG is centered so all motors are loaded equally.
Flight logs on IRIS with deadcat mixer showed that
- all motors are equally loaded during hover (actuator_outputs 0 to 3 have similar values)
- a negative pitch offset is building up soon after takeoff (visible in actuator_controls)
This commit is contained in:
Julien Lecoeur
2018-01-16 10:09:16 +01:00
committed by Lorenz Meier
parent b184b61457
commit 0e65753568
13 changed files with 13 additions and 13 deletions

View File

@@ -63,7 +63,7 @@ attitude_estimator_q start
local_position_estimator start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_dc.main.mix
mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_w.main.mix
mavlink start -x -u 14558 -r 4000000
mavlink start -x -u 14559 -r 4000000 -m onboard -o 14541
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14558