mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-22 07:45:29 +03:00
Use ARRAYLEN macro where applicable
This commit is contained in:
parent
8462dd1bea
commit
90e792e243
9 changed files with 19 additions and 13 deletions
|
@ -141,7 +141,7 @@ static uint8_t ppmEventIndex = 0;
|
|||
|
||||
void ppmISREvent(eventSource_e source, uint32_t capture)
|
||||
{
|
||||
ppmEventIndex = (ppmEventIndex + 1) % (sizeof(ppmEvents) / sizeof(ppmEvents[0]));
|
||||
ppmEventIndex = (ppmEventIndex + 1) % ARRAYLEN(ppmEvents);
|
||||
|
||||
ppmEvents[ppmEventIndex].source = source;
|
||||
ppmEvents[ppmEventIndex].capture = capture;
|
||||
|
|
|
@ -108,7 +108,7 @@ typedef struct pageEntry_s {
|
|||
} pageEntry_t;
|
||||
|
||||
static const char tickerCharacters[] = "|/-\\"; // use 2/4/8 characters so that the divide is optimal.
|
||||
#define TICKER_CHARACTER_COUNT (sizeof(tickerCharacters) / sizeof(char))
|
||||
#define TICKER_CHARACTER_COUNT ARRAYLEN(tickerCharacters)
|
||||
|
||||
typedef enum {
|
||||
PAGE_STATE_FLAG_NONE = 0,
|
||||
|
@ -364,7 +364,7 @@ static void showRateProfilePage(void)
|
|||
i2c_OLED_send_string(dev, lineBuffer);
|
||||
}
|
||||
|
||||
#define SATELLITE_COUNT (sizeof(GPS_svinfo_cno) / sizeof(GPS_svinfo_cno[0]))
|
||||
#define SATELLITE_COUNT ARRAYLEN(GPS_svinfo_cno)
|
||||
#define SATELLITE_GRAPH_LEFT_OFFSET ((SCREEN_CHARACTER_COLUMN_COUNT - SATELLITE_COUNT) / 2)
|
||||
|
||||
#ifdef USE_GPS
|
||||
|
|
|
@ -127,7 +127,7 @@ static const gpsInitData_t gpsInitData[] = {
|
|||
{ GPS_BAUDRATE_9600, BAUD_9600, "$PUBX,41,1,0003,0001,9600,0*16\r\n", "" }
|
||||
};
|
||||
|
||||
#define GPS_INIT_DATA_ENTRY_COUNT (sizeof(gpsInitData) / sizeof(gpsInitData[0]))
|
||||
#define GPS_INIT_DATA_ENTRY_COUNT ARRAYLEN(gpsInitData)
|
||||
|
||||
#define DEFAULT_BAUD_RATE_INDEX 0
|
||||
|
||||
|
|
|
@ -115,7 +115,7 @@ static uint8_t serialPortCount;
|
|||
const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
|
||||
400000, 460800, 500000, 921600, 1000000, 1500000, 2000000, 2470000}; // see baudRate_e
|
||||
|
||||
#define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0]))
|
||||
#define BAUD_RATE_COUNT ARRAYLEN(baudRates)
|
||||
|
||||
serialPortConfig_t *serialFindPortConfigurationMutable(serialPortIdentifier_e identifier)
|
||||
{
|
||||
|
|
|
@ -33,6 +33,8 @@
|
|||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/transponder_ir.h"
|
||||
#include "drivers/system.h"
|
||||
|
@ -61,7 +63,7 @@ static bool transponderRepeat = false;
|
|||
// timers
|
||||
static timeUs_t nextUpdateAtUs = 0;
|
||||
|
||||
#define JITTER_DURATION_COUNT (sizeof(jitterDurations) / sizeof(uint8_t))
|
||||
#define JITTER_DURATION_COUNT ARRAYLEN(jitterDurations)
|
||||
static uint8_t jitterDurations[] = {0,9,4,8,3,9,6,7,1,6,9,7,8,2,6};
|
||||
|
||||
const transponderRequirement_t transponderRequirements[TRANSPONDER_PROVIDER_COUNT] = {
|
||||
|
|
|
@ -34,6 +34,7 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "pg/pg.h"
|
||||
|
@ -99,7 +100,7 @@ static const uint8_t mavRates[] = {
|
|||
[MAV_DATA_STREAM_EXTRA2] = 10 //2Hz
|
||||
};
|
||||
|
||||
#define MAXSTREAMS (sizeof(mavRates) / sizeof(mavRates[0]))
|
||||
#define MAXSTREAMS ARRAYLEN(mavRates)
|
||||
|
||||
static uint8_t mavTicks[MAXSTREAMS];
|
||||
static mavlink_message_t mavMsg;
|
||||
|
|
|
@ -23,6 +23,7 @@ extern "C" {
|
|||
#include "common/axis.h"
|
||||
#include "common/sensor_alignment.h"
|
||||
#include "common/sensor_alignment_impl.h"
|
||||
#include "common/utils.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
@ -289,7 +290,7 @@ static void testBuildAlignmentWithStandardAlignment(sensor_align_e alignment, se
|
|||
|
||||
buildAlignmentFromStandardAlignment(&sensorAlignment, alignment);
|
||||
|
||||
for (int i = 0; i < (int)(sizeof(sensorAlignment.raw) / sizeof(sensorAlignment.raw[0])); i++) {
|
||||
for (unsigned i = 0; i < ARRAYLEN(sensorAlignment.raw); i++) {
|
||||
EXPECT_EQ(expectedSensorAlignment.raw[i], sensorAlignment.raw[i]) << "Sensor alignment was not updated. alignment: " << alignment;
|
||||
}
|
||||
}
|
||||
|
@ -314,7 +315,7 @@ TEST(AlignSensorTest, AttemptBuildAlignmentFromCustomAlignment)
|
|||
|
||||
sensorAlignment_t expectedSensorAlignment = SENSOR_ALIGNMENT(1, 2, 3);
|
||||
|
||||
for (int i = 0; i < (int)(sizeof(sensorAlignment.raw) / sizeof(sensorAlignment.raw[0])); i++) {
|
||||
for (unsigned i = 0; i < ARRAYLEN(sensorAlignment.raw); i++) {
|
||||
EXPECT_EQ(expectedSensorAlignment.raw[i], sensorAlignment.raw[i]) << "Custom alignment should not be updated.";
|
||||
}
|
||||
}
|
||||
|
@ -327,7 +328,7 @@ TEST(AlignSensorTest, AttemptBuildAlignmentFromDefaultAlignment)
|
|||
|
||||
sensorAlignment_t expectedSensorAlignment = SENSOR_ALIGNMENT(1, 2, 3);
|
||||
|
||||
for (int i = 0; i < (int)(sizeof(sensorAlignment.raw) / sizeof(sensorAlignment.raw[0])); i++) {
|
||||
for (unsigned i = 0; i < ARRAYLEN(sensorAlignment.raw); i++) {
|
||||
EXPECT_EQ(expectedSensorAlignment.raw[i], sensorAlignment.raw[i]) << "Default alignment should not be updated.";
|
||||
}
|
||||
}
|
||||
|
|
|
@ -18,6 +18,7 @@
|
|||
|
||||
extern "C" {
|
||||
#include "common/encoding.h"
|
||||
#include "common/utils.h"
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
|
@ -48,7 +49,7 @@ TEST(EncodingTest, ZigzagEncodingTest)
|
|||
{ 2147483647, 4294967294},
|
||||
{-2147483648, 4294967295},
|
||||
};
|
||||
int expectationCount = sizeof(expectations) / sizeof(expectations[0]);
|
||||
int expectationCount = ARRAYLEN(expectations);
|
||||
|
||||
// expect
|
||||
|
||||
|
@ -67,7 +68,7 @@ TEST(EncodingTest, FloatToIntEncodingTest)
|
|||
{2.0, 0x40000000}, // Exponent should be in the top bits
|
||||
{4.5, 0x40900000}
|
||||
};
|
||||
int expectationCount = sizeof(expectations) / sizeof(expectations[0]);
|
||||
int expectationCount = ARRAYLEN(expectations);
|
||||
|
||||
// expect
|
||||
|
||||
|
|
|
@ -27,6 +27,7 @@ extern "C" {
|
|||
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
|
@ -165,7 +166,7 @@ TEST(LedStripTest, parseLedStripConfig)
|
|||
};
|
||||
|
||||
// when
|
||||
for (uint8_t index = 0; index < (sizeof(ledStripConfigCommands) / sizeof(ledStripConfigCommands[0])); index++) {
|
||||
for (uint8_t index = 0; index < ARRAYLEN(ledStripConfigCommands); index++) {
|
||||
EXPECT_TRUE(parseLedStripConfig(index, ledStripConfigCommands[index]));
|
||||
}
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue