mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 05:15:25 +03:00
BV/BIT macro consolidation
This commit is contained in:
parent
9ae2fe6d69
commit
c688c2bc8b
8 changed files with 34 additions and 38 deletions
|
@ -138,7 +138,7 @@ static uint8_t standbyConfig;
|
|||
|
||||
void NRF24L01_Initialize(uint8_t baseConfig)
|
||||
{
|
||||
standbyConfig = BV(NRF24L01_00_CONFIG_PWR_UP) | baseConfig;
|
||||
standbyConfig = BIT(NRF24L01_00_CONFIG_PWR_UP) | baseConfig;
|
||||
NRF24L01_InitGpio();
|
||||
// nRF24L01+ needs 100 milliseconds settling time from PowerOnReset to PowerDown mode
|
||||
static const uint32_t settlingTimeUs = 100000;
|
||||
|
@ -159,7 +159,7 @@ void NRF24L01_Initialize(uint8_t baseConfig)
|
|||
void NRF24L01_SetupBasic(void)
|
||||
{
|
||||
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No auto acknowledgment
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0));
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BIT(NRF24L01_02_EN_RXADDR_ERX_P0));
|
||||
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES); // 5-byte RX/TX address
|
||||
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x00); // Disable dynamic payload length on all pipes
|
||||
}
|
||||
|
@ -181,7 +181,7 @@ void NRF24L01_SetRxMode(void)
|
|||
{
|
||||
NRF24_CE_LO(); // drop into standby mode
|
||||
// set the PRIM_RX bit
|
||||
NRF24L01_WriteReg(NRF24L01_00_CONFIG, standbyConfig | BV(NRF24L01_00_CONFIG_PRIM_RX));
|
||||
NRF24L01_WriteReg(NRF24L01_00_CONFIG, standbyConfig | BIT(NRF24L01_00_CONFIG_PRIM_RX));
|
||||
NRF24L01_ClearAllInterrupts();
|
||||
// finally set CE high to start enter RX mode
|
||||
NRF24_CE_HI();
|
||||
|
@ -207,7 +207,7 @@ void NRF24L01_SetTxMode(void)
|
|||
void NRF24L01_ClearAllInterrupts(void)
|
||||
{
|
||||
// Writing to the STATUS register clears the specified interrupt bits
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_RX_DR) | BV(NRF24L01_07_STATUS_TX_DS) | BV(NRF24L01_07_STATUS_MAX_RT));
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BIT(NRF24L01_07_STATUS_RX_DR) | BIT(NRF24L01_07_STATUS_TX_DS) | BIT(NRF24L01_07_STATUS_MAX_RT));
|
||||
}
|
||||
|
||||
void NRF24L01_SetChannel(uint8_t channel)
|
||||
|
@ -217,7 +217,7 @@ void NRF24L01_SetChannel(uint8_t channel)
|
|||
|
||||
bool NRF24L01_ReadPayloadIfAvailable(uint8_t *data, uint8_t length)
|
||||
{
|
||||
if (NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BV(NRF24L01_17_FIFO_STATUS_RX_EMPTY)) {
|
||||
if (NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BIT(NRF24L01_17_FIFO_STATUS_RX_EMPTY)) {
|
||||
return false;
|
||||
}
|
||||
NRF24L01_ReadPayload(data, length);
|
||||
|
@ -239,11 +239,11 @@ bool NRF24L01_ReadPayloadIfAvailableFast(uint8_t *data, uint8_t length)
|
|||
ENABLE_RX();
|
||||
rxSpiTransferByte(R_REGISTER | (REGISTER_MASK & NRF24L01_07_STATUS));
|
||||
const uint8_t status = rxSpiTransferByte(NOP);
|
||||
if ((status & BV(NRF24L01_07_STATUS_RX_DR)) == 0) {
|
||||
if ((status & BIT(NRF24L01_07_STATUS_RX_DR)) == 0) {
|
||||
ret = true;
|
||||
// clear RX_DR flag
|
||||
rxSpiTransferByte(W_REGISTER | (REGISTER_MASK & NRF24L01_07_STATUS));
|
||||
rxSpiTransferByte(BV(NRF24L01_07_STATUS_RX_DR));
|
||||
rxSpiTransferByte(BIT(NRF24L01_07_STATUS_RX_DR));
|
||||
rxSpiTransferByte(R_RX_PAYLOAD);
|
||||
for (uint8_t i = 0; i < length; i++) {
|
||||
data[i] = rxSpiTransferByte(NOP);
|
||||
|
|
|
@ -30,8 +30,6 @@
|
|||
|
||||
#define NRF24L01_MAX_PAYLOAD_SIZE 32
|
||||
|
||||
#define BV(x) (1<<(x)) // bit value
|
||||
|
||||
// Register map of nRF24L01
|
||||
enum {
|
||||
NRF24L01_00_CONFIG = 0x00,
|
||||
|
|
|
@ -234,7 +234,7 @@ rx_spi_received_e cx10Nrf24DataReceived(uint8_t *payload)
|
|||
NRF24L01_SetTxMode();// enter transmit mode to send the packet
|
||||
// wait for the ACK packet to send before changing channel
|
||||
static const int fifoDelayUs = 100;
|
||||
while (!(NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BV(NRF24L01_17_FIFO_STATUS_TX_EMPTY))) {
|
||||
while (!(NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BIT(NRF24L01_17_FIFO_STATUS_TX_EMPTY))) {
|
||||
delayMicroseconds(fifoDelayUs);
|
||||
totalDelayUs += fifoDelayUs;
|
||||
}
|
||||
|
@ -244,7 +244,7 @@ rx_spi_received_e cx10Nrf24DataReceived(uint8_t *payload)
|
|||
XN297_WritePayload(payload, payloadSize, rxAddr);
|
||||
NRF24L01_SetTxMode();// enter transmit mode to send the packet
|
||||
// wait for the ACK packet to send before changing channel
|
||||
while (!(NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BV(NRF24L01_17_FIFO_STATUS_TX_EMPTY))) {
|
||||
while (!(NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BIT(NRF24L01_17_FIFO_STATUS_TX_EMPTY))) {
|
||||
delayMicroseconds(fifoDelayUs);
|
||||
totalDelayUs += fifoDelayUs;
|
||||
}
|
||||
|
|
|
@ -275,7 +275,7 @@ static void inavSetBound(void)
|
|||
|
||||
static void writeAckPayload(const uint8_t *data, uint8_t length)
|
||||
{
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_MAX_RT));
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BIT(NRF24L01_07_STATUS_MAX_RT));
|
||||
NRF24L01_WriteAckPayload(data, length, NRF24L01_PIPE0);
|
||||
}
|
||||
|
||||
|
@ -377,16 +377,16 @@ static void inavNrf24Setup(rx_spi_protocol_e protocol, const uint32_t *rxSpiId,
|
|||
UNUSED(rfChannelHoppingCount);
|
||||
|
||||
// sets PWR_UP, EN_CRC, CRCO - 2 byte CRC, only get IRQ pin interrupt on RX_DR
|
||||
NRF24L01_Initialize(BV(NRF24L01_00_CONFIG_EN_CRC) | BV(NRF24L01_00_CONFIG_CRCO) | BV(NRF24L01_00_CONFIG_MASK_MAX_RT) | BV(NRF24L01_00_CONFIG_MASK_TX_DS));
|
||||
NRF24L01_Initialize(BIT(NRF24L01_00_CONFIG_EN_CRC) | BIT(NRF24L01_00_CONFIG_CRCO) | BIT(NRF24L01_00_CONFIG_MASK_MAX_RT) | BIT(NRF24L01_00_CONFIG_MASK_TX_DS));
|
||||
|
||||
#ifdef USE_AUTO_ACKKNOWLEDGEMENT
|
||||
NRF24L01_WriteReg(NRF24L01_01_EN_AA, BV(NRF24L01_01_EN_AA_ENAA_P0)); // auto acknowledgment on P0
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0));
|
||||
NRF24L01_WriteReg(NRF24L01_01_EN_AA, BIT(NRF24L01_01_EN_AA_ENAA_P0)); // auto acknowledgment on P0
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BIT(NRF24L01_02_EN_RXADDR_ERX_P0));
|
||||
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES); // 5-byte RX/TX address
|
||||
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0);
|
||||
NRF24L01_Activate(0x73); // activate R_RX_PL_WID, W_ACK_PAYLOAD, and W_TX_PAYLOAD_NOACK registers
|
||||
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF24L01_1D_FEATURE_EN_ACK_PAY) | BV(NRF24L01_1D_FEATURE_EN_DPL));
|
||||
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, BV(NRF24L01_1C_DYNPD_DPL_P0)); // enable dynamic payload length on P0
|
||||
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BIT(NRF24L01_1D_FEATURE_EN_ACK_PAY) | BIT(NRF24L01_1D_FEATURE_EN_DPL));
|
||||
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, BIT(NRF24L01_1C_DYNPD_DPL_P0)); // enable dynamic payload length on P0
|
||||
//NRF24L01_Activate(0x73); // deactivate R_RX_PL_WID, W_ACK_PAYLOAD, and W_TX_PAYLOAD_NOACK registers
|
||||
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rxTxAddr, RX_TX_ADDR_LEN);
|
||||
|
|
|
@ -148,7 +148,7 @@ void knNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *packet)
|
|||
|
||||
static rx_spi_received_e readrx(uint8_t *packet)
|
||||
{
|
||||
if (!(NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_STATUS_RX_DR))) {
|
||||
if (!(NRF24L01_ReadReg(NRF24L01_07_STATUS) & BIT(NRF24L01_07_STATUS_RX_DR))) {
|
||||
uint32_t t = micros() - packet_timer;
|
||||
if (t > rx_timeout) {
|
||||
if (bind_phase == PHASE_RECEIVED) {
|
||||
|
@ -160,7 +160,7 @@ static rx_spi_received_e readrx(uint8_t *packet)
|
|||
return RX_SPI_RECEIVED_NONE;
|
||||
}
|
||||
packet_timer = micros();
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_RX_DR)); // clear the RX_DR flag
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BIT(NRF24L01_07_STATUS_RX_DR)); // clear the RX_DR flag
|
||||
NRF24L01_ReadPayload(packet, KN_PAYLOAD_SIZE);
|
||||
NRF24L01_FlushRx();
|
||||
|
||||
|
@ -179,14 +179,14 @@ rx_spi_received_e knNrf24DataReceived(uint8_t *packet)
|
|||
|
||||
static void knNrf24Setup(rx_spi_protocol_e protocol)
|
||||
{
|
||||
NRF24L01_Initialize(BV(NRF24L01_00_CONFIG_EN_CRC) | BV(NRF24L01_00_CONFIG_CRCO)); // 2-bytes CRC
|
||||
NRF24L01_Initialize(BIT(NRF24L01_00_CONFIG_EN_CRC) | BIT(NRF24L01_00_CONFIG_CRCO)); // 2-bytes CRC
|
||||
|
||||
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgment
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0)); // Enable data pipe 0
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BIT(NRF24L01_02_EN_RXADDR_ERX_P0)); // Enable data pipe 0
|
||||
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES); // 5-byte RX/TX address
|
||||
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x00);
|
||||
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_1Mbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_RX_DR) | BV(NRF24L01_07_STATUS_TX_DS) | BV(NRF24L01_07_STATUS_MAX_RT)); // Clear data ready, data sent, and retransmit
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BIT(NRF24L01_07_STATUS_RX_DR) | BIT(NRF24L01_07_STATUS_TX_DS) | BIT(NRF24L01_07_STATUS_MAX_RT)); // Clear data ready, data sent, and retransmit
|
||||
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, KN_PAYLOAD_SIZE); // bytes of data payload for pipe 0
|
||||
NRF24L01_WriteReg(NRF24L01_17_FIFO_STATUS, 0x00); // Just in case, no real bits to write here
|
||||
|
||||
|
|
|
@ -274,7 +274,7 @@ rx_spi_received_e symaNrf24DataReceived(uint8_t *payload)
|
|||
static void symaNrf24Setup(rx_spi_protocol_e protocol)
|
||||
{
|
||||
symaProtocol = protocol;
|
||||
NRF24L01_Initialize(BV(NRF24L01_00_CONFIG_EN_CRC) | BV( NRF24L01_00_CONFIG_CRCO)); // sets PWR_UP, EN_CRC, CRCO - 2 byte CRC
|
||||
NRF24L01_Initialize(BIT(NRF24L01_00_CONFIG_EN_CRC) | BIT( NRF24L01_00_CONFIG_CRCO)); // sets PWR_UP, EN_CRC, CRCO - 2 byte CRC
|
||||
NRF24L01_SetupBasic();
|
||||
|
||||
if (symaProtocol == RX_SPI_NRF24_SYMA_X) {
|
||||
|
|
|
@ -202,7 +202,7 @@ void v202Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *packet)
|
|||
|
||||
static rx_spi_received_e readrx(uint8_t *packet)
|
||||
{
|
||||
if (!(NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_STATUS_RX_DR))) {
|
||||
if (!(NRF24L01_ReadReg(NRF24L01_07_STATUS) & BIT(NRF24L01_07_STATUS_RX_DR))) {
|
||||
uint32_t t = micros() - packet_timer;
|
||||
if (t > rx_timeout) {
|
||||
switch_channel();
|
||||
|
@ -211,7 +211,7 @@ static rx_spi_received_e readrx(uint8_t *packet)
|
|||
return RX_SPI_RECEIVED_NONE;
|
||||
}
|
||||
packet_timer = micros();
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_RX_DR)); // clear the RX_DR flag
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BIT(NRF24L01_07_STATUS_RX_DR)); // clear the RX_DR flag
|
||||
NRF24L01_ReadPayload(packet, V2X2_PAYLOAD_SIZE);
|
||||
NRF24L01_FlushRx();
|
||||
|
||||
|
@ -230,10 +230,10 @@ rx_spi_received_e v202Nrf24DataReceived(uint8_t *packet)
|
|||
|
||||
static void v202Nrf24Setup(rx_spi_protocol_e protocol)
|
||||
{
|
||||
NRF24L01_Initialize(BV(NRF24L01_00_CONFIG_EN_CRC) | BV(NRF24L01_00_CONFIG_CRCO)); // 2-bytes CRC
|
||||
NRF24L01_Initialize(BIT(NRF24L01_00_CONFIG_EN_CRC) | BIT(NRF24L01_00_CONFIG_CRCO)); // 2-bytes CRC
|
||||
|
||||
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgment
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0)); // Enable data pipe 0
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BIT(NRF24L01_02_EN_RXADDR_ERX_P0)); // Enable data pipe 0
|
||||
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES); // 5-byte RX/TX address
|
||||
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0xFF); // 4ms retransmit t/o, 15 tries
|
||||
if (protocol == RX_SPI_NRF24_V202_250K) {
|
||||
|
@ -241,7 +241,7 @@ static void v202Nrf24Setup(rx_spi_protocol_e protocol)
|
|||
} else {
|
||||
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_1Mbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);
|
||||
}
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_RX_DR) | BV(NRF24L01_07_STATUS_TX_DS) | BV(NRF24L01_07_STATUS_MAX_RT)); // Clear data ready, data sent, and retransmit
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BIT(NRF24L01_07_STATUS_RX_DR) | BIT(NRF24L01_07_STATUS_TX_DS) | BIT(NRF24L01_07_STATUS_MAX_RT)); // Clear data ready, data sent, and retransmit
|
||||
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, V2X2_PAYLOAD_SIZE); // bytes of data payload for pipe 0
|
||||
NRF24L01_WriteReg(NRF24L01_17_FIFO_STATUS, 0x00); // Just in case, no real bits to write here
|
||||
#define RX_TX_ADDR_LEN 5
|
||||
|
|
|
@ -522,8 +522,6 @@ static void crsfFrameDisplayPortClear(sbuf_t *dst)
|
|||
|
||||
#endif
|
||||
|
||||
#define BV(x) (1 << (x)) // bit value
|
||||
|
||||
// schedule array to decide how often each type of frame is sent
|
||||
typedef enum {
|
||||
CRSF_FRAME_START_INDEX = 0,
|
||||
|
@ -570,24 +568,24 @@ static void processCrsf(void)
|
|||
sbuf_t crsfPayloadBuf;
|
||||
sbuf_t *dst = &crsfPayloadBuf;
|
||||
|
||||
if (currentSchedule & BV(CRSF_FRAME_ATTITUDE_INDEX)) {
|
||||
if (currentSchedule & BIT(CRSF_FRAME_ATTITUDE_INDEX)) {
|
||||
crsfInitializeFrame(dst);
|
||||
crsfFrameAttitude(dst);
|
||||
crsfFinalize(dst);
|
||||
}
|
||||
if (currentSchedule & BV(CRSF_FRAME_BATTERY_SENSOR_INDEX)) {
|
||||
if (currentSchedule & BIT(CRSF_FRAME_BATTERY_SENSOR_INDEX)) {
|
||||
crsfInitializeFrame(dst);
|
||||
crsfFrameBatterySensor(dst);
|
||||
crsfFinalize(dst);
|
||||
}
|
||||
|
||||
if (currentSchedule & BV(CRSF_FRAME_FLIGHT_MODE_INDEX)) {
|
||||
if (currentSchedule & BIT(CRSF_FRAME_FLIGHT_MODE_INDEX)) {
|
||||
crsfInitializeFrame(dst);
|
||||
crsfFrameFlightMode(dst);
|
||||
crsfFinalize(dst);
|
||||
}
|
||||
#ifdef USE_GPS
|
||||
if (currentSchedule & BV(CRSF_FRAME_GPS_INDEX)) {
|
||||
if (currentSchedule & BIT(CRSF_FRAME_GPS_INDEX)) {
|
||||
crsfInitializeFrame(dst);
|
||||
crsfFrameGps(dst);
|
||||
crsfFinalize(dst);
|
||||
|
@ -619,19 +617,19 @@ void initCrsfTelemetry(void)
|
|||
|
||||
int index = 0;
|
||||
if (sensors(SENSOR_ACC) && telemetryIsSensorEnabled(SENSOR_PITCH | SENSOR_ROLL | SENSOR_HEADING)) {
|
||||
crsfSchedule[index++] = BV(CRSF_FRAME_ATTITUDE_INDEX);
|
||||
crsfSchedule[index++] = BIT(CRSF_FRAME_ATTITUDE_INDEX);
|
||||
}
|
||||
if ((isBatteryVoltageConfigured() && telemetryIsSensorEnabled(SENSOR_VOLTAGE))
|
||||
|| (isAmperageConfigured() && telemetryIsSensorEnabled(SENSOR_CURRENT | SENSOR_FUEL))) {
|
||||
crsfSchedule[index++] = BV(CRSF_FRAME_BATTERY_SENSOR_INDEX);
|
||||
crsfSchedule[index++] = BIT(CRSF_FRAME_BATTERY_SENSOR_INDEX);
|
||||
}
|
||||
if (telemetryIsSensorEnabled(SENSOR_MODE)) {
|
||||
crsfSchedule[index++] = BV(CRSF_FRAME_FLIGHT_MODE_INDEX);
|
||||
crsfSchedule[index++] = BIT(CRSF_FRAME_FLIGHT_MODE_INDEX);
|
||||
}
|
||||
#ifdef USE_GPS
|
||||
if (featureIsEnabled(FEATURE_GPS)
|
||||
&& telemetryIsSensorEnabled(SENSOR_ALTITUDE | SENSOR_LAT_LONG | SENSOR_GROUND_SPEED | SENSOR_HEADING)) {
|
||||
crsfSchedule[index++] = BV(CRSF_FRAME_GPS_INDEX);
|
||||
crsfSchedule[index++] = BIT(CRSF_FRAME_GPS_INDEX);
|
||||
}
|
||||
#endif
|
||||
crsfScheduleCount = (uint8_t)index;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue