Browse Source

dshot: remove BOARD_DSHOT_MOTOR_ASSIGNMENT & handle timer channel gaps

master
Beat Küng 3 years ago committed by Daniel Agar
parent
commit
92769bd2b2
  1. 1
      boards/cubepilot/cubeorange/src/board_config.h
  2. 1
      boards/cubepilot/cubeyellow/src/board_config.h
  3. 1
      boards/holybro/durandal-v1/src/board_config.h
  4. 1
      boards/holybro/pix32v5/src/board_config.h
  5. 1
      boards/modalai/fc-v1/src/board_config.h
  6. 1
      boards/modalai/fc-v2/src/board_config.h
  7. 1
      boards/mro/ctrl-zero-h7-oem/src/board_config.h
  8. 1
      boards/mro/ctrl-zero-h7/src/board_config.h
  9. 1
      boards/mro/pixracerpro/src/board_config.h
  10. 1
      boards/omnibus/f4sd/src/board_config.h
  11. 1
      boards/px4/fmu-v2/src/board_config.h
  12. 1
      boards/px4/fmu-v3/src/board_config.h
  13. 1
      boards/px4/fmu-v4/src/board_config.h
  14. 1
      boards/px4/fmu-v5/src/board_config.h
  15. 1
      boards/px4/fmu-v5x/src/board_config.h
  16. 1
      boards/px4/fmu-v6u/src/board_config.h
  17. 1
      boards/px4/fmu-v6x/src/board_config.h
  18. 1
      boards/spracing/h7extreme/src/board_config.h
  19. 1
      boards/uvify/core/src/board_config.h
  20. 14
      platforms/nuttx/src/px4/common/include/px4_platform/io_timer_init.h
  21. 3
      platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/io_timer.h
  22. 2
      platforms/nuttx/src/px4/nxp/kinetis/include/px4_arch/io_timer.h
  23. 2
      platforms/nuttx/src/px4/nxp/s32k1xx/include/px4_arch/io_timer.h
  24. 2
      platforms/nuttx/src/px4/rpi/rpi_common/include/px4_arch/io_timer.h
  25. 22
      platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c
  26. 2
      platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/io_timer.h

1
boards/cubepilot/cubeorange/src/board_config.h

@ -149,7 +149,6 @@ @@ -149,7 +149,6 @@
#define BOARD_HAS_STATIC_MANIFEST 1
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5};
#define BOARD_ENABLE_CONSOLE_BUFFER

1
boards/cubepilot/cubeyellow/src/board_config.h

@ -144,7 +144,6 @@ @@ -144,7 +144,6 @@
#define BOARD_HAS_STATIC_MANIFEST 1
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5};
#define BOARD_ENABLE_CONSOLE_BUFFER

1
boards/holybro/durandal-v1/src/board_config.h

@ -181,7 +181,6 @@ @@ -181,7 +181,6 @@
#define BOARD_NUM_IO_TIMERS 4
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7, 9, 8};
/* Power supply control and monitoring GPIOs */

1
boards/holybro/pix32v5/src/board_config.h

@ -430,7 +430,6 @@ @@ -430,7 +430,6 @@
#define BOARD_NUM_IO_TIMERS 5
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7, 8, 9, 10};
__BEGIN_DECLS

1
boards/modalai/fc-v1/src/board_config.h

@ -262,7 +262,6 @@ @@ -262,7 +262,6 @@
#define BOARD_NUM_IO_TIMERS 5
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7};
__BEGIN_DECLS

1
boards/modalai/fc-v2/src/board_config.h

@ -199,7 +199,6 @@ @@ -199,7 +199,6 @@
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 8
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7};
/* Power supply control and monitoring GPIOs */
#define GPIO_nVDD_USB_VALID /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13) /* Low for USB power, High for DC power */

1
boards/mro/ctrl-zero-h7-oem/src/board_config.h

@ -157,7 +157,6 @@ @@ -157,7 +157,6 @@
#define BOARD_NUM_IO_TIMERS 3
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7};
#define BOARD_ENABLE_CONSOLE_BUFFER

1
boards/mro/ctrl-zero-h7/src/board_config.h

@ -157,7 +157,6 @@ @@ -157,7 +157,6 @@
#define BOARD_NUM_IO_TIMERS 3
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7};
#define BOARD_ENABLE_CONSOLE_BUFFER

