mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
HAL_ChibiOS: use ARRAY_SIZE_SIMPLE
this allows for boards without a device type (eg. no SPI bus)
This commit is contained in:
parent
7aeab8f5a8
commit
f5c8754d75
@ -58,7 +58,7 @@ const ChibiAnalogIn::pin_info ChibiAnalogIn::pin_config[] = {
|
||||
{ 15, VOLTAGE_SCALING*2 }, // analog airspeed sensor, 2:1 scaling
|
||||
};
|
||||
|
||||
#define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE(ChibiAnalogIn::pin_config)
|
||||
#define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE_SIMPLE(ChibiAnalogIn::pin_config)
|
||||
|
||||
// samples filled in by ADC DMA engine
|
||||
adcsample_t ChibiAnalogIn::samples[ADC_DMA_BUF_DEPTH*ADC_GRP1_NUM_CHANNELS];
|
||||
|
@ -49,7 +49,7 @@ static struct gpio_entry {
|
||||
#endif
|
||||
};
|
||||
|
||||
#define NUM_PINS ARRAY_SIZE(_gpio_tab)
|
||||
#define NUM_PINS ARRAY_SIZE_SIMPLE(_gpio_tab)
|
||||
#define PIN_ENABLED(pin) ((pin)<NUM_PINS && _gpio_tab[pin].enabled)
|
||||
|
||||
/*
|
||||
@ -57,7 +57,7 @@ static struct gpio_entry {
|
||||
*/
|
||||
static struct gpio_entry *gpio_by_pin_num(uint8_t pin_num)
|
||||
{
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
|
||||
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(_gpio_tab); i++) {
|
||||
if (pin_num == _gpio_tab[i].pin_num) {
|
||||
if (!_gpio_tab[i].enabled) {
|
||||
return NULL;
|
||||
@ -125,7 +125,7 @@ void ChibiGPIO::init()
|
||||
{
|
||||
extStart(&EXTD1, &extcfg);
|
||||
uint8_t pwm_count = AP_BoardConfig::get_pwm_count();
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
|
||||
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(_gpio_tab); i++) {
|
||||
uint8_t pin_num = _gpio_tab[i].pin_num;
|
||||
if (pin_num >= 50 && pin_num <= 55) {
|
||||
// enable GPIOs based on BRD_PWM_COUNT
|
||||
|
@ -31,7 +31,7 @@ static const struct I2CInfo {
|
||||
using namespace ChibiOS;
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
I2CBus I2CDeviceManager::businfo[ARRAY_SIZE(I2CD)];
|
||||
I2CBus I2CDeviceManager::businfo[ARRAY_SIZE_SIMPLE(I2CD)];
|
||||
|
||||
// get a handle for DMA sharing DMA channels with other subsystems
|
||||
void I2CBus::dma_init(void)
|
||||
@ -44,7 +44,7 @@ void I2CBus::dma_init(void)
|
||||
// setup I2C buses
|
||||
I2CDeviceManager::I2CDeviceManager(void)
|
||||
{
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(I2CD); i++) {
|
||||
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(I2CD); i++) {
|
||||
businfo[i].busnum = i;
|
||||
businfo[i].dma_init();
|
||||
/*
|
||||
@ -205,7 +205,7 @@ I2CDeviceManager::get_device(uint8_t bus, uint8_t address,
|
||||
bool use_smbus,
|
||||
uint32_t timeout_ms)
|
||||
{
|
||||
if (bus >= ARRAY_SIZE(I2CD)) {
|
||||
if (bus >= ARRAY_SIZE_SIMPLE(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));
|
||||
|
@ -58,7 +58,7 @@ const struct ChibiRCOutput::pwm_group ChibiRCOutput::pwm_group_list[] =
|
||||
}
|
||||
};
|
||||
|
||||
#define NUM_GROUPS ARRAY_SIZE(pwm_group_list)
|
||||
#define NUM_GROUPS ARRAY_SIZE_SIMPLE(pwm_group_list)
|
||||
|
||||
void ChibiRCOutput::init()
|
||||
{
|
||||
|
@ -276,12 +276,12 @@ SPIDeviceManager::get_device(const char *name)
|
||||
{
|
||||
/* Find the bus description in the table */
|
||||
uint8_t i;
|
||||
for (i = 0; i<ARRAY_SIZE(device_table); i++) {
|
||||
for (i = 0; i<ARRAY_SIZE_SIMPLE(device_table); i++) {
|
||||
if (strcmp(device_table[i].name, name) == 0) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (i == ARRAY_SIZE(device_table)) {
|
||||
if (i == ARRAY_SIZE_SIMPLE(device_table)) {
|
||||
printf("SPI: Invalid device name: %s\n", name);
|
||||
return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(nullptr);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user