ESC/Output Configuration Missing in QGroundControl for Custom STM32H743BIT6 PX4 Port

Hello PX4 Community,

I have ported PX4 to a custom flight controller based on the STM32H743BIT6 and completed all of my board-specific configuration. When I connect the board to QGroundControl and select the quadcopter airframe, the “Motors” tab only shows the motor test interface and basic throttle channels. There are no options to choose an ESC protocol (e.g. OneShot, DShot) or map specific timers/channels to motor outputs.

For example, I want to assign Timer 1, Channel 3 to Motor 1 (and similarly map the other timer channels to Motors 2–4), but I can’t find any parameters or settings in QGC to do this.

Could anyone please advise:

  1. How to enable ESC protocol selection in QGroundControl for a custom board?
  2. Which PX4 parameters or configuration files define the ESC output protocol and channel mapping?
  3. An example of mapping, for instance, Timer 1 Channel 3 → Motor 1 for a STM32H7 board.

Here is my code related to motors,

/****************************************************************************
 *
 *   Copyright (C) 2020 PX4 Development Team. All rights reserved.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions
 * are met:
 *
 * 1. Redistributions of source code must retain the above copyright
 *    notice, this list of conditions and the following disclaimer.
 * 2. Redistributions in binary form must reproduce the above copyright
 *    notice, this list of conditions and the following disclaimer in
 *    the documentation and/or other materials provided with the
 *    distribution.
 * 3. Neither the name PX4 nor the names of its contributors may be
 *    used to endorse or promote products derived from this software
 *    without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
 * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 *
 ****************************************************************************/

#include <px4_arch/io_timer_hw_description.h>

constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
	initIOTimer(Timer::Timer5, DMA{DMA::Index1}),
	initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
	initIOTimer(Timer::Timer2, DMA{DMA::Index1}),
};

constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {

	initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}),
	initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}),
	initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}),
	initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel1}, {GPIO::PortB, GPIO::Pin6}),
	initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}),
	initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}),
	initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortD, GPIO::Pin15}),
	initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}),
	initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}),
	initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}),
};

constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
	initIOTimerChannelMapping(io_timers, timer_io_channels);

/****************************************************************************
 *
 *   Copyright (c) 2020 PX4 Development Team. All rights reserved.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions
 * are met:
 *
 * 1. Redistributions of source code must retain the above copyright
 *    notice, this list of conditions and the following disclaimer.
 * 2. Redistributions in binary form must reproduce the above copyright
 *    notice, this list of conditions and the following disclaimer in
 *    the documentation and/or other materials provided with the
 *    distribution.
 * 3. Neither the name PX4 nor the names of its contributors may be
 *    used to endorse or promote products derived from this software
 *    without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
 * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 *
 ****************************************************************************/

/**
 * @file board_config.h
 *
 * Board internal definitions
 */

#pragma once

#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stm32_gpio.h>

#define BOARD_HAS_LED_PWM             0
#define BTN_LED_G   (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4)

#define CONFIG_BOARD_USB_VBUS_SENSE_DISABLED
/* ADC channels */
#define PX4_ADC_GPIO  \
	/* PF13  */  GPIO_ADC2_INP2,   \
	/* PF11  */  GPIO_ADC1_INP2,   \
	/* PF9  */   GPIO_ADC3_INP2,   \
	/* PF12  */  GPIO_ADC1_INP6,   \
	/* PF7 */    GPIO_ADC3_INP3


/* Define Channel numbers must match above GPIO pins */
#define ADC_BATTERY_VOLTAGE_CHANNEL           2 /* PF13  */
#define ADC_BATTERY_CURRENT_CHANNEL           2 /* PF11  */
#define ADC1_3V3_IN_CHANNEL                   2 /* PF9  */   // SPARE2_ADC1: ADC3.3
#define ADC_RSSI_IN_CHANNEL                   6 /* PF12 */
#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL    3 /* PF7  */

#define BOARD_ADC_BRICK_VALID 1

#define BOARD_ADC_OPEN_CIRCUIT_V     (5.6f)

#define ADC_CHANNELS \
	((1 << ADC_BATTERY_VOLTAGE_CHANNEL) |    \
	 (1 << ADC_BATTERY_CURRENT_CHANNEL) |    \
	 (1 << ADC1_3V3_IN_CHANNEL)         |    \
	 (1 << ADC_RSSI_IN_CHANNEL)         |    \
	 (1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL))


/* CAN Silence Silent mode control */
#define GPIO_CAN1_SILENT_S0  /* PI10  */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN10)
#define GPIO_CAN2_SILENT_S1  /* PH15  */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN15)


/* PWM */
#define DIRECT_PWM_OUTPUT_CHANNELS   10
#define BOARD_NUM_IO_TIMERS           3

#define BOARD_HAS_PWM_DRIVE_LEDS 0

/* Power supply control and monitoring GPIOs */
#define BOARD_NUMBER_BRICKS             1

#define VDD_GPS_TELEM_EN    (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN13) /* PI13  */
#define VDD_GPS_TELEM_FAULT   (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTI|GPIO_PIN14) /* PI14 */