1
boards/mro/pixracerpro/src/board_config.h

@ -146,7 +146,6 @@ @@ -146,7 +146,6 @@
#define BOARD_ADC_BRICK_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
#define BOARD_NUM_IO_TIMERS 3
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7};
#define BOARD_DMA_ALLOC_POOL_SIZE 5120 /* This board provides a DMA pool and APIs */
#define BOARD_HAS_ON_RESET 1 /* This board provides the board_on_reset interface */
#define BOARD_ENABLE_CONSOLE_BUFFER

1
boards/omnibus/f4sd/src/board_config.h

@ -147,7 +147,6 @@ @@ -147,7 +147,6 @@
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_CONSOLE_BUFFER_SIZE (1024*3)
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {0, 1, 3, 2};
__BEGIN_DECLS

1
boards/px4/fmu-v2/src/board_config.h

@ -158,7 +158,6 @@ @@ -158,7 +158,6 @@
#define BOARD_HAS_ON_RESET 1
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5};
__BEGIN_DECLS

1
boards/px4/fmu-v3/src/board_config.h

@ -158,7 +158,6 @@ @@ -158,7 +158,6 @@
#define BOARD_HAS_ON_RESET 1
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5};
/* Internal IMU Heater
*

1
boards/px4/fmu-v4/src/board_config.h

@ -179,7 +179,6 @@ @@ -179,7 +179,6 @@
#define BOARD_HAS_ON_RESET 1
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5};
__BEGIN_DECLS

1
boards/px4/fmu-v5/src/board_config.h

@ -433,7 +433,6 @@ @@ -433,7 +433,6 @@
#define BOARD_NUM_IO_TIMERS 5
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7, 8, 9, 10};
__BEGIN_DECLS

1
boards/px4/fmu-v5x/src/board_config.h

@ -218,7 +218,6 @@ @@ -218,7 +218,6 @@
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 9
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7, 8};
/* Power supply control and monitoring GPIOs */

1
boards/px4/fmu-v6u/src/board_config.h

@ -196,7 +196,6 @@ @@ -196,7 +196,6 @@
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 9
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7, 8};
/* Power supply control and monitoring GPIOs */

1
boards/px4/fmu-v6x/src/board_config.h

@ -236,7 +236,6 @@ @@ -236,7 +236,6 @@
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 9
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5, 6, 7, 8};
/* Power supply control and monitoring GPIOs */

1
boards/spracing/h7extreme/src/board_config.h

@ -133,7 +133,6 @@ @@ -133,7 +133,6 @@
#define BOARD_NUM_IO_TIMERS 3
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {1, 2, 3, 0, 4, 5, 6, 7};
__BEGIN_DECLS

1
boards/uvify/core/src/board_config.h

@ -178,7 +178,6 @@ @@ -178,7 +178,6 @@
#define BOARD_HAS_ON_RESET 1
#define BOARD_DSHOT_MOTOR_ASSIGNMENT {3, 2, 1, 0, 4, 5};
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_CONSOLE_BUFFER_SIZE (1024*3)

14
platforms/nuttx/src/px4/common/include/px4_platform/io_timer_init.h

