Loading 2 mixers in sitl simulation

Hi! Im wondering which is the correct way to load 2 mixers in SITL mode.

For SITL we have init scripts located at “posix-configs/SITL/init/ekf2”
They are loading mixers with “mixer load /dev/pwm_output0 ROMFS/sitl/mixers/somefile.mix” command.

At the same time they have “param set SYS_AUTOSTART NUMBER”

Where NUMBER points to startup script in “ROMFS/px4fmu_common/init.d” which uses “set MIXER some_name_without_mix_ext” and “set MIXER_AUX some_name_without_mix_ext” pointing to files in “ROMFS/px4fmu_common/mixers”.

Does it affects SITL in any way? It looks like mixers defined with “set MIXER” and “set MIXER_AUX” has no effect when doing SITL.
At the same time there is no way to load 2 mixers for SITL as only “mixer load /dev/pwm_output0 …” is working and “mixer load /dev/pwm_output1 …” produces an error:

ERROR [mixer] can’t open /dev/pwm_output1
ERROR [mixer] failed to load mixer

So how can I load 2 mixers in SITL?

Try “mixer append” for the second one

mixer load /dev/pwm_output0 ROMFS/sitl/mixers/somefile.mix
mixer append /dev/pwm_output0 ROMFS/sitl/mixers/otherfile.mix

1 Like

Hi Bart!

Thank you for your answer.

I gave it a try and it seems kind of working when number of control channels is not big enough. For example I was able to add one more layer of 4 motors to quad rotor model having already 4 motors. Doing mixer append made them kind of working together. Each layer was controlled independently I believe but together they was able to make model to fly.

Then I tried to do the same with standard_vtol_sitl. I added one more layer of 4 motors to it. Now it has 11 control channels in total. I used mixer append to add one standard quad rotor controller for new layer of motors (R: 4x 10000 10000 10000 0). And I see those motors not rotating at all.

Maybe there are some restrictions on total number of control channels available in SITL?

I even tried to change mixer file adding this line (R: 4x 10000 10000 10000 0) at the end just to not do any mixer append and load a single mixer file. The result is the same. Those new motors not rotating at all.

Check the output on the console for clues

The output as follows. Nothing really suspicious for me. Except for couple of warnings, but those are always there and not prohibit the model from working in configuration with number of channels less than 8.

[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.1.85
[Dbg] [gazebo_mavlink_interface.cpp:160] joint [front_right_top_joint] found for channel[0] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:160] joint [back_left_top_joint] found for channel[1] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:160] joint [front_left_top_joint] found for channel[2] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:160] joint [back_right_top_joint] found for channel[3] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:160] joint [pusher_joint] found for channel[4] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:160] joint [front_right_bottom_joint] found for channel[8] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:160] joint [back_left_bottom_joint] found for channel[9] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:160] joint [front_left_bottom_joint] found for channel[10] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:160] joint [back_right_bottom_joint] found for channel[11] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:160] joint [left_wing_and_elevon_joint] found for channel[5] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:160] joint [right_wing_and_elevon_joint] found for channel[6] joint control active for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:160] joint [elevator_joint] found for channel[7] joint control active for this channel.
SITL COMMAND: /Users/ali/Documents/Firmware/build/posix_sitl_default/px4 /Users/ali/Documents/Firmware /Users/ali/Documents/Firmware/posix-configs/SITL/init/ekf2/universal
data path: /Users/ali/Documents/Firmware
commands file: /Users/ali/Documents/Firmware/posix-configs/SITL/init/ekf2/universal


| ___ \ \ \ / / / |
| |/ / \ V / / /| |
| __/ / \ / /
| |
| | / /^\ \ ___ |
_| / / |_/

px4 starting.

INFO [dataman] Unknown restart, data manager file ‘rootfs/fs/microsd/dataman’ size is 11405132 bytes
INFO [platforms__posix__drivers__ledsim] LED::init
INFO [platforms__posix__drivers__ledsim] LED::init
INFO [simulator] Waiting for initial data on UDP port 14560. Please start the flight simulator to proceed…
Gazebo multi-robot simulator, version 8.1.1
Copyright © 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.1.85
INFO [simulator] Got initial simulation data, running sim…
INFO [pwm_out_sim] MODE_8PWM
INFO [tone_alarm] startup
WARN [vtol_att_control] failed setting min values
INFO [commander] Takeoff detected
WARN [vtol_att_control] failed setting max values
WARN [vtol_att_control] failed setting min values
.
.
INFO [mavlink] mode: Normal, data rate: 2000000 B/s on udp port 14556 remote port 14550
INFO [mavlink] mode: Onboard, data rate: 2000000 B/s on udp port 14557 remote port 14540
INFO [mavlink] MAVLink only on localhost (set param MAV_BROADCAST = 1 to enable network)
INFO [logger] logger started (mode=all)
pxh> INFO [logger] Start file log
INFO [logger] Opened log file: rootfs/fs/microsd/log/2018-03-10/18_55_03.ulg
INFO [commander] Landing detected
INFO [lib__ecl] EKF aligned, (pressure height, IMU buf: 22, OBS buf: 14)
INFO [lib__ecl] EKF GPS checks passed (WGS-84 origin set)
INFO [commander] home alt: 488.12
INFO [lib__ecl] EKF commencing GPS fusion
INFO [commander] home: 47.3977418, 8.5455934, 488.04
INFO [tone_alarm] home_set

INFO [pwm_out_sim] MODE_8PWM

Thanks @Bart for your point. I found in sources that there are different modes like MODE_8PWM, MODE_14PWM, MODE_16PWM etc. So It seems like MODE_14PWM should play nice for me. But I can’t find command to set this kind of mode. Could you pls point to particular documentation page where that described? Or at least provide with appropriate command to add to my init script?

In your init script, try something like this

pwm_out_sim mode_pwm16
instead of
pwm_out_sim mode_pwm

Many thanks, @Bart! This finally solved the issue. Unfortunately all this stuff is not well documented yet or I was searching not hard enough.

Feel free to suggest updates to the documentation :wink:

Hi a63uh,
There is no “pwm_out_sim mode_pwm” in init script of version 1.9.0. May you let me know where I can get it? Thanks in advance.