Pixhawk 2.1 Cube Black / PX4 V1.11.1 No PWM Output when Armed

Hi all,

New to the PX4 software stack, been trying to get it running on a Pixhawk 2.1 cube black. Ultimately I need to use all 14 channels for servo PWM outputs, but for now just focusing on getting a single channel to move.

I am building a custom image based on V1.11.1, with just custom airframe and mixer files built in (added to ROMFS before build). The airframe calls init.d/rc.mc_defaults and all I’m trying to achieve at this point is having the throttle output (a servo) react to changes in the throttle stick on my RC.

I have an FrSky Taranis-plus RC with X8R receiver connected to RCin, piping the channels over SBus to the Pixhawk. I have set up my RC channels through QGC, and have verified in both QGC and by observing the appropriate uorb topic that my RC inputs are properly detected.

I have verified that I can directly command the servo (MAIN CH1) using ‘pwm test …’

I am able to ARM/DISARM just fine, and have disabled the safety switch / pre-arm functionality entirely.

I have also verified that the attitude and rate controller modules are running as expected, and the uorb topic actuator_controls is updated in response to changes in my RC inputs. However, monitoring actuator_outputs shows they remain fixed.

This suggests to me that there is something wrong with my mixer, but I cannot figure out what exactly is going on. Here is my (main) mixer file – again, I’m only focused on the throttle (channel 1) outputs at the moment.

Throttle
-----------------

M: 1
O:      10000  10000      0 -10000  10000
S: 0 1      0  10000      0 -10000  10000

EjectorFrPitchDown
--------------

M: 1
O:      -10000  -10000      0 -10000  10000
S: 0 0   20000       0  10000 -10000  10000


EjectorFrRollRight
-------------

M: 1
O:      -10000  -10000      0 -10000  10000
S: 0 0   20000       0  10000 -10000  10000


EjectorRrRollRight
------------

M: 1
O:       10000   10000      0 -10000  10000
S: 0 0   10000   10000      0 -10000  10000


EjectorRrPitchUp
------------

M: 1
O:       10000   10000      0 -10000  10000
S: 0 0   10000   10000      0 -10000  10000


EjectorRrRollLeft
------------

M: 1
O:       10000   10000      0 -10000  10000
S: 0 0   10000   10000      0 -10000  10000

EjectorFrRollLeft
------------

M: 1
O:       10000   10000      0 -10000  10000
S: 0 0   10000   10000      0 -10000  10000


CSurfFrPitch
------------

M: 1
O:       10000   10000      0 -10000  10000
S: 0 0   10000   10000      0 -10000  10000

And here is my airframe file:

#!nsh
#
# @name Foobar
#
# @type Custom
# @class Custom
#
# @output MAIN1 T3 - Throttle
# @output MAIN2 B1 - EjectorFrPitchDown
# @output MAIN3 B2 - EjectorFrRollRight
# @output MAIN4 B3 - EjectorRrRollRight
# @output MAIN5 B4 - EjectorRrPitchUp
# @output MAIN6 B5 - EjectorRrRollLeft
# @output MAIN7 B6 - EjectorFrRollLeft
# @output MAIN8 G1 - CSurfFrPitch
#
# @output AUX1 G2 - CSurfRrPitch
# @output AUX2 S2 - CSurfFrRt
# @output AUX3 S4 - CSurfFrLt
# @output AUX4 S6 - CSurfRrRt
# @output AUX5 S8 - CSurfRrLt
# @output AUX6 K3 - Kill
#
# @maintainer Alex Volkov <volkov@motivo.com>
#

sh /etc/init.d/rc.mc_defaults



set MAV_TYPE 2	

set MIXER foobar
set PWM_OUT 12345678

set MIXER_AUX foobar_aux
set PWM_AUX_OUT 123456

set PWM_RATE 100
set PWM_AUX_RATE 100

Been trying to figure this out for a few days now but just can’t seem to get it. Does anyone have any suggestions? Am I missing something obvious?

I have what appears to be the exact same issue:

PX4 Mini
Custom Airframe and Mixer file
PWM outputs on channels 1,5,6,7,8.

In my case, the servos can also be commanded using “pwm test” from the console. They also respond to changes in attitude rate, seemingly trying to control. When I arm the vehicle, the throttle channel 1 goes to its setpoint (1500), causing the motor to spin. But nothing i’ve done has made the vehicle respond to inputs from the sticks on the radio.

