Global: use new version of ARRAY_SIZE

This commit is contained in:
Lucas De Marchi 2018-08-02 16:27:17 -07:00 committed by Andrew Tridgell
parent 57ee0e29f6
commit 668c941717
9 changed files with 22 additions and 22 deletions

View File

@ -27,7 +27,7 @@ static uint8_t last_uart;
int16_t cin(unsigned timeout_ms)
{
uint8_t b = 0;
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(uarts); i++) {
for (uint8_t i=0; i<ARRAY_SIZE(uarts); i++) {
if (locked_uart == -1 || locked_uart == i) {
if (chnReadTimeout(uarts[i], &b, 1, chTimeMS2I(timeout_ms)) == 1) {
last_uart = i;
@ -41,7 +41,7 @@ int16_t cin(unsigned timeout_ms)
int cin_word(uint32_t *wp, unsigned timeout_ms)
{
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(uarts); i++) {
for (uint8_t i=0; i<ARRAY_SIZE(uarts); i++) {
if (locked_uart == -1 || locked_uart == i) {
if (chnReadTimeout(uarts[i], (uint8_t *)wp, 4, chTimeMS2I(timeout_ms)) == 4) {
last_uart = i;
@ -146,14 +146,14 @@ uint32_t get_mcu_desc(uint32_t max, uint8_t *revstr)
mcu_des_t des = mcu_descriptions[STM32_UNKNOWN];
for (int i = 0; i < ARRAY_SIZE_SIMPLE(mcu_descriptions); i++) {
for (int i = 0; i < ARRAY_SIZE(mcu_descriptions); i++) {
if (mcuid == mcu_descriptions[i].mcuid) {
des = mcu_descriptions[i];
break;
}
}
for (int i = 0; i < ARRAY_SIZE_SIMPLE(silicon_revs); i++) {
for (int i = 0; i < ARRAY_SIZE(silicon_revs); i++) {
if (silicon_revs[i].revid == revid) {
des.rev = silicon_revs[i].rev;
}
@ -185,7 +185,7 @@ bool check_limit_flash_1M(void)
uint32_t idcode = (*(uint32_t *)DBGMCU_BASE);
uint16_t revid = ((idcode & REVID_MASK) >> 16);
for (int i = 0; i < ARRAY_SIZE_SIMPLE(silicon_revs); i++) {
for (int i = 0; i < ARRAY_SIZE(silicon_revs); i++) {
if (silicon_revs[i].revid == revid) {
return silicon_revs[i].limit_flash_size_1M;
}
@ -342,7 +342,7 @@ void init_uarts(void)
#if HAL_USE_SERIAL == TRUE
sercfg.speed = BOOTLOADER_BAUDRATE;
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(uarts); i++) {
for (uint8_t i=0; i<ARRAY_SIZE(uarts); i++) {
#if HAL_USE_SERIAL_USB == TRUE
if (uarts[i] == (BaseChannel *)&SDU1) {
continue;

View File

@ -57,7 +57,7 @@ using namespace ChibiOS;
*/
const AnalogIn::pin_info AnalogIn::pin_config[] = HAL_ANALOG_PINS;
#define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE_SIMPLE(AnalogIn::pin_config)
#define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE(AnalogIn::pin_config)
// samples filled in by ADC DMA engine
adcsample_t *AnalogIn::samples;

View File

@ -28,7 +28,7 @@ static struct gpio_entry {
ioline_t pal_line;
} _gpio_tab[] = HAL_GPIO_PINS;
#define NUM_PINS ARRAY_SIZE_SIMPLE(_gpio_tab)
#define NUM_PINS ARRAY_SIZE(_gpio_tab)
#define PIN_ENABLED(pin) ((pin)<NUM_PINS && _gpio_tab[pin].enabled)
/*
@ -36,7 +36,7 @@ static struct gpio_entry {
*/
static struct gpio_entry *gpio_by_pin_num(uint8_t pin_num, bool check_enabled=true)
{
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(_gpio_tab); i++) {
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
if (pin_num == _gpio_tab[i].pin_num) {
if (check_enabled && !_gpio_tab[i].enabled) {
return NULL;
@ -56,7 +56,7 @@ void GPIO::init()
{
// auto-disable pins being used for PWM output based on BRD_PWM_COUNT parameter
uint8_t pwm_count = AP_BoardConfig::get_pwm_count();
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(_gpio_tab); i++) {
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
struct gpio_entry *g = &_gpio_tab[i];
if (g->pwm_num != 0) {
g->enabled = g->pwm_num > pwm_count;

View File

@ -34,7 +34,7 @@ static const struct I2CInfo {
using namespace ChibiOS;
extern const AP_HAL::HAL& hal;
I2CBus I2CDeviceManager::businfo[ARRAY_SIZE_SIMPLE(I2CD)];
I2CBus I2CDeviceManager::businfo[ARRAY_SIZE(I2CD)];
#ifndef HAL_I2C_BUS_BASE
#define HAL_I2C_BUS_BASE 0
@ -94,7 +94,7 @@ void I2CBus::clear_bus(ioline_t scl_line, uint8_t scl_af)
// setup I2C buses
I2CDeviceManager::I2CDeviceManager(void)
{
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(I2CD); i++) {
for (uint8_t i=0; i<ARRAY_SIZE(I2CD); i++) {
businfo[i].busnum = i;
businfo[i].dma_init();
/*
@ -296,7 +296,7 @@ I2CDeviceManager::get_device(uint8_t bus, uint8_t address,
uint32_t timeout_ms)
{
bus -= HAL_I2C_BUS_BASE;
if (bus >= ARRAY_SIZE_SIMPLE(I2CD)) {
if (bus >= ARRAY_SIZE(I2CD)) {
return AP_HAL::OwnPtr<AP_HAL::I2CDevice>(nullptr);
}
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(new I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms));
@ -308,7 +308,7 @@ I2CDeviceManager::get_device(uint8_t bus, uint8_t address,
*/
uint32_t I2CDeviceManager::get_bus_mask(void) const
{
return ((1U << ARRAY_SIZE_SIMPLE(I2CD)) - 1) << HAL_I2C_BUS_BASE;
return ((1U << ARRAY_SIZE(I2CD)) - 1) << HAL_I2C_BUS_BASE;
}
/*

View File

@ -37,7 +37,7 @@ extern AP_IOMCU iomcu;
struct RCOutput::pwm_group RCOutput::pwm_group_list[] = { HAL_PWM_GROUPS };
struct RCOutput::irq_state RCOutput::irq;
#define NUM_GROUPS ARRAY_SIZE_SIMPLE(pwm_group_list)
#define NUM_GROUPS ARRAY_SIZE(pwm_group_list)
// marker for a disabled channel
#define CHAN_DISABLED 255

View File

@ -183,7 +183,7 @@ bool SPIDevice::clock_pulse(uint32_t n)
uint16_t SPIDevice::derive_freq_flag_bus(uint8_t busid, uint32_t _frequency)
{
uint32_t spi_clock_freq = SPI1_CLOCK;
if (busid > 0 && uint8_t(busid-1) < ARRAY_SIZE_SIMPLE(bus_clocks)) {
if (busid > 0 && uint8_t(busid-1) < ARRAY_SIZE(bus_clocks)) {
spi_clock_freq = bus_clocks[busid-1] / 2;
}
@ -314,12 +314,12 @@ SPIDeviceManager::get_device(const char *name)
{
/* Find the bus description in the table */
uint8_t i;
for (i = 0; i<ARRAY_SIZE_SIMPLE(device_table); i++) {
for (i = 0; i<ARRAY_SIZE(device_table); i++) {
if (strcmp(device_table[i].name, name) == 0) {
break;
}
}
if (i == ARRAY_SIZE_SIMPLE(device_table)) {
if (i == ARRAY_SIZE(device_table)) {
printf("SPI: Invalid device name: %s\n", name);
return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(nullptr);
}
@ -366,7 +366,7 @@ void SPIDevice::test_clock_freq(void)
// time it takes to do the transfer
uint16_t len = 1024;
uint8_t *buf = (uint8_t *)hal.util->malloc_type(len, AP_HAL::Util::MEM_DMA_SAFE);
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(spi_devices); i++) {
for (uint8_t i=0; i<ARRAY_SIZE(spi_devices); i++) {
SPIConfig spicfg {};
const uint32_t target_freq = 2000000UL;
// use a clock divisor of 256 for maximum resolution

View File

@ -552,7 +552,7 @@ void AP_IOMCU::set_freq(uint16_t chmask, uint16_t freq)
{
const uint8_t masks[] = { 0x03,0x0C,0xF0 };
// ensure mask is legal for the timer layout
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(masks); i++) {
for (uint8_t i=0; i<ARRAY_SIZE(masks); i++) {
if (chmask & masks[i]) {
chmask |= masks[i];
}

View File

@ -30,7 +30,7 @@ const AP_ROMFS::embedded_file AP_ROMFS::files[] = {};
*/
const uint8_t *AP_ROMFS::find_file(const char *name, uint32_t &size)
{
for (uint16_t i=0; i<ARRAY_SIZE_SIMPLE(files); i++) {
for (uint16_t i=0; i<ARRAY_SIZE(files); i++) {
if (strcmp(name, files[i].filename) == 0) {
size = files[i].size;
return files[i].contents;

View File

@ -127,7 +127,7 @@ static struct {
static void count_msg(const char *name)
{
for (uint16_t i=0; i<ARRAY_SIZE_SIMPLE(counters); i++) {
for (uint16_t i=0; i<ARRAY_SIZE(counters); i++) {
if (counters[i].msg_name == name) {
counters[i].count++;
break;