#define VDD_RC_EN   (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN15) /* PI15  */
#define VDD_RC_FAULT    (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTJ|GPIO_PIN1) /* PJ1 */

#define VDD_PERIPHERAL_EN_PIN      (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN2) /* PB2  */
#define VDD_PERIPHERAL_FAULT_PIN  (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN1)  /* PB1 */

#define SD_CARD_PWR_EN    (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTJ|GPIO_PIN0)   /* PJ0  */
#define SESNORS_PWR_EN    (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTJ|GPIO_PIN2)  /* PJ2  */

#define VDD_GPS_POWER_EN(on_true)    px4_arch_gpiowrite(VDD_GPS_TELEM_EN, !(on_true))
#define VDD_RC_POWER_EN(on_true)    px4_arch_gpiowrite(VDD_RC_EN, !(on_true))
#define VDD_EXTERNAL_PERIPHERALS_POWER_EN(on_true)    px4_arch_gpiowrite(VDD_PERIPHERAL_EN_PIN, !(on_true))
#define VDD_SDCARD_POWER_EN(on_true)    px4_arch_gpiowrite(SD_CARD_PWR_EN, !(on_true))
#define VDD_INTERNAL_SENSORS_POWER_EN(on_true)    px4_arch_gpiowrite(SESNORS_PWR_EN, !(on_true))
#define GPS_LED_EN(on_true)    px4_arch_gpiowrite(BTN_LED_G, !(on_true))


#define READ_GPS_TEL_FAULT_DETECTED()     (!px4_arch_gpioread(VDD_GPS_TELEM_FAULT))
#define READ_RC_FAULT_DETECTED()     (!px4_arch_gpioread(VDD_RC_FAULT))
#define READ_PERIPHERALS_FAULT_DETECTED()     (!px4_arch_gpioread(VDD_PERIPHERAL_FAULT_PIN))


/* Tone alarm output */
#define TONE_ALARM_TIMER        8  /* timer 15 */
#define TONE_ALARM_CHANNEL      2  /* PE5 TIM15_CH1 */

#define GPIO_TONE_ALARM_IDLE    /* PI0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTJ|GPIO_PIN10) // ALARM
#define GPIO_TONE_ALARM         GPIO_TIM8_CH2OUT_3

 /* High-resolution timer */
#define HRT_TIMER               1  /* use timer3 for the HRT */
#define HRT_TIMER_CHANNEL       2  /* use capture/compare channel 3 */


#define HRT_PPM_CHANNEL		3
#define GPIO_PPM_IN             GPIO_TIM1_CH3IN_3
#define RC_SERIAL_PORT          "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE

/**
 * GPIO PPM_IN on PB4 T3C1
 * SPEKTRUM_RX (it's TX or RX in Bind) on UART8 PE0
 *   Inversion is possible in the UART and can drive GPIO_PPM_IN as an output
 */
#define GPIO_PPM_IN_AS_OUT           (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTJ|GPIO_PIN9)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART()       /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true)      px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))

/* RSSI_IN */
#define GPIO_RSSI_IN                   /* PF12  */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN12)

/* Safety Switch is only on FMU */
#define FMU_LED_AMBER                 /* PG4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4) // FMU_LED_AMBER
#define GPIO_BTN_SAFETY               /* PG5 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTG|GPIO_PIN5) // SAFETY_SW

#define GPIO_LED_SAFETY FMU_LED_AMBER

/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120

/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1

#define OTG_HS_DP (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN15)
#define OTG_HS_DM (GPIO_ALT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN14)


#define BOARD_ENABLE_CONSOLE_BUFFER

#define PX4_GPIO_INIT_LIST { \
	        PX4_ADC_GPIO,                            \
		GPIO_CAN1_RX,                            \
		GPIO_CAN2_TX,                            \
		GPIO_CAN2_RX,                            \
		GPIO_CAN1_SILENT_S0,                     \
		GPIO_CAN2_SILENT_S1,                     \
		SESNORS_PWR_EN,                          \
		VDD_RC_EN,                               \
		VDD_RC_FAULT,                            \
		VDD_PERIPHERAL_EN_PIN,                   \
		VDD_PERIPHERAL_FAULT_PIN,                \
		VDD_GPS_TELEM_EN,                        \
		VDD_GPS_TELEM_FAULT,                     \
		SD_CARD_PWR_EN,                          \
		GPIO_RSSI_IN,                            \
		OTG_HS_DP,				 \
		OTG_HS_DM,				 \
		PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0),        \
		PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1),        \
		PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D2),        \
		PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D3),        \
		PX4_GPIO_PIN_OFF(GPIO_SDMMC1_CK),        \
		PX4_GPIO_PIN_OFF(GPIO_SDMMC1_CMD),       \
		GPIO_TONE_ALARM_IDLE,                    \
		GPIO_BTN_SAFETY,                         \
		BTN_LED_G,                               \
	}

__BEGIN_DECLS
#ifndef __ASSEMBLY__

extern void stm32_spiinitialize(void);
extern void board_peripheral_reset(int ms);

#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS

One strange thing happened PWM_AUX_FUNCx param missing, all AUX params missing!
Thank you!
— Jimit