Here’s more info on my setup and the behavior

Airframe:

sh /etc/init.d/rc.mc_defaults

 if [ $AUTOCNF = yes ]
 then
	param set BAT1_N_CELLS 6
	param set BAT1_CAPACITY 3650
	param set BAT1_V_CHARGED 4.35
	param set BAT1_V_EMPTY 3.5

	param set BAT_N_CELLS 6
	param set BAT_CAPACITY 3650
	param set BAT_V_CHARGED 4.35
	param set BAT_V_EMPTY 3.5

	param set COM_DISARM_PRFLT 0   #no arming timeout for inactivity

	param set CAL_MAG0_EN 0

	param set SENS_BOARD_ROT 24
fi

set MAV_TYPE 22  #message type
# Set mixer.
set MIXER foo

set PWM_OUT 1
set PWM_AUX_RATE 50
set PWM_AUX_OUT 5678

Mixer:

Motor mixer
------------
M: 1
S: 0 3 10000 10000 0 0 10000

Z:
Z:
Z:

Actuator mixer
--------------
Channel 5   UPR RIGHT
Channel 6   LWR RIGHT
Channel 7   LWR LEFT
Channel 8   UPR LEFT

M: 3
S: 0 0   10000   10000    0 -10000  10000
S: 0 1   10000   10000    0 -10000  10000
S: 0 2   10000   10000    0 -10000  10000

M: 3
S: 0 0  -10000  -10000    0 -10000  10000
S: 0 1   10000   10000    0 -10000  10000
S: 0 2   10000   10000    0 -10000  10000

M: 3
S: 0 0   10000   10000    0 -10000  10000
S: 0 1   10000   10000    0 -10000  10000
S: 0 2   10000   10000    0 -10000  10000

M: 3
S: 0 0  -10000  -10000    0 -10000  10000
S: 0 1   10000   10000    0 -10000  10000
S: 0 2   10000   10000    0 -10000  10000

here are the outputs from “pwm info”, “actuator_outputs” and “actuator_controls_0”

here is the out put from “listener manual_control_setpoint” with the sticks moved to extreme (three of four sticks)

So an update:

If i change from “rc.mc_defaults” to “rc.fw_defaults”, the behavior is as i expect - servos can be commanded in the prearmed state and the mixer behavior (5X simple mixers) is as i would expect based on the docs.

So the question becomes - is there something about the MC position or other controllers that prohibits outputs? Keeping in mind the actuators are not controlled even when armed.

@dcg Confirmed the same – switching to “rc.fw_defaults” (and changing MAV_TYPE to 1 for fixed wing is the only configuration I’ve tested so far that yields any activity on the actuator_outputs topic.

Another thing I’ve noticed is that MAV_TYPE seems to have a significant effect on what configuration is booted up, though the name of the variable would imply it’s just mavlink metadata. With “rc.fw_defaults” called in my airframe file, changing MAV_TYPE to 2 spins up the multicopter stability controllers, and also breaks the controller output propagating through the mixer module to the actuator_outputs topic. Other MAV_TYPE values (I only tried 22) also have similar effects.

Returning the init script to “rc.mc_defaults” with MAV_TYPE set to 2 yields the same behavior as previously described, with activity on actuator_controls not passing on through the mixer module to actuator_outputs.

Oof, okay. Haven’t verified with an actual servo, but I finally have activity on the actuator_outputs topics (both instances). Apparently I had CBRK_RATE_CTRL set at some point in my parameters, which disables the rate controller output. Explains why rc.fw_defaults ran fine but rc.mc_defaults was problematic. Unfortunate that this circuit breaker parameter lets you arm without at least spitting out warnings in console…

I dont recall setting CBRK_RATE_CTRL on purpose, is there a default value that gets set somewhere?

Would be interested to hear your results with a servo.

edit: yep i dont even have CBRK_RATE_CTRL as a parameter in my config. @avolkov

Well two things:

  1. it turns out CBRK_RATE_CTRL is enabled when you run the MC_Defaults startup script
  2. the commands are not passed on in “position” mode when using the MC_defaults, but they are in manual or stabilized.

So there’s that mystery solved. Except that Yaw doesnt respond to stick now. Throttle, Roll, and Pitch do, but not yaw.