Home » Blog » About the PWM output of Pixhawk

About the PWM output of Pixhawk

— Last modified: xiaoke das.xiaoke@gmail.com 2015/12/16 02:36

This page is still under construction.

Correspondance between the timers and the PWM channel

Pixhawk uses the 100-pin ARM STM32F427, THE Timer Pin PWM channel PinDesc TIM1_CH4 45 1 PE14 TIM1_CH3 44 2 PE13 TIM1_CH2 42 3 PE11 TIM1_CH1 40 4 PE9 TIM4_CH2 60 5 PD13 TIM4_CH3 61 6 PD14

About the timers in STM32F4

From the description of the datasheet, there are “12 general-purpose 16-bit timers including 2 PWM timers for motor control, 2 general-purpose 32-bit timers”.

These 12 general purpose timers consist of two 16-bit advanced-control timers, TIM1 and TIM8, two 32-bit general purpose timers, TIM2 and TIM5, and another eight 16-bit general purpose timers, TIM3, TIM4, TIM9, TIM10, TIM11, TIM12, TIM13, and TIM14. Besides, it also have TIM6 and TIM7 as two basic timers.

The advanced-control timers are mainly intended for PWM output. Each of the timer has 6 multiplexed channels. The general purpose timers can all be used to generate PWM outputs and there are 4 multiplexed channels for each of the timers.

The timers and channels used in pixhawk are listed in the table above.

Fow 400Hz PWM, the period is 1/400*1000 000 = 2500 us

If the maximum period is restricted to 2000 us, then the maximum voltage is 80% of the battery voltage.

For 50 Hz PWM, the period is 1/50*1000 000 = 20 000 us

It seems that the internal parameters are all defined w.r.t. 400Hz PWM, however, the default PWM rate is 50Hz

The pixhawk source files on PWM are quite confusing, the following are what I tried to understand.

The codes can be roughly be devided into two layers, device driver and user application layers.

The device driver layer deals with direct communication with the PWM output of the chip, i.e. direct accessing the Timers of the chip. The user application layer are higher-layer functions constructed by PX4 fmu. There are definitely extra PWM functions implemented, which I'll discuss whenever encountered.

First, the bottom layer of the PWM function consists of two seemingly unrelated files, src/drivers/drv_pwm_output.h, ./src/drivers/stm32/drv_pwm_servo.c, ./src/drivers/stm32/drv_pwm_servo.h I don't know why they are arranged like this, basically, the two header files 'drv_pwm_output.h' and 'drv_pwm_servo.h' together serve as the header file for the source file drv_pwm_servo.c

After understanding this, we can go further into the details of this driver.

Basically, two things are defined in this driver: 1) restrictions, e.g. the number of channels of pwm and the max min duty cycle of them. 2) accessing functions.

Note the value PWM_HIGHEST_MAX, this is the lowest level of restrictions on the maximum powerlevel you can achieve from the PWM, if it is set to 2500, it means the power can be connected directly to the motor.

For the functions, the following are declared

/*
 * Low-level PWM output interface.
 *
 * This is the low-level API to the platform-specific PWM driver.
 */

/**
 * Intialise the PWM servo outputs using the specified configuration.
 *
 * @param channel_mask	Bitmask of channels (LSB = channel 0) to enable.
 *			This allows some of the channels to remain configured
 *			as GPIOs or as another function.
 * @return		OK on success.
 */
__EXPORT extern int	up_pwm_servo_init(uint32_t channel_mask);

/**
 PM* De-initialise the PWM servo outputs.
 */
__EXPORT extern void	up_pwm_servo_deinit(void);

/**
 * Arm or disarm servo outputs.
 *
 * When disarmed, servos output no pulse.
 *
 * @bug This function should, but does not, guarantee that any pulse
 *      currently in progress is cleanly completed.
 *
 * @param armed		If true, outputs are armed; if false they
 *			are disarmed.
 */
__EXPORT extern void	up_pwm_servo_arm(bool armed);

/**
 * Set the servo update rate for all rate groups.
 *
 * @param rate		The update rate in Hz to set.
 * @return		OK on success, -ERANGE if an unsupported update rate is set.
 */
__EXPORT extern int	up_pwm_servo_set_rate(unsigned rate);

/**
 * Get a bitmap of output channels assigned to a given rate group.
 *
 * @param group		The rate group to query. Rate groups are assigned contiguously
 *			starting from zero.
 * @return		A bitmap of channels assigned to the rate group, or zero if
 *			the group number has no channels.
 */
__EXPORT extern uint32_t up_pwm_servo_get_rate_group(unsigned group);

/**
 * Set the update rate for a given rate group.
 *
 * @param group		The rate group whose update rate will be changed.
 * @param rate		The update rate in Hz.
 * @return		OK if the group was adjusted, -ERANGE if an unsupported update rate is set.
 */
__EXPORT extern int	up_pwm_servo_set_rate_group_update(unsigned group, unsigned rate);

/**
 * Set the current output value for a channel.
 *
 * @param channel	The channel to set.
 * @param value		The output pulse width in microseconds.
 */
__EXPORT extern int	up_pwm_servo_set(unsigned channel, servo_position_t value);

/**
 * Get the current output value for a channel.
 *
 * @param channel	The channel to read.
 * @return		The output pulse width in microseconds, or zero if
 *			outputs are not armed or not configured.
 */
