Browse Source

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)
sbg
Julien Lecoeur 7 years ago committed by Lorenz Meier
parent
commit
0e65753568
  1. 2
      ROMFS/px4fmu_common/init.d/10016_3dr_iris
  2. 2
      posix-configs/SITL/init/ekf2/iris
  3. 2
      posix-configs/SITL/init/ekf2/iris_1
  4. 2
      posix-configs/SITL/init/ekf2/iris_2
  5. 2
      posix-configs/SITL/init/ekf2/iris_irlock
  6. 2
      posix-configs/SITL/init/ekf2/iris_rplidar
  7. 2
      posix-configs/SITL/init/ekf2/multiple_iris
  8. 2
      posix-configs/SITL/init/lpe/iris
  9. 2
      posix-configs/SITL/init/lpe/iris_1
  10. 2
      posix-configs/SITL/init/lpe/iris_2
  11. 2
      posix-configs/SITL/init/lpe/iris_irlock
  12. 2
      posix-configs/SITL/init/lpe/iris_opt_flow
  13. 2
      posix-configs/SITL/init/lpe/iris_rplidar

2
ROMFS/px4fmu_common/init.d/10016_3dr_iris

@ -40,6 +40,6 @@ then @@ -40,6 +40,6 @@ then
param set BAT_A_PER_V 15.39103
fi
set MIXER quad_dc
set MIXER quad_w
set PWM_OUT 1234

2
posix-configs/SITL/init/ekf2/iris

@ -60,7 +60,7 @@ navigator start @@ -60,7 +60,7 @@ navigator start
ekf2 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 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

2
posix-configs/SITL/init/ekf2/iris_1

@ -62,7 +62,7 @@ navigator start @@ -62,7 +62,7 @@ navigator start
ekf2 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 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

2
posix-configs/SITL/init/ekf2/iris_2

@ -62,7 +62,7 @@ navigator start @@ -62,7 +62,7 @@ navigator start
ekf2 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

2
posix-configs/SITL/init/ekf2/iris_irlock

@ -62,7 +62,7 @@ ekf2 start @@ -62,7 +62,7 @@ ekf2 start
landing_target_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 -u 14556 -r 4000000
mavlink start -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

2
posix-configs/SITL/init/ekf2/iris_rplidar

@ -60,7 +60,7 @@ navigator start @@ -60,7 +60,7 @@ navigator start
ekf2 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 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

2
posix-configs/SITL/init/ekf2/multiple_iris

@ -60,7 +60,7 @@ navigator start @@ -60,7 +60,7 @@ navigator start
ekf2 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 _MAVPORT_ -r 4000000 -o _MAVOPORT_
mavlink start -x -u _MAVPORT2_ -r 4000000 -m onboard -o _MAVOPORT2_
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u _MAVPORT_

2
posix-configs/SITL/init/lpe/iris

@ -61,7 +61,7 @@ attitude_estimator_q start @@ -61,7 +61,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 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

2
posix-configs/SITL/init/lpe/iris_1

@ -63,7 +63,7 @@ attitude_estimator_q start @@ -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 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

2
posix-configs/SITL/init/lpe/iris_2

@ -63,7 +63,7 @@ attitude_estimator_q start @@ -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

2
posix-configs/SITL/init/lpe/iris_irlock

@ -70,7 +70,7 @@ local_position_estimator start @@ -70,7 +70,7 @@ local_position_estimator start
landing_target_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 -u 14556 -r 4000000
mavlink start -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

2
posix-configs/SITL/init/lpe/iris_opt_flow

@ -79,7 +79,7 @@ attitude_estimator_q start @@ -79,7 +79,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 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556

2
posix-configs/SITL/init/lpe/iris_rplidar

@ -61,7 +61,7 @@ attitude_estimator_q start @@ -61,7 +61,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 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

Loading…
Cancel
Save