mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_HAL_Linux: use ARRAY_SIZE macro
This commit is contained in:
parent
b83708f77f
commit
cfc2972e51
@ -38,6 +38,9 @@
|
|||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#include <AP_Common.h>
|
||||||
|
|
||||||
#include "dsm.h"
|
#include "dsm.h"
|
||||||
|
|
||||||
#define DSM_FRAME_SIZE 16 /**<DSM frame size in bytes*/
|
#define DSM_FRAME_SIZE 16 /**<DSM frame size in bytes*/
|
||||||
@ -159,7 +162,7 @@ dsm_guess_format(bool reset, const uint8_t dsm_frame[16])
|
|||||||
unsigned votes10 = 0;
|
unsigned votes10 = 0;
|
||||||
unsigned votes11 = 0;
|
unsigned votes11 = 0;
|
||||||
|
|
||||||
for (unsigned i = 0; i < (sizeof(masks) / sizeof(masks[0])); i++) {
|
for (unsigned i = 0; i < ARRAY_SIZE(masks); i++) {
|
||||||
|
|
||||||
if (cs10 == masks[i])
|
if (cs10 == masks[i])
|
||||||
votes10++;
|
votes10++;
|
||||||
|
@ -40,7 +40,7 @@ void loop(void)
|
|||||||
|
|
||||||
hal.console->printf("Scanning SPI bus devices\n");
|
hal.console->printf("Scanning SPI bus devices\n");
|
||||||
|
|
||||||
for (uint8_t i=0; i<sizeof(whoami_list)/sizeof(whoami_list[0]); i++) {
|
for (uint8_t i=0; i < ARRAY_SIZE(whoami_list); i++) {
|
||||||
spi = hal.spi->device(whoami_list[i].dev);
|
spi = hal.spi->device(whoami_list[i].dev);
|
||||||
if (spi == NULL) {
|
if (spi == NULL) {
|
||||||
hal.console->printf("Failed to get SPI device for %s\n", whoami_list[i].name);
|
hal.console->printf("Failed to get SPI device for %s\n", whoami_list[i].name);
|
||||||
|
Loading…
Reference in New Issue
Block a user