__EXPORT extern servo_position_t up_pwm_servo_get(unsigned channel);

__END_DECLS

From the implementations of the above function in drv_pwm_servo.c, we can find that by lowest level, it means the registers of the corresponding timers are set, so that the properties of the outputs from those timers are changed.

/** get a single specific servo value */
#define PWM_SERVO_GET(_servo)	_PX4_IOC(_PWM_SERVO_BASE, 0x40 + _servo)

Then what is this _PX4_IOC ?

In src/platforms/px4_defines.h, there are the following lines

/*
 * NuttX Specific defines
 */
#if defined(__PX4_NUTTX)
.
.
.
#define _PX4_IOC(x,y) _IOC(x,y)
.
.
.
/*
 * POSIX Specific defines
 */
#elif defined(__PX4_POSIX)
.
.
.
// NuttX _IOC is equivalent to Linux _IO
#define _PX4_IOC(x,y) _IO(x,y)
.
.
.
#endif

in file ./NuttX/nuttx/include/nuttx/fs/ioctl.h, the definition of _IOC in nuttx is

#define _IOC(type,nr)   ((type)|(nr))

which is pretty simple. The following is one I found from linux kernel, located at /usr/include/asm-generic/ioctl.h, which is much more complicated, just listed here for reference.

#define _IOC_NRBITS     8
#define _IOC_TYPEBITS   8

#ifndef _IOC_SIZEBITS
# define _IOC_SIZEBITS  14
#endif

#ifndef _IOC_DIRBITS
# define _IOC_DIRBITS   2
#endif


#define _IOC_NRSHIFT	0
#define _IOC_TYPESHIFT	(_IOC_NRSHIFT+_IOC_NRBITS)
#define _IOC_SIZESHIFT	(_IOC_TYPESHIFT+_IOC_TYPEBITS)
#define _IOC_DIRSHIFT	(_IOC_SIZESHIFT+_IOC_SIZEBITS)
...
#define _IOC(dir,type,nr,size) \
        (((dir)  << _IOC_DIRSHIFT) | \
         ((type) << _IOC_TYPESHIFT) | \
         ((nr)   << _IOC_NRSHIFT) | \
         ((size) << _IOC_SIZESHIFT))

Basically the macro _IOC generates a data or a command by shifting various bits and logical operations. But it does not actually issue this generated data or command to any registers or devices.

./src/drivers/px4fmu/fmu.cpp <code> switch (cmd) {

case PWM_SERVO_ARM:
	up_pwm_servo_arm(true);
	break;
case PWM_SERVO_SET_ARM_OK:
case PWM_SERVO_CLEAR_ARM_OK:
case PWM_SERVO_SET_FORCE_SAFETY_OFF:
case PWM_SERVO_SET_FORCE_SAFETY_ON:
	// these are no-ops, as no safety switch
	break;
case PWM_SERVO_DISARM:
	up_pwm_servo_arm(false);
	break;
case PWM_SERVO_GET_DEFAULT_UPDATE_RATE:
	*(uint32_t *)arg = _pwm_default_rate;
	break;
case PWM_SERVO_SET_UPDATE_RATE:
	ret = set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, arg);
	break;

<code> It can be seen that the bottom level pwm functions are called.

Next, we come to the higher-level fmu.cpp

src/drivers/px4fmu/fmu.cpp,

there is a big class defined called PX4FMU, which manages various operations of the board, including the PWM. As to the PWM, the following functions are defined

int		set_mode(Mode mode);  // Configure for PWM output.
int		set_pwm_alt_rate(unsigned rate);
int		set_pwm_alt_channels(uint32_t channels);
int		set_pwm_rate(unsigned rate_map, unsigned default_rate, unsigned alt_rate);
int		pwm_ioctl(file *filp, int cmd, unsigned long arg);
void		update_pwm_rev_mask();
void		publish_pwm_outputs(uint16_t *values, size_t numvalues);

All functions contained there are implemented in px4fmu/fmu.cpp.

It seems that we've found out all the PWM functions and the corresponding restrictions, but when I changed

the parameter definition

PARAM_DEFINE_INT32(PWM_MIN, 400);

in ./src/modules/sensors/sensor_params.c

The complier simply issues out an error message

Default value is smaller than min: PWM_MIN default:400 min:800 CMakeFiles/xml_gen.dir/build.make:106: recipe for target 'parameters.xml' failed

So where the hell is this 800 minimum value restrictions? Since I've already changed the PWM_LOWEST_MIN constant in src/drivers/drv_pwm_output.h to 50. You'll never be able to guess, that the restrictions actually lie in the comments /** * Set the minimum PWM for the MAIN outputs * * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM * REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE * THE SYSTEM TO PUT CHANGES INTO EFFECT. * * Set to 1000 for industry default or 900 to increase servo travel. * * @min 800 * @max 1400 * @unit microseconds * @group PWM Outputs */ Somehow the complier parses the last four lines

* @min 800 * @max 1400 * @unit microseconds * @group PWM Outputs

to get the range of this parameter, and terminates if the parameter value is not within this range.

There is still the last problem, the default PWM rate is 50 Hz, which is quite bizzar, since all the pwm values are calculated with respect to a 400Hz PWM. This default value 50 scatters all over the place in file src/drivers/px4fmu/fmu.cpp.