@ -58,6 +58,8 @@ static inline constexpr io_timers_channel_mapping_t initIOTimerChannelMapping(co @@ -58,6 +58,8 @@ static inline constexpr io_timers_channel_mapping_t initIOTimerChannelMapping(co
}
uint32_t first_channel = UINT32_MAX;
uint32_t min_timer_channel = UINT32_MAX;
uint32_t max_timer_channel = 0;
uint32_t channel_count = 0;
for (uint32_t channel = 0; channel < MAX_TIMER_IO_CHANNELS; ++channel) {
@ -74,11 +76,23 @@ static inline constexpr io_timers_channel_mapping_t initIOTimerChannelMapping(co @@ -74,11 +76,23 @@ static inline constexpr io_timers_channel_mapping_t initIOTimerChannelMapping(co
}
++channel_count;
if (timer_io_channels_conf[channel].timer_channel < min_timer_channel) {
min_timer_channel = timer_io_channels_conf[channel].timer_channel;
}
if (timer_io_channels_conf[channel].timer_channel > max_timer_channel) {
max_timer_channel = timer_io_channels_conf[channel].timer_channel;
}
}
}
if (first_channel == UINT32_MAX) { //unused timer, channel_count is 0
first_channel = 0;
} else {
ret.element[i].lowest_timer_channel = min_timer_channel;
ret.element[i].channel_count_including_gaps = max_timer_channel - min_timer_channel + 1;
}
ret.element[i].first_channel_index = first_channel;

3
platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/io_timer.h

@ -86,6 +86,8 @@ typedef struct io_timers_t { @@ -86,6 +86,8 @@ typedef struct io_timers_t {
typedef struct io_timers_channel_mapping_element_t {
uint32_t first_channel_index;
uint32_t channel_count;
uint32_t lowest_timer_channel;
uint32_t channel_count_including_gaps;
} io_timers_channel_mapping_element_t;
/* mapping for each io_timers to timer_io_channels */
@ -102,6 +104,7 @@ typedef struct timer_io_channels_t { @@ -102,6 +104,7 @@ typedef struct timer_io_channels_t {
uint8_t val_offset; /* IMXRT_FLEXPWM_SM0VAL3_OFFSET or IMXRT_FLEXPWM_SM0VAL5_OFFSET */
uint8_t sub_module; /* 0 based sub module offset */
uint8_t sub_module_bits; /* LDOK and CLDOK bits */
uint8_t timer_channel; /* Unused */
} timer_io_channels_t;
#define SM0 0

2
platforms/nuttx/src/px4/nxp/kinetis/include/px4_arch/io_timer.h

@ -91,6 +91,8 @@ typedef struct io_timers_t { @@ -91,6 +91,8 @@ typedef struct io_timers_t {
typedef struct io_timers_channel_mapping_element_t {
uint32_t first_channel_index;
uint32_t channel_count;
uint32_t lowest_timer_channel;
uint32_t channel_count_including_gaps;
} io_timers_channel_mapping_element_t;
/* mapping for each io_timers to timer_io_channels */

2
platforms/nuttx/src/px4/nxp/s32k1xx/include/px4_arch/io_timer.h

@ -87,6 +87,8 @@ typedef struct io_timers_t { @@ -87,6 +87,8 @@ typedef struct io_timers_t {
typedef struct io_timers_channel_mapping_element_t {
uint32_t first_channel_index;
uint32_t channel_count;
uint32_t lowest_timer_channel;
uint32_t channel_count_including_gaps;
} io_timers_channel_mapping_element_t;
/* mapping for each io_timers to timer_io_channels */

2
platforms/nuttx/src/px4/rpi/rpi_common/include/px4_arch/io_timer.h

@ -97,6 +97,8 @@ typedef struct io_timers_t { @@ -97,6 +97,8 @@ typedef struct io_timers_t {
typedef struct io_timers_channel_mapping_element_t {
uint32_t first_channel_index;
uint32_t channel_count;
uint32_t lowest_timer_channel;
uint32_t channel_count_including_gaps;
} io_timers_channel_mapping_element_t;
/* mapping for each io_timers to timer_io_channels */

22
platforms/nuttx/src/px4/stm/stm32_common/dshot/dshot.c

@ -82,10 +82,6 @@ static uint8_t dshot_burst_buffer_array[DSHOT_TIMERS * DSHOT_BURST_BUFFER_SIZE(M @@ -82,10 +82,6 @@ static uint8_t dshot_burst_buffer_array[DSHOT_TIMERS * DSHOT_BURST_BUFFER_SIZE(M
px4_cache_aligned_data() = {};
static uint32_t *dshot_burst_buffer[DSHOT_TIMERS] = {};
#ifdef BOARD_DSHOT_MOTOR_ASSIGNMENT
static const uint8_t motor_assignment[MOTORS_NUMBER] = BOARD_DSHOT_MOTOR_ASSIGNMENT;
#endif /* BOARD_DSHOT_MOTOR_ASSIGNMENT */
int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq)
{
unsigned buffer_offset = 0;
@ -104,7 +100,7 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq) @@ -104,7 +100,7 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq)
#pragma GCC diagnostic ignored "-Wcast-align"
dshot_burst_buffer[timer] = (uint32_t *)&dshot_burst_buffer_array[buffer_offset];
#pragma GCC diagnostic pop
buffer_offset += DSHOT_BURST_BUFFER_SIZE(io_timers_channel_mapping.element[timer].channel_count);
buffer_offset += DSHOT_BURST_BUFFER_SIZE(io_timers_channel_mapping.element[timer].channel_count_including_gaps);
if (buffer_offset > sizeof(dshot_burst_buffer_array)) {
return -EINVAL; // something is wrong with the board configuration or some other logic
@ -140,9 +136,10 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq) @@ -140,9 +136,10 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq)
for (uint8_t timer_index = 0; (timer_index < DSHOT_TIMERS) && (OK == ret_val); timer_index++) {
if (true == dshot_handler[timer_index].init) {
dshot_handler[timer_index].dma_size = io_timers_channel_mapping.element[timer_index].channel_count *
dshot_handler[timer_index].dma_size = io_timers_channel_mapping.element[timer_index].channel_count_including_gaps *
ONE_MOTOR_BUFF_SIZE;
io_timer_set_dshot_mode(timer_index, dshot_pwm_freq, io_timers_channel_mapping.element[timer_index].channel_count);
io_timer_set_dshot_mode(timer_index, dshot_pwm_freq,
io_timers_channel_mapping.element[timer_index].channel_count_including_gaps);
dshot_handler[timer_index].dma_handle = stm32_dmachannel(io_timers[timer_index].dshot.dmamap);
@ -164,7 +161,7 @@ void up_dshot_trigger(void) @@ -164,7 +161,7 @@ void up_dshot_trigger(void)
// Flush cache so DMA sees the data
up_clean_dcache((uintptr_t)dshot_burst_buffer[timer],
(uintptr_t)dshot_burst_buffer[timer] +
DSHOT_BURST_BUFFER_SIZE(io_timers_channel_mapping.element[timer].channel_count));
DSHOT_BURST_BUFFER_SIZE(io_timers_channel_mapping.element[timer].channel_count_including_gaps));
px4_stm32_dmasetup(dshot_handler[timer].dma_handle,
io_timers[timer].base + STM32_GTIM_DMAR_OFFSET,
@ -192,10 +189,6 @@ void dshot_motor_data_set(unsigned motor_number, uint16_t throttle, bool telemet @@ -192,10 +189,6 @@ void dshot_motor_data_set(unsigned motor_number, uint16_t throttle, bool telemet
uint16_t packet = 0;
uint16_t checksum = 0;
#ifdef BOARD_DSHOT_MOTOR_ASSIGNMENT
motor_number = motor_assignment[motor_number];
#endif /* BOARD_DSHOT_MOTOR_ASSIGNMENT */
packet |= throttle << DSHOT_THROTTLE_POSITION;
packet |= ((uint16_t)telemetry & 0x01) << DSHOT_TELEMETRY_POSITION;
@ -213,8 +206,9 @@ void dshot_motor_data_set(unsigned motor_number, uint16_t throttle, bool telemet @@ -213,8 +206,9 @@ void dshot_motor_data_set(unsigned motor_number, uint16_t throttle, bool telemet
unsigned timer = timer_io_channels[motor_number].timer_index;
uint32_t *buffer = dshot_burst_buffer[timer];
unsigned num_motors = io_timers_channel_mapping.element[timer].channel_count;
unsigned timer_channel_index = motor_number - io_timers_channel_mapping.element[timer].first_channel_index;
const io_timers_channel_mapping_element_t *mapping = &io_timers_channel_mapping.element[timer];
unsigned num_motors = mapping->channel_count_including_gaps;
unsigned timer_channel_index = timer_io_channels[motor_number].timer_channel - mapping->lowest_timer_channel;
for (unsigned motor_data_index = 0; motor_data_index < ONE_MOTOR_DATA_SIZE; motor_data_index++) {
buffer[motor_data_index * num_motors + timer_channel_index] =

2
platforms/nuttx/src/px4/stm/stm32_common/include/px4_arch/io_timer.h

@ -102,6 +102,8 @@ typedef struct io_timers_t { @@ -102,6 +102,8 @@ typedef struct io_timers_t {
typedef struct io_timers_channel_mapping_element_t {
uint32_t first_channel_index;
uint32_t channel_count;
uint32_t lowest_timer_channel;
uint32_t channel_count_including_gaps;
} io_timers_channel_mapping_element_t;
/* mapping for each io_timers to timer_io_channels */

Loading…
Cancel
Save