diff --git a/sw/airborne/arch/linux/mcu_periph/i2c_arch.c b/sw/airborne/arch/linux/mcu_periph/i2c_arch.c index 9ded62d343..4fcf70e470 100644 --- a/sw/airborne/arch/linux/mcu_periph/i2c_arch.c +++ b/sw/airborne/arch/linux/mcu_periph/i2c_arch.c @@ -44,7 +44,7 @@ void i2c_setbitrate(struct i2c_periph *p __attribute__((unused)), int bitrate _ bool i2c_idle(struct i2c_periph *p __attribute__((unused))) { - return TRUE; + return true; } #pragma GCC diagnostic push @@ -68,7 +68,7 @@ bool i2c_submit(struct i2c_periph *p, struct i2c_transaction *t) /* if write failed, increment error counter queue_full_cnt */ p->errors->queue_full_cnt++; t->status = I2CTransFailed; - return TRUE; + return true; } break; // Just reading @@ -79,7 +79,7 @@ bool i2c_submit(struct i2c_periph *p, struct i2c_transaction *t) /* if read failed, increment error counter ack_fail_cnt */ p->errors->ack_fail_cnt++; t->status = I2CTransFailed; - return TRUE; + return true; } break; // First Transmit and then read with repeated start @@ -96,7 +96,7 @@ bool i2c_submit(struct i2c_periph *p, struct i2c_transaction *t) /* if write/read failed, increment error counter miss_start_stop_cnt */ p->errors->miss_start_stop_cnt++; t->status = I2CTransFailed; - return TRUE; + return true; } break; default: @@ -105,7 +105,7 @@ bool i2c_submit(struct i2c_periph *p, struct i2c_transaction *t) // Successfull transfer t->status = I2CTransSuccess; - return TRUE; + return true; } #pragma GCC diagnostic pop diff --git a/sw/airborne/arch/linux/mcu_periph/spi_arch.c b/sw/airborne/arch/linux/mcu_periph/spi_arch.c index deb5d85081..a835b95bc1 100644 --- a/sw/airborne/arch/linux/mcu_periph/spi_arch.c +++ b/sw/airborne/arch/linux/mcu_periph/spi_arch.c @@ -89,7 +89,7 @@ bool spi_submit(struct spi_periph *p, struct spi_transaction *t) if (ioctl(fd, SPI_IOC_MESSAGE(1), &xfer) < 0) { t->status = SPITransFailed; - return FALSE; + return false; } /* copy recieved data if we had to use an extra rx_buffer */ @@ -98,20 +98,20 @@ bool spi_submit(struct spi_periph *p, struct spi_transaction *t) } t->status = SPITransSuccess; - return TRUE; + return true; } #pragma GCC diagnostic pop bool spi_lock(struct spi_periph *p, uint8_t slave) { // not implemented - return FALSE; + return false; } bool spi_resume(struct spi_periph *p, uint8_t slave) { // not implemented - return FALSE; + return false; } diff --git a/sw/airborne/arch/linux/mcu_periph/sys_time_arch.c b/sw/airborne/arch/linux/mcu_periph/sys_time_arch.c index 723a5ed55d..1c32e6ae1b 100644 --- a/sw/airborne/arch/linux/mcu_periph/sys_time_arch.c +++ b/sw/airborne/arch/linux/mcu_periph/sys_time_arch.c @@ -136,7 +136,7 @@ static void sys_tick_handler(void) if (sys_time.timer[i].in_use && sys_time.nb_tick >= sys_time.timer[i].end_time) { sys_time.timer[i].end_time += sys_time.timer[i].duration; - sys_time.timer[i].elapsed = TRUE; + sys_time.timer[i].elapsed = true; /* call registered callbacks, WARNING: they will be executed in the sys_time thread! */ if (sys_time.timer[i].cb) { sys_time.timer[i].cb(i); diff --git a/sw/airborne/arch/lpc21/ADS8344.c b/sw/airborne/arch/lpc21/ADS8344.c index 5e620418ba..0953c73e3f 100644 --- a/sw/airborne/arch/lpc21/ADS8344.c +++ b/sw/airborne/arch/lpc21/ADS8344.c @@ -88,7 +88,7 @@ static uint8_t channel; void ADS8344_init(void) { channel = 0; - ADS8344_available = FALSE; + ADS8344_available = false; /* setup pins for SSP (SCK, MISO, MOSI) */ PINSEL1 |= 2 << 2 | 2 << 4 | 2 << 6; @@ -146,7 +146,7 @@ void SPI1_ISR(void) channel++; if (channel > 7) { channel = 0; - ADS8344_available = TRUE; + ADS8344_available = true; } send_request(); SpiClearRti(); diff --git a/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c b/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c index 5884c72c94..5e7d024814 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c +++ b/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c @@ -356,7 +356,7 @@ bool i2c_submit(struct i2c_periph *p, struct i2c_transaction *t) /* queue full */ p->errors->queue_full_cnt++; t->status = I2CTransFailed; - return FALSE; + return false; } t->status = I2CTransPending; @@ -378,7 +378,7 @@ bool i2c_submit(struct i2c_periph *p, struct i2c_transaction *t) //VICIntEnable = VIC_BIT(*vic); enableIRQ(); - return TRUE; + return true; } void i2c_event(void) { } diff --git a/sw/airborne/arch/lpc21/mcu_periph/pwm_input_arch.c b/sw/airborne/arch/lpc21/mcu_periph/pwm_input_arch.c index b2ebd688f9..6939a99131 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/pwm_input_arch.c +++ b/sw/airborne/arch/lpc21/mcu_periph/pwm_input_arch.c @@ -89,10 +89,10 @@ void pwm_input_isr1(void) T0CCR &= ~TCCR_CR3_F; #if USE_PWM_INPUT1 == PWM_PULSE_TYPE_ACTIVE_HIGH pwm_input_duty_tics[0] = t_fall - t_rise; - pwm_input_duty_valid[0] = TRUE; + pwm_input_duty_valid[0] = true; #elif USE_PWM_INPUT1 == PWM_PULSE_TYPE_ACTIVE_LOW pwm_input_period_tics[0] = t_fall - t_oldfall; - pwm_input_period_valid[0] = TRUE; + pwm_input_period_valid[0] = true; t_oldfall = t_fall; #endif //ACTIVE_HIGH } else if (T0CCR & TCCR_CR3_R) { @@ -101,10 +101,10 @@ void pwm_input_isr1(void) T0CCR &= ~TCCR_CR3_R; #if USE_PWM_INPUT1 == PWM_PULSE_TYPE_ACTIVE_LOW pwm_input_duty_tics[0] = t_rise - t_fall; - pwm_input_duty_valid[0] = TRUE; + pwm_input_duty_valid[0] = true; #elif USE_PWM_INPUT1 == PWM_PULSE_TYPE_ACTIVE_HIGH pwm_input_period_tics[0] = t_rise - t_oldrise; - pwm_input_period_valid[0] = TRUE; + pwm_input_period_valid[0] = true; t_oldrise = t_rise; #endif //ACTIVE_LOW } @@ -128,10 +128,10 @@ void pwm_input_isr2(void) T0CCR &= ~TCCR_CR0_F; #if USE_PWM_INPUT2 == PWM_PULSE_TYPE_ACTIVE_HIGH pwm_input_duty_tics[1] = t_fall - t_rise; - pwm_input_duty_valid[1] = TRUE; + pwm_input_duty_valid[1] = true; #elif USE_PWM_INPUT2 == PWM_PULSE_TYPE_ACTIVE_LOW pwm_input_period_tics[1] = t_fall - t_oldfall; - pwm_input_period_valid[1] = TRUE; + pwm_input_period_valid[1] = true; t_oldfall = t_fall; #endif //ACTIVE_HIGH } else if (T0CCR & TCCR_CR0_R) { @@ -140,10 +140,10 @@ void pwm_input_isr2(void) T0CCR &= ~TCCR_CR0_R; #if USE_PWM_INPUT2 == PWM_PULSE_TYPE_ACTIVE_LOW pwm_input_duty_tics[1] = t_rise - t_fall; - pwm_input_duty_valid[1] = TRUE; + pwm_input_duty_valid[1] = true; #elif USE_PWM_INPUT2 == PWM_PULSE_TYPE_ACTIVE_HIGH pwm_input_period_tics[1] = t_rise - t_oldrise; - pwm_input_period_valid[1] = TRUE; + pwm_input_period_valid[1] = true; t_oldrise = t_rise; #endif //ACTIVE_LOW } diff --git a/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c b/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c index cb7609a0f5..ad76c5433d 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c +++ b/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c @@ -499,7 +499,7 @@ bool spi_submit(struct spi_periph *p, struct spi_transaction *t) if (idx >= SPI_TRANSACTION_QUEUE_LEN) { idx = 0; } if (idx == p->trans_extract_idx) { t->status = SPITransFailed; - return FALSE; /* queue full */ + return false; /* queue full */ } t->status = SPITransPending; @@ -521,7 +521,7 @@ bool spi_submit(struct spi_periph *p, struct spi_transaction *t) //VICIntEnable = VIC_BIT(*vic); //restoreIRQ(cpsr); // restore global interrupts enableIRQ(); - return TRUE; + return true; } @@ -567,10 +567,10 @@ bool spi_lock(struct spi_periph *p, uint8_t slave) if (slave < 254 && p->suspend == 0) { p->suspend = slave + 1; // 0 is reserved for unlock state VICIntEnable = VIC_BIT(*vic); - return TRUE; + return true; } VICIntEnable = VIC_BIT(*vic); - return FALSE; + return false; } bool spi_resume(struct spi_periph *p, uint8_t slave) @@ -584,10 +584,10 @@ bool spi_resume(struct spi_periph *p, uint8_t slave) SpiStart(p, p->trans[p->trans_extract_idx]); } VICIntEnable = VIC_BIT(*vic); - return TRUE; + return true; } VICIntEnable = VIC_BIT(*vic); - return FALSE; + return false; } #endif /* SPI_MASTER */ @@ -681,7 +681,7 @@ bool spi_slave_register(struct spi_periph *p, struct spi_transaction *t) if (p->trans_insert_idx >= 1) { t->status = SPITransFailed; - return FALSE; + return false; } t->status = SPITransPending; p->status = SPIIdle; @@ -697,18 +697,18 @@ bool spi_slave_register(struct spi_periph *p, struct spi_transaction *t) SpiSetDataSize(p, t->dss); - return TRUE; + return true; } bool spi_slave_wait(struct spi_periph *p) { if (p->trans_insert_idx == 0) { // no transaction registered - return FALSE; + return false; } // Start waiting SpiSlaveStart(p, p->trans[p->trans_extract_idx]); - return TRUE; + return true; } #endif /* SPI_SLAVE */ diff --git a/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c b/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c index 528a344ef8..26b9e601f3 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c +++ b/sw/airborne/arch/lpc21/mcu_periph/spi_slave_hs_arch.c @@ -107,7 +107,7 @@ static void SSP_ISR(void) __attribute__((naked)); // Functions for the generic device API static int spi_slave_hs_check_free_space(struct spi_slave_hs *p __attribute__((unused)), uint8_t len __attribute__((unused))) { - return TRUE; + return true; } static void spi_slave_hs_transmit(struct spi_slave_hs *p __attribute__((unused)), uint8_t byte) diff --git a/sw/airborne/arch/lpc21/mcu_periph/sys_time_arch.c b/sw/airborne/arch/lpc21/mcu_periph/sys_time_arch.c index 0e0ec59f4c..b14e1282e9 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/sys_time_arch.c +++ b/sw/airborne/arch/lpc21/mcu_periph/sys_time_arch.c @@ -168,7 +168,7 @@ static inline void sys_tick_irq_handler(void) if (sys_time.timer[i].in_use && sys_time.nb_tick >= sys_time.timer[i].end_time) { sys_time.timer[i].end_time += sys_time.timer[i].duration; - sys_time.timer[i].elapsed = TRUE; + sys_time.timer[i].elapsed = true; if (sys_time.timer[i].cb) { sys_time.timer[i].cb(i); } diff --git a/sw/airborne/arch/lpc21/modules/core/trigger_ext_hw.c b/sw/airborne/arch/lpc21/modules/core/trigger_ext_hw.c index 61b235efb3..ffc44bc3fd 100644 --- a/sw/airborne/arch/lpc21/modules/core/trigger_ext_hw.c +++ b/sw/airborne/arch/lpc21/modules/core/trigger_ext_hw.c @@ -36,7 +36,7 @@ void TRIG_ISR() if (msec_of_cpu_ticks(delta_t0_temp) > 10) { trigger_delta_t0 = delta_t0_temp; last = trigger_t0; - trigger_ext_valid = TRUE; + trigger_ext_valid = true; } } @@ -52,6 +52,6 @@ void trigger_ext_init(void) #else #error "trig_ext_hw.h: Unknown PULSE_TYPE" #endif - trigger_ext_valid = FALSE; + trigger_ext_valid = false; } diff --git a/sw/airborne/arch/lpc21/modules/sensors/trig_ext_hw.c b/sw/airborne/arch/lpc21/modules/sensors/trig_ext_hw.c index a2b6609819..e0ede7b4ca 100644 --- a/sw/airborne/arch/lpc21/modules/sensors/trig_ext_hw.c +++ b/sw/airborne/arch/lpc21/modules/sensors/trig_ext_hw.c @@ -19,7 +19,7 @@ void TRIG_ISR() if (msec_of_cpu_ticks(delta_t0_temp) > 10) { delta_t0 = delta_t0_temp; last = trigger_t0; - trig_ext_valid = TRUE; + trig_ext_valid = true; } } @@ -35,6 +35,6 @@ void trig_ext_init(void) #else #error "trig_ext_hw.h: Unknown PULSE_TYPE" #endif - trig_ext_valid = FALSE; + trig_ext_valid = false; } diff --git a/sw/airborne/arch/lpc21/subsystems/imu/imu_aspirin_arch.c b/sw/airborne/arch/lpc21/subsystems/imu/imu_aspirin_arch.c index 8077d30f99..b23bf7171d 100644 --- a/sw/airborne/arch/lpc21/subsystems/imu/imu_aspirin_arch.c +++ b/sw/airborne/arch/lpc21/subsystems/imu/imu_aspirin_arch.c @@ -37,7 +37,7 @@ void exti15_10_irq_handler(void) // if(EXTI_GetITStatus(EXTI_Line14) != RESET) // EXTI_ClearITPendingBit(EXTI_Line14); - //imu_aspirin.gyro_eoc = TRUE; + //imu_aspirin.gyro_eoc = true; //imu_aspirin.status = AspirinStatusReadingGyro; } @@ -59,5 +59,5 @@ void exti2_irq_handler(void) void dma1_c4_irq_handler(void) { - //imu_aspirin.accel_available = TRUE; + //imu_aspirin.accel_available = true; } diff --git a/sw/airborne/arch/lpc21/subsystems/imu/imu_crista_arch.c b/sw/airborne/arch/lpc21/subsystems/imu/imu_crista_arch.c index c992f76104..da31fda1e9 100644 --- a/sw/airborne/arch/lpc21/subsystems/imu/imu_crista_arch.c +++ b/sw/airborne/arch/lpc21/subsystems/imu/imu_crista_arch.c @@ -114,7 +114,7 @@ void SPI1_ISR(void) channel++; if (channel > 7 - 1) { channel = 0; - ADS8344_available = TRUE; + ADS8344_available = true; ADS8344Unselect(); } else { send_request(); diff --git a/sw/airborne/arch/sim/mcu_periph/i2c_arch.c b/sw/airborne/arch/sim/mcu_periph/i2c_arch.c index f2c4085092..705e00d9f1 100644 --- a/sw/airborne/arch/sim/mcu_periph/i2c_arch.c +++ b/sw/airborne/arch/sim/mcu_periph/i2c_arch.c @@ -27,8 +27,8 @@ #include "mcu_periph/i2c.h" -bool i2c_idle(struct i2c_periph *p __attribute__((unused))) { return TRUE; } -bool i2c_submit(struct i2c_periph *p __attribute__((unused)), struct i2c_transaction *t __attribute__((unused))) { return TRUE;} +bool i2c_idle(struct i2c_periph *p __attribute__((unused))) { return true; } +bool i2c_submit(struct i2c_periph *p __attribute__((unused)), struct i2c_transaction *t __attribute__((unused))) { return true;} void i2c_event(void) { } void i2c2_setbitrate(int bitrate __attribute__((unused))) { } diff --git a/sw/airborne/arch/sim/mcu_periph/spi_arch.c b/sw/airborne/arch/sim/mcu_periph/spi_arch.c index 978d37f292..83b5b087a4 100644 --- a/sw/airborne/arch/sim/mcu_periph/spi_arch.c +++ b/sw/airborne/arch/sim/mcu_periph/spi_arch.c @@ -27,7 +27,7 @@ #include "mcu_periph/spi.h" -bool spi_submit(struct spi_periph *p __attribute__((unused)), struct spi_transaction *t __attribute__((unused))) { return TRUE;} +bool spi_submit(struct spi_periph *p __attribute__((unused)), struct spi_transaction *t __attribute__((unused))) { return true;} void spi_init_slaves(void) {} @@ -35,7 +35,7 @@ void spi_slave_select(uint8_t slave __attribute__((unused))) {} void spi_slave_unselect(uint8_t slave __attribute__((unused))) {} -bool spi_lock(struct spi_periph *p __attribute__((unused)), uint8_t slave __attribute__((unused))) { return TRUE; } +bool spi_lock(struct spi_periph *p __attribute__((unused)), uint8_t slave __attribute__((unused))) { return true; } -bool spi_resume(struct spi_periph *p __attribute__((unused)), uint8_t slave __attribute__((unused))) { return TRUE; } +bool spi_resume(struct spi_periph *p __attribute__((unused)), uint8_t slave __attribute__((unused))) { return true; } diff --git a/sw/airborne/arch/sim/mcu_periph/sys_time_arch.c b/sw/airborne/arch/sim/mcu_periph/sys_time_arch.c index b5b69dd82a..22612644bf 100644 --- a/sw/airborne/arch/sim/mcu_periph/sys_time_arch.c +++ b/sw/airborne/arch/sim/mcu_periph/sys_time_arch.c @@ -47,7 +47,7 @@ void sys_tick_handler(void) if (sys_time.timer[i].in_use && sys_time.nb_tick >= sys_time.timer[i].end_time) { sys_time.timer[i].end_time += sys_time.timer[i].duration; - sys_time.timer[i].elapsed = TRUE; + sys_time.timer[i].elapsed = true; if (sys_time.timer[i].cb) { sys_time.timer[i].cb(i); } diff --git a/sw/airborne/arch/sim/modules/core/trigger_ext_hw.c b/sw/airborne/arch/sim/modules/core/trigger_ext_hw.c index 0763981327..6d3db7f317 100644 --- a/sw/airborne/arch/sim/modules/core/trigger_ext_hw.c +++ b/sw/airborne/arch/sim/modules/core/trigger_ext_hw.c @@ -26,6 +26,6 @@ void trigger_ext_init(void) { - trigger_ext_valid = FALSE; + trigger_ext_valid = false; } diff --git a/sw/airborne/arch/sim/sim_ap.c b/sw/airborne/arch/sim/sim_ap.c index f92ba99e1f..64b71d95e1 100644 --- a/sw/airborne/arch/sim/sim_ap.c +++ b/sw/airborne/arch/sim/sim_ap.c @@ -138,7 +138,7 @@ value set_datalink_message(value s) dl_buffer[i] = ss[i]; } - dl_msg_available = TRUE; + dl_msg_available = true; DlCheckAndParse(); return Val_unit; diff --git a/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c b/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c index 1ccacd5851..16fa4b7239 100644 --- a/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c +++ b/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c @@ -68,7 +68,7 @@ void radio_control_feed(void) RADIO_MODE_NEUTRAL, \ RADIO_MODE_MIN, \ RADIO_MODE_MAX); - ppm_frame_available = TRUE; + ppm_frame_available = true; } #else //RADIO_CONTROL void radio_control_feed(void) {} @@ -84,7 +84,7 @@ value update_rc_channel(value c, value v) value send_ppm(value unit) { - ppm_frame_available = TRUE; + ppm_frame_available = true; return unit; } #else // RADIO_CONTROL diff --git a/sw/airborne/arch/sim/subsystems/radio_control/spektrum_arch.c b/sw/airborne/arch/sim/subsystems/radio_control/spektrum_arch.c index 63bb31bdcc..3480ecd2b3 100644 --- a/sw/airborne/arch/sim/subsystems/radio_control/spektrum_arch.c +++ b/sw/airborne/arch/sim/subsystems/radio_control/spektrum_arch.c @@ -43,7 +43,7 @@ void radio_control_spektrum_try_bind(void) {} void radio_control_impl_init(void) { - spektrum_available = FALSE; + spektrum_available = false; } void RadioControlEventImp(void (*frame_handler)(void)) { @@ -53,7 +53,7 @@ void RadioControlEventImp(void (*frame_handler)(void)) radio_control.status = RC_OK; (*frame_handler)(); } - spektrum_available = FALSE; + spektrum_available = false; } #if USE_NPS @@ -65,7 +65,7 @@ void radio_control_feed(void) radio_control.values[RADIO_YAW] = nps_radio_control.yaw * MAX_PPRZ; radio_control.values[RADIO_THROTTLE] = nps_radio_control.throttle * MAX_PPRZ; radio_control.values[RADIO_MODE] = nps_radio_control.mode * MAX_PPRZ; - spektrum_available = TRUE; + spektrum_available = true; } #else //RADIO_CONTROL void radio_control_feed(void) {} @@ -89,7 +89,7 @@ value update_rc_channel(value c, value v) value send_ppm(value unit) { - spektrum_available = TRUE; + spektrum_available = true; return unit; } #else // RADIO_CONTROL diff --git a/sw/airborne/arch/stm32/led_hw.h b/sw/airborne/arch/stm32/led_hw.h index d5004de98c..2fbd2eaaf2 100644 --- a/sw/airborne/arch/stm32/led_hw.h +++ b/sw/airborne/arch/stm32/led_hw.h @@ -82,11 +82,11 @@ extern uint8_t led_status[NB_LED]; GPIO_CNF_OUTPUT_PUSHPULL, \ GPIO15); \ for(uint8_t _cnt=0; _cntwatchdog > WD_DELAY) { - return FALSE; + return false; } uint8_t temp; @@ -1428,7 +1428,7 @@ bool i2c_submit(struct i2c_periph *periph, struct i2c_transaction *t) // queue full periph->errors->queue_full_cnt++; t->status = I2CTransFailed; - return FALSE; + return false; } t->status = I2CTransPending; @@ -1462,7 +1462,7 @@ bool i2c_submit(struct i2c_periph *periph, struct i2c_transaction *t) /* else it will be started by the interrupt handler when the previous transactions completes */ __enable_irq(); - return TRUE; + return true; } bool i2c_idle(struct i2c_periph *periph) @@ -1475,7 +1475,7 @@ bool i2c_idle(struct i2c_periph *periph) #ifdef I2C_DEBUG_LED #if USE_I2C1 if (periph == &i2c1) { - return TRUE; + return true; } #endif #endif @@ -1484,6 +1484,6 @@ bool i2c_idle(struct i2c_periph *periph) if (periph->status == I2CIdle) { return !(BIT_X_IS_SET_IN_REG(I2C_SR2_BUSY, I2C_SR2(i2c))); } else { - return FALSE; + return false; } } diff --git a/sw/airborne/arch/stm32/mcu_periph/pwm_input_arch.c b/sw/airborne/arch/stm32/mcu_periph/pwm_input_arch.c index 0da7150250..140d3bdec0 100644 --- a/sw/airborne/arch/stm32/mcu_periph/pwm_input_arch.c +++ b/sw/airborne/arch/stm32/mcu_periph/pwm_input_arch.c @@ -208,12 +208,12 @@ void tim1_cc_isr(void) { if ((TIM1_SR & TIM1_CC_IF_PERIOD) != 0) { timer_clear_flag(TIM1, TIM1_CC_IF_PERIOD); pwm_input_period_tics[TIM1_PWM_INPUT_IDX] = TIM1_CCR_PERIOD; - pwm_input_period_valid[TIM1_PWM_INPUT_IDX] = TRUE; + pwm_input_period_valid[TIM1_PWM_INPUT_IDX] = true; } if ((TIM1_SR & TIM1_CC_IF_DUTY) != 0) { timer_clear_flag(TIM1, TIM1_CC_IF_DUTY); pwm_input_duty_tics[TIM1_PWM_INPUT_IDX] = TIM1_CCR_DUTY; - pwm_input_duty_valid[TIM1_PWM_INPUT_IDX] = TRUE; + pwm_input_duty_valid[TIM1_PWM_INPUT_IDX] = true; } } @@ -225,12 +225,12 @@ void tim2_isr(void) { if ((TIM2_SR & TIM2_CC_IF_PERIOD) != 0) { timer_clear_flag(TIM2, TIM2_CC_IF_PERIOD); pwm_input_period_tics[TIM2_PWM_INPUT_IDX] = TIM2_CCR_PERIOD; - pwm_input_period_valid[TIM2_PWM_INPUT_IDX] = TRUE; + pwm_input_period_valid[TIM2_PWM_INPUT_IDX] = true; } if ((TIM2_SR & TIM2_CC_IF_DUTY) != 0) { timer_clear_flag(TIM2, TIM2_CC_IF_DUTY); pwm_input_duty_tics[TIM2_PWM_INPUT_IDX] = TIM2_CCR_DUTY; - pwm_input_duty_valid[TIM2_PWM_INPUT_IDX] = TRUE; + pwm_input_duty_valid[TIM2_PWM_INPUT_IDX] = true; } if ((TIM2_SR & TIM_SR_UIF) != 0) { timer_clear_flag(TIM2, TIM_SR_UIF); @@ -246,12 +246,12 @@ void tim3_isr(void) { if ((TIM3_SR & TIM3_CC_IF_PERIOD) != 0) { timer_clear_flag(TIM3, TIM3_CC_IF_PERIOD); pwm_input_period_tics[TIM3_PWM_INPUT_IDX] = TIM3_CCR_PERIOD; - pwm_input_period_valid[TIM3_PWM_INPUT_IDX] = TRUE; + pwm_input_period_valid[TIM3_PWM_INPUT_IDX] = true; } if ((TIM3_SR & TIM3_CC_IF_DUTY) != 0) { timer_clear_flag(TIM3, TIM3_CC_IF_DUTY); pwm_input_duty_tics[TIM3_PWM_INPUT_IDX] = TIM3_CCR_DUTY; - pwm_input_duty_valid[TIM3_PWM_INPUT_IDX] = TRUE; + pwm_input_duty_valid[TIM3_PWM_INPUT_IDX] = true; } if ((TIM3_SR & TIM_SR_UIF) != 0) { timer_clear_flag(TIM3, TIM_SR_UIF); @@ -267,12 +267,12 @@ void tim5_isr(void) { if ((TIM5_SR & TIM5_CC_IF_PERIOD) != 0) { timer_clear_flag(TIM5, TIM5_CC_IF_PERIOD); pwm_input_period_tics[TIM5_PWM_INPUT_IDX] = TIM5_CCR_PERIOD; - pwm_input_period_valid[TIM5_PWM_INPUT_IDX] = TRUE; + pwm_input_period_valid[TIM5_PWM_INPUT_IDX] = true; } if ((TIM5_SR & TIM5_CC_IF_DUTY) != 0) { timer_clear_flag(TIM5, TIM5_CC_IF_DUTY); pwm_input_duty_tics[TIM5_PWM_INPUT_IDX] = TIM5_CCR_DUTY; - pwm_input_duty_valid[TIM5_PWM_INPUT_IDX] = TRUE; + pwm_input_duty_valid[TIM5_PWM_INPUT_IDX] = true; } if ((TIM5_SR & TIM_SR_UIF) != 0) { timer_clear_flag(TIM5, TIM_SR_UIF); @@ -300,12 +300,12 @@ void tim8_cc_isr(void) { if ((TIM8_SR & TIM8_CC_IF_PERIOD) != 0) { timer_clear_flag(TIM8, TIM8_CC_IF_PERIOD); pwm_input_period_tics[TIM8_PWM_INPUT_IDX] = TIM8_CCR_PERIOD; - pwm_input_period_valid[TIM8_PWM_INPUT_IDX] = TRUE; + pwm_input_period_valid[TIM8_PWM_INPUT_IDX] = true; } if ((TIM8_SR & TIM8_CC_IF_DUTY) != 0) { timer_clear_flag(TIM8, TIM8_CC_IF_DUTY); pwm_input_duty_tics[TIM8_PWM_INPUT_IDX] = TIM8_CCR_DUTY; - pwm_input_duty_valid[TIM8_PWM_INPUT_IDX] = TRUE; + pwm_input_duty_valid[TIM8_PWM_INPUT_IDX] = true; } } @@ -318,12 +318,12 @@ void tim1_brk_tim9_isr(void) { if ((TIM9_SR & TIM9_CC_IF_PERIOD) != 0) { timer_clear_flag(TIM9, TIM9_CC_IF_PERIOD); pwm_input_period_tics[TIM9_PWM_INPUT_IDX] = TIM9_CCR_PERIOD; - pwm_input_period_valid[TIM9_PWM_INPUT_IDX] = TRUE; + pwm_input_period_valid[TIM9_PWM_INPUT_IDX] = true; } if ((TIM9_SR & TIM9_CC_IF_DUTY) != 0) { timer_clear_flag(TIM9, TIM9_CC_IF_DUTY); pwm_input_duty_tics[TIM9_PWM_INPUT_IDX] = TIM9_CCR_DUTY; - pwm_input_duty_valid[TIM9_PWM_INPUT_IDX] = TRUE; + pwm_input_duty_valid[TIM9_PWM_INPUT_IDX] = true; } if ((TIM9_SR & TIM_SR_UIF) != 0) { timer_clear_flag(TIM9, TIM_SR_UIF); diff --git a/sw/airborne/arch/stm32/mcu_periph/spi_arch.c b/sw/airborne/arch/stm32/mcu_periph/spi_arch.c index e3bfa18d23..521a4e93da 100644 --- a/sw/airborne/arch/stm32/mcu_periph/spi_arch.c +++ b/sw/airborne/arch/stm32/mcu_periph/spi_arch.c @@ -267,7 +267,7 @@ bool spi_submit(struct spi_periph *p, struct spi_transaction *t) if (idx >= SPI_TRANSACTION_QUEUE_LEN) { idx = 0; } if ((idx == p->trans_extract_idx) || ((t->input_length == 0) && (t->output_length == 0))) { t->status = SPITransFailed; - return FALSE; /* queue full or input_length and output_length both 0 */ + return false; /* queue full or input_length and output_length both 0 */ // TODO can't tell why it failed here if it does } @@ -287,7 +287,7 @@ bool spi_submit(struct spi_periph *p, struct spi_transaction *t) } //FIXME spi_arch_int_enable(p); - return TRUE; + return true; } bool spi_lock(struct spi_periph *p, uint8_t slave) @@ -296,10 +296,10 @@ bool spi_lock(struct spi_periph *p, uint8_t slave) if (slave < 254 && p->suspend == 0) { p->suspend = slave + 1; // 0 is reserved for unlock state spi_arch_int_enable(p); - return TRUE; + return true; } spi_arch_int_enable(p); - return FALSE; + return false; } bool spi_resume(struct spi_periph *p, uint8_t slave) @@ -312,10 +312,10 @@ bool spi_resume(struct spi_periph *p, uint8_t slave) spi_start_dma_transaction(p, p->trans[p->trans_extract_idx]); } spi_arch_int_enable(p); - return TRUE; + return true; } spi_arch_int_enable(p); - return FALSE; + return false; } @@ -603,7 +603,7 @@ static void spi_start_dma_transaction(struct spi_periph *periph, struct spi_tran /* use dummy rx dma for the rest */ if (trans->output_length > trans->input_length) { /* Enable use of second dma transfer with dummy buffer (cleared in ISR) */ - dma->rx_extra_dummy_dma = TRUE; + dma->rx_extra_dummy_dma = true; } } #ifdef STM32F1 @@ -634,7 +634,7 @@ static void spi_start_dma_transaction(struct spi_periph *periph, struct spi_tran (uint32_t)trans->output_buf, trans->output_length, trans->dss, TRUE); if (trans->input_length > trans->output_length) { /* Enable use of second dma transfer with dummy buffer (cleared in ISR) */ - dma->tx_extra_dummy_dma = TRUE; + dma->tx_extra_dummy_dma = true; } } #ifdef STM32F1 @@ -696,9 +696,9 @@ void spi1_arch_init(void) spi1_dma.tx_nvic_irq = NVIC_DMA2_STREAM5_IRQ; #endif spi1_dma.tx_dummy_buf = 0; - spi1_dma.tx_extra_dummy_dma = FALSE; + spi1_dma.tx_extra_dummy_dma = false; spi1_dma.rx_dummy_buf = 0; - spi1_dma.rx_extra_dummy_dma = FALSE; + spi1_dma.rx_extra_dummy_dma = false; // set the default configuration set_default_comm_config(&spi1_dma.comm); @@ -784,9 +784,9 @@ void spi2_arch_init(void) spi2_dma.tx_nvic_irq = NVIC_DMA1_STREAM4_IRQ; #endif spi2_dma.tx_dummy_buf = 0; - spi2_dma.tx_extra_dummy_dma = FALSE; + spi2_dma.tx_extra_dummy_dma = false; spi2_dma.rx_dummy_buf = 0; - spi2_dma.rx_extra_dummy_dma = FALSE; + spi2_dma.rx_extra_dummy_dma = false; // set the default configuration set_default_comm_config(&spi2_dma.comm); @@ -873,9 +873,9 @@ void spi3_arch_init(void) spi3_dma.tx_nvic_irq = NVIC_DMA1_STREAM5_IRQ; #endif spi3_dma.tx_dummy_buf = 0; - spi3_dma.tx_extra_dummy_dma = FALSE; + spi3_dma.tx_extra_dummy_dma = false; spi3_dma.rx_dummy_buf = 0; - spi3_dma.rx_extra_dummy_dma = FALSE; + spi3_dma.rx_extra_dummy_dma = false; // set the default configuration set_default_comm_config(&spi3_dma.comm); @@ -1087,7 +1087,7 @@ void process_rx_dma_interrupt(struct spi_periph * periph) { */ /* Reset the flag so this only happens once in a transaction */ - dma->rx_extra_dummy_dma = FALSE; + dma->rx_extra_dummy_dma = false; /* Use the difference in length between rx and tx */ uint16_t len_remaining = trans->output_length - trans->input_length; @@ -1161,7 +1161,7 @@ void process_tx_dma_interrupt(struct spi_periph * periph) { */ /* Reset the flag so this only happens once in a transaction */ - dma->tx_extra_dummy_dma = FALSE; + dma->tx_extra_dummy_dma = false; /* Use the difference in length between tx and rx */ uint16_t len_remaining = trans->input_length - trans->output_length; @@ -1236,9 +1236,9 @@ void spi1_slave_arch_init(void) { spi1_dma.tx_nvic_irq = NVIC_DMA2_STREAM5_IRQ; #endif spi1_dma.tx_dummy_buf = 0; - spi1_dma.tx_extra_dummy_dma = FALSE; + spi1_dma.tx_extra_dummy_dma = false; spi1_dma.rx_dummy_buf = 0; - spi1_dma.rx_extra_dummy_dma = FALSE; + spi1_dma.rx_extra_dummy_dma = false; // set the default configuration set_default_comm_config(&spi1_dma.comm); @@ -1362,9 +1362,9 @@ void spi2_slave_arch_init(void) { spi2_dma.tx_nvic_irq = NVIC_DMA1_STREAM4_IRQ; #endif spi2_dma.tx_dummy_buf = 0; - spi2_dma.tx_extra_dummy_dma = FALSE; + spi2_dma.tx_extra_dummy_dma = false; spi2_dma.rx_dummy_buf = 0; - spi2_dma.rx_extra_dummy_dma = FALSE; + spi2_dma.rx_extra_dummy_dma = false; // set the default configuration set_default_comm_config(&spi2_dma.comm); @@ -1491,9 +1491,9 @@ void spi3_slave_arch_init(void) { spi3_dma.tx_nvic_irq = NVIC_DMA1_STREAM5_IRQ; #endif spi3_dma.tx_dummy_buf = 0; - spi3_dma.tx_extra_dummy_dma = FALSE; + spi3_dma.tx_extra_dummy_dma = false; spi3_dma.rx_dummy_buf = 0; - spi3_dma.rx_extra_dummy_dma = FALSE; + spi3_dma.rx_extra_dummy_dma = false; // set the default configuration set_default_comm_config(&spi3_dma.comm); @@ -1687,7 +1687,7 @@ bool spi_slave_register(struct spi_periph * periph, struct spi_transaction * tra /* enable dma interrupt */ spi_arch_int_enable(periph); - return TRUE; + return true; } void process_slave_rx_dma_interrupt(struct spi_periph * periph) { diff --git a/sw/airborne/arch/stm32/mcu_periph/sys_time_arch.c b/sw/airborne/arch/stm32/mcu_periph/sys_time_arch.c index 99dd072708..d57644e837 100644 --- a/sw/airborne/arch/stm32/mcu_periph/sys_time_arch.c +++ b/sw/airborne/arch/stm32/mcu_periph/sys_time_arch.c @@ -89,7 +89,7 @@ void sys_tick_handler(void) if (sys_time.timer[i].in_use && sys_time.nb_tick >= sys_time.timer[i].end_time) { sys_time.timer[i].end_time += sys_time.timer[i].duration; - sys_time.timer[i].elapsed = TRUE; + sys_time.timer[i].elapsed = true; if (sys_time.timer[i].cb) { sys_time.timer[i].cb(i); } diff --git a/sw/airborne/arch/stm32/mcu_periph/uart_arch.c b/sw/airborne/arch/stm32/mcu_periph/uart_arch.c index c09f5c5d17..8a17599095 100644 --- a/sw/airborne/arch/stm32/mcu_periph/uart_arch.c +++ b/sw/airborne/arch/stm32/mcu_periph/uart_arch.c @@ -125,7 +125,7 @@ void uart_put_byte(struct uart_periph *p, uint8_t data) p->tx_buf[p->tx_insert_idx] = data; p->tx_insert_idx = temp; } else { // no, set running flag and write to output register - p->tx_running = TRUE; + p->tx_running = true; usart_send((uint32_t)p->reg_addr, data); } @@ -144,7 +144,7 @@ static inline void usart_isr(struct uart_periph *p) p->tx_extract_idx++; p->tx_extract_idx %= UART_TX_BUFFER_SIZE; } else { - p->tx_running = FALSE; // clear running flag + p->tx_running = false; // clear running flag USART_CR1((uint32_t)p->reg_addr) &= ~USART_CR1_TXEIE; // Disable TX interrupt } } diff --git a/sw/airborne/arch/stm32/subsystems/imu/imu_aspirin_arch.c b/sw/airborne/arch/stm32/subsystems/imu/imu_aspirin_arch.c index 958a773a72..abaf9f902f 100644 --- a/sw/airborne/arch/stm32/subsystems/imu/imu_aspirin_arch.c +++ b/sw/airborne/arch/stm32/subsystems/imu/imu_aspirin_arch.c @@ -97,7 +97,7 @@ void exti15_10_isr(void) exti_reset_request(EXTI14); #ifdef ASPIRIN_USE_GYRO_INT - imu_aspirin.gyro_eoc = TRUE; + imu_aspirin.gyro_eoc = true; imu_aspirin.status = AspirinStatusReadingGyro; #endif diff --git a/sw/airborne/arch/stm32/subsystems/imu/imu_crista_arch.c b/sw/airborne/arch/stm32/subsystems/imu/imu_crista_arch.c index 9dca3e860a..486cb57fc9 100644 --- a/sw/airborne/arch/stm32/subsystems/imu/imu_crista_arch.c +++ b/sw/airborne/arch/stm32/subsystems/imu/imu_crista_arch.c @@ -160,7 +160,7 @@ void dma1_c4_irq_handler(void) ADS8344_values[channel] = (buf_in[1] << 8 | buf_in[2]) << 1 | buf_in[3] >> 7; channel++; if (channel > 6) { - ADS8344_available = TRUE; + ADS8344_available = true; ADS8344Unselect(); DMA_ITConfig(DMA1_Channel4, DMA_IT_TC, DISABLE); /* Disable SPI_2 Rx and TX request */ diff --git a/sw/airborne/arch/stm32/subsystems/imu/imu_krooz_sd_arch.c b/sw/airborne/arch/stm32/subsystems/imu/imu_krooz_sd_arch.c index 24659b0a3c..ad5c508669 100644 --- a/sw/airborne/arch/stm32/subsystems/imu/imu_krooz_sd_arch.c +++ b/sw/airborne/arch/stm32/subsystems/imu/imu_krooz_sd_arch.c @@ -30,10 +30,10 @@ void exti9_5_isr(void) /* clear EXTI */ if (EXTI_PR & EXTI6) { exti_reset_request(EXTI6); - imu_krooz.hmc_eoc = TRUE; + imu_krooz.hmc_eoc = true; } if (EXTI_PR & EXTI5) { exti_reset_request(EXTI5); - imu_krooz.mpu_eoc = TRUE; + imu_krooz.mpu_eoc = true; } } diff --git a/sw/airborne/arch/stm32/usb_ser_hw.c b/sw/airborne/arch/stm32/usb_ser_hw.c index 7c31ddf736..c2c30d2e76 100644 --- a/sw/airborne/arch/stm32/usb_ser_hw.c +++ b/sw/airborne/arch/stm32/usb_ser_hw.c @@ -291,7 +291,7 @@ static bool usb_connected; // use suspend callback to detect disconnect static void suspend_cb(void) { - usb_connected = FALSE; + usb_connected = false; } /** @@ -312,7 +312,7 @@ static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) cdcacm_control_request); // use config and suspend callback to detect connect - usb_connected = TRUE; + usb_connected = true; usbd_register_suspend_callback(usbd_dev, suspend_cb); } @@ -334,13 +334,13 @@ bool fifo_put(fifo_t *fifo, uint8_t c) next = (fifo->head + 1) % VCOM_FIFO_SIZE; if (next == fifo->tail) { // full - return FALSE; + return false; } fifo->buf[fifo->head] = c; fifo->head = next; - return TRUE; + return true; } @@ -350,7 +350,7 @@ bool fifo_get(fifo_t *fifo, uint8_t *pc) // check if FIFO has data if (fifo->head == fifo->tail) { - return FALSE; + return false; } next = (fifo->tail + 1) % VCOM_FIFO_SIZE; @@ -358,7 +358,7 @@ bool fifo_get(fifo_t *fifo, uint8_t *pc) *pc = fifo->buf[fifo->tail]; fifo->tail = next; - return TRUE; + return true; } @@ -552,7 +552,7 @@ void VCOM_init(void) usbd_register_set_config_callback(my_usbd_dev, cdcacm_set_config); // disconnected by default - usb_connected = FALSE; + usb_connected = false; // Configure generic device usb_serial.device.periph = (void *)(&usb_serial); diff --git a/sw/airborne/boards/apogee/baro_board.c b/sw/airborne/boards/apogee/baro_board.c index afd23116ab..4f751321f4 100644 --- a/sw/airborne/boards/apogee/baro_board.c +++ b/sw/airborne/boards/apogee/baro_board.c @@ -83,7 +83,7 @@ void baro_init(void) startup_cnt = BARO_STARTUP_COUNTER; #if APOGEE_BARO_SDLOG - log_apogee_baro_started = FALSE; + log_apogee_baro_started = false; #endif } @@ -97,7 +97,7 @@ void baro_periodic(void) if (startup_cnt > 0 && apogee_baro.data_available) { // Run some loops to get correct readings from the adc --startup_cnt; - apogee_baro.data_available = FALSE; + apogee_baro.data_available = false; #ifdef BARO_LED LED_TOGGLE(BARO_LED); if (startup_cnt == 0) { @@ -118,13 +118,13 @@ void apogee_baro_event(void) AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, pressure); float temp = apogee_baro.temperature / 16.0f; AbiSendMsgTEMPERATURE(BARO_BOARD_SENDER_ID, temp); - apogee_baro.data_available = FALSE; + apogee_baro.data_available = false; #if APOGEE_BARO_SDLOG if (pprzLogFile != -1) { if (!log_apogee_baro_started) { sdLogWriteLog(pprzLogFile, "APOGEE_BARO: Pres(Pa) Temp(degC) GPS_fix TOW(ms) Week Lat(1e7deg) Lon(1e7deg) HMSL(mm) gpseed(cm/s) course(1e7deg) climb(cm/s)\n"); - log_apogee_baro_started = TRUE; + log_apogee_baro_started = true; } sdLogWriteLog(pprzLogFile, "apogee_baro: %9.4f %9.4f %d %d %d %d %d %d %d %d %d\n", pressure,temp, diff --git a/sw/airborne/boards/apogee/chibios-libopencm3/board.c b/sw/airborne/boards/apogee/chibios-libopencm3/board.c index e05c47d014..f202fbf86b 100644 --- a/sw/airborne/boards/apogee/chibios-libopencm3/board.c +++ b/sw/airborne/boards/apogee/chibios-libopencm3/board.c @@ -66,7 +66,7 @@ void __early_init(void) { */ bool sdc_lld_is_write_protected(SDCDriver *sdcp) { (void)sdcp; - return FALSE; + return false; } /** @@ -90,7 +90,7 @@ bool mmc_lld_is_card_inserted(MMCDriver *mmcp) { (void)mmcp; /* TODO: Fill the implementation.*/ - return TRUE; + return true; } /** @@ -100,7 +100,7 @@ bool mmc_lld_is_write_protected(MMCDriver *mmcp) { (void)mmcp; /* TODO: Fill the implementation.*/ - return FALSE; + return false; } #endif diff --git a/sw/airborne/boards/apogee/imu_apogee.c b/sw/airborne/boards/apogee/imu_apogee.c index d48560658c..8ca65bac7e 100644 --- a/sw/airborne/boards/apogee/imu_apogee.c +++ b/sw/airborne/boards/apogee/imu_apogee.c @@ -84,7 +84,7 @@ PRINT_CONFIG_VAR(MAG_PRESCALER) bool configure_mag_slave(Mpu60x0ConfigSet mpu_set, void *mpu); bool configure_mag_slave(Mpu60x0ConfigSet mpu_set __attribute__((unused)), void *mpu __attribute__((unused))) { - return TRUE; + return true; } #endif @@ -95,7 +95,7 @@ struct ImuApogee imu_apogee; bool configure_baro_slave(Mpu60x0ConfigSet mpu_set, void *mpu); bool configure_baro_slave(Mpu60x0ConfigSet mpu_set __attribute__((unused)), void *mpu __attribute__((unused))) { - return TRUE; + return true; } void imu_impl_init(void) @@ -111,7 +111,7 @@ void imu_impl_init(void) // set MPU in bypass mode for the baro imu_apogee.mpu.config.nb_slaves = 1; imu_apogee.mpu.config.slaves[0].configure = &configure_baro_slave; - imu_apogee.mpu.config.i2c_bypass = TRUE; + imu_apogee.mpu.config.i2c_bypass = true; #if APOGEE_USE_MPU9150 // if using MPU9150, internal mag needs to be configured ak8975_init(&imu_apogee.ak, &(IMU_APOGEE_I2C_DEV), AK8975_I2C_SLV_ADDR); @@ -161,7 +161,7 @@ void imu_apogee_event(void) (int32_t)(-imu_apogee.mpu.data_accel.value[IMU_APOGEE_CHAN_Z]) }; VECT3_COPY(imu.accel_unscaled, accel); - imu_apogee.mpu.data_available = FALSE; + imu_apogee.mpu.data_available = false; imu_scale_gyro(&imu); imu_scale_accel(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_BOARD_ID, now_ts, &imu.gyro); @@ -177,7 +177,7 @@ void imu_apogee_event(void) (int32_t)( imu_apogee.ak.data.value[IMU_APOGEE_CHAN_Z]) }; VECT3_COPY(imu.mag_unscaled, mag); - imu_apogee.ak.data_available = FALSE; + imu_apogee.ak.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_BOARD_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/boards/ardrone/actuators.c b/sw/airborne/boards/ardrone/actuators.c index b3f7e2386c..98e6bcd0ee 100644 --- a/sw/airborne/boards/ardrone/actuators.c +++ b/sw/airborne/boards/ardrone/actuators.c @@ -169,7 +169,7 @@ int actuators_ardrone_cmd(uint8_t cmd, uint8_t *reply, int replylen) void actuators_ardrone_motor_status(void); void actuators_ardrone_motor_status(void) { - static bool last_motor_on = FALSE; + static bool last_motor_on = false; // Reset Flipflop sequence static bool reset_flipflop_counter = 0; diff --git a/sw/airborne/boards/ardrone/baro_board.c b/sw/airborne/boards/ardrone/baro_board.c index 876e3a33bb..208c6f4404 100644 --- a/sw/airborne/boards/ardrone/baro_board.c +++ b/sw/airborne/boards/ardrone/baro_board.c @@ -103,6 +103,6 @@ void ardrone_baro_event(void) float pressure = (float)press_pascal; AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, pressure); } - navdata.baro_available = FALSE; + navdata.baro_available = false; } } diff --git a/sw/airborne/boards/ardrone/navdata.c b/sw/airborne/boards/ardrone/navdata.c index 1031f9b08c..0f6eeadee2 100644 --- a/sw/airborne/boards/ardrone/navdata.c +++ b/sw/airborne/boards/ardrone/navdata.c @@ -61,7 +61,7 @@ struct navdata_t navdata; /** Buffer filled in the thread (maximum one navdata packet) */ static uint8_t navdata_buffer[NAVDATA_PACKET_SIZE]; /** flag to indicate new packet is available in buffer */ -static bool navdata_available = FALSE; +static bool navdata_available = false; /* syncronization variables */ static pthread_mutex_t navdata_mutex = PTHREAD_MUTEX_INITIALIZER; @@ -178,7 +178,7 @@ bool navdata_init() if (navdata.fd < 0) { printf("[navdata] Unable to open navdata board connection(/dev/ttyO1)\n"); - return FALSE; + return false; } /* Update the settings of the UART connection */ @@ -201,10 +201,10 @@ bool navdata_init() } // Reset available flags - navdata_available = FALSE; - navdata.baro_calibrated = FALSE; - navdata.baro_available = FALSE; - navdata.imu_lost = FALSE; + navdata_available = false; + navdata.baro_calibrated = false; + navdata.baro_available = false; + navdata.imu_lost = false; // Set all statistics to 0 navdata.checksum_errors = 0; @@ -219,9 +219,9 @@ bool navdata_init() /* Read the baro calibration(blocking) */ if (!navdata_baro_calib()) { printf("[navdata] Could not acquire baro calibration!\n"); - return FALSE; + return false; } - navdata.baro_calibrated = TRUE; + navdata.baro_calibrated = true; /* Start acquisition */ navdata_cmd_send(NAVDATA_CMD_START); @@ -234,7 +234,7 @@ bool navdata_init() pthread_t navdata_thread; if (pthread_create(&navdata_thread, NULL, navdata_read, NULL) != 0) { printf("[navdata] Could not create navdata reading thread!\n"); - return FALSE; + return false; } #if PERIODIC_TELEMETRY @@ -242,8 +242,8 @@ bool navdata_init() #endif /* Set to initialized */ - navdata.is_initialized = TRUE; - return TRUE; + navdata.is_initialized = true; + return true; } @@ -313,7 +313,7 @@ static void *navdata_read(void *data __attribute__((unused))) /* Set flag that we have new valid navdata */ pthread_mutex_lock(&navdata_mutex); - navdata_available = TRUE; + navdata_available = true; pthread_mutex_unlock(&navdata_mutex); } } @@ -356,7 +356,7 @@ void navdata_update() memcpy(&navdata.measure, navdata_buffer, NAVDATA_PACKET_SIZE); /* reset the flag */ - navdata_available = FALSE; + navdata_available = false; /* signal that we copied the buffer and new packet can be read */ pthread_cond_signal(&navdata_cond); pthread_mutex_unlock(&navdata_mutex); @@ -422,7 +422,7 @@ static bool navdata_baro_calib(void) uint8_t calibBuffer[22]; if (full_read(navdata.fd, calibBuffer, sizeof calibBuffer) < 0) { printf("[navdata] Could not read calibration data."); - return FALSE; + return false; } /* Convert the read bytes */ @@ -438,7 +438,7 @@ static bool navdata_baro_calib(void) navdata.bmp180_calib.mc = calibBuffer[18] << 8 | calibBuffer[19]; navdata.bmp180_calib.md = calibBuffer[20] << 8 | calibBuffer[21]; - return TRUE; + return true; } /** @@ -459,7 +459,7 @@ static void mag_freeze_check(void) fprintf(stderr, "mag freeze detected, resetting!\n"); /* set imu_lost flag */ - navdata.imu_lost = TRUE; + navdata.imu_lost = true; navdata.lost_imu_frames++; /* Stop acquisition */ @@ -478,7 +478,7 @@ static void mag_freeze_check(void) MagFreezeCounter = 0; /* reset counter back to zero */ } } else { - navdata.imu_lost = FALSE; + navdata.imu_lost = false; /* Reset counter if value _does_ change */ MagFreezeCounter = 0; } @@ -505,34 +505,34 @@ static void baro_update_logic(void) if (temp_or_press_was_updated_last == 0) { /* Last update was press so we are now waiting for temp */ /* temp was updated */ - temp_or_press_was_updated_last = TRUE; + temp_or_press_was_updated_last = true; /* This means that press must remain constant */ if (lastpressval != 0) { /* If pressure was updated: this is a sync error */ if (lastpressval != navdata.measure.pressure) { /* wait for temp again */ - temp_or_press_was_updated_last = FALSE; + temp_or_press_was_updated_last = false; sync_errors++; //printf("Baro-Logic-Error (expected updated temp, got press)\n"); } } } else { /* press was updated */ - temp_or_press_was_updated_last = FALSE; + temp_or_press_was_updated_last = false; /* This means that temp must remain constant */ if (lasttempval != 0) { /* If temp was updated: this is a sync error */ if (lasttempval != navdata.measure.temperature_pressure) { /* wait for press again */ - temp_or_press_was_updated_last = TRUE; + temp_or_press_was_updated_last = true; sync_errors++; //printf("Baro-Logic-Error (expected updated press, got temp)\n"); } else { /* We now got valid pressure and temperature */ - navdata.baro_available = TRUE; + navdata.baro_available = true; } } } @@ -540,13 +540,13 @@ static void baro_update_logic(void) /* Detected a pressure swap */ if (lastpressval != 0 && lasttempval != 0 && ABS(lastpressval - navdata.measure.pressure) > ABS(lasttempval - navdata.measure.pressure)) { - navdata.baro_available = FALSE; + navdata.baro_available = false; } /* Detected a temprature swap */ if (lastpressval != 0 && lasttempval != 0 && ABS(lasttempval - navdata.measure.temperature_pressure) > ABS(lastpressval - navdata.measure.temperature_pressure)) { - navdata.baro_available = FALSE; + navdata.baro_available = false; } lasttempval = navdata.measure.temperature_pressure; @@ -600,7 +600,7 @@ static void baro_update_logic(void) if (spike_detected > 0) { /* disable kalman filter use */ - navdata.baro_available = FALSE; + navdata.baro_available = false; // override both to last good navdata.measure.pressure = lastpressval_nospike; diff --git a/sw/airborne/boards/baro_board_ms5611_i2c.c b/sw/airborne/boards/baro_board_ms5611_i2c.c index b7d2225483..df62004f81 100644 --- a/sw/airborne/boards/baro_board_ms5611_i2c.c +++ b/sw/airborne/boards/baro_board_ms5611_i2c.c @@ -106,7 +106,7 @@ void baro_event(void) AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, pressure); float temp = bb_ms5611.data.temperature / 100.0f; AbiSendMsgTEMPERATURE(BARO_BOARD_SENDER_ID, temp); - bb_ms5611.data_available = FALSE; + bb_ms5611.data_available = false; #ifdef BARO_LED RunOnceEvery(10, LED_TOGGLE(BARO_LED)); diff --git a/sw/airborne/boards/baro_board_ms5611_spi.c b/sw/airborne/boards/baro_board_ms5611_spi.c index c0486c8946..a28eb8aa40 100644 --- a/sw/airborne/boards/baro_board_ms5611_spi.c +++ b/sw/airborne/boards/baro_board_ms5611_spi.c @@ -94,7 +94,7 @@ void baro_event(void) AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, pressure); float temp = bb_ms5611.data.temperature / 100.0f; AbiSendMsgTEMPERATURE(BARO_BOARD_SENDER_ID, temp); - bb_ms5611.data_available = FALSE; + bb_ms5611.data_available = false; #ifdef BARO_LED RunOnceEvery(10, LED_TOGGLE(BARO_LED)); diff --git a/sw/airborne/boards/bebop/video.c b/sw/airborne/boards/bebop/video.c index 0262c287a8..04d8f19f15 100644 --- a/sw/airborne/boards/bebop/video.c +++ b/sw/airborne/boards/bebop/video.c @@ -66,11 +66,11 @@ static bool write_reg(int fd, char *addr_val, uint8_t cnt) if (write(fd, addr_val, cnt) != cnt) { printf("Write failed!\n"); - return FALSE; + return false; } if (write(fd, addr_val, 2) != 2) { printf("Write2 failed!\n"); - return FALSE; + return false; } while (read(fd, resp, cnt - 2) != cnt - 2) { ; } for (i = 0; i < cnt - 2; i++) { @@ -79,7 +79,7 @@ static bool write_reg(int fd, char *addr_val, uint8_t cnt) return write_reg(fd, addr_val, cnt); } } - return TRUE; + return true; } static bool _write(int fd, char *data, uint8_t cnt) @@ -87,7 +87,7 @@ static bool _write(int fd, char *data, uint8_t cnt) if (write(fd, data, cnt) != cnt) { printf("Failed!\n"); } - return TRUE; + return true; } #pragma GCC diagnostic push diff --git a/sw/airborne/boards/hbmini/baro_board.c b/sw/airborne/boards/hbmini/baro_board.c index 8ab4c42be8..b959dc099d 100644 --- a/sw/airborne/boards/hbmini/baro_board.c +++ b/sw/airborne/boards/hbmini/baro_board.c @@ -58,7 +58,7 @@ void bmp_baro_event(void) if (baro_bmp085.data_available) { float pressure = (float)baro_bmp085.pressure; AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, pressure); - baro_bmp085.data_available = FALSE; + baro_bmp085.data_available = false; #ifdef BARO_LED RunOnceEvery(10, LED_TOGGLE(BARO_LED)); #endif diff --git a/sw/airborne/boards/hbmini/imu_hbmini.c b/sw/airborne/boards/hbmini/imu_hbmini.c index e2886d29d8..5bab935a47 100644 --- a/sw/airborne/boards/hbmini/imu_hbmini.c +++ b/sw/airborne/boards/hbmini/imu_hbmini.c @@ -117,7 +117,7 @@ void imu_hbmini_event(void) imu.mag_unscaled.y = imu_hbmini.hmc.data.value[IMU_MAG_Y_CHAN]; imu.mag_unscaled.x = imu_hbmini.hmc.data.value[IMU_MAG_Z_CHAN]; - imu_hbmini.hmc.data_available = FALSE; + imu_hbmini.hmc.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_BOARD_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/boards/krooz/imu_krooz.c b/sw/airborne/boards/krooz/imu_krooz.c index ff4a49f48e..6cf66c3465 100644 --- a/sw/airborne/boards/krooz/imu_krooz.c +++ b/sw/airborne/boards/krooz/imu_krooz.c @@ -75,7 +75,7 @@ void imu_impl_init(void) imu_krooz.mpu.config.dlpf_cfg = KROOZ_LOWPASS_FILTER; imu_krooz.mpu.config.gyro_range = KROOZ_GYRO_RANGE; imu_krooz.mpu.config.accel_range = KROOZ_ACCEL_RANGE; - imu_krooz.mpu.config.drdy_int_enable = TRUE; + imu_krooz.mpu.config.drdy_int_enable = true; hmc58xx_init(&imu_krooz.hmc, &(IMU_KROOZ_I2C_DEV), HMC58XX_ADDR); @@ -89,8 +89,8 @@ void imu_impl_init(void) VECT3_ASSIGN(imu_krooz.accel_sum, 0, 0, 0); imu_krooz.meas_nb = 0; - imu_krooz.hmc_eoc = FALSE; - imu_krooz.mpu_eoc = FALSE; + imu_krooz.hmc_eoc = false; + imu_krooz.mpu_eoc = false; imu_krooz_sd_arch_init(); } @@ -147,7 +147,7 @@ void imu_krooz_event(void) { if (imu_krooz.mpu_eoc) { mpu60x0_i2c_read(&imu_krooz.mpu); - imu_krooz.mpu_eoc = FALSE; + imu_krooz.mpu_eoc = false; } // If the MPU6050 I2C transaction has succeeded: convert the data @@ -156,12 +156,12 @@ void imu_krooz_event(void) RATES_ADD(imu_krooz.rates_sum, imu_krooz.mpu.data_rates.rates); VECT3_ADD(imu_krooz.accel_sum, imu_krooz.mpu.data_accel.vect); imu_krooz.meas_nb++; - imu_krooz.mpu.data_available = FALSE; + imu_krooz.mpu.data_available = false; } if (imu_krooz.hmc_eoc) { hmc58xx_read(&imu_krooz.hmc); - imu_krooz.hmc_eoc = FALSE; + imu_krooz.hmc_eoc = false; } // If the HMC5883 I2C transaction has succeeded: convert the data @@ -169,7 +169,7 @@ void imu_krooz_event(void) if (imu_krooz.hmc.data_available) { VECT3_ASSIGN(imu.mag_unscaled, imu_krooz.hmc.data.vect.y, -imu_krooz.hmc.data.vect.x, imu_krooz.hmc.data.vect.z); UpdateMedianFilterVect3Int(median_mag, imu.mag_unscaled); - imu_krooz.hmc.data_available = FALSE; + imu_krooz.hmc.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_BOARD_ID, get_sys_time_usec(), &imu.mag); } diff --git a/sw/airborne/boards/krooz/imu_krooz_memsic.c b/sw/airborne/boards/krooz/imu_krooz_memsic.c index 40c6f898a8..d143e28b99 100644 --- a/sw/airborne/boards/krooz/imu_krooz_memsic.c +++ b/sw/airborne/boards/krooz/imu_krooz_memsic.c @@ -76,7 +76,7 @@ void imu_impl_init(void) imu_krooz.mpu.config.dlpf_cfg = KROOZ_LOWPASS_FILTER; imu_krooz.mpu.config.gyro_range = KROOZ_GYRO_RANGE; imu_krooz.mpu.config.accel_range = KROOZ_ACCEL_RANGE; - imu_krooz.mpu.config.drdy_int_enable = TRUE; + imu_krooz.mpu.config.drdy_int_enable = true; hmc58xx_init(&imu_krooz.hmc, &(IMU_KROOZ_I2C_DEV), HMC58XX_ADDR); @@ -90,8 +90,8 @@ void imu_impl_init(void) VECT3_ASSIGN(imu_krooz.accel_sum, 0, 0, 0); imu_krooz.meas_nb = 0; - imu_krooz.hmc_eoc = FALSE; - imu_krooz.mpu_eoc = FALSE; + imu_krooz.hmc_eoc = false; + imu_krooz.mpu_eoc = false; imu_krooz.ad7689_trans.slave_idx = IMU_KROOZ_SPI_SLAVE_IDX; imu_krooz.ad7689_trans.select = SPISelectUnselect; @@ -162,7 +162,7 @@ void imu_krooz_event(void) { if (imu_krooz.mpu_eoc) { mpu60x0_i2c_read(&imu_krooz.mpu); - imu_krooz.mpu_eoc = FALSE; + imu_krooz.mpu_eoc = false; } // If the MPU6050 I2C transaction has succeeded: convert the data @@ -170,7 +170,7 @@ void imu_krooz_event(void) if (imu_krooz.mpu.data_available) { RATES_ADD(imu_krooz.rates_sum, imu_krooz.mpu.data_rates.rates); imu_krooz.meas_nb++; - imu_krooz.mpu.data_available = FALSE; + imu_krooz.mpu.data_available = false; } if (SysTimeTimer(ad7689_event_timer) > 215) { @@ -216,7 +216,7 @@ void imu_krooz_event(void) if (imu_krooz.hmc_eoc) { hmc58xx_read(&imu_krooz.hmc); - imu_krooz.hmc_eoc = FALSE; + imu_krooz.hmc_eoc = false; } // If the HMC5883 I2C transaction has succeeded: convert the data @@ -224,7 +224,7 @@ void imu_krooz_event(void) if (imu_krooz.hmc.data_available) { VECT3_ASSIGN(imu.mag_unscaled, imu_krooz.hmc.data.vect.y, -imu_krooz.hmc.data.vect.x, imu_krooz.hmc.data.vect.z); UpdateMedianFilterVect3Int(median_mag, imu.mag_unscaled); - imu_krooz.hmc.data_available = FALSE; + imu_krooz.hmc.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_BOARD_ID, get_sys_time_usec(), &imu.mag); } diff --git a/sw/airborne/boards/lisa_l/baro_board.c b/sw/airborne/boards/lisa_l/baro_board.c index 57663ceb85..2c44511285 100644 --- a/sw/airborne/boards/lisa_l/baro_board.c +++ b/sw/airborne/boards/lisa_l/baro_board.c @@ -77,7 +77,7 @@ void baro_init(void) LED_OFF(BARO_LED); #endif baro_board.status = LBS_UNINITIALIZED; - baro_board.running = FALSE; + baro_board.running = false; } @@ -109,7 +109,7 @@ void baro_periodic(void) // baro_board.status = LBS_UNINITIALIZED; break; case LBS_INITIALIZING_DIFF_1: - baro_board.running = TRUE; + baro_board.running = true; case LBS_READ_DIFF: baro_board_read_from_current_register(BARO_ABS_ADDR); baro_board.status = LBS_READING_ABS; diff --git a/sw/airborne/boards/lisa_m/baro_board.c b/sw/airborne/boards/lisa_m/baro_board.c index cb34bd2a4f..daf96d61df 100644 --- a/sw/airborne/boards/lisa_m/baro_board.c +++ b/sw/airborne/boards/lisa_m/baro_board.c @@ -78,7 +78,7 @@ void baro_event(void) AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, pressure); float temp = baro_bmp085.temperature / 10.0f; AbiSendMsgTEMPERATURE(BARO_BOARD_SENDER_ID, temp); - baro_bmp085.data_available = FALSE; + baro_bmp085.data_available = false; #ifdef BARO_LED RunOnceEvery(10, LED_TOGGLE(BARO_LED)); #endif diff --git a/sw/airborne/boards/lisa_mx/baro_board.c b/sw/airborne/boards/lisa_mx/baro_board.c index 9f2711f9f7..6bcfc273e0 100644 --- a/sw/airborne/boards/lisa_mx/baro_board.c +++ b/sw/airborne/boards/lisa_mx/baro_board.c @@ -77,7 +77,7 @@ void baro_event(void) AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, pressure); float temp = baro_bmp085.temperature / 10.0f; AbiSendMsgTEMPERATURE(BARO_BOARD_SENDER_ID, temp); - baro_bmp085.data_available = FALSE; + baro_bmp085.data_available = false; #ifdef BARO_LED RunOnceEvery(10, LED_TOGGLE(BARO_LED)); #endif diff --git a/sw/airborne/boards/navgo/baro_board.c b/sw/airborne/boards/navgo/baro_board.c index a9ff7e5290..8ee32b366e 100644 --- a/sw/airborne/boards/navgo/baro_board.c +++ b/sw/airborne/boards/navgo/baro_board.c @@ -88,6 +88,6 @@ void navgo_baro_event(void) float pressure = NAVGO_BARO_SENS * (mcp355x_data + NAVGO_BARO_OFFSET); AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, pressure); } - mcp355x_data_available = FALSE; + mcp355x_data_available = false; } } diff --git a/sw/airborne/boards/navgo/imu_navgo.c b/sw/airborne/boards/navgo/imu_navgo.c index c516703b0f..4fff970763 100644 --- a/sw/airborne/boards/navgo/imu_navgo.c +++ b/sw/airborne/boards/navgo/imu_navgo.c @@ -128,7 +128,7 @@ void imu_navgo_event(void) #if NAVGO_USE_MEDIAN_FILTER UpdateMedianFilterRatesInt(median_gyro, imu.gyro_unscaled); #endif - imu_navgo.itg.data_available = FALSE; + imu_navgo.itg.data_available = false; imu_scale_gyro(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_BOARD_ID, now_ts, &imu.gyro); } @@ -140,7 +140,7 @@ void imu_navgo_event(void) #if NAVGO_USE_MEDIAN_FILTER UpdateMedianFilterVect3Int(median_accel, imu.accel_unscaled); #endif - imu_navgo.adxl.data_available = FALSE; + imu_navgo.adxl.data_available = false; imu_scale_accel(&imu); AbiSendMsgIMU_ACCEL_INT32(IMU_BOARD_ID, now_ts, &imu.accel); } @@ -152,7 +152,7 @@ void imu_navgo_event(void) #if NAVGO_USE_MEDIAN_FILTER UpdateMedianFilterVect3Int(median_mag, imu.mag_unscaled); #endif - imu_navgo.hmc.data_available = FALSE; + imu_navgo.hmc.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_BOARD_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/boards/navstik/baro_board.c b/sw/airborne/boards/navstik/baro_board.c index 3dd191e13f..2c74862e82 100644 --- a/sw/airborne/boards/navstik/baro_board.c +++ b/sw/airborne/boards/navstik/baro_board.c @@ -63,7 +63,7 @@ void baro_event(void) AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, pressure); float temp = baro_bmp085.temperature / 10.0f; AbiSendMsgTEMPERATURE(BARO_BOARD_SENDER_ID, temp); - baro_bmp085.data_available = FALSE; + baro_bmp085.data_available = false; #ifdef BARO_LED RunOnceEvery(10, LED_TOGGLE(BARO_LED)); #endif diff --git a/sw/airborne/boards/umarim/baro_board.c b/sw/airborne/boards/umarim/baro_board.c index 613f52ed37..d865b40da8 100644 --- a/sw/airborne/boards/umarim/baro_board.c +++ b/sw/airborne/boards/umarim/baro_board.c @@ -80,7 +80,7 @@ void umarim_baro_event(void) float pressure = UMARIM_BARO_SENS * Ads1114GetValue(BARO_ABS_ADS); AbiSendMsgBARO_ABS(BARO_BOARD_SENDER_ID, pressure); } - BARO_ABS_ADS.data_available = FALSE; + BARO_ABS_ADS.data_available = false; } } diff --git a/sw/airborne/boards/umarim/imu_umarim.c b/sw/airborne/boards/umarim/imu_umarim.c index 5006a02d7b..8876b17a5e 100644 --- a/sw/airborne/boards/umarim/imu_umarim.c +++ b/sw/airborne/boards/umarim/imu_umarim.c @@ -108,7 +108,7 @@ void imu_umarim_event(void) itg3200_event(&imu_umarim.itg); if (imu_umarim.itg.data_available) { RATES_COPY(imu.gyro_unscaled, imu_umarim.itg.data.rates); - imu_umarim.itg.data_available = FALSE; + imu_umarim.itg.data_available = false; imu_scale_gyro(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_BOARD_ID, now_ts, &imu.gyro); } @@ -118,7 +118,7 @@ void imu_umarim_event(void) if (imu_umarim.adxl.data_available) { VECT3_ASSIGN(imu.accel_unscaled, imu_umarim.adxl.data.vect.y, -imu_umarim.adxl.data.vect.x, imu_umarim.adxl.data.vect.z); - imu_umarim.adxl.data_available = FALSE; + imu_umarim.adxl.data_available = false; imu_scale_accel(&imu); AbiSendMsgIMU_ACCEL_INT32(IMU_BOARD_ID, now_ts, &imu.accel); } diff --git a/sw/airborne/firmwares/fixedwing/autopilot.c b/sw/airborne/firmwares/fixedwing/autopilot.c index 6d8cc899ee..e499c99b81 100644 --- a/sw/airborne/firmwares/fixedwing/autopilot.c +++ b/sw/airborne/firmwares/fixedwing/autopilot.c @@ -175,15 +175,15 @@ void autopilot_send_mode(void) void autopilot_init(void) { pprz_mode = PPRZ_MODE_AUTO2; - kill_throttle = FALSE; - launch = FALSE; + kill_throttle = false; + launch = false; autopilot_flight_time = 0; lateral_mode = LATERAL_MODE_MANUAL; - gps_lost = FALSE; + gps_lost = false; - power_switch = FALSE; + power_switch = false; #ifdef POWER_SWITCH_GPIO gpio_setup_output(POWER_SWITCH_GPIO); gpio_clear(POWER_SWITCH_GPIO); diff --git a/sw/airborne/firmwares/fixedwing/autopilot.h b/sw/airborne/firmwares/fixedwing/autopilot.h index 9e2d754fae..2a7aa3d2eb 100644 --- a/sw/airborne/firmwares/fixedwing/autopilot.h +++ b/sw/airborne/firmwares/fixedwing/autopilot.h @@ -66,7 +66,7 @@ extern uint8_t mcu1_status; extern uint16_t autopilot_flight_time; #define autopilot_ResetFlightTimeAndLaunch(_) { \ - autopilot_flight_time = 0; launch = FALSE; \ + autopilot_flight_time = 0; launch = false; \ } diff --git a/sw/airborne/firmwares/fixedwing/chibios-libopencm3/chibios_init.c b/sw/airborne/firmwares/fixedwing/chibios-libopencm3/chibios_init.c index 4eb1f83c28..09b2de413f 100644 --- a/sw/airborne/firmwares/fixedwing/chibios-libopencm3/chibios_init.c +++ b/sw/airborne/firmwares/fixedwing/chibios-libopencm3/chibios_init.c @@ -56,7 +56,7 @@ Thread *pprzThdPtr = NULL; static WORKING_AREA(wa_thd_heartbeat, 2048); void chibios_launch_heartbeat (void); -bool sdOk = FALSE; +bool sdOk = false; diff --git a/sw/airborne/firmwares/fixedwing/fixedwing_datalink.c b/sw/airborne/firmwares/fixedwing/fixedwing_datalink.c index faaa516f01..01748bcb74 100644 --- a/sw/airborne/firmwares/fixedwing/fixedwing_datalink.c +++ b/sw/airborne/firmwares/fixedwing/fixedwing_datalink.c @@ -136,7 +136,7 @@ void firmware_parse_msg(void) uint8_t l = DL_HITL_UBX_ubx_payload_length(dl_buffer); uint8_t *ubx_payload = DL_HITL_UBX_ubx_payload(dl_buffer); memcpy(ubx_msg_buf, ubx_payload, l); - gps_msg_received = TRUE; + gps_msg_received = true; } } break; diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index 2f8dfecd00..5bbbb64369 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -347,13 +347,13 @@ static inline uint8_t pprz_mode_update(void) } #endif // RADIO_AUTO_MODE } else { - return FALSE; + return false; } } #else // not RADIO_CONTROL static inline uint8_t pprz_mode_update(void) { - return FALSE; + return false; } #endif @@ -365,7 +365,7 @@ static inline uint8_t mcu1_status_update(void) mcu1_status = new_status; return changed; } - return FALSE; + return false; } @@ -390,7 +390,7 @@ static inline void copy_from_to_fbw(void) */ static inline void telecommand_task(void) { - uint8_t mode_changed = FALSE; + uint8_t mode_changed = false; copy_from_to_fbw(); /* really_lost is true if we lost RC in MANUAL or AUTO1 */ @@ -400,11 +400,11 @@ static inline void telecommand_task(void) if (pprz_mode != PPRZ_MODE_HOME && pprz_mode != PPRZ_MODE_GPS_OUT_OF_ORDER && launch) { if (too_far_from_home) { pprz_mode = PPRZ_MODE_HOME; - mode_changed = TRUE; + mode_changed = true; } if (really_lost) { pprz_mode = RC_LOST_MODE; - mode_changed = TRUE; + mode_changed = true; } } if (bit_is_set(fbw_state->status, AVERAGED_CHANNELS_SENT)) { @@ -455,7 +455,7 @@ static inline void telecommand_task(void) #ifndef SITL if (!autopilot_flight_time) { if (pprz_mode == PPRZ_MODE_AUTO2 && fbw_state->channels[RADIO_THROTTLE] > THROTTLE_THRESHOLD_TAKEOFF) { - launch = TRUE; + launch = true; } } #endif @@ -471,14 +471,14 @@ static inline void telecommand_task(void) */ void reporting_task(void) { - static uint8_t boot = TRUE; + static uint8_t boot = true; /* initialisation phase during boot */ if (boot) { #if DOWNLINK send_autopilot_version(&(DefaultChannel).trans_tx, &(DefaultDevice).device); #endif - boot = FALSE; + boot = false; } /* then report periodicly */ else { @@ -511,12 +511,12 @@ void navigation_task(void) last_pprz_mode = pprz_mode; pprz_mode = PPRZ_MODE_GPS_OUT_OF_ORDER; autopilot_send_mode(); - gps_lost = TRUE; + gps_lost = true; } } else if (gps_lost) { /* GPS is ok */ /** If aircraft was in failsafe mode, come back in previous mode */ pprz_mode = last_pprz_mode; - gps_lost = FALSE; + gps_lost = false; autopilot_send_mode(); } } @@ -550,7 +550,7 @@ void navigation_task(void) || pprz_mode == PPRZ_MODE_GPS_OUT_OF_ORDER) { #ifdef H_CTL_RATE_LOOP /* Be sure to be in attitude mode, not roll */ - h_ctl_auto1_rate = FALSE; + h_ctl_auto1_rate = false; #endif if (lateral_mode >= LATERAL_MODE_COURSE) { h_ctl_course_loop(); /* aka compute nav_desired_roll */ @@ -607,7 +607,7 @@ void attitude_loop(void) link_mcu_send(); #elif defined INTER_MCU && defined SINGLE_MCU /**Directly set the flag indicating to FBW that shared buffer is available*/ - inter_mcu_received_ap = TRUE; + inter_mcu_received_ap = true; #endif } @@ -677,7 +677,7 @@ void monitor_task(void) if (!autopilot_flight_time && stateGetHorizontalSpeedNorm_f() > MIN_SPEED_FOR_TAKEOFF) { autopilot_flight_time = 1; - launch = TRUE; /* Not set in non auto launch */ + launch = true; /* Not set in non auto launch */ #if DOWNLINK uint16_t time_sec = sys_time.nb_sec; DOWNLINK_SEND_TAKEOFF(DefaultChannel, DefaultDevice, &time_sec); @@ -723,7 +723,7 @@ void event_task_ap(void) if (inter_mcu_received_fbw) { /* receive radio control task from fbw */ - inter_mcu_received_fbw = FALSE; + inter_mcu_received_fbw = false; telecommand_task(); } diff --git a/sw/airborne/firmwares/fixedwing/main_chibios_libopencm3.c b/sw/airborne/firmwares/fixedwing/main_chibios_libopencm3.c index d9880d852c..01ee2fe249 100644 --- a/sw/airborne/firmwares/fixedwing/main_chibios_libopencm3.c +++ b/sw/airborne/firmwares/fixedwing/main_chibios_libopencm3.c @@ -48,7 +48,7 @@ static int32_t pprz_thd(void *arg); static bool sdlogOk ; -bool pprzReady = FALSE; +bool pprzReady = false; int main(void) { @@ -65,7 +65,7 @@ int main(void) chibios_chThdSleepMilliseconds(100); launch_pprz_thd(&pprz_thd); - pprzReady = TRUE; + pprzReady = true; // Call PPRZ periodic and event functions while (TRUE) { chibios_chThdSleepMilliseconds(1000); diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.c b/sw/airborne/firmwares/fixedwing/main_fbw.c index 95466f7102..781d7553c8 100644 --- a/sw/airborne/firmwares/fixedwing/main_fbw.c +++ b/sw/airborne/firmwares/fixedwing/main_fbw.c @@ -71,7 +71,7 @@ pprz_t command_yaw_trim; volatile uint8_t fbw_new_actuators = 0; -uint8_t ap_has_been_ok = FALSE; +uint8_t ap_has_been_ok = false; tid_t fbw_periodic_tid; ///< id for periodic_task_fbw() timer tid_t electrical_tid; ///< id for electrical_periodic() timer @@ -211,7 +211,7 @@ void post_inter_mcu_received_ap(void) {}; void pre_inter_mcu_received_ap(void) { if (ap_ok) { - ap_has_been_ok = TRUE; + ap_has_been_ok = true; } if ((ap_has_been_ok) && (!ap_ok)) { commands[COMMAND_FORCECRASH] = 9600; @@ -275,7 +275,7 @@ void inter_mcu_event_handle(void) pre_inter_mcu_received_ap(); if (inter_mcu_received_ap) { - inter_mcu_received_ap = FALSE; + inter_mcu_received_ap = false; inter_mcu_event_task(); command_roll_trim = ap_state->command_roll_trim; command_pitch_trim = ap_state->command_pitch_trim; @@ -303,7 +303,7 @@ void inter_mcu_event_handle(void) #ifdef MCU_SPI_LINK if (link_mcu_received) { - link_mcu_received = FALSE; + link_mcu_received = false; inter_mcu_fill_fbw_state(); /** Prepares the next message for AP */ link_mcu_restart(); /** Prepares the next SPI communication */ } diff --git a/sw/airborne/firmwares/fixedwing/nav.c b/sw/airborne/firmwares/fixedwing/nav.c index 5b1b30b5ab..243240e740 100644 --- a/sw/airborne/firmwares/fixedwing/nav.c +++ b/sw/airborne/firmwares/fixedwing/nav.c @@ -65,8 +65,8 @@ static float nav_carrot_leg_progress; /** length of the current leg (m) */ static float nav_leg_length; -bool nav_in_circle = FALSE; -bool nav_in_segment = FALSE; +bool nav_in_circle = false; +bool nav_in_segment = false; float nav_circle_x, nav_circle_y, nav_circle_radius; float nav_segment_x_1, nav_segment_y_1, nav_segment_x_2, nav_segment_y_2; uint8_t horizontal_mode; @@ -98,8 +98,8 @@ void nav_init_stage(void) stage_time = 0; nav_circle_radians = 0; nav_circle_radians_no_rewind = 0; - nav_in_circle = FALSE; - nav_in_segment = FALSE; + nav_in_circle = false; + nav_in_segment = false; nav_shift = 0; } @@ -149,7 +149,7 @@ void nav_circle_XY(float x, float y, float radius) } fly_to_xy(x + cosf(alpha_carrot)*radius_carrot, y + sinf(alpha_carrot)*radius_carrot); - nav_in_circle = TRUE; + nav_in_circle = true; nav_circle_x = x; nav_circle_y = y; nav_circle_radius = radius; @@ -236,7 +236,7 @@ bool nav_compute_baseleg(uint8_t wp_af, uint8_t wp_td, uint8_t wp_baseleg, float baseleg_out_qdr += M_PI; } - return FALSE; + return false; } bool nav_compute_final_from_glide(uint8_t wp_af, uint8_t wp_td, float glide) @@ -255,7 +255,7 @@ bool nav_compute_final_from_glide(uint8_t wp_af, uint8_t wp_td, float glide) waypoints[wp_af].y = waypoints[wp_td].y + y_1 * h_0 * glide; waypoints[wp_af].a = waypoints[wp_af].a; - return FALSE; + return false; } @@ -273,7 +273,7 @@ static inline bool compute_TOD(uint8_t _af, uint8_t _td, uint8_t _tod, float gli WaypointX(_tod) = WaypointX(_td) + td_af_x / td_af * td_tod; WaypointY(_tod) = WaypointY(_td) + td_af_y / td_af * td_tod; WaypointAlt(_tod) = WaypointAlt(_af); - return FALSE; + return false; } @@ -341,7 +341,7 @@ bool nav_approaching_xy(float x, float y, float from_x, float from_y, float appr dist2_to_wp = pw_x * pw_x + pw_y * pw_y; float min_dist = approaching_time * stateGetHorizontalSpeedNorm_f(); if (dist2_to_wp < min_dist * min_dist) { - return TRUE; + return true; } float scal_prod = (x - from_x) * pw_x + (y - from_y) * pw_y; return (scal_prod < 0.); @@ -392,7 +392,7 @@ void nav_route_xy(float last_wp_x, float last_wp_y, float wp_x, float wp_y) float carrot = CARROT * NOMINAL_AIRSPEED; nav_carrot_leg_progress = nav_leg_progress + Max(carrot / nav_leg_length, 0.); - nav_in_segment = TRUE; + nav_in_segment = true; nav_segment_x_1 = last_wp_x; nav_segment_y_1 = last_wp_y; nav_segment_x_2 = wp_x; @@ -438,7 +438,7 @@ void nav_home(void) */ void nav_periodic_task(void) { - nav_survey_active = FALSE; + nav_survey_active = false; compute_dist2_to_home(); dist2_to_wp = 0.; @@ -484,7 +484,7 @@ static void send_wp_moved(struct transport_tx *trans, struct link_device *dev) bool DownlinkSendWpNr(uint8_t _wp) { DownlinkSendWp(&(DefaultChannel).trans_tx, &(DefaultDevice).device, _wp); - return FALSE; + return false; } diff --git a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.c b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.c index eb7e4dbd16..85a2d8caae 100644 --- a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.c +++ b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.c @@ -309,7 +309,7 @@ void h_ctl_init(void) h_ctl_course_dgain = H_CTL_COURSE_DGAIN; h_ctl_roll_max_setpoint = H_CTL_ROLL_MAX_SETPOINT; - h_ctl_disabled = FALSE; + h_ctl_disabled = false; h_ctl_roll_setpoint = 0.; h_ctl_roll_attitude_gain = H_CTL_ROLL_ATTITUDE_GAIN; @@ -349,7 +349,7 @@ void h_ctl_init(void) h_ctl_pitch_of_roll = H_CTL_PITCH_OF_ROLL; #endif - use_airspeed_ratio = FALSE; + use_airspeed_ratio = false; airspeed_ratio2 = 1.; #if USE_PITCH_TRIM diff --git a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.c b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.c index 6dfa04044f..02994c0e70 100644 --- a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.c +++ b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.c @@ -145,7 +145,7 @@ void h_ctl_init(void) h_ctl_pitch_mode = 0; #endif - h_ctl_disabled = FALSE; + h_ctl_disabled = false; h_ctl_roll_setpoint = 0.; #ifdef H_CTL_ROLL_PGAIN diff --git a/sw/airborne/firmwares/motor_bench/main_motor_bench.c b/sw/airborne/firmwares/motor_bench/main_motor_bench.c index 6fae8fe56f..9fcf98f742 100644 --- a/sw/airborne/firmwares/motor_bench/main_motor_bench.c +++ b/sw/airborne/firmwares/motor_bench/main_motor_bench.c @@ -101,12 +101,12 @@ static inline void main_event_task(void) ReadPprzBuffer(); if (pprz_msg_received) { pprz_parse_payload(); - pprz_msg_received = FALSE; + pprz_msg_received = false; } } if (dl_msg_available) { main_dl_parse_msg(); - dl_msg_available = FALSE; + dl_msg_available = false; } } diff --git a/sw/airborne/firmwares/motor_bench/mb_tacho.c b/sw/airborne/firmwares/motor_bench/mb_tacho.c index 92191a9c4c..02fb07af7d 100644 --- a/sw/airborne/firmwares/motor_bench/mb_tacho.c +++ b/sw/airborne/firmwares/motor_bench/mb_tacho.c @@ -32,7 +32,7 @@ uint32_t mb_tacho_get_duration(void) if (got_one_pulse) { my_duration = mb_tacho_duration; } - got_one_pulse = FALSE; + got_one_pulse = false; mcu_int_enable(); return my_duration; } diff --git a/sw/airborne/firmwares/motor_bench/mb_tacho.h b/sw/airborne/firmwares/motor_bench/mb_tacho.h index b003726c51..bd1bcc341b 100644 --- a/sw/airborne/firmwares/motor_bench/mb_tacho.h +++ b/sw/airborne/firmwares/motor_bench/mb_tacho.h @@ -21,7 +21,7 @@ extern volatile uint16_t mb_tacho_nb_pulse; mb_tacho_averaged += diff; \ mb_tacho_nb_pulse++; \ tmb_last = t_now; \ - got_one_pulse = TRUE; \ + got_one_pulse = true; \ } #endif /* MB_TACHO_H */ diff --git a/sw/airborne/firmwares/motor_bench/mb_twi_controller.c b/sw/airborne/firmwares/motor_bench/mb_twi_controller.c index 1053c22609..30722eac96 100644 --- a/sw/airborne/firmwares/motor_bench/mb_twi_controller.c +++ b/sw/airborne/firmwares/motor_bench/mb_twi_controller.c @@ -13,7 +13,7 @@ uint8_t mb_twi_i2c_done; void mb_twi_controller_init(void) { mb_twi_nb_overun = 0; - mb_twi_i2c_done = TRUE; + mb_twi_i2c_done = true; } void mb_twi_controller_set(float throttle) diff --git a/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.c b/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.c index 6881d80414..e23f4e8aa9 100644 --- a/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.c +++ b/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.c @@ -25,8 +25,8 @@ uint8_t mb_twi_i2c_done; void mb_twi_controller_init(void) { mb_twi_nb_overun = 0; - mb_twi_i2c_done = TRUE; - mb_twi_controller_asctech_command = FALSE; + mb_twi_i2c_done = true; + mb_twi_controller_asctech_command = false; mb_twi_controller_asctech_command_type = MB_TWI_CONTROLLER_COMMAND_NONE; mb_twi_controller_asctech_addr = MB_TWI_CONTROLLER_ASCTECH_ADDR_FRONT; } @@ -36,7 +36,7 @@ void mb_twi_controller_set(float throttle) if (mb_twi_i2c_done) { if (mb_twi_controller_asctech_command) { - mb_twi_controller_asctech_command = FALSE; + mb_twi_controller_asctech_command = false; switch (mb_twi_controller_asctech_command_type) { case MB_TWI_CONTROLLER_COMMAND_TEST : @@ -44,7 +44,7 @@ void mb_twi_controller_set(float throttle) i2c0_buf[1] = mb_twi_controller_asctech_addr; i2c0_buf[2] = 0; i2c0_buf[3] = 231 + mb_twi_controller_asctech_addr; - // mb_twi_i2c_done = FALSE; + // mb_twi_i2c_done = false; i2c0_transmit(MB_TWI_CONTROLLER_ADDR, 4, &mb_twi_i2c_done); break; @@ -53,7 +53,7 @@ void mb_twi_controller_set(float throttle) i2c0_buf[1] = mb_twi_controller_asctech_addr; i2c0_buf[2] = 0; i2c0_buf[3] = 234 + mb_twi_controller_asctech_addr; - // mb_twi_i2c_done = FALSE; + // mb_twi_i2c_done = false; i2c0_transmit(MB_TWI_CONTROLLER_ADDR, 4, &mb_twi_i2c_done); break; @@ -64,7 +64,7 @@ void mb_twi_controller_set(float throttle) i2c0_buf[3] = 230 + mb_twi_controller_asctech_addr + mb_twi_controller_asctech_new_addr; mb_twi_controller_asctech_addr = mb_twi_controller_asctech_new_addr; - // mb_twi_i2c_done = FALSE; + // mb_twi_i2c_done = false; i2c0_transmit(MB_TWI_CONTROLLER_ADDR, 4, &mb_twi_i2c_done); break; @@ -79,7 +79,7 @@ void mb_twi_controller_set(float throttle) i2c0_buf[1] = roll; i2c0_buf[2] = yaw; i2c0_buf[3] = power; - // mb_twi_i2c_done = FALSE; + // mb_twi_i2c_done = false; i2c0_transmit(MB_TWI_CONTROLLER_ADDR, 4, &mb_twi_i2c_done); } } else { diff --git a/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.h b/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.h index ed10fa9dd3..69eb13c43a 100644 --- a/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.h +++ b/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.h @@ -19,12 +19,12 @@ extern uint8_t mb_twi_controller_asctech_addr; extern uint8_t mb_twi_controller_asctech_new_addr; #define mb_twi_controller_asctech_SetCommand(value) { \ - mb_twi_controller_asctech_command = TRUE; \ + mb_twi_controller_asctech_command = true; \ mb_twi_controller_asctech_command_type = value; \ } #define mb_twi_controller_asctech_SetAddr(value) { \ - mb_twi_controller_asctech_command = TRUE; \ + mb_twi_controller_asctech_command = true; \ mb_twi_controller_asctech_command_type = MB_TWI_CONTROLLER_COMMAND_SET_ADDR; \ mb_twi_controller_asctech_new_addr = value; \ } diff --git a/sw/airborne/firmwares/motor_bench/mb_twi_controller_mkk.c b/sw/airborne/firmwares/motor_bench/mb_twi_controller_mkk.c index 76916365bd..cf4e19119a 100644 --- a/sw/airborne/firmwares/motor_bench/mb_twi_controller_mkk.c +++ b/sw/airborne/firmwares/motor_bench/mb_twi_controller_mkk.c @@ -23,7 +23,7 @@ uint8_t mb_buss_twi_i2c_done; void mb_twi_controller_init(void) { mb_buss_twi_nb_overun = 0; - mb_buss_twi_i2c_done = TRUE; + mb_buss_twi_i2c_done = true; } void mb_twi_controller_set(float throttle) diff --git a/sw/airborne/firmwares/motor_bench/turntable_systime.c b/sw/airborne/firmwares/motor_bench/turntable_systime.c index 78da429609..34c8cfc2a5 100644 --- a/sw/airborne/firmwares/motor_bench/turntable_systime.c +++ b/sw/airborne/firmwares/motor_bench/turntable_systime.c @@ -54,7 +54,7 @@ static inline void sys_tick_irq_handler(void) if (sys_time.timer[i].in_use && sys_time.nb_tick >= sys_time.timer[i].end_time) { sys_time.timer[i].end_time += sys_time.timer[i].duration; - sys_time.timer[i].elapsed = TRUE; + sys_time.timer[i].elapsed = true; if (sys_time.timer[i].cb) { sys_time.timer[i].cb(i); } } } @@ -81,7 +81,7 @@ void TIMER0_ISR(void) lp_pulse = (lp_pulse + diff) / 2; pulse_last_t = t_now; nb_pulse++; - // got_one_pulse = TRUE; + // got_one_pulse = true; T0IR = TIR_CR0I; } } diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.c b/sw/airborne/firmwares/rotorcraft/autopilot.c index 765594548b..7377040e07 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.c +++ b/sw/airborne/firmwares/rotorcraft/autopilot.c @@ -111,7 +111,7 @@ static inline int ahrs_is_aligned(void) PRINT_CONFIG_MSG("Using AUTOPILOT_DISABLE_AHRS_KILL") static inline int ahrs_is_aligned(void) { - return TRUE; + return true; } #endif @@ -288,16 +288,16 @@ void autopilot_init(void) { /* mode is finally set at end of init if MODE_STARTUP is not KILL */ autopilot_mode = AP_MODE_KILL; - autopilot_motors_on = FALSE; + autopilot_motors_on = false; kill_throttle = ! autopilot_motors_on; - autopilot_in_flight = FALSE; + autopilot_in_flight = false; autopilot_in_flight_counter = 0; autopilot_mode_auto2 = MODE_AUTO2; - autopilot_ground_detected = FALSE; - autopilot_detect_ground_once = FALSE; + autopilot_ground_detected = false; + autopilot_detect_ground_once = false; autopilot_flight_time = 0; - autopilot_rc = TRUE; - autopilot_power_switch = FALSE; + autopilot_rc = true; + autopilot_power_switch = false; #ifdef POWER_SWITCH_GPIO gpio_setup_output(POWER_SWITCH_GPIO); gpio_clear(POWER_SWITCH_GPIO); // POWER OFF @@ -380,8 +380,8 @@ void autopilot_periodic(void) /* Reset ground detection _after_ running flight plan */ if (!autopilot_in_flight) { - autopilot_ground_detected = FALSE; - autopilot_detect_ground_once = FALSE; + autopilot_ground_detected = false; + autopilot_detect_ground_once = false; } /* Set fixed "failsafe" commands from airframe file if in KILL mode. @@ -417,7 +417,7 @@ void autopilot_set_mode(uint8_t new_autopilot_mode) break; #endif case AP_MODE_KILL: - autopilot_in_flight = FALSE; + autopilot_in_flight = false; autopilot_in_flight_counter = 0; guidance_h_mode_changed(GUIDANCE_H_MODE_KILL); break; @@ -528,9 +528,9 @@ bool autopilot_guided_goto_ned(float x, float y, float z, float heading) guidance_h_set_guided_pos(x, y); guidance_h_set_guided_heading(heading); guidance_v_set_guided_z(z); - return TRUE; + return true; } - return FALSE; + return false; } bool autopilot_guided_goto_ned_relative(float dx, float dy, float dz, float dyaw) @@ -542,7 +542,7 @@ bool autopilot_guided_goto_ned_relative(float dx, float dy, float dz, float dyaw float heading = stateGetNedToBodyEulers_f()->psi + dyaw; return autopilot_guided_goto_ned(x, y, z, heading); } - return FALSE; + return false; } bool autopilot_guided_goto_body_relative(float dx, float dy, float dz, float dyaw) @@ -555,7 +555,7 @@ bool autopilot_guided_goto_body_relative(float dx, float dy, float dz, float dya float heading = psi + dyaw; return autopilot_guided_goto_ned(x, y, z, heading); } - return FALSE; + return false; } bool autopilot_guided_move_ned(float vx, float vy, float vz, float heading) @@ -564,9 +564,9 @@ bool autopilot_guided_move_ned(float vx, float vy, float vz, float heading) guidance_h_set_guided_vel(vx, vy); guidance_h_set_guided_heading(heading); guidance_v_set_guided_vz(vz); - return TRUE; + return true; } - return FALSE; + return false; } void autopilot_check_in_flight(bool motors_on) @@ -579,7 +579,7 @@ void autopilot_check_in_flight(bool motors_on) (fabsf(stateGetAccelNed_f()->z) < AUTOPILOT_IN_FLIGHT_MIN_ACCEL)) { autopilot_in_flight_counter--; if (autopilot_in_flight_counter == 0) { - autopilot_in_flight = FALSE; + autopilot_in_flight = false; } } else { /* thrust, speed or accel not above min threshold, reset counter */ autopilot_in_flight_counter = AUTOPILOT_IN_FLIGHT_TIME; @@ -594,7 +594,7 @@ void autopilot_check_in_flight(bool motors_on) if (stabilization_cmd[COMMAND_THRUST] > AUTOPILOT_IN_FLIGHT_MIN_THRUST) { autopilot_in_flight_counter++; if (autopilot_in_flight_counter == AUTOPILOT_IN_FLIGHT_TIME) { - autopilot_in_flight = TRUE; + autopilot_in_flight = true; } } else { /* currently not in_flight and thrust below threshold, reset counter */ autopilot_in_flight_counter = 0; @@ -607,9 +607,9 @@ void autopilot_check_in_flight(bool motors_on) void autopilot_set_motors_on(bool motors_on) { if (autopilot_mode != AP_MODE_KILL && ahrs_is_aligned() && motors_on) { - autopilot_motors_on = TRUE; + autopilot_motors_on = true; } else { - autopilot_motors_on = FALSE; + autopilot_motors_on = false; } kill_throttle = ! autopilot_motors_on; autopilot_arming_set(autopilot_motors_on); diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.h b/sw/airborne/firmwares/rotorcraft/autopilot.h index c6cfa98974..a64f774a9c 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.h +++ b/sw/airborne/firmwares/rotorcraft/autopilot.h @@ -153,8 +153,8 @@ static inline void DetectGroundEvent(void) struct NedCoor_f *accel = stateGetAccelNed_f(); if (accel->z < -THRESHOLD_GROUND_DETECT || accel->z > THRESHOLD_GROUND_DETECT) { - autopilot_ground_detected = TRUE; - autopilot_detect_ground_once = FALSE; + autopilot_ground_detected = true; + autopilot_detect_ground_once = false; } } } diff --git a/sw/airborne/firmwares/rotorcraft/autopilot_arming_switch.h b/sw/airborne/firmwares/rotorcraft/autopilot_arming_switch.h index 7d915021dd..fcdeef6fb7 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot_arming_switch.h +++ b/sw/airborne/firmwares/rotorcraft/autopilot_arming_switch.h @@ -48,7 +48,7 @@ bool autopilot_unarmed_in_auto; static inline void autopilot_arming_init(void) { autopilot_arming_state = STATE_UNINIT; - autopilot_unarmed_in_auto = FALSE; + autopilot_unarmed_in_auto = false; } static inline void autopilot_arming_set(bool motors_on) @@ -61,9 +61,9 @@ static inline void autopilot_arming_set(bool motors_on) /* if turned off in an AUTO mode, remember it so it can be turned on again in AUTO */ if (autopilot_mode != MODE_MANUAL && autopilot_mode != AP_MODE_KILL && autopilot_mode != AP_MODE_FAILSAFE) { - autopilot_unarmed_in_auto = TRUE; + autopilot_unarmed_in_auto = true; } else { - autopilot_unarmed_in_auto = FALSE; + autopilot_unarmed_in_auto = false; } } } @@ -80,7 +80,7 @@ static inline void autopilot_arming_check_motors_on(void) { switch (autopilot_arming_state) { case STATE_UNINIT: - autopilot_motors_on = FALSE; + autopilot_motors_on = false; if (kill_switch_is_on()) { autopilot_arming_state = STATE_STARTABLE; } else { @@ -88,13 +88,13 @@ static inline void autopilot_arming_check_motors_on(void) } break; case STATE_WAITING: - autopilot_motors_on = FALSE; + autopilot_motors_on = false; if (kill_switch_is_on()) { autopilot_arming_state = STATE_STARTABLE; } break; case STATE_STARTABLE: - autopilot_motors_on = FALSE; + autopilot_motors_on = false; /* don't allow to start if in KILL mode or kill switch is on */ if (autopilot_mode == AP_MODE_KILL || kill_switch_is_on()) { break; @@ -107,17 +107,17 @@ static inline void autopilot_arming_check_motors_on(void) case STATE_MOTORS_ON: if (kill_switch_is_on()) { /* kill motors, go to startable state */ - autopilot_motors_on = FALSE; + autopilot_motors_on = false; autopilot_arming_state = STATE_STARTABLE; /* if turned off in an AUTO mode, remember it so it can be turned on again in AUTO */ if (autopilot_mode != MODE_MANUAL && autopilot_mode != AP_MODE_KILL && autopilot_mode != AP_MODE_FAILSAFE) { - autopilot_unarmed_in_auto = TRUE; + autopilot_unarmed_in_auto = true; } else { - autopilot_unarmed_in_auto = FALSE; + autopilot_unarmed_in_auto = false; } } else { - autopilot_motors_on = TRUE; + autopilot_motors_on = true; } break; default: diff --git a/sw/airborne/firmwares/rotorcraft/autopilot_arming_throttle.h b/sw/airborne/firmwares/rotorcraft/autopilot_arming_throttle.h index 3483dd2dd4..99ad493d07 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot_arming_throttle.h +++ b/sw/airborne/firmwares/rotorcraft/autopilot_arming_throttle.h @@ -50,7 +50,7 @@ static inline void autopilot_arming_init(void) { autopilot_arming_state = STATE_UNINIT; autopilot_arming_delay_counter = 0; - autopilot_unarmed_in_auto = FALSE; + autopilot_unarmed_in_auto = false; } static inline void autopilot_arming_set(bool motors_on) @@ -79,7 +79,7 @@ static inline void autopilot_arming_check_motors_on(void) switch (autopilot_arming_state) { case STATE_UNINIT: - autopilot_motors_on = FALSE; + autopilot_motors_on = false; autopilot_arming_delay_counter = 0; if (THROTTLE_STICK_DOWN()) { autopilot_arming_state = STATE_MOTORS_OFF_READY; @@ -88,14 +88,14 @@ static inline void autopilot_arming_check_motors_on(void) } break; case STATE_WAITING: - autopilot_motors_on = FALSE; + autopilot_motors_on = false; autopilot_arming_delay_counter = 0; if (THROTTLE_STICK_DOWN()) { autopilot_arming_state = STATE_MOTORS_OFF_READY; } break; case STATE_MOTORS_OFF_READY: - autopilot_motors_on = FALSE; + autopilot_motors_on = false; autopilot_arming_delay_counter = 0; if (!THROTTLE_STICK_DOWN() && rc_attitude_sticks_centered() && @@ -104,7 +104,7 @@ static inline void autopilot_arming_check_motors_on(void) } break; case STATE_ARMING: - autopilot_motors_on = FALSE; + autopilot_motors_on = false; autopilot_arming_delay_counter++; if (THROTTLE_STICK_DOWN() || !rc_attitude_sticks_centered() || @@ -115,23 +115,23 @@ static inline void autopilot_arming_check_motors_on(void) } break; case STATE_MOTORS_ON: - autopilot_motors_on = TRUE; + autopilot_motors_on = true; autopilot_arming_delay_counter = AUTOPILOT_ARMING_DELAY; if (THROTTLE_STICK_DOWN()) { autopilot_arming_state = STATE_UNARMING; } break; case STATE_UNARMING: - autopilot_motors_on = TRUE; + autopilot_motors_on = true; autopilot_arming_delay_counter--; if (!THROTTLE_STICK_DOWN()) { autopilot_arming_state = STATE_MOTORS_ON; } else if (autopilot_arming_delay_counter == 0) { autopilot_arming_state = STATE_MOTORS_OFF_READY; if (autopilot_mode != MODE_MANUAL) { - autopilot_unarmed_in_auto = TRUE; + autopilot_unarmed_in_auto = true; } else { - autopilot_unarmed_in_auto = FALSE; + autopilot_unarmed_in_auto = false; } } break; diff --git a/sw/airborne/firmwares/rotorcraft/autopilot_arming_yaw.h b/sw/airborne/firmwares/rotorcraft/autopilot_arming_yaw.h index db72278387..d7bfc72ac4 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot_arming_yaw.h +++ b/sw/airborne/firmwares/rotorcraft/autopilot_arming_yaw.h @@ -94,7 +94,7 @@ static inline void autopilot_arming_check_motors_on(void) case STATUS_MOTORS_AUTOMATICALLY_OFF: // Motors were disarmed externally //(possibly due to crash) //wait extra delay before enabling the normal arming state machine - autopilot_motors_on = FALSE; + autopilot_motors_on = false; autopilot_motors_on_counter = 0; if (THROTTLE_STICK_DOWN() && YAW_STICK_CENTERED()) { // stick released autopilot_check_motor_status = STATUS_MOTORS_AUTOMATICALLY_OFF_SAFETY_WAIT; @@ -107,14 +107,14 @@ static inline void autopilot_arming_check_motors_on(void) } break; case STATUS_MOTORS_OFF: - autopilot_motors_on = FALSE; + autopilot_motors_on = false; autopilot_motors_on_counter = 0; if (THROTTLE_STICK_DOWN() && YAW_STICK_PUSHED()) { // stick pushed autopilot_check_motor_status = STATUS_M_OFF_STICK_PUSHED; } break; case STATUS_M_OFF_STICK_PUSHED: - autopilot_motors_on = FALSE; + autopilot_motors_on = false; autopilot_motors_on_counter++; if (autopilot_motors_on_counter >= MOTOR_ARMING_DELAY) { autopilot_check_motor_status = STATUS_START_MOTORS; @@ -123,21 +123,21 @@ static inline void autopilot_arming_check_motors_on(void) } break; case STATUS_START_MOTORS: - autopilot_motors_on = TRUE; + autopilot_motors_on = true; autopilot_motors_on_counter = MOTOR_ARMING_DELAY; if (!(THROTTLE_STICK_DOWN() && YAW_STICK_PUSHED())) { // wait until stick released autopilot_check_motor_status = STATUS_MOTORS_ON; } break; case STATUS_MOTORS_ON: - autopilot_motors_on = TRUE; + autopilot_motors_on = true; autopilot_motors_on_counter = MOTOR_ARMING_DELAY; if (THROTTLE_STICK_DOWN() && YAW_STICK_PUSHED()) { // stick pushed autopilot_check_motor_status = STATUS_M_ON_STICK_PUSHED; } break; case STATUS_M_ON_STICK_PUSHED: - autopilot_motors_on = TRUE; + autopilot_motors_on = true; autopilot_motors_on_counter--; if (autopilot_motors_on_counter == 0) { autopilot_check_motor_status = STATUS_STOP_MOTORS; @@ -146,7 +146,7 @@ static inline void autopilot_arming_check_motors_on(void) } break; case STATUS_STOP_MOTORS: - autopilot_motors_on = FALSE; + autopilot_motors_on = false; autopilot_motors_on_counter = 0; if (!(THROTTLE_STICK_DOWN() && YAW_STICK_PUSHED())) { // wait until stick released autopilot_check_motor_status = STATUS_MOTORS_OFF; diff --git a/sw/airborne/firmwares/rotorcraft/autopilot_rc_helpers.h b/sw/airborne/firmwares/rotorcraft/autopilot_rc_helpers.h index 5e5aabab83..bd9ca01467 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot_rc_helpers.h +++ b/sw/airborne/firmwares/rotorcraft/autopilot_rc_helpers.h @@ -61,15 +61,15 @@ static inline bool rc_attitude_sticks_centered(void) static inline bool kill_switch_is_on(void) { if (radio_control.values[RADIO_KILL_SWITCH] < 0) { - return TRUE; + return true; } else { - return FALSE; + return false; } } #else static inline bool kill_switch_is_on(void) { - return FALSE; + return false; } #endif diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c index b3e481a563..14ab2564d1 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c @@ -643,9 +643,9 @@ bool guidance_h_set_guided_pos(float x, float y) ClearBit(guidance_h.sp.mask, 5); guidance_h.sp.pos.x = POS_BFP_OF_REAL(x); guidance_h.sp.pos.y = POS_BFP_OF_REAL(y); - return TRUE; + return true; } - return FALSE; + return false; } bool guidance_h_set_guided_heading(float heading) @@ -654,9 +654,9 @@ bool guidance_h_set_guided_heading(float heading) ClearBit(guidance_h.sp.mask, 7); guidance_h.sp.heading = ANGLE_BFP_OF_REAL(heading); INT32_ANGLE_NORMALIZE(guidance_h.sp.heading); - return TRUE; + return true; } - return FALSE; + return false; } bool guidance_h_set_guided_vel(float vx, float vy) @@ -666,7 +666,7 @@ bool guidance_h_set_guided_vel(float vx, float vy) SetBit(guidance_h.sp.mask, 5); guidance_h.sp.speed.x = SPEED_BFP_OF_REAL(vx); guidance_h.sp.speed.y = SPEED_BFP_OF_REAL(vy); - return TRUE; + return true; } - return FALSE; + return false; } diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c index fdb6613072..4f48c23cee 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c @@ -184,7 +184,7 @@ void guidance_v_init(void) guidance_v_nominal_throttle = GUIDANCE_V_NOMINAL_HOVER_THROTTLE; guidance_v_adapt_throttle_enabled = GUIDANCE_V_ADAPT_THROTTLE_ENABLED; - guidance_v_guided_vel_enabled = FALSE; + guidance_v_guided_vel_enabled = false; gv_adapt_init(); @@ -311,7 +311,7 @@ void guidance_v_run(bool in_flight) break; case GUIDANCE_V_MODE_HOVER: - guidance_v_guided_vel_enabled = FALSE; + guidance_v_guided_vel_enabled = false; case GUIDANCE_V_MODE_GUIDED: if (guidance_v_guided_vel_enabled) { gv_update_ref_from_zd_sp(guidance_v_zd_sp, stateGetPositionNed_i()->z); @@ -463,19 +463,19 @@ static void run_hover_loop(bool in_flight) bool guidance_v_set_guided_z(float z) { if (guidance_v_mode == GUIDANCE_V_MODE_GUIDED) { - guidance_v_guided_vel_enabled = FALSE; + guidance_v_guided_vel_enabled = false; guidance_v_z_sp = POS_BFP_OF_REAL(z); - return TRUE; + return true; } - return FALSE; + return false; } bool guidance_v_set_guided_vz(float vz) { if (guidance_v_mode == GUIDANCE_V_MODE_GUIDED) { - guidance_v_guided_vel_enabled = TRUE; + guidance_v_guided_vel_enabled = true; guidance_v_zd_sp = SPEED_BFP_OF_REAL(vz); - return TRUE; + return true; } - return FALSE; + return false; } diff --git a/sw/airborne/firmwares/rotorcraft/main.c b/sw/airborne/firmwares/rotorcraft/main.c index 9fad32cb3a..550297dea3 100644 --- a/sw/airborne/firmwares/rotorcraft/main.c +++ b/sw/airborne/firmwares/rotorcraft/main.c @@ -300,14 +300,14 @@ STATIC_INLINE void main_periodic(void) STATIC_INLINE void telemetry_periodic(void) { - static uint8_t boot = TRUE; + static uint8_t boot = true; /* initialisation phase during boot */ if (boot) { #if DOWNLINK send_autopilot_version(&(DefaultChannel).trans_tx, &(DefaultDevice).device); #endif - boot = FALSE; + boot = false; } /* then report periodicly */ else { diff --git a/sw/airborne/firmwares/rotorcraft/main_fbw.c b/sw/airborne/firmwares/rotorcraft/main_fbw.c index 30dda611b9..a47037c7af 100644 --- a/sw/airborne/firmwares/rotorcraft/main_fbw.c +++ b/sw/airborne/firmwares/rotorcraft/main_fbw.c @@ -221,7 +221,7 @@ static void autopilot_on_rc_frame(void) /* if manual */ if (fbw_mode == FBW_MODE_MANUAL) { - autopilot_motors_on = TRUE; + autopilot_motors_on = true; #ifdef SetCommandsFromRC SetCommandsFromRC(commands, radio_control.values); #else @@ -238,7 +238,7 @@ static void autopilot_on_ap_command(void) if (fbw_mode != FBW_MODE_MANUAL) { SetCommands(intermcu_commands); } else { - autopilot_motors_on = TRUE; + autopilot_motors_on = true; } } diff --git a/sw/airborne/firmwares/rotorcraft/navigation.c b/sw/airborne/firmwares/rotorcraft/navigation.c index 658d7423f2..c1d4357441 100644 --- a/sw/airborne/firmwares/rotorcraft/navigation.c +++ b/sw/airborne/firmwares/rotorcraft/navigation.c @@ -182,7 +182,7 @@ void nav_init(void) nav_leg_progress = 0; nav_leg_length = 1; - too_far_from_home = FALSE; + too_far_from_home = false; dist2_to_home = 0; dist2_to_wp = 0; @@ -328,7 +328,7 @@ bool nav_approaching_from(struct EnuCoor_i *wp, struct EnuCoor_i *from, int16_t /* return TRUE if we have arrived */ if (dist_to_point < BFP_OF_REAL(ARRIVED_AT_WAYPOINT, INT32_POS_FRAC / 2)) { - return TRUE; + return true; } /* if coming from a valid waypoint */ @@ -340,7 +340,7 @@ bool nav_approaching_from(struct EnuCoor_i *wp, struct EnuCoor_i *from, int16_t return (diff.x * from_diff.x + diff.y * from_diff.y < 0); } - return FALSE; + return false; } bool nav_check_wp_time(struct EnuCoor_i *wp, uint16_t stay_time) @@ -348,12 +348,12 @@ bool nav_check_wp_time(struct EnuCoor_i *wp, uint16_t stay_time) uint16_t time_at_wp; uint32_t dist_to_point; static uint16_t wp_entry_time = 0; - static bool wp_reached = FALSE; + static bool wp_reached = false; static struct EnuCoor_i wp_last = { 0, 0, 0 }; struct Int32Vect2 diff; if ((wp_last.x != wp->x) || (wp_last.y != wp->y)) { - wp_reached = FALSE; + wp_reached = false; wp_last = *wp; } VECT2_DIFF(diff, *wp, *stateGetPositionEnu_i()); @@ -361,7 +361,7 @@ bool nav_check_wp_time(struct EnuCoor_i *wp, uint16_t stay_time) dist_to_point = int32_vect2_norm(&diff); if (dist_to_point < BFP_OF_REAL(ARRIVED_AT_WAYPOINT, INT32_POS_FRAC / 2)) { if (!wp_reached) { - wp_reached = TRUE; + wp_reached = true; wp_entry_time = autopilot_flight_time; time_at_wp = 0; } else { @@ -369,13 +369,13 @@ bool nav_check_wp_time(struct EnuCoor_i *wp, uint16_t stay_time) } } else { time_at_wp = 0; - wp_reached = FALSE; + wp_reached = false; } if (time_at_wp > stay_time) { INT_VECT3_ZERO(wp_last); - return TRUE; + return true; } - return FALSE; + return false; } static inline void nav_set_altitude(void) @@ -417,7 +417,7 @@ void nav_periodic_task(void) { RunOnceEvery(NAV_FREQ, { stage_time++; block_time++; }); - nav_survey_active = FALSE; + nav_survey_active = false; dist2_to_wp = 0; @@ -454,9 +454,9 @@ void navigation_update_wp_from_speed(uint8_t wp, struct Int16Vect3 speed_sp, int bool nav_detect_ground(void) { - if (!autopilot_ground_detected) { return FALSE; } - autopilot_ground_detected = FALSE; - return TRUE; + if (!autopilot_ground_detected) { return false; } + autopilot_ground_detected = false; + return true; } bool nav_is_in_flight(void) @@ -510,7 +510,7 @@ bool nav_set_heading_rad(float rad) { nav_heading = ANGLE_BFP_OF_REAL(rad); INT32_COURSE_NORMALIZE(nav_heading); - return FALSE; + return false; } /** Set nav_heading in degrees. */ @@ -532,7 +532,7 @@ bool nav_set_heading_towards(float x, float y) } // return false so it can be called from the flightplan // meaning it will continue to the next stage - return FALSE; + return false; } /** Set heading in the direction of a waypoint */ @@ -545,5 +545,5 @@ bool nav_set_heading_towards_waypoint(uint8_t wp) bool nav_set_heading_current(void) { nav_heading = stateGetNedToBodyEulers_i()->psi; - return FALSE; + return false; } diff --git a/sw/airborne/firmwares/rotorcraft/navigation.h b/sw/airborne/firmwares/rotorcraft/navigation.h index 52ea525462..9d5d6cac25 100644 --- a/sw/airborne/firmwares/rotorcraft/navigation.h +++ b/sw/airborne/firmwares/rotorcraft/navigation.h @@ -101,16 +101,16 @@ extern bool nav_set_heading_current(void); #define CARROT 0 #endif -#define NavKillThrottle() ({ if (autopilot_mode == AP_MODE_NAV) { autopilot_set_motors_on(FALSE); } FALSE; }) -#define NavResurrect() ({ if (autopilot_mode == AP_MODE_NAV) { autopilot_set_motors_on(TRUE); } FALSE; }) +#define NavKillThrottle() ({ if (autopilot_mode == AP_MODE_NAV) { autopilot_set_motors_on(FALSE); } false; }) +#define NavResurrect() ({ if (autopilot_mode == AP_MODE_NAV) { autopilot_set_motors_on(TRUE); } false; }) -#define NavSetGroundReferenceHere() ({ nav_reset_reference(); FALSE; }) -#define NavSetAltitudeReferenceHere() ({ nav_reset_alt(); FALSE; }) +#define NavSetGroundReferenceHere() ({ nav_reset_reference(); false; }) +#define NavSetAltitudeReferenceHere() ({ nav_reset_alt(); false; }) -#define NavSetWaypointHere(_wp) ({ waypoint_set_here_2d(_wp); FALSE; }) -#define NavCopyWaypoint(_wp1, _wp2) ({ waypoint_copy(_wp1, _wp2); FALSE; }) -#define NavCopyWaypointPositionOnly(_wp1, _wp2) ({ waypoint_position_copy(_wp1, _wp2); FALSE; }) +#define NavSetWaypointHere(_wp) ({ waypoint_set_here_2d(_wp); false; }) +#define NavCopyWaypoint(_wp1, _wp2) ({ waypoint_copy(_wp1, _wp2); false; }) +#define NavCopyWaypointPositionOnly(_wp1, _wp2) ({ waypoint_position_copy(_wp1, _wp2); false; }) /** Normalize a degree angle between 0 and 359 */ #define NormCourse(x) { \ @@ -200,7 +200,7 @@ bool nav_check_wp_time(struct EnuCoor_i *wp, uint16_t stay_time); nav_roll = ANGLE_BFP_OF_REAL(_roll); \ } -#define NavStartDetectGround() ({ autopilot_detect_ground_once = TRUE; FALSE; }) +#define NavStartDetectGround() ({ autopilot_detect_ground_once = true; false; }) #define NavDetectGround() nav_detect_ground() #define nav_IncreaseShift(x) {} diff --git a/sw/airborne/firmwares/tutorial/main_demo5.c b/sw/airborne/firmwares/tutorial/main_demo5.c index 514e5d128b..34fc19d8f8 100644 --- a/sw/airborne/firmwares/tutorial/main_demo5.c +++ b/sw/airborne/firmwares/tutorial/main_demo5.c @@ -46,12 +46,12 @@ static inline void main_event_task(void) ReadPprzBuffer(); if (pprz_msg_received) { pprz_parse_payload(); - pprz_msg_received = FALSE; + pprz_msg_received = false; } } if (dl_msg_available) { main_dl_parse_msg(); - dl_msg_available = FALSE; + dl_msg_available = false; LED_TOGGLE(1); } } diff --git a/sw/airborne/firmwares/wind_tunnel/main.c b/sw/airborne/firmwares/wind_tunnel/main.c index b0a30bafa8..7f121c345c 100644 --- a/sw/airborne/firmwares/wind_tunnel/main.c +++ b/sw/airborne/firmwares/wind_tunnel/main.c @@ -70,7 +70,7 @@ static inline void main_event_task(void) // spi baro if (spi_message_received) { /* Got a message on SPI. */ - spi_message_received = FALSE; + spi_message_received = false; wt_baro_event(); uint16_t temp = 0; float alt = 0.; diff --git a/sw/airborne/firmwares/wind_tunnel/wt_baro.c b/sw/airborne/firmwares/wind_tunnel/wt_baro.c index 29d6587a18..bf74ccf75b 100644 --- a/sw/airborne/firmwares/wind_tunnel/wt_baro.c +++ b/sw/airborne/firmwares/wind_tunnel/wt_baro.c @@ -71,8 +71,8 @@ void wt_baro_init(void) send1_on_spi(CMD_INIT_5); send1_on_spi(CMD_INIT_6); - status_read_data = FALSE; - wt_baro_available = FALSE; + status_read_data = false; + wt_baro_available = false; } @@ -110,7 +110,7 @@ void wt_baro_event(void) data = Uint24(buf_input); /* Compute pressure */ wt_baro_pressure = data; - wt_baro_available = TRUE; + wt_baro_available = true; } /* else nothing to read */ status_read_data = !status_read_data; diff --git a/sw/airborne/inter_mcu.c b/sw/airborne/inter_mcu.c index c5c5246446..235fd01948 100644 --- a/sw/airborne/inter_mcu.c +++ b/sw/airborne/inter_mcu.c @@ -37,8 +37,8 @@ struct fbw_state *fbw_state = &link_mcu_from_fbw_msg.payload.from_fbw; struct ap_state *ap_state = &link_mcu_from_ap_msg.payload.from_ap; #endif /* ! SINGLE_MCU */ -volatile bool inter_mcu_received_fbw = FALSE; -volatile bool inter_mcu_received_ap = FALSE; +volatile bool inter_mcu_received_fbw = false; +volatile bool inter_mcu_received_ap = false; #ifdef FBW /** Variables for monitoring AP communication status */ diff --git a/sw/airborne/inter_mcu.h b/sw/airborne/inter_mcu.h index 74eca348d6..cda7252e06 100644 --- a/sw/airborne/inter_mcu.h +++ b/sw/airborne/inter_mcu.h @@ -95,7 +95,7 @@ static inline void inter_mcu_init(void) fbw_state->status = 0; fbw_state->nb_err = 0; - ap_ok = FALSE; + ap_ok = false; } @@ -127,7 +127,7 @@ static inline void inter_mcu_fill_fbw_state(void) fbw_state->energy = electrical.energy; #if defined SINGLE_MCU /**Directly set the flag indicating to AP that shared buffer is available*/ - inter_mcu_received_fbw = TRUE; + inter_mcu_received_fbw = true; #endif } @@ -135,14 +135,14 @@ static inline void inter_mcu_fill_fbw_state(void) static inline void inter_mcu_event_task(void) { time_since_last_ap = 0; - ap_ok = TRUE; + ap_ok = true; } /** Monitors AP. Set ::ap_ok to false if AP is down for a long time. */ static inline void inter_mcu_periodic_task(void) { if (time_since_last_ap >= AP_STALLED_TIME) { - ap_ok = FALSE; + ap_ok = false; #ifdef SINGLE_MCU // Keep filling the buffer even if no AP commands are received inter_mcu_fill_fbw_state(); diff --git a/sw/airborne/link_mcu_can.c b/sw/airborne/link_mcu_can.c index 942bc4b5d0..8cb21b805f 100644 --- a/sw/airborne/link_mcu_can.c +++ b/sw/airborne/link_mcu_can.c @@ -71,7 +71,7 @@ void link_mcu_on_can_msg(uint32_t id, uint8_t *data, int len) #ifdef LINK_MCU_LED LED_TOGGLE(LINK_MCU_LED); #endif - inter_mcu_received_ap = TRUE; + inter_mcu_received_ap = true; } if (id == MSG_INTERMCU_COMMAND_EXTRA_ID) { @@ -108,7 +108,7 @@ void link_mcu_on_can_msg(uint32_t id, uint8_t *data, int len) #ifdef LINK_MCU_LED LED_TOGGLE(LINK_MCU_LED); #endif - inter_mcu_received_fbw = TRUE; + inter_mcu_received_fbw = true; } } diff --git a/sw/airborne/link_mcu_spi.c b/sw/airborne/link_mcu_spi.c index 70418f52ab..b573d4eff0 100644 --- a/sw/airborne/link_mcu_spi.c +++ b/sw/airborne/link_mcu_spi.c @@ -79,16 +79,16 @@ void link_mcu_event_task(void) /* A message has been received */ ComputeChecksum(link_mcu_from_ap_msg); - link_mcu_received = TRUE; + link_mcu_received = true; if (link_mcu_from_ap_msg.checksum == crc) { - inter_mcu_received_ap = TRUE; + inter_mcu_received_ap = true; } else { fbw_state->nb_err++; } } if (link_mcu_trans.status == SPITransFailed) { link_mcu_trans.status = SPITransDone; - link_mcu_received = TRUE; + link_mcu_received = true; fbw_state->nb_err++; } } @@ -153,14 +153,14 @@ void link_mcu_event_task(void) /* A message has been received */ ComputeChecksum(link_mcu_from_fbw_msg); if (link_mcu_from_fbw_msg.checksum == crc) { - inter_mcu_received_fbw = TRUE; + inter_mcu_received_fbw = true; } else { link_mcu_nb_err++; } } if (link_mcu_trans.status == SPITransFailed) { link_mcu_trans.status = SPITransDone; - link_mcu_received = TRUE; + link_mcu_received = true; link_mcu_nb_err++; } } diff --git a/sw/airborne/link_mcu_usart.c b/sw/airborne/link_mcu_usart.c index 565e8b835d..067e2e5d46 100644 --- a/sw/airborne/link_mcu_usart.c +++ b/sw/airborne/link_mcu_usart.c @@ -218,7 +218,7 @@ void intermcu_parse(uint8_t c) if (c != intermcu_data.ck_b) { goto error; } - intermcu_data.msg_available = TRUE; + intermcu_data.msg_available = true; goto restart; break; default: @@ -283,7 +283,7 @@ static void send_fbw_status(struct transport_tx *trans, struct link_device *dev) void link_mcu_init(void) { intermcu_data.status = LINK_MCU_UNINIT; - intermcu_data.msg_available = FALSE; + intermcu_data.msg_available = false; intermcu_data.error_cnt = 0; #ifdef AP #if PERIODIC_TELEMETRY @@ -309,7 +309,7 @@ void parse_mavpilot_msg(void) #ifdef LINK_MCU_LED LED_TOGGLE(LINK_MCU_LED); #endif - inter_mcu_received_ap = TRUE; + inter_mcu_received_ap = true; } else if (intermcu_data.msg_id == MSG_INTERMCU_RADIO_ID) { #if RADIO_CONTROL_NB_CHANNEL > 10 #error "INTERMCU UART CAN ONLY SEND 10 RADIO CHANNELS OR THE UART WILL BE OVERFILLED" @@ -331,7 +331,7 @@ void parse_mavpilot_msg(void) #ifdef LINK_MCU_LED LED_TOGGLE(LINK_MCU_LED); #endif - inter_mcu_received_fbw = TRUE; + inter_mcu_received_fbw = true; } } } @@ -379,7 +379,7 @@ void link_mcu_event_task(void) intermcu_parse(InterMcuUartGetch()); if (intermcu_data.msg_available) { parse_mavpilot_msg(); - intermcu_data.msg_available = FALSE; + intermcu_data.msg_available = false; } } } diff --git a/sw/airborne/mcu_periph/spi.c b/sw/airborne/mcu_periph/spi.c index 3402ad748b..1e78d0df21 100644 --- a/sw/airborne/mcu_periph/spi.c +++ b/sw/airborne/mcu_periph/spi.c @@ -81,7 +81,7 @@ void spi_init(struct spi_periph *p) p->trans_extract_idx = 0; p->status = SPIIdle; p->mode = SPIMaster; - p->suspend = FALSE; + p->suspend = false; } #endif /* SPI_MASTER */ @@ -139,7 +139,7 @@ extern void spi_slave_init(struct spi_periph *p) p->trans_extract_idx = 0; p->status = SPIIdle; p->mode = SPISlave; - p->suspend = FALSE; + p->suspend = false; } #endif /* SPI_SLAVE */ diff --git a/sw/airborne/mcu_periph/sys_time.c b/sw/airborne/mcu_periph/sys_time.c index 026b622a1a..4080553dff 100644 --- a/sw/airborne/mcu_periph/sys_time.c +++ b/sw/airborne/mcu_periph/sys_time.c @@ -41,10 +41,10 @@ int sys_time_register_timer(float duration, sys_time_cb cb) for (int i = 0; i < SYS_TIME_NB_TIMER; i++) { if (!sys_time.timer[i].in_use) { sys_time.timer[i].cb = cb; - sys_time.timer[i].elapsed = FALSE; + sys_time.timer[i].elapsed = false; sys_time.timer[i].end_time = start_time + sys_time_ticks_of_sec(duration); sys_time.timer[i].duration = sys_time_ticks_of_sec(duration); - sys_time.timer[i].in_use = TRUE; + sys_time.timer[i].in_use = true; return i; } } @@ -54,9 +54,9 @@ int sys_time_register_timer(float duration, sys_time_cb cb) void sys_time_cancel_timer(tid_t id) { - sys_time.timer[id].in_use = FALSE; + sys_time.timer[id].in_use = false; sys_time.timer[id].cb = NULL; - sys_time.timer[id].elapsed = FALSE; + sys_time.timer[id].elapsed = false; sys_time.timer[id].end_time = 0; sys_time.timer[id].duration = 0; } @@ -80,9 +80,9 @@ void sys_time_init(void) sys_time.resolution = 1.0 / sys_time.ticks_per_sec; for (unsigned int i = 0; i < SYS_TIME_NB_TIMER; i++) { - sys_time.timer[i].in_use = FALSE; + sys_time.timer[i].in_use = false; sys_time.timer[i].cb = NULL; - sys_time.timer[i].elapsed = FALSE; + sys_time.timer[i].elapsed = false; sys_time.timer[i].end_time = 0; sys_time.timer[i].duration = 0; } diff --git a/sw/airborne/mcu_periph/sys_time.h b/sw/airborne/mcu_periph/sys_time.h index d5acd582d9..94ac166110 100644 --- a/sw/airborne/mcu_periph/sys_time.h +++ b/sw/airborne/mcu_periph/sys_time.h @@ -111,10 +111,10 @@ extern void sys_time_update_timer(tid_t id, float duration); static inline bool sys_time_check_and_ack_timer(tid_t id) { if (sys_time.timer[id].elapsed) { - sys_time.timer[id].elapsed = FALSE; - return TRUE; + sys_time.timer[id].elapsed = false; + return true; } - return FALSE; + return false; } /** diff --git a/sw/airborne/mcu_periph/uart.c b/sw/airborne/mcu_periph/uart.c index 7bde2745b6..ab8d69696f 100644 --- a/sw/airborne/mcu_periph/uart.c +++ b/sw/airborne/mcu_periph/uart.c @@ -236,7 +236,7 @@ void uart_periph_init(struct uart_periph *p) p->rx_extract_idx = 0; p->tx_insert_idx = 0; p->tx_extract_idx = 0; - p->tx_running = FALSE; + p->tx_running = false; p->ore = 0; p->ne_err = 0; p->fe_err = 0; diff --git a/sw/airborne/modules/air_data/air_data.c b/sw/airborne/modules/air_data/air_data.c index 2486fe6f4a..2716f3b5d0 100644 --- a/sw/airborne/modules/air_data/air_data.c +++ b/sw/airborne/modules/air_data/air_data.c @@ -109,13 +109,13 @@ static void pressure_abs_cb(uint8_t __attribute__((unused)) sender_id, float pre } float h = stateGetPositionLla_f()->alt - geoid_separation; air_data.qnh = pprz_isa_ref_pressure_of_height_full(air_data.pressure, h) / 100.f; - air_data.calc_qnh_once = FALSE; + air_data.calc_qnh_once = false; } if (air_data.calc_amsl_baro && air_data.qnh > 0) { air_data.amsl_baro = pprz_isa_height_of_pressure_full(air_data.pressure, air_data.qnh * 100.f); - air_data.amsl_baro_valid = TRUE; + air_data.amsl_baro_valid = true; } /* reset baro health counter */ @@ -180,8 +180,8 @@ void air_data_init(void) air_data.calc_tas_factor = AIR_DATA_CALC_TAS_FACTOR; air_data.calc_amsl_baro = AIR_DATA_CALC_AMSL_BARO; air_data.tas_factor = AIR_DATA_TAS_FACTOR; - air_data.calc_qnh_once = TRUE; - air_data.amsl_baro_valid = FALSE; + air_data.calc_qnh_once = true; + air_data.amsl_baro_valid = false; /* initialize the output variables * pressure, qnh, temperature and airspeed to invalid values, @@ -229,7 +229,7 @@ void air_data_periodic(void) if (baro_health_counter > 0) { baro_health_counter--; } else { - air_data.amsl_baro_valid = FALSE; + air_data.amsl_baro_valid = false; } } diff --git a/sw/airborne/modules/cam_control/point.c b/sw/airborne/modules/cam_control/point.c index ad93e6d1ac..395c383c39 100644 --- a/sw/airborne/modules/cam_control/point.c +++ b/sw/airborne/modules/cam_control/point.c @@ -341,8 +341,8 @@ void vPoint(float fPlaneEast, float fPlaneNorth, float fPlaneAltitude, vMultiplyMatrixByVector(&sv_cam_projection, smRotation, sv_cam_projection_buf); #if defined(RADIO_CAM_LOCK) - if ((float)(*fbw_state).channels[RADIO_CAM_LOCK] > MAX_PPRZ / 2)) && pprz_mode == PPRZ_MODE_AUTO2) { cam_lock = TRUE; } - if ((float)(*fbw_state).channels[RADIO_CAM_LOCK] < MIN_PPRZ / 2 && pprz_mode == PPRZ_MODE_AUTO2) { cam_lock = FALSE; } + if ((float)(*fbw_state).channels[RADIO_CAM_LOCK] > MAX_PPRZ / 2)) && pprz_mode == PPRZ_MODE_AUTO2) { cam_lock = true; } + if ((float)(*fbw_state).channels[RADIO_CAM_LOCK] < MIN_PPRZ / 2 && pprz_mode == PPRZ_MODE_AUTO2) { cam_lock = false; } #endif // When the variable "cam_lock" is set then the last calculated position is set as the target waypoint. if (cam_lock == FALSE) { diff --git a/sw/airborne/modules/cartography/cartography.c b/sw/airborne/modules/cartography/cartography.c index 1fa61c8b96..9ec8555d07 100644 --- a/sw/airborne/modules/cartography/cartography.c +++ b/sw/airborne/modules/cartography/cartography.c @@ -168,7 +168,7 @@ void stop_carto(void) bool nav_survey_Inc_railnumberSinceBoot(void) { railnumberSinceBoot++; - return FALSE; + return false; } /////////////////////////////////////////////////////////////////////////////////////////////// bool nav_survey_Snapshoot(void) @@ -176,7 +176,7 @@ bool nav_survey_Snapshoot(void) camera_snapshot_image_number = railnumberSinceBoot; PRTDEBSTR(SNAPSHOT) cartography_periodic_downlink_carto_status = MODULES_START; - return FALSE; + return false; } /////////////////////////////////////////////////////////////////////////////////////////////// @@ -185,7 +185,7 @@ bool nav_survey_Snapshoot_Continu(void) camera_snapshot_image_number = railnumberSinceBoot; PRTDEBSTR(SNAPSHOT) cartography_periodic_downlink_carto_status = MODULES_START; - return TRUE; + return true; } /////////////////////////////////////////////////////////////////////////////////////////////// @@ -194,7 +194,7 @@ bool nav_survey_StopSnapshoot(void) camera_snapshot_image_number = 0; PRTDEBSTR(STOP SNAPSHOT) cartography_periodic_downlink_carto_status = MODULES_START; - return FALSE; + return false; } /////////////////////////////////////////////////////////////////////////////////////////////// @@ -207,7 +207,7 @@ bool nav_survey_computefourth_corner(uint8_t wp1, uint8_t wp2, uint8_t wp3, uin PRTDEBSTR(nav_survey_computefourth_corner) PRTDEB(f, waypoints[wp4].x) PRTDEB(f, waypoints[wp4].y) - return FALSE; + return false; } //////////////////////////////////////////////////////////////////////////////////////////////// @@ -313,7 +313,7 @@ bool nav_survey_ComputeProjectionOnLine(struct point pointAf, struct point poin bool nav_survey_losange_carto_init(uint8_t wp1, uint8_t wp2, uint8_t wp3, float distrailinit, float distplusinit) { //PRTDEBSTR(nav_survey_losange_carto_init) - survey_losange_uturn = FALSE; + survey_losange_uturn = false; point1.x = waypoints[wp1].x; //the coordinates are in meter units, taken from the flight plan, in float type @@ -357,7 +357,7 @@ bool nav_survey_losange_carto_init(uint8_t wp1, uint8_t wp2, uint8_t wp3, float PRTDEB(f, norm13) //if (distrail<1e-15) //inutile distrail=0 pour recollage et dans ce cas, il prend la valeur norm13 - // return FALSE; + // return false; if (fabs(distrailinit) <= 1) { @@ -382,10 +382,10 @@ bool nav_survey_losange_carto_init(uint8_t wp1, uint8_t wp2, uint8_t wp3, float railnumber = -1; // the state is before the first rail, which is numbered 0 if (norm12 < 1e-15) { - return FALSE; + return false; } if (norm13 < 1e-15) { - return FALSE; + return false; } @@ -405,7 +405,7 @@ bool nav_survey_losange_carto_init(uint8_t wp1, uint8_t wp2, uint8_t wp3, float } - return FALSE; //Init function must return false, so that the next function in the flight plan is automatically executed + return false; //Init function must return false, so that the next function in the flight plan is automatically executed //dans le flight_plan.h // if (! (nav_survey_losange_carto())) // NextStageAndBreak(); @@ -438,15 +438,15 @@ bool nav_survey_losange_carto(void) //sortir du bloc si données abhérantes if (norm13 < 1e-15) { PRTDEBSTR(norm13 < 1e-15) - return FALSE; + return false; } if (norm12 < 1e-15) { PRTDEBSTR(norm13 < 1e-15) - return FALSE; + return false; } if (distrail < 1e-15) { PRTDEBSTR(distrail < 1e-15) - return FALSE; + return false; } if (survey_losange_uturn == FALSE) { @@ -537,7 +537,7 @@ bool nav_survey_losange_carto(void) // nav_survey_ComputeProjectionOnLine(pointA,pointB,stateGetPositionEnu_f()->x,stateGetPositionEnu_f()->y,&normAM,&normBM,&distancefromrail); if ((normAM > distplus) && (normBM > distplus) && (distancefromrail < distrail / 2)) { - //CAMERA_SNAPSHOT_REQUIERED=TRUE; + //CAMERA_SNAPSHOT_REQUIERED=true; //camera_snapshot_image_number++; camera_snapshot_image_number = railnumberSinceBoot; PRTDEBSTR(SNAPSHOT) @@ -552,17 +552,17 @@ bool nav_survey_losange_carto(void) PRTDEB(d, railnumber) PRTDEB(d, railnumberSinceBoot) - //CAMERA_SNAPSHOT_REQUIERED=TRUE; + //CAMERA_SNAPSHOT_REQUIERED=true; //camera_snapshot_image_number++; PRTDEBSTR(UTURN) - survey_losange_uturn = TRUE; + survey_losange_uturn = true; } if (railnumber > numberofrailtodo) { PRTDEBSTR(fin nav_survey_losange_carto) - return FALSE; //apparament, l'avion va au bloc suivant lorsque la fonction renvoie false + return false; //apparament, l'avion va au bloc suivant lorsque la fonction renvoie false } } @@ -613,7 +613,7 @@ bool nav_survey_losange_carto(void) if ((DISTXY(stateGetPositionEnu_f()->x, stateGetPositionEnu_f()->y, pointB.x, pointB.y) < DISTLIMIT) || (angle_between > -10 && angle_between < 10)) { //l'avion fait le rail suivant - survey_losange_uturn = FALSE; + survey_losange_uturn = false; PRTDEBSTR(FIN UTURN - IMPAIR) } } else { //if ((railnumber %2)==0) //rail précédent n1, 3, 5, donc seconde direction, de wp2 vers wp1 @@ -657,7 +657,7 @@ bool nav_survey_losange_carto(void) if ((DISTXY(stateGetPositionEnu_f()->x, stateGetPositionEnu_f()->y, pointB.x, pointB.y) < DISTLIMIT) || (angle_between > -10 && angle_between < 10)) { //l'avion fait le rail suivant - survey_losange_uturn = FALSE; + survey_losange_uturn = false; PRTDEBSTR(FIN UTURN - PAIR) } } @@ -675,7 +675,7 @@ bool nav_survey_losange_carto(void) nav_route_xy(pointA.x, pointA.y, pointB.x, pointB.y); if (DISTXY(stateGetPositionEnu_f()->x, stateGetPositionEnu_f()->y, pointB.x, pointB.y) < DISTLIMIT) { //l'avion fait le rail suivant - survey_losange_uturn = FALSE; + survey_losange_uturn = false; PRTDEBSTR(FIN TRANSIT - IMPAIR) } } else { //if ((railnumber %2)==0) //rail précédent n1, 3, 5, donc seconde direction, de wp2 vers wp1 @@ -689,7 +689,7 @@ bool nav_survey_losange_carto(void) nav_route_xy(pointA.x, pointA.y, pointB.x, pointB.y); if (DISTXY(stateGetPositionEnu_f()->x, stateGetPositionEnu_f()->y, pointB.x, pointB.y) < DISTLIMIT) { //l'avion fait le rail suivant - survey_losange_uturn = FALSE; + survey_losange_uturn = false; PRTDEBSTR(FIN TRANSIT - PAIR) } @@ -707,7 +707,7 @@ bool nav_survey_losange_carto(void) cartography_periodic_downlink_carto_status = MODULES_START; - return TRUE; //apparament pour les fonctions de tache=> true + return true; //apparament pour les fonctions de tache=> true } //////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/sw/airborne/modules/com/generic_com.c b/sw/airborne/modules/com/generic_com.c index fced0efecf..7a8850f509 100644 --- a/sw/airborne/modules/com/generic_com.c +++ b/sw/airborne/modules/com/generic_com.c @@ -51,7 +51,7 @@ bool active_com; void generic_com_init(void) { - active_com = FALSE; + active_com = false; com_trans.status = I2CTransDone; } @@ -99,13 +99,13 @@ void generic_com_event(void) void start_com(void) { - active_com = TRUE; + active_com = true; com_trans.status = I2CTransDone; } void stop_com(void) { - active_com = FALSE; + active_com = false; com_trans.buf[0] = active_com; i2c_transmit(&GENERIC_COM_I2C_DEV, &com_trans, GENERIC_COM_SLAVE_ADDR, 1); } diff --git a/sw/airborne/modules/com/usb_serial_stm32_example1.c b/sw/airborne/modules/com/usb_serial_stm32_example1.c index b5c3af2df8..1675afa0da 100644 --- a/sw/airborne/modules/com/usb_serial_stm32_example1.c +++ b/sw/airborne/modules/com/usb_serial_stm32_example1.c @@ -45,7 +45,7 @@ void init_usb_serial(void) { VCOM_init(); cmd_idx = 0; - cmd_avail = FALSE; + cmd_avail = false; } @@ -62,7 +62,7 @@ void usb_serial_parse_packet(int data) if (c == '\r' || c == '\n') { // command complete - cmd_avail = TRUE; + cmd_avail = true; // add termination characters and the prompt into buffer VCOM_putchar('\r'); VCOM_putchar('\n'); @@ -131,6 +131,6 @@ void event_usb_serial(void) } if (cmd_avail) { cmd_execute(); - cmd_avail = FALSE; + cmd_avail = false; } } diff --git a/sw/airborne/modules/com/usb_serial_stm32_example2.c b/sw/airborne/modules/com/usb_serial_stm32_example2.c index 56ae3fc40e..f210509397 100644 --- a/sw/airborne/modules/com/usb_serial_stm32_example2.c +++ b/sw/airborne/modules/com/usb_serial_stm32_example2.c @@ -44,7 +44,7 @@ uint8_t big_buffer[] = void init_usb_serial(void) { VCOM_init(); - run = FALSE; + run = false; } /** @@ -77,10 +77,10 @@ void usb_serial_parse_packet(int data) VCOM_putchar('\n'); if (c == 'S') { - run = FALSE; + run = false; } if (c == 'R') { - run = TRUE; + run = true; } VCOM_send_message(); } diff --git a/sw/airborne/modules/computer_vision/bebop_front_camera.c b/sw/airborne/modules/computer_vision/bebop_front_camera.c index 10e5c33410..cd4636af8a 100644 --- a/sw/airborne/modules/computer_vision/bebop_front_camera.c +++ b/sw/airborne/modules/computer_vision/bebop_front_camera.c @@ -72,7 +72,7 @@ struct bebopfrontcamera_t bebop_front_camera = { void bebop_front_camera_take_shot(bool take) { - bebop_front_camera.take_shot = TRUE; + bebop_front_camera.take_shot = true; } /** * Handles all the video streaming and saving of the image shots @@ -99,7 +99,7 @@ static void *bebop_front_camera_thread(void *data __attribute__((unused))) } // Start streaming - bebop_front_camera.is_streaming = TRUE; + bebop_front_camera.is_streaming = true; while (bebop_front_camera.is_streaming) { // Wait for a new frame (blocking) struct image_t img; @@ -110,7 +110,7 @@ static void *bebop_front_camera_thread(void *data __attribute__((unused))) if (bebop_front_camera.take_shot) { // Save the image bebop_front_camera_save_shot(&img_color, &img_jpeg, &img); - bebop_front_camera.take_shot = FALSE; + bebop_front_camera.take_shot = false; } jpeg_encode_image(&img_color, &img_jpeg, 80, 0); @@ -190,7 +190,7 @@ void bebop_front_camera_stop(void) } // Stop the streaming thread - bebop_front_camera.is_streaming = FALSE; + bebop_front_camera.is_streaming = false; // Stop the capturing if (!v4l2_stop_capture(bebop_front_camera.dev)) { diff --git a/sw/airborne/modules/computer_vision/cv_blob_locator.c b/sw/airborne/modules/computer_vision/cv_blob_locator.c index 16d5fc9630..b14d689811 100644 --- a/sw/airborne/modules/computer_vision/cv_blob_locator.c +++ b/sw/airborne/modules/computer_vision/cv_blob_locator.c @@ -48,9 +48,9 @@ int record_video = 0; volatile uint32_t blob_locator = 0; -volatile bool blob_enabled = FALSE; -volatile bool marker_enabled = FALSE; -volatile bool window_enabled = FALSE; +volatile bool blob_enabled = false; +volatile bool marker_enabled = false; +volatile bool window_enabled = false; // Computer vision thread struct image_t* cv_marker_func(struct image_t *img); @@ -255,24 +255,24 @@ void cv_blob_locator_event(void) { switch (cv_blob_locator_type) { case 1: - blob_enabled = TRUE; - marker_enabled = FALSE; - window_enabled = FALSE; + blob_enabled = true; + marker_enabled = false; + window_enabled = false; break; case 2: - blob_enabled = FALSE; - marker_enabled = TRUE; - window_enabled = FALSE; + blob_enabled = false; + marker_enabled = true; + window_enabled = false; break; case 3: - blob_enabled = FALSE; - marker_enabled = FALSE; - window_enabled = TRUE; + blob_enabled = false; + marker_enabled = false; + window_enabled = true; break; default: - blob_enabled = FALSE; - marker_enabled = FALSE; - window_enabled = FALSE; + blob_enabled = false; + marker_enabled = false; + window_enabled = false; break; } if (blob_locator != 0) { diff --git a/sw/airborne/modules/computer_vision/cv_blob_locator.h b/sw/airborne/modules/computer_vision/cv_blob_locator.h index 4f7e86707d..6ed3738a4d 100644 --- a/sw/airborne/modules/computer_vision/cv_blob_locator.h +++ b/sw/airborne/modules/computer_vision/cv_blob_locator.h @@ -54,9 +54,9 @@ extern void cv_blob_locator_stop(void); cv_blob_locator_start(); \ } -#define StartVision(X) { start_vision(); FALSE; } -#define StartVisionLand(X) { start_vision_land(); FALSE; } -#define StopVision(X) { stop_vision(); FALSE; } +#define StartVision(X) { start_vision(); false; } +#define StartVisionLand(X) { start_vision_land(); false; } +#define StopVision(X) { stop_vision(); false; } extern void start_vision(void); diff --git a/sw/airborne/modules/computer_vision/lib/v4l/v4l2.c b/sw/airborne/modules/computer_vision/lib/v4l/v4l2.c index 55d5afafc0..ccdc4a40d4 100644 --- a/sw/airborne/modules/computer_vision/lib/v4l/v4l2.c +++ b/sw/airborne/modules/computer_vision/lib/v4l/v4l2.c @@ -136,14 +136,14 @@ bool v4l2_init_subdev(char *subdev_name, uint8_t pad, uint8_t which, uint16_t co int fd = open(subdev_name, O_RDWR, 0); if (fd < 0) { printf("[v4l2] Cannot open subdevice '%s': %d, %s\n", subdev_name, errno, strerror(errno)); - return FALSE; + return false; } // Try to get the subdevice data format settings if (ioctl(fd, VIDIOC_SUBDEV_G_FMT, &sfmt) < 0) { printf("[v4l2] Could not get subdevice data format settings of %s\n", subdev_name); close(fd); - return FALSE; + return false; } // Set the new settings @@ -158,12 +158,12 @@ bool v4l2_init_subdev(char *subdev_name, uint8_t pad, uint8_t which, uint16_t co if (ioctl(fd, VIDIOC_SUBDEV_S_FMT, &sfmt) < 0) { printf("[v4l2] Could not set subdevice data format settings of %s\n", subdev_name); close(fd); - return FALSE; + return false; } // Close the device close(fd); - return TRUE; + return true; } /** @@ -343,7 +343,7 @@ bool v4l2_image_get_nonblock(struct v4l2_device *dev, struct image_t *img) // Check if we really got an image if (img_idx == V4L2_IMG_NONE) { - return FALSE; + return false; } else { // Set the image img->type = IMAGE_YUV422; @@ -353,7 +353,7 @@ bool v4l2_image_get_nonblock(struct v4l2_device *dev, struct image_t *img) img->buf_size = dev->buffers[img_idx].length; img->buf = dev->buffers[img_idx].buf; memcpy(&img->ts, &dev->buffers[img_idx].timestamp, sizeof(struct timeval)); - return TRUE; + return true; } } @@ -392,7 +392,7 @@ bool v4l2_start_capture(struct v4l2_device *dev) // Check if not already running if (dev->thread != (pthread_t)NULL) { printf("[v4l2] There is already a capturing thread running for %s\n", dev->name); - return FALSE; + return false; } // Enqueue all buffers @@ -406,7 +406,7 @@ bool v4l2_start_capture(struct v4l2_device *dev) buf.index = i; if (ioctl(dev->fd, VIDIOC_QBUF, &buf) < 0) { printf("[v4l2] Could not enqueue buffer %d during start capture for %s\n", i, dev->name); - return FALSE; + return false; } } @@ -414,7 +414,7 @@ bool v4l2_start_capture(struct v4l2_device *dev) type = V4L2_BUF_TYPE_VIDEO_CAPTURE; if (ioctl(dev->fd, VIDIOC_STREAMON, &type) < 0) { printf("[v4l2] Could not start stream of %s, %d %s\n", dev->name, errno, strerror(errno)); - return FALSE; + return false; } //Start the capturing thread @@ -430,10 +430,10 @@ bool v4l2_start_capture(struct v4l2_device *dev) // Reset the thread dev->thread = (pthread_t) NULL; - return FALSE; + return false; } - return TRUE; + return true; } /** @@ -450,26 +450,26 @@ bool v4l2_stop_capture(struct v4l2_device *dev) // First check if still running if (dev->thread == (pthread_t) NULL) { printf("[v4l2] Already stopped capture for %s\n", dev->name); - return FALSE; + return false; } // Stop the stream type = V4L2_BUF_TYPE_VIDEO_CAPTURE; if (ioctl(dev->fd, VIDIOC_STREAMOFF, &type) < 0) { printf("[v4l2] Could not stop stream of %s\n", dev->name); - return FALSE; + return false; } // Stop the thread if (pthread_cancel(dev->thread) < 0) { printf("[v4l2] Could not cancel thread for %s\n", dev->name); - return FALSE; + return false; } // Wait for the thread to be finished pthread_join(dev->thread, NULL); dev->thread = (pthread_t) NULL; - return TRUE; + return true; } /** diff --git a/sw/airborne/modules/computer_vision/lib/vision/fast_rosten.c b/sw/airborne/modules/computer_vision/lib/vision/fast_rosten.c index 60c8370614..4def67673b 100644 --- a/sw/airborne/modules/computer_vision/lib/vision/fast_rosten.c +++ b/sw/airborne/modules/computer_vision/lib/vision/fast_rosten.c @@ -67,13 +67,13 @@ struct point_t *fast9_detect(struct image_t *img, uint8_t threshold, uint16_t mi for (x = 3 + x_padding; x < img->w - 3 - x_padding; x++) { // First check if we aren't in range vertical (TODO: fix less intensive way) if (min_dist > 0) { - bool need_skip = FALSE; + bool need_skip = false; // Go trough all the previous corners for (i = 0; i < corner_cnt; i++) { if (x - min_dist < ret_corners[i].x && ret_corners[i].x < x + min_dist && y - min_dist < ret_corners[i].y && ret_corners[i].y < y + min_dist) { - need_skip = TRUE; + need_skip = true; break; } } diff --git a/sw/airborne/modules/computer_vision/lib/vision/lucas_kanade.c b/sw/airborne/modules/computer_vision/lib/vision/lucas_kanade.c index b60fab3d6c..e2c4a01a09 100644 --- a/sw/airborne/modules/computer_vision/lib/vision/lucas_kanade.c +++ b/sw/airborne/modules/computer_vision/lib/vision/lucas_kanade.c @@ -124,7 +124,7 @@ struct flow_t *opticFlowLK(struct image_t *new_img, struct image_t *old_img, str // (a * Ax + (1-a) * Ax+1) - (a * Bx + (1-a) * Bx+1) // (4) iterate over taking steps in the image to minimize the error: - bool tracked = TRUE; + bool tracked = true; for (uint8_t it = 0; it < max_iterations; it++) { struct point_t new_point = { vectors[new_p].pos.x + vectors[new_p].flow_x, @@ -133,7 +133,7 @@ struct flow_t *opticFlowLK(struct image_t *new_img, struct image_t *old_img, str // If the pixel is outside ROI, do not track it if (new_point.x / subpixel_factor < half_window_size || (old_img->w - new_point.x / subpixel_factor) < half_window_size || new_point.y / subpixel_factor < half_window_size || (old_img->h - new_point.y / subpixel_factor) < half_window_size) { - tracked = FALSE; + tracked = false; break; } @@ -143,7 +143,7 @@ struct flow_t *opticFlowLK(struct image_t *new_img, struct image_t *old_img, str // [b] determine the image difference between the two neighborhoods uint32_t error = image_difference(&window_I, &window_J, &window_diff); if (error > error_threshold && it > max_iterations / 2) { - tracked = FALSE; + tracked = false; break; } diff --git a/sw/airborne/modules/computer_vision/opticflow/opticflow_calculator.c b/sw/airborne/modules/computer_vision/opticflow/opticflow_calculator.c index ab3828ab41..281556167b 100644 --- a/sw/airborne/modules/computer_vision/opticflow/opticflow_calculator.c +++ b/sw/airborne/modules/computer_vision/opticflow/opticflow_calculator.c @@ -151,7 +151,7 @@ void opticflow_calc_init(struct opticflow_t *opticflow, uint16_t w, uint16_t h) image_create(&opticflow->prev_img_gray, w, h, IMAGE_GRAYSCALE); /* Set the previous values */ - opticflow->got_first_img = FALSE; + opticflow->got_first_img = false; opticflow->prev_phi = 0.0; opticflow->prev_theta = 0.0; @@ -197,7 +197,7 @@ void calc_fast9_lukas_kanade(struct opticflow_t *opticflow, struct opticflow_sta // Copy to previous image if not set if (!opticflow->got_first_img) { image_copy(&opticflow->img_gray, &opticflow->prev_img_gray); - opticflow->got_first_img = TRUE; + opticflow->got_first_img = true; } // ************************************************************************************* diff --git a/sw/airborne/modules/computer_vision/opticflow_module.c b/sw/airborne/modules/computer_vision/opticflow_module.c index 9896eca86c..4cada86567 100644 --- a/sw/airborne/modules/computer_vision/opticflow_module.c +++ b/sw/airborne/modules/computer_vision/opticflow_module.c @@ -120,7 +120,7 @@ void opticflow_module_init(void) // Initialize the opticflow calculation opticflow_calc_init(&opticflow, 320, 240); - opticflow_got_result = FALSE; + opticflow_got_result = false; #ifdef OPTICFLOW_SUBDEV PRINT_CONFIG_MSG("[opticflow_module] Configuring a subdevice!") @@ -182,7 +182,7 @@ void opticflow_module_run(void) opticflow_result.noise_measurement ); } - opticflow_got_result = FALSE; + opticflow_got_result = false; } pthread_mutex_unlock(&opticflow_mutex); } @@ -262,7 +262,7 @@ static void *opticflow_module_calc(void *data __attribute__((unused))) // Copy the result if finished pthread_mutex_lock(&opticflow_mutex); memcpy(&opticflow_result, &temp_result, sizeof(struct opticflow_result_t)); - opticflow_got_result = TRUE; + opticflow_got_result = true; pthread_mutex_unlock(&opticflow_mutex); #if OPTICFLOW_DEBUG diff --git a/sw/airborne/modules/computer_vision/video_thread.c b/sw/airborne/modules/computer_vision/video_thread.c index 6254cc1ccc..19acb0e179 100644 --- a/sw/airborne/modules/computer_vision/video_thread.c +++ b/sw/airborne/modules/computer_vision/video_thread.c @@ -175,7 +175,7 @@ static void *video_thread_function(void *data) clock_gettime(CLOCK_MONOTONIC, &time_prev); // Start streaming - video_thread.is_running = TRUE; + video_thread.is_running = true; while (video_thread.is_running) { // get time in us since last run @@ -212,7 +212,7 @@ static void *video_thread_function(void *data) // Check if we need to take a shot if (video_thread.take_shot) { video_thread_save_shot(img_final, &img_jpeg); - video_thread.take_shot = FALSE; + video_thread.take_shot = false; } // Run processing if required @@ -290,7 +290,7 @@ void video_thread_stop(void) } // Stop the streaming thread - video_thread.is_running = FALSE; + video_thread.is_running = false; // Stop the capturing if (!v4l2_stop_capture(video_thread.dev)) { diff --git a/sw/airborne/modules/computer_vision/viewvideo.c b/sw/airborne/modules/computer_vision/viewvideo.c index 4f5283f66e..d00977276d 100644 --- a/sw/airborne/modules/computer_vision/viewvideo.c +++ b/sw/airborne/modules/computer_vision/viewvideo.c @@ -201,7 +201,7 @@ void viewvideo_init(void) cv_add(viewvideo_function); - viewvideo.is_streaming = TRUE; + viewvideo.is_streaming = true; #if VIEWVIDEO_USE_NETCAT // Create an Netcat receiver file for the streaming diff --git a/sw/airborne/modules/datalink/mavlink_decoder.h b/sw/airborne/modules/datalink/mavlink_decoder.h index d93d482d26..d4a33d87f5 100644 --- a/sw/airborne/modules/datalink/mavlink_decoder.h +++ b/sw/airborne/modules/datalink/mavlink_decoder.h @@ -216,7 +216,7 @@ static inline void parse_mavlink(struct mavlink_transport *t, uint8_t c) if (c != (t->checksum >> 8)) { goto error; } - t->trans.msg_received = TRUE; + t->trans.msg_received = true; goto restart; default: goto error; @@ -259,7 +259,7 @@ static inline void mavlink_check_and_parse(struct link_device *dev, struct mavli } if (trans->trans.msg_received) { mavlink_parse_payload(trans); - trans->trans.msg_received = FALSE; + trans->trans.msg_received = false; } } } diff --git a/sw/airborne/modules/datalink/xtend_rssi.c b/sw/airborne/modules/datalink/xtend_rssi.c index 44b7093117..df91ea0830 100644 --- a/sw/airborne/modules/datalink/xtend_rssi.c +++ b/sw/airborne/modules/datalink/xtend_rssi.c @@ -56,7 +56,7 @@ void xtend_rssi_periodic(void) if (pwm_input_duty_valid[XTEND_RSSI_PWM_ARRAY_INDEX]) { duty_percent = (duty_tics * 100) / cpu_ticks_of_usec(XTEND_RSSI_PWM_PERIOD_USEC); rssi_dB_fade_margin = (2 * duty_percent + 10) / 3; //not sure if this is right, datasheet isn't very informative - pwm_input_duty_valid[XTEND_RSSI_PWM_ARRAY_INDEX] = FALSE; + pwm_input_duty_valid[XTEND_RSSI_PWM_ARRAY_INDEX] = false; } DOWNLINK_SEND_XTEND_RSSI(DefaultChannel, DefaultDevice, &datalink_time, diff --git a/sw/airborne/modules/digital_cam/catia/catia.c b/sw/airborne/modules/digital_cam/catia/catia.c index 2cc93adf57..305edb0f0e 100644 --- a/sw/airborne/modules/digital_cam/catia/catia.c +++ b/sw/airborne/modules/digital_cam/catia/catia.c @@ -61,7 +61,7 @@ int main(int argc, char *argv[]) // Parse serial commands if (mora_protocol.msg_received) { // Process Only Once - mora_protocol.msg_received = FALSE; + mora_protocol.msg_received = false; // Shoot an image if not busy if (mora_protocol.msg_id == MORA_SHOOT) { diff --git a/sw/airborne/modules/digital_cam/catia/protocol.c b/sw/airborne/modules/digital_cam/catia/protocol.c index 647ae72e02..02f8379e3c 100644 --- a/sw/airborne/modules/digital_cam/catia/protocol.c +++ b/sw/airborne/modules/digital_cam/catia/protocol.c @@ -63,7 +63,7 @@ void parse_mora(struct mora_transport *t, uint8_t c) if (c != t->ck_b) { goto error; } - t->msg_received = TRUE; + t->msg_received = true; goto restart; default: goto error; diff --git a/sw/airborne/modules/digital_cam/catia/protocol.h b/sw/airborne/modules/digital_cam/catia/protocol.h index 8c06ff1cc8..9ecee1bc9f 100644 --- a/sw/airborne/modules/digital_cam/catia/protocol.h +++ b/sw/airborne/modules/digital_cam/catia/protocol.h @@ -38,6 +38,7 @@ #define MORA_TRANSPORT_H #include +#include #include "std.h" ///////////////////////////////////////////////////////////////////// @@ -131,7 +132,7 @@ struct mora_transport { uint8_t payload[256]; uint8_t error; uint8_t msg_id; - uint8_t msg_received; + bool msg_received; uint8_t payload_len; // specific pprz transport variables uint8_t status; diff --git a/sw/airborne/modules/digital_cam/catia/serial.h b/sw/airborne/modules/digital_cam/catia/serial.h index 5dead8683b..637ed1e766 100644 --- a/sw/airborne/modules/digital_cam/catia/serial.h +++ b/sw/airborne/modules/digital_cam/catia/serial.h @@ -8,7 +8,7 @@ int serial_init(char *port_name); static inline int ttyUSB0ChAvailable(void) { - return FALSE; + return false; } #define ttyUSB0Transmit(_char) \ diff --git a/sw/airborne/modules/display/max7456.c b/sw/airborne/modules/display/max7456.c index 373b2039fc..0ef5f3bb62 100644 --- a/sw/airborne/modules/display/max7456.c +++ b/sw/airborne/modules/display/max7456.c @@ -65,7 +65,7 @@ char osd_str_buf[OSD_STRING_SIZE]; char osd_char = ' '; uint8_t step = 0; uint16_t osd_char_address = 0; -uint8_t osd_attr = FALSE; +uint8_t osd_attr = false; enum max7456_osd_status_codes { OSD_UNINIT, @@ -87,10 +87,10 @@ enum osd_attributes { }; uint8_t max7456_osd_status = OSD_UNINIT; -uint8_t osd_enable = TRUE; +uint8_t osd_enable = true; uint8_t osd_enable_val = OSD_IMAGE_ENABLE; uint8_t osd_stat_reg = 0; -bool osd_stat_reg_valid = FALSE; +bool osd_stat_reg_valid = false; void max7456_init(void) { @@ -234,7 +234,7 @@ void max7456_event(void) break; case (OSD_READ_STATUS): osd_stat_reg = max7456_trans.input_buf[0]; - osd_stat_reg_valid = TRUE; + osd_stat_reg_valid = true; max7456_osd_status = OSD_FINISHED; break; case (OSD_S_STEP1): diff --git a/sw/airborne/modules/enose/anemotaxis.c b/sw/airborne/modules/enose/anemotaxis.c index d94470ee75..d62b518194 100644 --- a/sw/airborne/modules/enose/anemotaxis.c +++ b/sw/airborne/modules/enose/anemotaxis.c @@ -24,7 +24,7 @@ bool nav_anemotaxis_downwind(uint8_t c, float radius) float wind_dir = atan2(wind->x, wind->y); waypoints[c].x = waypoints[WP_HOME].x + radius * cos(wind_dir); waypoints[c].y = waypoints[WP_HOME].y + radius * sin(wind_dir); - return FALSE; + return false; } bool nav_anemotaxis_init(uint8_t c) @@ -36,7 +36,7 @@ bool nav_anemotaxis_init(uint8_t c) waypoints[c].x = stateGetPositionEnu_f()->x + DEFAULT_CIRCLE_RADIUS * cos(wind_dir + M_PI); waypoints[c].y = stateGetPositionEnu_f()->y + DEFAULT_CIRCLE_RADIUS * sin(wind_dir + M_PI); last_plume_was_here(); - return FALSE; + return false; } bool nav_anemotaxis(uint8_t c, uint8_t c1, uint8_t c2, uint8_t plume) @@ -104,5 +104,5 @@ bool nav_anemotaxis(uint8_t c, uint8_t c1, uint8_t c2, uint8_t plume) break; } chemo_sensor = 0; - return TRUE; + return true; } diff --git a/sw/airborne/modules/enose/chemotaxis.c b/sw/airborne/modules/enose/chemotaxis.c index dcf242e8ab..88f83c09dd 100644 --- a/sw/airborne/modules/enose/chemotaxis.c +++ b/sw/airborne/modules/enose/chemotaxis.c @@ -22,7 +22,7 @@ bool nav_chemotaxis_init(uint8_t c, uint8_t plume) sign = 1; waypoints[plume].x = waypoints[c].x; waypoints[plume].y = waypoints[c].y; - return FALSE; + return false; } bool nav_chemotaxis(uint8_t c, uint8_t plume) @@ -53,5 +53,5 @@ bool nav_chemotaxis(uint8_t c, uint8_t plume) } NavCircleWaypoint(c, radius); - return TRUE; + return true; } diff --git a/sw/airborne/modules/enose/enose.c b/sw/airborne/modules/enose/enose.c index 47bfd8da7e..bb7fa9d614 100644 --- a/sw/airborne/modules/enose/enose.c +++ b/sw/airborne/modules/enose/enose.c @@ -30,8 +30,8 @@ void enose_init(void) enose_val[i] = 0; } enose_status = ENOSE_IDLE; - enose_conf_requested = TRUE; - enose_i2c_done = TRUE; + enose_conf_requested = true; + enose_i2c_done = true; #ifdef ADC_CHANNEL_PID adc_buf_channel(ADC_CHANNEL_PID, &buf_PID, ADC_CHANNEL_PID_NB_SAMPLES); @@ -42,7 +42,7 @@ void enose_init(void) void enose_set_heat(uint8_t no_sensor, uint8_t value) { enose_heat[no_sensor] = value; - enose_conf_requested = TRUE; + enose_conf_requested = true; } @@ -59,18 +59,18 @@ void enose_periodic(void) const uint8_t msg[] = { ENOSE_PWM_ADDR, enose_heat[0], enose_heat[1], enose_heat[2] }; memcpy((void *)i2c0_buf, msg, sizeof(msg)); i2c0_transmit(ENOSE_SLAVE_ADDR, sizeof(msg), &enose_i2c_done); - enose_i2c_done = FALSE; - enose_conf_requested = FALSE; + enose_i2c_done = false; + enose_conf_requested = false; } else if (enose_status == ENOSE_IDLE) { enose_status = ENOSE_MEASURING_WR; const uint8_t msg[] = { ENOSE_DATA_ADDR }; memcpy((void *)i2c0_buf, msg, sizeof(msg)); i2c0_transmit(ENOSE_SLAVE_ADDR, sizeof(msg), &enose_i2c_done); - enose_i2c_done = FALSE; + enose_i2c_done = false; } else if (enose_status == ENOSE_MEASURING_WR) { enose_status = ENOSE_MEASURING_RD; i2c0_receive(ENOSE_SLAVE_ADDR, 6, &enose_i2c_done); - enose_i2c_done = FALSE; + enose_i2c_done = false; } else if (enose_status == ENOSE_MEASURING_RD) { uint16_t val = (i2c0_buf[0] << 8) | i2c0_buf[1]; if (val < 5000) { diff --git a/sw/airborne/modules/geo_mag/geo_mag.c b/sw/airborne/modules/geo_mag/geo_mag.c index 17e13cf35a..19edf93df7 100644 --- a/sw/airborne/modules/geo_mag/geo_mag.c +++ b/sw/airborne/modules/geo_mag/geo_mag.c @@ -44,15 +44,15 @@ struct GeoMag geo_mag; void geo_mag_init(void) { - geo_mag.calc_once = FALSE; - geo_mag.ready = FALSE; + geo_mag.calc_once = false; + geo_mag.ready = false; } void geo_mag_periodic(void) { //FIXME: kill_throttle has no place in a geomag module if (!geo_mag.ready && GpsFixValid() && kill_throttle) { - geo_mag.calc_once = TRUE; + geo_mag.calc_once = true; } } @@ -86,7 +86,7 @@ void geo_mag_event(void) float_vect3_normalize(&h); AbiSendMsgGEO_MAG(GEO_MAG_SENDER_ID, &h); - geo_mag.ready = TRUE; + geo_mag.ready = true; } - geo_mag.calc_once = FALSE; + geo_mag.calc_once = false; } diff --git a/sw/airborne/modules/gps/gps_ubx_ucenter.c b/sw/airborne/modules/gps/gps_ubx_ucenter.c index 869f86f247..e43a46f906 100644 --- a/sw/airborne/modules/gps/gps_ubx_ucenter.c +++ b/sw/airborne/modules/gps/gps_ubx_ucenter.c @@ -263,7 +263,7 @@ static bool gps_ubx_ucenter_autobaud(uint8_t nr) case 3: if (gps_ubx_ucenter.reply == GPS_UBX_UCENTER_REPLY_ACK) { gps_ubx_ucenter.baud_init = gps_ubx_ucenter.baud_run; - return FALSE; + return false; } gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE; uart_periph_set_baudrate(&(UBX_GPS_LINK), B9600); // Maybe the factory default? @@ -272,7 +272,7 @@ static bool gps_ubx_ucenter_autobaud(uint8_t nr) case 4: if (gps_ubx_ucenter.reply == GPS_UBX_UCENTER_REPLY_ACK) { gps_ubx_ucenter.baud_init = gps_ubx_ucenter.baud_run; - return FALSE; + return false; } gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE; uart_periph_set_baudrate(&(UBX_GPS_LINK), B57600); // The high-rate default? @@ -281,7 +281,7 @@ static bool gps_ubx_ucenter_autobaud(uint8_t nr) case 5: if (gps_ubx_ucenter.reply == GPS_UBX_UCENTER_REPLY_ACK) { gps_ubx_ucenter.baud_init = gps_ubx_ucenter.baud_run; - return FALSE; + return false; } gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE; uart_periph_set_baudrate(&(UBX_GPS_LINK), B4800); // Default NMEA baudrate? @@ -290,7 +290,7 @@ static bool gps_ubx_ucenter_autobaud(uint8_t nr) case 6: if (gps_ubx_ucenter.reply == GPS_UBX_UCENTER_REPLY_ACK) { gps_ubx_ucenter.baud_init = gps_ubx_ucenter.baud_run; - return FALSE; + return false; } gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE; uart_periph_set_baudrate(&(UBX_GPS_LINK), B115200); // Last possible option for ublox @@ -299,7 +299,7 @@ static bool gps_ubx_ucenter_autobaud(uint8_t nr) case 7: if (gps_ubx_ucenter.reply == GPS_UBX_UCENTER_REPLY_ACK) { gps_ubx_ucenter.baud_init = gps_ubx_ucenter.baud_run; - return FALSE; + return false; } gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE; uart_periph_set_baudrate(&(UBX_GPS_LINK), B230400); // Last possible option for ublox @@ -308,18 +308,18 @@ static bool gps_ubx_ucenter_autobaud(uint8_t nr) case 8: if (gps_ubx_ucenter.reply == GPS_UBX_UCENTER_REPLY_ACK) { gps_ubx_ucenter.baud_init = gps_ubx_ucenter.baud_run; - return FALSE; + return false; } // Autoconfig Failed... let's setup the failsafe baudrate // Should we try even a different baudrate? gps_ubx_ucenter.baud_init = 0; // Set as zero to indicate that we couldn't verify the baudrate uart_periph_set_baudrate(&(UBX_GPS_LINK), B9600); - return FALSE; + return false; default: break; } - return TRUE; + return true; } #endif /* GPS_I2C */ ///////////////////////////////////// @@ -574,11 +574,11 @@ static bool gps_ubx_ucenter_configure(uint8_t nr) DEBUG_PRINT("%u\n", gps_ubx_ucenter.replies[i]); } #endif - return FALSE; + return false; default: break; } gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE; - return TRUE; // Continue, except for the last case + return true; // Continue, except for the last case } diff --git a/sw/airborne/modules/gsm/gsm.c b/sw/airborne/modules/gsm/gsm.c index c89dd3a55b..fa9285a88a 100644 --- a/sw/airborne/modules/gsm/gsm.c +++ b/sw/airborne/modules/gsm/gsm.c @@ -150,7 +150,7 @@ void gsm_init(void) // // Send_AT(); // gsm_status = STATUS_SEND_AT; - // gsm_gsm_init_status = FALSE; + // gsm_gsm_init_status = false; } gcs_index = 0; gcs_index_max = 0; @@ -170,7 +170,7 @@ void gsm_init_report(void) /* Second call */ Send_AT(); gsm_status = STATUS_SEND_AT; - gsm_gsm_init_report_status = FALSE; + gsm_gsm_init_report_status = false; } } diff --git a/sw/airborne/modules/gumstix_interface/qr_code_spi_link.c b/sw/airborne/modules/gumstix_interface/qr_code_spi_link.c index bf7a9bfcdd..2695810e30 100644 --- a/sw/airborne/modules/gumstix_interface/qr_code_spi_link.c +++ b/sw/airborne/modules/gumstix_interface/qr_code_spi_link.c @@ -32,7 +32,7 @@ //struct qr_code_spi_link_data qr_code_spi_link_data; struct spi_transaction qr_code_spi_link_transaction; -static volatile bool qr_code_spi_data_available = FALSE; +static volatile bool qr_code_spi_data_available = false; uint8_t testDataOut[3] = {1, 2, 3}; uint8_t testDataIn[3] = {9, 9, 9}; @@ -58,7 +58,7 @@ void qr_code_spi_link_init(void) void qr_code_spi_link_periodic(void) { if (qr_code_spi_data_available) { - qr_code_spi_data_available = FALSE; + qr_code_spi_data_available = false; uint16_t x, y; memcpy(&x, qr_code_spi_link_transaction.input_buf, 2); memcpy(&y, qr_code_spi_link_transaction.input_buf + 2, 2); @@ -69,7 +69,7 @@ void qr_code_spi_link_periodic(void) static void qr_code_spi_link_trans_cb(struct spi_transaction *trans __attribute__((unused))) { - qr_code_spi_data_available = TRUE; + qr_code_spi_data_available = true; } diff --git a/sw/airborne/modules/hott/hott.c b/sw/airborne/modules/hott/hott.c index d603493ddc..f41ea9e4f2 100644 --- a/sw/airborne/modules/hott/hott.c +++ b/sw/airborne/modules/hott/hott.c @@ -51,20 +51,20 @@ #define HOTT_TELEMETRY_VARIO_SENSOR_ID 0x89 static uint32_t hott_event_timer; // 1ms software timer -static bool hott_telemetry_is_sending = FALSE; +static bool hott_telemetry_is_sending = false; static uint16_t hott_telemetry_sendig_msgs_id = 0; #if HOTT_SIM_GPS_SENSOR -bool HOTT_REQ_UPDATE_GPS = FALSE; +bool HOTT_REQ_UPDATE_GPS = false; #endif #if HOTT_SIM_EAM_SENSOR -bool HOTT_REQ_UPDATE_EAM = FALSE; +bool HOTT_REQ_UPDATE_EAM = false; #endif #if HOTT_SIM_VARIO_SENSOR -bool HOTT_REQ_UPDATE_VARIO = FALSE; +bool HOTT_REQ_UPDATE_VARIO = false; #endif #if HOTT_SIM_GAM_SENSOR -bool HOTT_REQ_UPDATE_GAM = FALSE; +bool HOTT_REQ_UPDATE_GAM = false; #endif // HoTT serial send buffer pointer @@ -132,28 +132,28 @@ void hott_periodic(void) if ((hott_telemetry_sendig_msgs_id != HOTT_TELEMETRY_EAM_SENSOR_ID) && HOTT_REQ_UPDATE_EAM == TRUE) { hott_update_eam_msg(&hott_eam_msg); - HOTT_REQ_UPDATE_EAM = FALSE; + HOTT_REQ_UPDATE_EAM = false; } #endif #if HOTT_SIM_GAM_SENSOR if ((hott_telemetry_sendig_msgs_id != HOTT_TELEMETRY_GAM_SENSOR_ID) && HOTT_REQ_UPDATE_GAM == TRUE) { hott_update_gam_msg(&hott_gam_msg); - HOTT_REQ_UPDATE_GAM = FALSE; + HOTT_REQ_UPDATE_GAM = false; } #endif #if HOTT_SIM_GPS_SENSOR if ((hott_telemetry_sendig_msgs_id != HOTT_TELEMETRY_GPS_SENSOR_ID) && HOTT_REQ_UPDATE_GPS == TRUE) { hott_update_gps_msg(&hott_gam_msg); - HOTT_REQ_UPDATE_GPS = FALSE; + HOTT_REQ_UPDATE_GPS = false; } #endif #if HOTT_SIM_VARIO_SENSOR if ((hott_telemetry_sendig_msgs_id != HOTT_TELEMETRY_VARIO_SENSOR_ID) && HOTT_REQ_UPDATE_VARIO == TRUE) { hott_update_vario_msg(&hott_gam_msg); - HOTT_REQ_UPDATE_VARIO = FALSE; + HOTT_REQ_UPDATE_VARIO = false; } #endif } @@ -170,13 +170,13 @@ static void hott_send_telemetry_data(void) { static int16_t msg_crc = 0; if (!hott_telemetry_is_sending) { - hott_telemetry_is_sending = TRUE; + hott_telemetry_is_sending = true; hott_enable_transmitter(); } if (hott_msg_len == 0) { hott_msg_ptr = 0; - hott_telemetry_is_sending = FALSE; + hott_telemetry_is_sending = false; hott_telemetry_sendig_msgs_id = 0; msg_crc = 0; hott_enable_receiver(); @@ -232,28 +232,28 @@ static void hott_check_serial_data(uint32_t tnow) #if HOTT_SIM_EAM_SENSOR if (addr == HOTT_TELEMETRY_EAM_SENSOR_ID) { hott_send_msg((int8_t *)&hott_eam_msg, sizeof(struct HOTT_EAM_MSG)); - HOTT_REQ_UPDATE_EAM = TRUE; + HOTT_REQ_UPDATE_EAM = true; break; } #endif #if HOTT_SIM_GAM_SENSOR if (addr == HOTT_TELEMETRY_GAM_SENSOR_ID) { hott_send_msg((int8_t *)&hott_gam_msg, sizeof(struct HOTT_GAM_MSG)); - HOTT_REQ_UPDATE_GAM = TRUE; + HOTT_REQ_UPDATE_GAM = true; break; } #endif #if HOTT_SIM_GPS_SENSOR if (addr == HOTT_TELEMETRY_GPS_SENSOR_ID) { hott_send_msg((int8_t *)&hott_gps_msg, sizeof(struct HOTT_GPS_MSG)); - HOTT_REQ_UPDATE_GPS = TRUE; + HOTT_REQ_UPDATE_GPS = true; break; } #endif #if HOTT_SIM_VARIO_SENSOR if (addr == HOTT_TELEMETRY_VARIO_SENSOR_ID) { hott_send_msg((int8_t *)&hott_vario_msg, sizeof(struct HOTT_VARIO_MSG)); - HOTT_REQ_UPDATE_VARIO = TRUE; + HOTT_REQ_UPDATE_VARIO = true; break; } #endif diff --git a/sw/airborne/modules/ins/ahrs_chimu_spi.c b/sw/airborne/modules/ins/ahrs_chimu_spi.c index 21ee99e57d..f5edc7fd15 100644 --- a/sw/airborne/modules/ins/ahrs_chimu_spi.c +++ b/sw/airborne/modules/ins/ahrs_chimu_spi.c @@ -70,8 +70,8 @@ void ahrs_chimu_register(void) void ahrs_chimu_init(void) { - ahrs_chimu.is_enabled = TRUE; - ahrs_chimu.is_aligned = FALSE; + ahrs_chimu.is_enabled = true; + ahrs_chimu.is_aligned = false; // uint8_t ping[7] = {CHIMU_STX, CHIMU_STX, 0x01, CHIMU_BROADCAST, MSG00_PING, 0x00, 0xE6 }; uint8_t rate[12] = {CHIMU_STX, CHIMU_STX, 0x06, CHIMU_BROADCAST, MSG10_UARTSETTINGS, 0x05, 0xff, 0x79, 0x00, 0x00, 0x01, 0x76 }; // 50Hz attitude only + SPI @@ -120,7 +120,7 @@ void parse_ins_msg(void) } //FIXME - ahrs_chimu.is_aligned = TRUE; + ahrs_chimu.is_aligned = true; if (ahrs_chimu.is_enabled) { struct FloatEulers att = { diff --git a/sw/airborne/modules/ins/ahrs_chimu_uart.c b/sw/airborne/modules/ins/ahrs_chimu_uart.c index 22d042cb89..c1b16891bd 100644 --- a/sw/airborne/modules/ins/ahrs_chimu_uart.c +++ b/sw/airborne/modules/ins/ahrs_chimu_uart.c @@ -46,8 +46,8 @@ void ahrs_chimu_register(void) void ahrs_chimu_init(void) { - ahrs_chimu.is_enabled = TRUE; - ahrs_chimu.is_aligned = FALSE; + ahrs_chimu.is_enabled = true; + ahrs_chimu.is_aligned = false; uint8_t ping[7] = {CHIMU_STX, CHIMU_STX, 0x01, CHIMU_BROADCAST, MSG00_PING, 0x00, 0xE6 }; uint8_t rate[12] = {CHIMU_STX, CHIMU_STX, 0x06, CHIMU_BROADCAST, MSG10_UARTSETTINGS, 0x05, 0xff, 0x79, 0x00, 0x00, 0x01, 0x76 }; // 50Hz attitude only + SPI @@ -92,7 +92,7 @@ void parse_ins_msg(void) CHIMU_DATA.m_attitude.euler.phi -= 2 * M_PI; } - ahrs_chimu.is_aligned = TRUE; + ahrs_chimu.is_aligned = true; if (ahrs_chimu.is_enabled) { struct FloatEulers att = { diff --git a/sw/airborne/modules/ins/imu_chimu.c b/sw/airborne/modules/ins/imu_chimu.c index bcbb09f530..2b6c77d7ff 100644 --- a/sw/airborne/modules/ins/imu_chimu.c +++ b/sw/airborne/modules/ins/imu_chimu.c @@ -153,7 +153,7 @@ unsigned char CHIMU_Parse( CHIMU_PARSER_DATA *pstData) /* resulting data */ { - char bUpdate = FALSE; + unsigned char bUpdate = 0; switch (pstData->m_State) { case CHIMU_STATE_MACHINE_START: // Waiting for start character 0xAE @@ -164,7 +164,7 @@ unsigned char CHIMU_Parse( } else { ;; } - bUpdate = FALSE; + bUpdate = 0; break; case CHIMU_STATE_MACHINE_HEADER2: // Waiting for second header character 0xAE if (btData == 0xAE) { @@ -214,14 +214,14 @@ unsigned char CHIMU_Parse( (unsigned long)(pstData->m_MsgLen) + 5)) & 0xFF); pstData->m_State = CHIMU_STATE_MACHINE_XSUM; } else { - return FALSE; + return 0; } break; case CHIMU_STATE_MACHINE_XSUM: // Verify pstData->m_ReceivedChecksum = btData; pstData->m_FullMessage[pstData->m_Index++] = btData; if (pstData->m_Checksum != pstData->m_ReceivedChecksum) { - bUpdate = FALSE; + bUpdate = 0; //BuiltInTest(BIT_COM_UART_RECEIPTFAIL, BIT_FAIL); } else { //Xsum passed, go parse it. @@ -283,7 +283,7 @@ static CHIMU_attitude_data GetEulersFromQuat(CHIMU_attitude_data attitude) static unsigned char BitTest(unsigned char input, unsigned char n) { //Test a bit in n and return TRUE or FALSE - if (input & (1 << n)) { return TRUE; } else { return FALSE; } + if (input & (1 << n)) { return 1; } else { return 0; } } unsigned char CHIMU_ProcessMessage(unsigned char *pMsgID __attribute__((unused)), unsigned char *pPayloadData, CHIMU_PARSER_DATA *pstData) @@ -307,7 +307,7 @@ unsigned char CHIMU_ProcessMessage(unsigned char *pMsgID __attribute__((unused)) pstData->gCHIMU_SW_SerialNumber = (pPayloadData[CHIMU_index] << 8) & (0x0000FF00); CHIMU_index++; pstData->gCHIMU_SW_SerialNumber += pPayloadData[CHIMU_index]; CHIMU_index++; - return TRUE; + return 1; break; case CHIMU_Msg_1_IMU_Raw: break; @@ -334,7 +334,7 @@ unsigned char CHIMU_ProcessMessage(unsigned char *pMsgID __attribute__((unused)) memmove(&pstData->m_sensor.spare1, &pPayloadData[CHIMU_index], sizeof(pstData->m_sensor.spare1)); CHIMU_index += (sizeof(pstData->m_sensor.spare1)); pstData->m_sensor.spare1 = FloatSwap(pstData->m_sensor.spare1); - return TRUE; + return 1; break; case CHIMU_Msg_3_IMU_Attitude: //Attitude message data from CHIMU @@ -410,7 +410,7 @@ unsigned char CHIMU_ProcessMessage(unsigned char *pMsgID __attribute__((unused)) //TODO: Log BIT that indicates IMU message incoming failed (maybe SPI error?) } - return TRUE; + return 1; break; case CHIMU_Msg_4_BiasSF: case CHIMU_Msg_5_BIT: @@ -426,8 +426,8 @@ unsigned char CHIMU_ProcessMessage(unsigned char *pMsgID __attribute__((unused)) case CHIMU_Msg_15_SFCheck: break; default: - return FALSE; + return 0; break; } - return FALSE; + return 0; } diff --git a/sw/airborne/modules/ins/ins_arduimu.c b/sw/airborne/modules/ins/ins_arduimu.c index 42f06aaa25..d1e661a890 100644 --- a/sw/airborne/modules/ins/ins_arduimu.c +++ b/sw/airborne/modules/ins/ins_arduimu.c @@ -55,10 +55,10 @@ void ArduIMU_init(void) ardu_gps_trans.buf[0] = 0; ardu_gps_trans.buf[1] = 0; messageNr = 0; - imu_daten_angefordert = FALSE; - gps_daten_abgespeichert = FALSE; - gps_daten_versendet_msg1 = FALSE; - gps_daten_versendet_msg2 = FALSE; + imu_daten_angefordert = false; + gps_daten_abgespeichert = false; + gps_daten_versendet_msg1 = false; + gps_daten_versendet_msg2 = false; ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT; ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT; // pitch_of_throttle_gain = PITCH_OF_THROTTLE_GAIN; @@ -70,7 +70,7 @@ void ArduIMU_periodicGPS(void) { if (gps_daten_versendet_msg1 == TRUE && gps_daten_versendet_msg2 == TRUE) { - gps_daten_abgespeichert = FALSE; + gps_daten_abgespeichert = false; } if (imu_daten_angefordert == TRUE) { @@ -97,7 +97,7 @@ void ArduIMU_periodicGPS(void) GPS_Data [12] = -gps.ned_vel.z; GPS_Data [13] = gps.num_sv; - gps_daten_abgespeichert = TRUE; + gps_daten_abgespeichert = true; } if (messageNr == 0) { @@ -136,7 +136,7 @@ void ArduIMU_periodicGPS(void) ardu_gps_trans.buf[28] = (uint8_t)(GPS_Data[6] >> 24); i2c_transmit(&ARDUIMU_I2C_DEV, &ardu_gps_trans, ArduIMU_SLAVE_ADDR, 28); - gps_daten_versendet_msg1 = TRUE; + gps_daten_versendet_msg1 = true; messageNr = 1; } else { @@ -156,7 +156,7 @@ void ArduIMU_periodicGPS(void) ardu_gps_trans.buf[13] = GPS_Data[11]; //sol flags i2c_transmit(&ARDUIMU_I2C_DEV, &ardu_gps_trans, ArduIMU_SLAVE_ADDR, 13); - gps_daten_versendet_msg2 = TRUE; + gps_daten_versendet_msg2 = true; messageNr = 0; } @@ -173,7 +173,7 @@ void ArduIMU_periodic(void) } i2c_receive(&ARDUIMU_I2C_DEV, &ardu_ins_trans, ArduIMU_SLAVE_ADDR, 12); - imu_daten_angefordert = TRUE; + imu_daten_angefordert = true; /* Buffer O: Roll Buffer 1: Pitch @@ -213,7 +213,7 @@ void IMU_Daten_verarbeiten(void) att.phi = (float)ArduIMU_data[0] * 0.01745329252 - ins_roll_neutral; att.theta = (float)ArduIMU_data[1] * 0.01745329252 - ins_pitch_neutral; att.psi = 0.; - imu_daten_angefordert = FALSE; + imu_daten_angefordert = false; stateSetNedToBodyEulers_f(&att); uint8_t arduimu_id = 102; diff --git a/sw/airborne/modules/ins/ins_arduimu_basic.c b/sw/airborne/modules/ins/ins_arduimu_basic.c index 1aa526a1f8..9a73b40479 100644 --- a/sw/airborne/modules/ins/ins_arduimu_basic.c +++ b/sw/airborne/modules/ins/ins_arduimu_basic.c @@ -89,10 +89,10 @@ void ArduIMU_init(void) ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT; ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT; - arduimu_calibrate_neutrals = FALSE; + arduimu_calibrate_neutrals = false; - high_accel_done = FALSE; - high_accel_flag = FALSE; + high_accel_done = false; + high_accel_flag = false; } #define FillBufWith32bit(_buf, _index, _value) { \ @@ -113,14 +113,14 @@ void ArduIMU_periodicGPS(void) // - high thrust float speed = stateGetHorizontalSpeedNorm_f(); if (speed < HIGH_ACCEL_LOW_SPEED && ap_state->commands[COMMAND_THROTTLE] > HIGH_ACCEL_HIGH_THRUST && !high_accel_done) { - high_accel_flag = TRUE; + high_accel_flag = true; } else { - high_accel_flag = FALSE; + high_accel_flag = false; if (speed > HIGH_ACCEL_LOW_SPEED && !high_accel_done) { - high_accel_done = TRUE; // After takeoff, don't use high accel before landing (GS small, Throttle small) + high_accel_done = true; // After takeoff, don't use high accel before landing (GS small, Throttle small) } if (speed < HIGH_ACCEL_HIGH_THRUST_RESUME && ap_state->commands[COMMAND_THROTTLE] < HIGH_ACCEL_HIGH_THRUST_RESUME) { - high_accel_done = FALSE; // Activate high accel after landing + high_accel_done = false; // Activate high accel after landing } } #endif @@ -135,7 +135,7 @@ void ArduIMU_periodicGPS(void) i2c_transmit(&ARDUIMU_I2C_DEV, &ardu_gps_trans, ArduIMU_SLAVE_ADDR, 15); // Reset calibration flag - if (arduimu_calibrate_neutrals) { arduimu_calibrate_neutrals = FALSE; } + if (arduimu_calibrate_neutrals) { arduimu_calibrate_neutrals = false; } } void ArduIMU_periodic(void) diff --git a/sw/airborne/modules/ins/ins_module.h b/sw/airborne/modules/ins/ins_module.h index bfb01dfad0..86a724eb26 100644 --- a/sw/airborne/modules/ins/ins_module.h +++ b/sw/airborne/modules/ins/ins_module.h @@ -97,7 +97,7 @@ static inline void ins_event_check_and_handle(void (* handler)(void)) if (ins_msg_received) { parse_ins_msg(); handler(); - ins_msg_received = FALSE; + ins_msg_received = false; } } diff --git a/sw/airborne/modules/ins/ins_vn100.c b/sw/airborne/modules/ins/ins_vn100.c index 3ba8db0750..3a6fd7e349 100644 --- a/sw/airborne/modules/ins/ins_vn100.c +++ b/sw/airborne/modules/ins/ins_vn100.c @@ -128,13 +128,13 @@ static inline bool ins_configure(void) ins_init_status++; break; case INS_VN100_READY : - return TRUE; + return true; } last_send_packet.CmdID = VN100_CmdID_WriteRegister; spi_submit(&(VN100_SPI_DEV), &vn100_trans); - return FALSE; + return false; } void vn100_periodic_task(void) diff --git a/sw/airborne/modules/ins/ins_xsens.c b/sw/airborne/modules/ins/ins_xsens.c index 33feafd5ad..b8f709d3bf 100644 --- a/sw/airborne/modules/ins/ins_xsens.c +++ b/sw/airborne/modules/ins/ins_xsens.c @@ -85,7 +85,7 @@ void ins_xsens_event(void) if (xsens.msg_received) { parse_xsens_msg(); handle_ins_msg(); - xsens.msg_received = FALSE; + xsens.msg_received = false; } } @@ -162,8 +162,8 @@ static void handle_ins_msg(void) update_state_interface(); if (xsens.new_attitude) { - new_ins_attitude = TRUE; - xsens.new_attitude = FALSE; + new_ins_attitude = true; + xsens.new_attitude = false; } #if USE_GPS_XSENS @@ -181,7 +181,7 @@ static void handle_ins_msg(void) SetBit(xsens.gps.valid_fields, GPS_VALID_COURSE_BIT); gps_xsens_publish(); - xsens.gps_available = FALSE; + xsens.gps_available = false; } #endif // USE_GPS_XSENS } diff --git a/sw/airborne/modules/ins/ins_xsens700.c b/sw/airborne/modules/ins/ins_xsens700.c index 0f10a185e2..1ead510db0 100644 --- a/sw/airborne/modules/ins/ins_xsens700.c +++ b/sw/airborne/modules/ins/ins_xsens700.c @@ -88,7 +88,7 @@ void ins_xsens700_event(void) if (xsens700.msg_received) { parse_xsens700_msg(); handle_ins_msg(); - xsens700.msg_received = FALSE; + xsens700.msg_received = false; } } @@ -170,8 +170,8 @@ void handle_ins_msg(void) update_state_interface(); if (xsens700.new_attitude) { - new_ins_attitude = TRUE; - xsens700.new_attitude = FALSE; + new_ins_attitude = true; + xsens700.new_attitude = false; } #if USE_GPS_XSENS @@ -189,7 +189,7 @@ void handle_ins_msg(void) SetBit(xsens700.gps.valid_fields, GPS_VALID_COURSE_BIT); gps_xsens700_publish(); - xsens700.gps_available = FALSE; + xsens700.gps_available = false; } #endif // USE_GPS_XSENS } diff --git a/sw/airborne/modules/loggers/high_speed_logger_direct_memory.c b/sw/airborne/modules/loggers/high_speed_logger_direct_memory.c index cbae93c878..97c06491b9 100644 --- a/sw/airborne/modules/loggers/high_speed_logger_direct_memory.c +++ b/sw/airborne/modules/loggers/high_speed_logger_direct_memory.c @@ -168,7 +168,7 @@ uint32_t current_unerased_addr = 0x00000000; ///The address at wich we will read next time uint32_t current_reading_addr = 0x00000000; ///Flag stating if the memory is being used -static volatile bool memory_ready = TRUE; +static volatile bool memory_ready = true; ///Structure used for general comunication with the memory struct spi_transaction memory_transaction; ///Structure used for sending values to the memory @@ -200,7 +200,7 @@ static void memory_read_values_cb(struct spi_transaction *trans); void memory_read_id(void) { - memory_ready = FALSE; + memory_ready = false; msg[0] = 0x9F; memory_transaction.output_buf = (uint8_t *) msg; @@ -219,7 +219,7 @@ void memory_read_id(void) */ void memory_send_wren(void) { - memory_ready = FALSE; + memory_ready = false; msg[0] = 0x06; memory_transaction.output_buf = (uint8_t *) msg; @@ -238,7 +238,7 @@ void memory_send_wren(void) */ void memory_send_wrdi(void) { - memory_ready = FALSE; + memory_ready = false; msg[0] = 0x04; memory_transaction.output_buf = (uint8_t *) msg; @@ -257,7 +257,7 @@ void memory_send_wrdi(void) */ void memory_read_status_1(void) { - memory_ready = FALSE; + memory_ready = false; msg[0] = 0x05; memory_transaction.output_buf = (uint8_t *) msg; @@ -279,7 +279,7 @@ void memory_read_status_1(void) static void memory_read_status_cb(struct spi_transaction *trans __attribute__((unused))) { - memory_ready = TRUE; + memory_ready = true; memory_status_byte = buff[1]; wait_answear_from_reading_memory = 0; @@ -295,7 +295,7 @@ void memory_erase_4k(uint32_t mem_addr) uint8_t *addr = (uint8_t *) &mem_addr; - memory_ready = FALSE; + memory_ready = false; msg[0] = 0x21; msg[1] = addr[3]; msg[2] = addr[2]; @@ -319,7 +319,7 @@ void memory_erase_4k(uint32_t mem_addr) void memory_completly_erase(void) { - memory_ready = FALSE; + memory_ready = false; msg[0] = 0xC7; memory_transaction.output_buf = (uint8_t *) msg; @@ -346,7 +346,7 @@ void memory_write_values(uint32_t mem_addr, uint8_t *values, uint8_t size) uint8_t *addr = (uint8_t *) &mem_addr; uint8_t i; - memory_ready = FALSE; + memory_ready = false; values_send_buffer[0] = 0x12; values_send_buffer[1] = addr[3]; values_send_buffer[2] = addr[2]; @@ -379,7 +379,7 @@ void memory_read_values(uint32_t mem_addr, uint8_t size) uint8_t *addr = (uint8_t *) &mem_addr; - memory_ready = FALSE; + memory_ready = false; msg[0] = 0x13; msg[1] = addr[3]; msg[2] = addr[2]; @@ -408,7 +408,7 @@ static void memory_read_values_cb(struct spi_transaction *trans __attribute__((u uint8_t msg_size = memory_transaction.input_length; - memory_ready = TRUE; + memory_ready = true; if (msg_size) { @@ -434,7 +434,7 @@ static void memory_read_values_cb(struct spi_transaction *trans __attribute__((u */ static void memory_transaction_done_cb(struct spi_transaction *trans __attribute__((unused))) { - memory_ready = TRUE; + memory_ready = true; } diff --git a/sw/airborne/modules/loggers/high_speed_logger_spi_link.c b/sw/airborne/modules/loggers/high_speed_logger_spi_link.c index 1307acddca..523c1533b6 100644 --- a/sw/airborne/modules/loggers/high_speed_logger_spi_link.c +++ b/sw/airborne/modules/loggers/high_speed_logger_spi_link.c @@ -28,7 +28,7 @@ struct high_speed_logger_spi_link_data high_speed_logger_spi_link_data; struct spi_transaction high_speed_logger_spi_link_transaction; -static volatile bool high_speed_logger_spi_link_ready = TRUE; +static volatile bool high_speed_logger_spi_link_ready = true; static void high_speed_logger_spi_link_trans_cb(struct spi_transaction *trans); @@ -54,7 +54,7 @@ void high_speed_logger_spi_link_init(void) void high_speed_logger_spi_link_periodic(void) { if (high_speed_logger_spi_link_ready) { - high_speed_logger_spi_link_ready = FALSE; + high_speed_logger_spi_link_ready = false; high_speed_logger_spi_link_data.gyro_p = imu.gyro_unscaled.p; high_speed_logger_spi_link_data.gyro_q = imu.gyro_unscaled.q; high_speed_logger_spi_link_data.gyro_r = imu.gyro_unscaled.r; @@ -73,7 +73,7 @@ void high_speed_logger_spi_link_periodic(void) static void high_speed_logger_spi_link_trans_cb(struct spi_transaction *trans __attribute__((unused))) { - high_speed_logger_spi_link_ready = TRUE; + high_speed_logger_spi_link_ready = true; } diff --git a/sw/airborne/modules/loggers/sdlogger_spi_direct.c b/sw/airborne/modules/loggers/sdlogger_spi_direct.c index 8ed873e074..22092fb2bc 100644 --- a/sw/airborne/modules/loggers/sdlogger_spi_direct.c +++ b/sw/airborne/modules/loggers/sdlogger_spi_direct.c @@ -349,10 +349,10 @@ bool sdlogger_spi_direct_check_free_space(struct sdlogger_spi_periph *p, uint8_t if (p->status == SDLogger_Logging) { /* Calculating free space in both buffers */ if ( (513 - p->sdcard_buf_idx) + (SDLOGGER_BUFFER_SIZE - p->idx) >= len) { - return TRUE; + return true; } } - return FALSE; + return false; } void sdlogger_spi_direct_put_byte(struct sdlogger_spi_periph *p, uint8_t data) diff --git a/sw/airborne/modules/meteo/humid_sht.c b/sw/airborne/modules/meteo/humid_sht.c index 2c1a7f34f3..17c49496ff 100644 --- a/sw/airborne/modules/meteo/humid_sht.c +++ b/sw/airborne/modules/meteo/humid_sht.c @@ -305,11 +305,11 @@ void humid_sht_init(void) gpio_clear(SHT_SCK_GPIO); - humid_sht_available = FALSE; + humid_sht_available = false; humid_sht_status = SHT_IDLE; #if SHT_SDLOG - log_sht_started = FALSE; + log_sht_started = false; #endif } @@ -345,18 +345,18 @@ void humid_sht_periodic(void) //LED_TOGGLE(2); } else { calc_sht(humidsht, tempsht, &fhumidsht, &ftempsht); - humid_sht_available = TRUE; + humid_sht_available = true; s_connectionreset(); s_start_measure(HUMI); humid_sht_status = SHT_MEASURING_HUMID; DOWNLINK_SEND_SHT_STATUS(DefaultChannel, DefaultDevice, &humidsht, &tempsht, &fhumidsht, &ftempsht); - humid_sht_available = FALSE; + humid_sht_available = false; #if SHT_SDLOG if (pprzLogFile != -1) { if (!log_sht_started) { sdLogWriteLog(pprzLogFile, "SHT75: Humid(pct) Temp(degC) GPS_fix TOW(ms) Week Lat(1e7deg) Lon(1e7deg) HMSL(mm) gspeed(cm/s) course(1e7deg) climb(cm/s)\n"); - log_sht_started = TRUE; + log_sht_started = true; } sdLogWriteLog(pprzLogFile, "sht75: %9.4f %9.4f %d %d %d %d %d %d %d %d %d\n", fhumidsht, ftempsht, diff --git a/sw/airborne/modules/meteo/meteo_france_DAQ.c b/sw/airborne/modules/meteo/meteo_france_DAQ.c index d7b9c21c53..872b991e1d 100644 --- a/sw/airborne/modules/meteo/meteo_france_DAQ.c +++ b/sw/airborne/modules/meteo/meteo_france_DAQ.c @@ -62,7 +62,7 @@ void init_mf_daq(void) gpio_setup_output(MF_DAQ_POWER_PORT, MF_DAQ_POWER_PIN); #endif meteo_france_DAQ_SetPower(mf_daq.power); - log_started = FALSE; + log_started = false; } void mf_daq_send_state(void) @@ -100,7 +100,7 @@ void mf_daq_send_report(void) if (log_started == FALSE) { // Log MD5SUM once DOWNLINK_SEND_ALIVE(pprzlog_tp, chibios_sdlog, 16, MD5SUM); - log_started = TRUE; + log_started = true; } // Log GPS for time reference uint8_t foo = 0; diff --git a/sw/airborne/modules/meteo/meteo_stick.c b/sw/airborne/modules/meteo/meteo_stick.c index 05dc634710..0aa864a4c1 100644 --- a/sw/airborne/modules/meteo/meteo_stick.c +++ b/sw/airborne/modules/meteo/meteo_stick.c @@ -216,7 +216,7 @@ void meteo_stick_init(void) // Init absolute pressure meteo_stick.pressure.config.mux = ADS1220_MUX_AIN0_AVSS; meteo_stick.pressure.config.gain = ADS1220_GAIN_1; - meteo_stick.pressure.config.pga_bypass = TRUE; + meteo_stick.pressure.config.pga_bypass = true; meteo_stick.pressure.config.rate = ADS1220_RATE_45_HZ; meteo_stick.pressure.config.conv = ADS1220_CONTINIOUS_CONVERSION; meteo_stick.pressure.config.vref = ADS1220_VREF_VDD; @@ -230,7 +230,7 @@ void meteo_stick_init(void) // Init differential pressure meteo_stick.diff_pressure.config.mux = ADS1220_MUX_AIN0_AVSS; meteo_stick.diff_pressure.config.gain = ADS1220_GAIN_2; - meteo_stick.diff_pressure.config.pga_bypass = TRUE; + meteo_stick.diff_pressure.config.pga_bypass = true; meteo_stick.diff_pressure.config.rate = ADS1220_RATE_45_HZ; meteo_stick.diff_pressure.config.conv = ADS1220_CONTINIOUS_CONVERSION; meteo_stick.diff_pressure.config.vref = ADS1220_VREF_VDD; @@ -244,7 +244,7 @@ void meteo_stick_init(void) // Init temperature meteo_stick.temperature.config.mux = ADS1220_MUX_AIN0_AIN1; meteo_stick.temperature.config.gain = ADS1220_GAIN_4; - meteo_stick.temperature.config.pga_bypass = TRUE; + meteo_stick.temperature.config.pga_bypass = true; meteo_stick.temperature.config.rate = ADS1220_RATE_45_HZ; meteo_stick.temperature.config.conv = ADS1220_CONTINIOUS_CONVERSION; meteo_stick.temperature.config.vref = ADS1220_VREF_EXTERNAL_REF; @@ -275,10 +275,10 @@ void meteo_stick_init(void) // Number of measurements before setting pitot offset pitot_counter = MS_PITOT_COUNTER; - meteo_stick.reset_dp_offset = FALSE; + meteo_stick.reset_dp_offset = false; #if LOG_MS - log_ptu_started = FALSE; + log_ptu_started = false; #endif } @@ -348,12 +348,12 @@ void meteo_stick_periodic(void) sdLogWriteLog(pprzLogFile, "#\n"); sdLogWriteLog(pprzLogFile, "P(adc) T(adc) H(ticks) P_diff(adc) P(hPa) T(C) H(\%) CAS(m/s) FIX TOW(ms) WEEK Lat(1e7rad) Lon(1e7rad) HMSL(mm) GS(cm/s) course(1e7rad) VZ(cm/s)\n"); - log_ptu_started = TRUE; + log_ptu_started = true; } #else sdLogWriteLog(pprzLogFile, "P(adc) T(adc) H(ticks) P_diff(adc) P(hPa) T(C) H(\%) CAS(m/s) FIX TOW(ms) WEEK Lat(1e7rad) Lon(1e7rad) HMSL(mm) GS(cm/s) course(1e7rad) VZ(cm/s)\n"); - log_ptu_started = TRUE; + log_ptu_started = true; #endif } else { sdLogWriteLog(pprzLogFile, "%d %d %d %d %.2f %.2f %.2f %.2f %d %d %d %d %d %d %d %d %d\n", @@ -376,7 +376,7 @@ void meteo_stick_periodic(void) // Check if DP offset reset is required if (meteo_stick.reset_dp_offset) { pitot_counter = MS_PITOT_COUNTER; - meteo_stick.reset_dp_offset = FALSE; + meteo_stick.reset_dp_offset = false; } } @@ -401,7 +401,7 @@ void meteo_stick_event(void) #if USE_MS_PRESSURE AbiSendMsgBARO_ABS(METEO_STICK_SENDER_ID, meteo_stick.current_pressure); #endif - meteo_stick.pressure.data_available = FALSE; + meteo_stick.pressure.data_available = false; } #endif @@ -423,7 +423,7 @@ void meteo_stick_event(void) AbiSendMsgBARO_DIFF(METEO_STICK_SENDER_ID, diff); #endif meteo_stick.current_airspeed = get_pitot(meteo_stick.diff_pressure.data); - meteo_stick.diff_pressure.data_available = FALSE; + meteo_stick.diff_pressure.data_available = false; } } #endif @@ -435,7 +435,7 @@ void meteo_stick_event(void) #if USE_MS_TEMPERATURE AbiSendMsgTEMPERATURE(METEO_STICK_SENDER_ID, meteo_stick.current_temperature); #endif - meteo_stick.temperature.data_available = FALSE; + meteo_stick.temperature.data_available = false; } #endif diff --git a/sw/airborne/modules/meteo/mf_ptu.c b/sw/airborne/modules/meteo/mf_ptu.c index f34bfe9809..333f53092f 100644 --- a/sw/airborne/modules/meteo/mf_ptu.c +++ b/sw/airborne/modules/meteo/mf_ptu.c @@ -89,7 +89,7 @@ void mf_ptu_init(void) humid_period = 0; #if LOG_PTU - log_ptu_started = FALSE; + log_ptu_started = false; #endif } @@ -107,7 +107,7 @@ void mf_ptu_periodic(void) if (!log_ptu_started) { sdLogWriteLog(pprzLogFile, "P(adc) T(adc) H(usec) GPS_fix TOW(ms) Week Lat(1e7rad) Lon(1e7rad) HMSL(mm) gpseed(cm/s) course(1e7rad) climb(cm/s)\n"); - log_ptu_started = TRUE; + log_ptu_started = true; } else { sdLogWriteLog(pprzLogFile, "%d %d %d %d %d %d %d %d %d %d %d %d\n", pressure_adc, temp_adc, humid_period, diff --git a/sw/airborne/modules/meteo/temp_temod.c b/sw/airborne/modules/meteo/temp_temod.c index b60875ffa1..bfa9d6e0ec 100644 --- a/sw/airborne/modules/meteo/temp_temod.c +++ b/sw/airborne/modules/meteo/temp_temod.c @@ -60,7 +60,7 @@ void temod_init(void) tmd_trans.status = I2CTransDone; #if TEMP_TEMOD_SDLOG - log_temod_started = FALSE; + log_temod_started = false; #endif } @@ -91,7 +91,7 @@ void temod_event(void) if (pprzLogFile != -1) { if (!log_temod_started) { sdLogWriteLog(pprzLogFile, "TEMOD: Temp(degC) GPS_fix TOW(ms) Week Lat(1e7deg) Lon(1e7deg) HMSL(mm) gspeed(cm/s) course(1e7deg) climb(cm/s)\n"); - log_temod_started = TRUE; + log_temod_started = true; } else { sdLogWriteLog(pprzLogFile, "temod: %9.4f %d %d %d %d %d %d %d %d %d\n", diff --git a/sw/airborne/modules/meteo/temp_tmp102.c b/sw/airborne/modules/meteo/temp_tmp102.c index 2a98612b59..cc2edcf220 100644 --- a/sw/airborne/modules/meteo/temp_tmp102.c +++ b/sw/airborne/modules/meteo/temp_tmp102.c @@ -62,7 +62,7 @@ struct i2c_transaction tmp_trans; void tmp102_init(void) { - tmp_meas_started = FALSE; + tmp_meas_started = false; /* configure 8Hz and enhanced mode */ tmp_trans.buf[0] = TMP102_CONF_REG; tmp_trans.buf[1] = TMP102_CONF1; @@ -74,7 +74,7 @@ void tmp102_periodic(void) { tmp_trans.buf[0] = TMP102_TEMP_REG; i2c_transceive(&TMP_I2C_DEV, &tmp_trans, TMP102_SLAVE_ADDR, 1, 2); - tmp_meas_started = TRUE; + tmp_meas_started = true; } void tmp102_event(void) diff --git a/sw/airborne/modules/meteo/windturbine.c b/sw/airborne/modules/meteo/windturbine.c index c7d8c7a5a1..57c841e6f4 100644 --- a/sw/airborne/modules/meteo/windturbine.c +++ b/sw/airborne/modules/meteo/windturbine.c @@ -53,7 +53,7 @@ void windturbine_periodic(void) &turb_id, &sync_itow, &cycle_time); - trigger_ext_valid = FALSE; + trigger_ext_valid = false; } } diff --git a/sw/airborne/modules/mission/mission_common.c b/sw/airborne/modules/mission/mission_common.c index 4a9bf692c6..e7ce945802 100644 --- a/sw/airborne/modules/mission/mission_common.c +++ b/sw/airborne/modules/mission/mission_common.c @@ -48,19 +48,19 @@ bool mission_insert(enum MissionInsertMode insert, struct _mission_element *elem { uint8_t tmp; // convert element if needed, return FALSE if failed - if (!mission_element_convert(element)) { return FALSE; } + if (!mission_element_convert(element)) { return false; } switch (insert) { case Append: tmp = (mission.insert_idx + 1) % MISSION_ELEMENT_NB; - if (tmp == mission.current_idx) { return FALSE; } // no room to insert element + if (tmp == mission.current_idx) { return false; } // no room to insert element mission.elements[mission.insert_idx] = *element; // add element mission.insert_idx = tmp; // move insert index break; case Prepend: if (mission.current_idx == 0) { tmp = MISSION_ELEMENT_NB - 1; } else { tmp = mission.current_idx - 1; } - if (tmp == mission.insert_idx) { return FALSE; } // no room to inser element + if (tmp == mission.insert_idx) { return false; } // no room to inser element mission.elements[tmp] = *element; // add element mission.current_idx = tmp; // move current index break; @@ -76,15 +76,15 @@ bool mission_insert(enum MissionInsertMode insert, struct _mission_element *elem break; default: // unknown insertion mode - return FALSE; + return false; } - return TRUE; + return true; } // Weak implementation of mission_element_convert (leave element unchanged) -bool __attribute__((weak)) mission_element_convert(struct _mission_element *el __attribute__((unused))) { return TRUE; } +bool __attribute__((weak)) mission_element_convert(struct _mission_element *el __attribute__((unused))) { return true; } // Get element @@ -125,7 +125,7 @@ void mission_status_report(void) int mission_parse_GOTO_WP(void) { - if (DL_MISSION_GOTO_WP_ac_id(dl_buffer) != AC_ID) { return FALSE; } // not for this aircraft + if (DL_MISSION_GOTO_WP_ac_id(dl_buffer) != AC_ID) { return false; } // not for this aircraft struct _mission_element me; me.type = MissionWP; @@ -141,7 +141,7 @@ int mission_parse_GOTO_WP(void) int mission_parse_GOTO_WP_LLA(void) { - if (DL_MISSION_GOTO_WP_LLA_ac_id(dl_buffer) != AC_ID) { return FALSE; } // not for this aircraft + if (DL_MISSION_GOTO_WP_LLA_ac_id(dl_buffer) != AC_ID) { return false; } // not for this aircraft struct LlaCoor_i lla; lla.lat = DL_MISSION_GOTO_WP_LLA_wp_lat(dl_buffer); @@ -151,7 +151,7 @@ int mission_parse_GOTO_WP_LLA(void) struct _mission_element me; me.type = MissionWP; // if there is no valid local coordinate, do not insert mission element - if (!mission_point_of_lla(&me.element.mission_wp.wp.wp_f, &lla)) { return FALSE; } + if (!mission_point_of_lla(&me.element.mission_wp.wp.wp_f, &lla)) { return false; } me.duration = DL_MISSION_GOTO_WP_LLA_duration(dl_buffer); enum MissionInsertMode insert = (enum MissionInsertMode)(DL_MISSION_GOTO_WP_LLA_insert(dl_buffer)); @@ -161,7 +161,7 @@ int mission_parse_GOTO_WP_LLA(void) int mission_parse_CIRCLE(void) { - if (DL_MISSION_CIRCLE_ac_id(dl_buffer) != AC_ID) { return FALSE; } // not for this aircraft + if (DL_MISSION_CIRCLE_ac_id(dl_buffer) != AC_ID) { return false; } // not for this aircraft struct _mission_element me; me.type = MissionCircle; @@ -178,7 +178,7 @@ int mission_parse_CIRCLE(void) int mission_parse_CIRCLE_LLA(void) { - if (DL_MISSION_CIRCLE_LLA_ac_id(dl_buffer) != AC_ID) { return FALSE; } // not for this aircraft + if (DL_MISSION_CIRCLE_LLA_ac_id(dl_buffer) != AC_ID) { return false; } // not for this aircraft struct LlaCoor_i lla; lla.lat = DL_MISSION_CIRCLE_LLA_center_lat(dl_buffer); @@ -188,7 +188,7 @@ int mission_parse_CIRCLE_LLA(void) struct _mission_element me; me.type = MissionCircle; // if there is no valid local coordinate, do not insert mission element - if (!mission_point_of_lla(&me.element.mission_circle.center.center_f, &lla)) { return FALSE; } + if (!mission_point_of_lla(&me.element.mission_circle.center.center_f, &lla)) { return false; } me.element.mission_circle.radius = DL_MISSION_CIRCLE_LLA_radius(dl_buffer); me.duration = DL_MISSION_CIRCLE_LLA_duration(dl_buffer); @@ -199,7 +199,7 @@ int mission_parse_CIRCLE_LLA(void) int mission_parse_SEGMENT(void) { - if (DL_MISSION_SEGMENT_ac_id(dl_buffer) != AC_ID) { return FALSE; } // not for this aircraft + if (DL_MISSION_SEGMENT_ac_id(dl_buffer) != AC_ID) { return false; } // not for this aircraft struct _mission_element me; me.type = MissionSegment; @@ -218,7 +218,7 @@ int mission_parse_SEGMENT(void) int mission_parse_SEGMENT_LLA(void) { - if (DL_MISSION_SEGMENT_LLA_ac_id(dl_buffer) != AC_ID) { return FALSE; } // not for this aircraft + if (DL_MISSION_SEGMENT_LLA_ac_id(dl_buffer) != AC_ID) { return false; } // not for this aircraft struct LlaCoor_i from_lla, to_lla; from_lla.lat = DL_MISSION_SEGMENT_LLA_segment_lat_1(dl_buffer); @@ -231,8 +231,8 @@ int mission_parse_SEGMENT_LLA(void) struct _mission_element me; me.type = MissionSegment; // if there is no valid local coordinate, do not insert mission element - if (!mission_point_of_lla(&me.element.mission_segment.from.from_f, &from_lla)) { return FALSE; } - if (!mission_point_of_lla(&me.element.mission_segment.to.to_f, &to_lla)) { return FALSE; } + if (!mission_point_of_lla(&me.element.mission_segment.from.from_f, &from_lla)) { return false; } + if (!mission_point_of_lla(&me.element.mission_segment.to.to_f, &to_lla)) { return false; } me.duration = DL_MISSION_SEGMENT_LLA_duration(dl_buffer); enum MissionInsertMode insert = (enum MissionInsertMode)(DL_MISSION_SEGMENT_LLA_insert(dl_buffer)); @@ -242,7 +242,7 @@ int mission_parse_SEGMENT_LLA(void) int mission_parse_PATH(void) { - if (DL_MISSION_PATH_ac_id(dl_buffer) != AC_ID) { return FALSE; } // not for this aircraft + if (DL_MISSION_PATH_ac_id(dl_buffer) != AC_ID) { return false; } // not for this aircraft struct _mission_element me; me.type = MissionPath; @@ -273,7 +273,7 @@ int mission_parse_PATH(void) int mission_parse_PATH_LLA(void) { - if (DL_MISSION_PATH_LLA_ac_id(dl_buffer) != AC_ID) { return FALSE; } // not for this aircraft + if (DL_MISSION_PATH_LLA_ac_id(dl_buffer) != AC_ID) { return false; } // not for this aircraft struct LlaCoor_i lla[MISSION_PATH_NB]; lla[0].lat = DL_MISSION_PATH_LLA_point_lat_1(dl_buffer); @@ -299,7 +299,7 @@ int mission_parse_PATH_LLA(void) if (me.element.mission_path.nb > MISSION_PATH_NB) { me.element.mission_path.nb = MISSION_PATH_NB; } for (i = 0; i < me.element.mission_path.nb; i++) { // if there is no valid local coordinate, do not insert mission element - if (!mission_point_of_lla(&me.element.mission_path.path.path_f[i], &lla[i])) { return FALSE; } + if (!mission_point_of_lla(&me.element.mission_path.path.path_f[i], &lla[i])) { return false; } } me.element.mission_path.path_idx = 0; me.duration = DL_MISSION_PATH_LLA_duration(dl_buffer); @@ -311,33 +311,33 @@ int mission_parse_PATH_LLA(void) int mission_parse_GOTO_MISSION(void) { - if (DL_GOTO_MISSION_ac_id(dl_buffer) != AC_ID) { return FALSE; } // not for this aircraft + if (DL_GOTO_MISSION_ac_id(dl_buffer) != AC_ID) { return false; } // not for this aircraft uint8_t mission_id = DL_GOTO_MISSION_mission_id(dl_buffer); if (mission_id < MISSION_ELEMENT_NB) { mission.current_idx = mission_id; - } else { return FALSE; } + } else { return false; } - return TRUE; + return true; } int mission_parse_NEXT_MISSION(void) { - if (DL_NEXT_MISSION_ac_id(dl_buffer) != AC_ID) { return FALSE; } // not for this aircraft + if (DL_NEXT_MISSION_ac_id(dl_buffer) != AC_ID) { return false; } // not for this aircraft - if (mission.current_idx == mission.insert_idx) { return FALSE; } // already at the last position + if (mission.current_idx == mission.insert_idx) { return false; } // already at the last position // increment current index mission.current_idx = (mission.current_idx + 1) % MISSION_ELEMENT_NB; - return TRUE; + return true; } int mission_parse_END_MISSION(void) { - if (DL_END_MISSION_ac_id(dl_buffer) != AC_ID) { return FALSE; } // not for this aircraft + if (DL_END_MISSION_ac_id(dl_buffer) != AC_ID) { return false; } // not for this aircraft // set current index to insert index (last position) mission.current_idx = mission.insert_idx; - return TRUE; + return true; } diff --git a/sw/airborne/modules/mission/mission_fw_nav.c b/sw/airborne/modules/mission/mission_fw_nav.c index 712a0c3f28..1b980b9e55 100644 --- a/sw/airborne/modules/mission/mission_fw_nav.c +++ b/sw/airborne/modules/mission/mission_fw_nav.c @@ -60,7 +60,7 @@ bool mission_point_of_lla(struct EnuCoor_f *point, struct LlaCoor_i *lla) point->y = waypoints[WP_HOME].y + dy; point->z = lla->alt; - return TRUE; + return true; } // navigation time step @@ -75,13 +75,13 @@ static inline bool mission_nav_wp(struct _mission_wp *wp) { if (nav_approaching_xy(wp->wp.wp_f.x, wp->wp.wp_f.y, last_wp_f.x, last_wp_f.y, CARROT)) { last_wp_f = wp->wp.wp_f; // store last wp - return FALSE; // end of mission element + return false; // end of mission element } // set navigation command fly_to_xy(wp->wp.wp_f.x, wp->wp.wp_f.y); NavVerticalAutoThrottleMode(0.); NavVerticalAltitudeMode(wp->wp.wp_f.z, 0.); - return TRUE; + return true; } /** Navigation function on a circle @@ -91,7 +91,7 @@ static inline bool mission_nav_circle(struct _mission_circle *circle) nav_circle_XY(circle->center.center_f.x, circle->center.center_f.y, circle->radius); NavVerticalAutoThrottleMode(0.); NavVerticalAltitudeMode(circle->center.center_f.z, 0.); - return TRUE; + return true; } /** Navigation function along a segment @@ -101,12 +101,12 @@ static inline bool mission_nav_segment(struct _mission_segment *segment) if (nav_approaching_xy(segment->to.to_f.x, segment->to.to_f.y, segment->from.from_f.x, segment->from.from_f.y, CARROT)) { last_wp_f = segment->to.to_f; - return FALSE; // end of mission element + return false; // end of mission element } nav_route_xy(segment->from.from_f.x, segment->from.from_f.y, segment->to.to_f.x, segment->to.to_f.y); NavVerticalAutoThrottleMode(0.); NavVerticalAltitudeMode(segment->to.to_f.z, 0.); // both altitude should be the same anyway - return TRUE; + return true; } /** Navigation function along a path @@ -114,7 +114,7 @@ static inline bool mission_nav_segment(struct _mission_segment *segment) static inline bool mission_nav_path(struct _mission_path *path) { if (path->nb == 0) { - return FALSE; // nothing to do + return false; // nothing to do } if (path->nb == 1) { // handle as a single waypoint @@ -124,7 +124,7 @@ static inline bool mission_nav_path(struct _mission_path *path) } if (path->path_idx == path->nb - 1) { last_wp_f = path->path.path_f[path->path_idx]; // store last wp - return FALSE; // end of path + return false; // end of path } // normal case struct EnuCoor_f from_f = path->path.path_f[path->path_idx]; @@ -135,7 +135,7 @@ static inline bool mission_nav_path(struct _mission_path *path) if (nav_approaching_xy(to_f.x, to_f.y, from_f.x, from_f.y, CARROT)) { path->path_idx++; // go to next segment } - return TRUE; + return true; } @@ -145,10 +145,10 @@ int mission_run() struct _mission_element *el = NULL; if ((el = mission_get()) == NULL) { // TODO do something special like a waiting circle before ending the mission ? - return FALSE; // end of mission + return false; // end of mission } - bool el_running = FALSE; + bool el_running = false; switch (el->type) { case MissionWP: el_running = mission_nav_wp(&(el->element.mission_wp)); @@ -178,5 +178,5 @@ int mission_run() mission.current_idx = (mission.current_idx + 1) % MISSION_ELEMENT_NB; } - return TRUE; + return true; } diff --git a/sw/airborne/modules/mission/mission_rotorcraft_nav.c b/sw/airborne/modules/mission/mission_rotorcraft_nav.c index 6f3f4bb900..ff918d5701 100644 --- a/sw/airborne/modules/mission/mission_rotorcraft_nav.c +++ b/sw/airborne/modules/mission/mission_rotorcraft_nav.c @@ -42,7 +42,7 @@ bool mission_point_of_lla(struct EnuCoor_f *point, struct LlaCoor_i *lla) { // return FALSE if there is no valid local coordinate system if (!state.ned_initialized_i) { - return FALSE; + return false; } // change geoid alt to ellipsoid alt @@ -72,7 +72,7 @@ bool mission_point_of_lla(struct EnuCoor_f *point, struct LlaCoor_i *lla) VECT2_SUM(*point, home, vect_from_home); point->z = tmp_enu_point_f.z; - return TRUE; + return true; } //Function that converts target wp from float point versions to int @@ -99,11 +99,11 @@ bool mission_element_convert(struct _mission_element *el) break; default: // invalid element type - return FALSE; + return false; break; } - return TRUE; + return true; } // navigation time step @@ -123,8 +123,8 @@ static inline bool mission_nav_wp(struct _mission_element *el) last_mission_wp = *target_wp; if (el->duration > 0.) { - if (nav_check_wp_time(target_wp, el->duration)) { return FALSE; } - } else { return FALSE; } + if (nav_check_wp_time(target_wp, el->duration)) { return false; } + } else { return false; } } //Go to Mission Waypoint @@ -133,7 +133,7 @@ static inline bool mission_nav_wp(struct _mission_element *el) NavVerticalAutoThrottleMode(RadOfDeg(0.000000)); NavVerticalAltitudeMode(POS_FLOAT_OF_BFP(target_wp->z), 0.); - return TRUE; + return true; } /** Navigation function on a circle @@ -150,10 +150,10 @@ static inline bool mission_nav_circle(struct _mission_element *el) NavVerticalAltitudeMode(POS_FLOAT_OF_BFP(center_wp->z), 0.); if (el->duration > 0. && mission.element_time >= el->duration) { - return FALSE; + return false; } - return TRUE; + return true; } /** Navigation function along a segment @@ -168,8 +168,8 @@ static inline bool mission_nav_segment(struct _mission_element *el) last_mission_wp = *to_wp; if (el->duration > 0.) { - if (nav_check_wp_time(to_wp, el->duration)) { return FALSE; } - } else { return FALSE; } + if (nav_check_wp_time(to_wp, el->duration)) { return false; } + } else { return false; } } //Route Between from-to @@ -178,7 +178,7 @@ static inline bool mission_nav_segment(struct _mission_element *el) NavVerticalAutoThrottleMode(RadOfDeg(0.0)); NavVerticalAltitudeMode(POS_FLOAT_OF_BFP(to_wp->z), 0.); - return TRUE; + return true; } @@ -187,7 +187,7 @@ static inline bool mission_nav_segment(struct _mission_element *el) static inline bool mission_nav_path(struct _mission_element *el) { if (el->element.mission_path.nb == 0) { - return FALSE; // nothing to do + return false; // nothing to do } if (el->element.mission_path.path_idx == 0) { //first wp of path @@ -215,9 +215,9 @@ static inline bool mission_nav_path(struct _mission_element *el) nav_route(from_wp, to_wp); NavVerticalAutoThrottleMode(RadOfDeg(0.0)); NavVerticalAltitudeMode(POS_FLOAT_OF_BFP(from_wp->z), 0.); - } else { return FALSE; } //end of path + } else { return false; } //end of path - return TRUE; + return true; } int mission_run() @@ -227,10 +227,10 @@ int mission_run() if ((el = mission_get()) == NULL) { mission.element_time = 0; mission.current_idx = 0; - return FALSE; // end of mission + return false; // end of mission } - bool el_running = FALSE; + bool el_running = false; switch (el->type) { case MissionWP: el_running = mission_nav_wp(el); @@ -258,6 +258,6 @@ int mission_run() // go to next element mission.current_idx = (mission.current_idx + 1) % MISSION_ELEMENT_NB; } - return TRUE; + return true; } diff --git a/sw/airborne/modules/multi/formation.c b/sw/airborne/modules/multi/formation.c index fdcb7ec12e..8f7482808e 100644 --- a/sw/airborne/modules/multi/formation.c +++ b/sw/airborne/modules/multi/formation.c @@ -78,18 +78,18 @@ int formation_init(void) form_mode = FORM_MODE; old_cruise = V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE; old_alt = GROUND_ALT + SECURITY_HEIGHT; - return FALSE; + return false; } int add_slot(uint8_t _id, float slot_e, float slot_n, float slot_a) { - if (_id != AC_ID && the_acs_id[_id] == 0) { return FALSE; } // no info for this AC + if (_id != AC_ID && the_acs_id[_id] == 0) { return false; } // no info for this AC DOWNLINK_SEND_FORMATION_SLOT_TM(DefaultChannel, DefaultDevice, &_id, &form_mode, &slot_e, &slot_n, &slot_a); formation[the_acs_id[_id]].status = IDLE; formation[the_acs_id[_id]].east = slot_e; formation[the_acs_id[_id]].north = slot_n; formation[the_acs_id[_id]].alt = slot_a; - return FALSE; + return false; } int start_formation(void) @@ -104,7 +104,7 @@ int start_formation(void) // store current cruise and alt old_cruise = v_ctl_auto_throttle_cruise_throttle; old_alt = nav_altitude; - return FALSE; + return false; } int stop_formation(void) @@ -121,7 +121,7 @@ int stop_formation(void) old_cruise = V_CTL_AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE; nav_altitude = old_alt; old_alt = GROUND_ALT + SECURITY_HEIGHT; - return FALSE; + return false; } @@ -159,14 +159,14 @@ int formation_flight(void) &formation[the_acs_id[AC_ID]].north, &formation[the_acs_id[AC_ID]].alt); } - if (formation[the_acs_id[AC_ID]].status != ACTIVE) { return FALSE; } // AC not ready + if (formation[the_acs_id[AC_ID]].status != ACTIVE) { return false; } // AC not ready // get leader info struct ac_info_ * leader = get_ac_info(leader_id); if (formation[the_acs_id[leader_id]].status == UNSET || formation[the_acs_id[leader_id]].status == IDLE) { // leader not ready or not in formation - return FALSE; + return false; } // compute slots in the right reference frame @@ -255,7 +255,7 @@ int formation_flight(void) Bound(cruise, V_CTL_AUTO_THROTTLE_MIN_CRUISE_THROTTLE, V_CTL_AUTO_THROTTLE_MAX_CRUISE_THROTTLE); v_ctl_auto_throttle_cruise_throttle = cruise; } - return TRUE; + return true; } void formation_pre_call(void) diff --git a/sw/airborne/modules/multi/potential.c b/sw/airborne/modules/multi/potential.c index de7b15d14e..849c4b3282 100644 --- a/sw/airborne/modules/multi/potential.c +++ b/sw/airborne/modules/multi/potential.c @@ -95,7 +95,7 @@ int potential_task(void) ++nb; } } - if (nb == 0) { return TRUE; } + if (nb == 0) { return true; } //potential_force.east /= nb; //potential_force.north /= nb; //potential_force.alt /= nb; @@ -126,6 +126,6 @@ int potential_task(void) DOWNLINK_SEND_POTENTIAL(DefaultChannel, DefaultDevice, &potential_force.east, &potential_force.north, &potential_force.alt, &potential_force.speed, &potential_force.climb); - return TRUE; + return true; } diff --git a/sw/airborne/modules/nav/nav_bungee_takeoff.c b/sw/airborne/modules/nav/nav_bungee_takeoff.c index b818b6657c..eced90b37e 100644 --- a/sw/airborne/modules/nav/nav_bungee_takeoff.c +++ b/sw/airborne/modules/nav/nav_bungee_takeoff.c @@ -155,7 +155,7 @@ bool nav_bungee_takeoff_setup(uint8_t bungee_wp) CTakeoffStatus = Launch; kill_throttle = 1; - return FALSE; + return false; } bool nav_bungee_takeoff_run(void) @@ -208,15 +208,15 @@ bool nav_bungee_takeoff_run(void) #endif ) { CTakeoffStatus = Finished; - return FALSE; + return false; } else { - return TRUE; + return true; } break; default: // Invalid status or Finished, end function - return FALSE; + return false; } - return TRUE; + return true; } diff --git a/sw/airborne/modules/nav/nav_catapult.c b/sw/airborne/modules/nav/nav_catapult.c index 38d0791aad..45e2ebe824 100644 --- a/sw/airborne/modules/nav/nav_catapult.c +++ b/sw/airborne/modules/nav/nav_catapult.c @@ -51,7 +51,7 @@ #include "subsystems/datalink/datalink.h" -static bool nav_catapult_armed = FALSE; +static bool nav_catapult_armed = false; static uint16_t nav_catapult_launch = 0; #ifndef NAV_CATAPULT_ACCELERATION_THRESHOLD @@ -134,10 +134,10 @@ void nav_catapult_highrate_module(void) bool nav_catapult_setup(void) { - nav_catapult_armed = TRUE; + nav_catapult_armed = true; nav_catapult_launch = 0; - return FALSE; + return false; } @@ -191,7 +191,7 @@ bool nav_catapult_run(uint8_t _to, uint8_t _climb) } - return TRUE; + return true; } @@ -200,6 +200,6 @@ bool nav_select_touch_down(uint8_t _td) WaypointX(_td) = stateGetPositionEnu_f()->x; WaypointY(_td) = stateGetPositionEnu_f()->y; WaypointAlt(_td) = stateGetPositionUtm_f()->alt; - return FALSE; + return false; } diff --git a/sw/airborne/modules/nav/nav_cube.c b/sw/airborne/modules/nav/nav_cube.c index 1b518f6193..916f5734eb 100644 --- a/sw/airborne/modules/nav/nav_cube.c +++ b/sw/airborne/modules/nav/nav_cube.c @@ -138,7 +138,7 @@ bool nav_cube_setup(uint8_t center, uint8_t tb, uint8_t te) nav_cube.nline_x--; nav_cube.nline_z--; - return FALSE; + return false; } bool nav_cube_run(int8_t j, int8_t i, @@ -147,10 +147,10 @@ bool nav_cube_run(int8_t j, int8_t i, { if (i > nav_cube.nline_x) { - return FALSE; + return false; } if (j > nav_cube.nline_z) { - return FALSE; + return false; } waypoints[dest_b].x = waypoints[src_b + i].x; @@ -169,5 +169,5 @@ bool nav_cube_run(int8_t j, int8_t i, waypoints[dest_e].a = ground_alt + SECURITY_HEIGHT; } - return FALSE; + return false; } diff --git a/sw/airborne/modules/nav/nav_drop.c b/sw/airborne/modules/nav/nav_drop.c index fe77417839..5e6c6048f8 100644 --- a/sw/airborne/modules/nav/nav_drop.c +++ b/sw/airborne/modules/nav/nav_drop.c @@ -206,7 +206,7 @@ bool compute_alignment(uint8_t w1, uint8_t w2, uint8_t wp_before, uint8_t wp_aft waypoints[wp_after].x = waypoints[w2].x + d_after * x_0; waypoints[wp_after].y = waypoints[w2].y + d_after * y_0; - return FALSE; + return false; } #endif /* WP_RELEASE */ diff --git a/sw/airborne/modules/nav/nav_flower.c b/sw/airborne/modules/nav/nav_flower.c index f7215ae09a..4ac8ff54ea 100644 --- a/sw/airborne/modules/nav/nav_flower.c +++ b/sw/airborne/modules/nav/nav_flower.c @@ -85,7 +85,7 @@ bool nav_flower_setup(uint8_t CenterWP, uint8_t EdgeWP) CircleX = 0; CircleY = 0; - return FALSE; + return false; } bool nav_flower_run(void) @@ -94,11 +94,11 @@ bool nav_flower_run(void) TransCurrentY = stateGetPositionEnu_f()->y - WaypointY(Center); DistanceFromCenter = sqrtf(TransCurrentX * TransCurrentX + TransCurrentY * TransCurrentY); - bool InCircle = TRUE; + bool InCircle = true; float CircleTheta; if (DistanceFromCenter > Flowerradius) { - InCircle = FALSE; + InCircle = false; } NavVerticalAutoThrottleMode(0); /* No pitch */ @@ -150,5 +150,5 @@ bool nav_flower_run(void) default: break; } - return TRUE; + return true; } diff --git a/sw/airborne/modules/nav/nav_gls.c b/sw/airborne/modules/nav/nav_gls.c index 8072955b46..f337479c16 100644 --- a/sw/airborne/modules/nav/nav_gls.c +++ b/sw/airborne/modules/nav/nav_gls.c @@ -54,7 +54,7 @@ float app_angle; float app_intercept_rate; float app_distance_af_sd; -bool init = TRUE; +bool init = true; #ifndef APP_TARGET_SPEED #define APP_TARGET_SPEED NOMINAL_AIRSPEED @@ -128,14 +128,14 @@ static inline bool gls_compute_TOD(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8 WaypointX(_af) = WaypointX(_sd) + td_af_x / td_af * app_distance_af_sd; WaypointY(_af) = WaypointY(_sd) + td_af_y / td_af * app_distance_af_sd; } - return FALSE; + return false; } /* end of gls_copute_TOD */ bool gls_start(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td) { - init = TRUE; + init = true; //struct FloatVect2* wind = stateGetHorizontalWindspeed_f(); //float wind_additional = sqrtf(wind->x*wind->x + wind->y*wind->y); // should be gusts only! @@ -152,7 +152,7 @@ bool gls_start(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td) // calculate Top Of Decent gls_compute_TOD(_af, _sd, _tod, _td); - return FALSE; + return false; } /* end of gls_init() */ @@ -165,7 +165,7 @@ bool gls_run(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td) #if USE_AIRSPEED v_ctl_auto_airspeed_setpoint = target_speed; #endif - init = FALSE; + init = false; } // calculate distance tod_td @@ -229,5 +229,5 @@ bool gls_run(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td) NavVerticalAutoThrottleMode(0); // throttle mode NavSegment(_af, _td); // horizontal mode (stay on localiser) - return TRUE; + return true; } // end of gls() diff --git a/sw/airborne/modules/nav/nav_line.c b/sw/airborne/modules/nav/nav_line.c index 0605cfd3ee..6a19a861ef 100644 --- a/sw/airborne/modules/nav/nav_line.c +++ b/sw/airborne/modules/nav/nav_line.c @@ -36,7 +36,7 @@ static enum line_status line_status; bool nav_line_setup(void) { line_status = LR12; - return FALSE; + return false; } bool nav_line_run(uint8_t l1, uint8_t l2, float radius) @@ -146,7 +146,7 @@ bool nav_line_run(uint8_t l1, uint8_t l2, float radius) } break; default: /* Should not occur !!! End the pattern */ - return FALSE; + return false; } - return TRUE; /* This pattern never ends */ + return true; /* This pattern never ends */ } diff --git a/sw/airborne/modules/nav/nav_line_border.c b/sw/airborne/modules/nav/nav_line_border.c index 22662e1e44..57e3d93bd3 100644 --- a/sw/airborne/modules/nav/nav_line_border.c +++ b/sw/airborne/modules/nav/nav_line_border.c @@ -40,7 +40,7 @@ static enum line_border_status line_border_status; bool nav_line_border_setup(void) { line_border_status = LR12; - return FALSE; + return false; } bool nav_line_border_run(uint8_t l1, uint8_t l2, float radius) @@ -133,7 +133,7 @@ bool nav_line_border_run(uint8_t l1, uint8_t l2, float radius) break; default: /* Should not occur !!! End the pattern */ - return FALSE; + return false; } - return TRUE; /* This pattern never ends */ + return true; /* This pattern never ends */ } diff --git a/sw/airborne/modules/nav/nav_line_osam.c b/sw/airborne/modules/nav/nav_line_osam.c index 1bfe4e66a8..410dc42972 100644 --- a/sw/airborne/modules/nav/nav_line_osam.c +++ b/sw/airborne/modules/nav/nav_line_osam.c @@ -161,13 +161,13 @@ bool nav_line_osam_run(uint8_t From_WP, uint8_t To_WP, float radius, float Space case FLFinished: CFLStatus = FLInitialize; nav_init_stage(); - return FALSE; + return false; break; default: break; } - return TRUE; + return true; } @@ -182,7 +182,7 @@ bool nav_line_osam_block_run(uint8_t First_WP, uint8_t Last_WP, float radius, fl FLBlockCount++; if (First_WP + FLBlockCount >= Last_WP) { FLBlockCount = 0; - return FALSE; + return false; } } } else { @@ -192,10 +192,10 @@ bool nav_line_osam_block_run(uint8_t First_WP, uint8_t Last_WP, float radius, fl FLBlockCount++; if (First_WP - FLBlockCount <= Last_WP) { FLBlockCount = 0; - return FALSE; + return false; } } } - return TRUE; + return true; } diff --git a/sw/airborne/modules/nav/nav_smooth.c b/sw/airborne/modules/nav/nav_smooth.c index c3eaf4f6a1..33fd8a371c 100644 --- a/sw/airborne/modules/nav/nav_smooth.c +++ b/sw/airborne/modules/nav/nav_smooth.c @@ -114,7 +114,7 @@ bool snav_init(uint8_t a, float desired_course_rad, float radius) wp_ta.a = wp_ca.a; ground_speed_timer = 0; - return FALSE; + return false; } diff --git a/sw/airborne/modules/nav/nav_spiral.c b/sw/airborne/modules/nav/nav_spiral.c index 86e264b33a..9999812744 100644 --- a/sw/airborne/modules/nav/nav_spiral.c +++ b/sw/airborne/modules/nav/nav_spiral.c @@ -81,7 +81,7 @@ bool nav_spiral_setup(uint8_t center_wp, uint8_t edge_wp, float radius_start, fl if (nav_spiral.dist_from_center > nav_spiral.radius) { nav_spiral.status = SpiralOutside; } - return FALSE; + return false; } bool nav_spiral_run(void) @@ -166,5 +166,5 @@ bool nav_spiral_run(void) NavVerticalAutoThrottleMode(0.); /* No pitch */ NavVerticalAltitudeMode(nav_spiral.center.z, 0.); /* No preclimb */ - return TRUE; + return true; } diff --git a/sw/airborne/modules/nav/nav_survey_disc.c b/sw/airborne/modules/nav/nav_survey_disc.c index d135b16d93..ea7bcb2131 100644 --- a/sw/airborne/modules/nav/nav_survey_disc.c +++ b/sw/airborne/modules/nav/nav_survey_disc.c @@ -53,7 +53,7 @@ bool nav_survey_disc_setup(float grid) disc_survey.sign = 1; disc_survey.c1.x = stateGetPositionEnu_f()->x; disc_survey.c1.y = stateGetPositionEnu_f()->y; - return FALSE; + return false; } bool nav_survey_disc_run(uint8_t center_wp, float radius) @@ -120,5 +120,5 @@ bool nav_survey_disc_run(uint8_t center_wp, float radius) NavVerticalAutoThrottleMode(0.); /* No pitch */ NavVerticalAltitudeMode(WaypointAlt(center_wp), 0.); /* No preclimb */ - return TRUE; + return true; } diff --git a/sw/airborne/modules/nav/nav_survey_poly_osam.c b/sw/airborne/modules/nav/nav_survey_poly_osam.c index d530290575..d8aa839ed1 100644 --- a/sw/airborne/modules/nav/nav_survey_poly_osam.c +++ b/sw/airborne/modules/nav/nav_survey_poly_osam.c @@ -168,7 +168,7 @@ bool nav_survey_poly_osam_setup(uint8_t EntryWP, uint8_t Size, float sw, float O CSurveyStatus = Init; if (Size == 0) { - return TRUE; + return true; } //Don't initialize if Polygon is too big or if the orientation is not between 0 and 90 @@ -329,7 +329,7 @@ bool nav_survey_poly_osam_setup(uint8_t EntryWP, uint8_t Size, float sw, float O LINE_STOP_FUNCTION; } - return FALSE; + return false; } bool nav_survey_poly_osam_run(void) @@ -341,7 +341,7 @@ bool nav_survey_poly_osam_run(void) static struct Point2D LastPoint; int i; bool LastHalfSweep; - static bool HalfSweep = FALSE; + static bool HalfSweep = false; float XIntercept1 = 0; float XIntercept2 = 0; float DInt1 = 0; @@ -412,10 +412,10 @@ bool nav_survey_poly_osam_run(void) if (LastPoint.y + (dSweep / 2) >= MaxY || LastPoint.y + (dSweep / 2) <= 0) { //Sweep back dSweep = -dSweep; if (LastHalfSweep) { - HalfSweep = FALSE; + HalfSweep = false; ys = LastPoint.y + (dSweep); } else { - HalfSweep = TRUE; + HalfSweep = true; ys = LastPoint.y + (dSweep / 2); } @@ -433,13 +433,13 @@ bool nav_survey_poly_osam_run(void) } else { SurveyCircleQdr = 180 - DegOfRad(SurveyTheta); } - HalfSweep = TRUE; + HalfSweep = true; } } else { // Normal sweep //Find y value of the first sweep - HalfSweep = FALSE; + HalfSweep = false; ys = LastPoint.y + dSweep; } @@ -547,11 +547,11 @@ bool nav_survey_poly_osam_run(void) } break; case Init: - return FALSE; + return false; default: - return FALSE; + return false; } - return TRUE; + return true; } diff --git a/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.c b/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.c index 8f79dd5f16..d4ce302c77 100644 --- a/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.c +++ b/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.c @@ -162,7 +162,7 @@ bool nav_survey_poly_setup(uint8_t EntryWP, uint8_t Size, float sw, float Orient CSurveyStatus = Init; if (Size == 0) { - return TRUE; + return true; } //Don't initialize if Polygon is too big or if the orientation is not between 0 and 90 @@ -309,7 +309,7 @@ bool nav_survey_poly_setup(uint8_t EntryWP, uint8_t Size, float sw, float Orient } - return FALSE; + return false; } //========================================================================================================================= @@ -323,7 +323,7 @@ bool nav_survey_poly_run(void) static struct EnuCoor_f LastPoint; int i; bool LastHalfSweep; - static bool HalfSweep = FALSE; + static bool HalfSweep = false; float XIntercept1 = 0; float XIntercept2 = 0; float DInt1 = 0; @@ -392,10 +392,10 @@ bool nav_survey_poly_run(void) } if (LastHalfSweep) { - HalfSweep = FALSE; + HalfSweep = false; ys = LastPoint.y + (dSweep); } else { - HalfSweep = TRUE; + HalfSweep = true; ys = LastPoint.y + (dSweep / 2); } @@ -403,7 +403,7 @@ bool nav_survey_poly_run(void) //fprintf(stderr,"cabe interiro\n"); //Find y value of the first sweep - HalfSweep = FALSE; + HalfSweep = false; ys = LastPoint.y + dSweep; } @@ -490,12 +490,12 @@ bool nav_survey_poly_run(void) break; case Init: - return FALSE; + return false; default: - return FALSE; + return false; } - return TRUE; + return true; } diff --git a/sw/airborne/modules/nav/nav_survey_polygon.c b/sw/airborne/modules/nav/nav_survey_polygon.c index 54dcd25ba7..ed0cc9bc39 100644 --- a/sw/airborne/modules/nav/nav_survey_polygon.c +++ b/sw/airborne/modules/nav/nav_survey_polygon.c @@ -58,15 +58,15 @@ static bool intercept_two_lines(struct FloatVect2 *p, struct FloatVect2 x, struc float divider, fac; divider = (((b2 - a2) * (y.x - x.x)) + ((x.y - y.y) * (b1 - a1))); - if (divider == 0) { return FALSE; } + if (divider == 0) { return false; } fac = ((y.x * (x.y - a2)) + (x.x * (a2 - y.y)) + (a1 * (y.y - x.y))) / divider; - if (fac > 1.0) { return FALSE; } - if (fac < 0.0) { return FALSE; } + if (fac > 1.0) { return false; } + if (fac < 0.0) { return false; } p->x = a1 + fac * (b1 - a1); p->y = a2 + fac * (b2 - a2); - return TRUE; + return true; } /** @@ -103,7 +103,7 @@ static bool get_two_intersects(struct FloatVect2 *x, struct FloatVect2 *y, struc } if (count != 2) { - return FALSE; + return false; } //change points @@ -119,7 +119,7 @@ static bool get_two_intersects(struct FloatVect2 *x, struct FloatVect2 *y, struc *y = tmp; } - return TRUE; + return true; } /** @@ -212,7 +212,7 @@ bool nav_survey_polygon_setup(uint8_t first_wp, uint8_t size, float angle, float if (!get_two_intersects(&survey.seg_start, &survey.seg_end, survey.seg_start, survey.seg_end)) { survey.stage = ERR; - return FALSE; + return false; } //center of the entry circle @@ -224,7 +224,7 @@ bool nav_survey_polygon_setup(uint8_t first_wp, uint8_t size, float angle, float survey.stage = ENTRY; - return FALSE; + return false; } /** @@ -269,7 +269,7 @@ bool nav_survey_polygon_run(void) VECT2_SUM(sum_start_sweep, survey.seg_start, survey.sweep_vec); VECT2_SUM(sum_end_sweep, survey.seg_end, survey.sweep_vec); if (!get_two_intersects(&survey.seg_start, &survey.seg_end, sum_start_sweep, sum_end_sweep)) { - return FALSE; + return false; } survey.ret_end.x = survey.seg_start.x - survey.sweep_vec.x - 2 * survey.rad_vec.x; @@ -309,5 +309,5 @@ bool nav_survey_polygon_run(void) } } - return TRUE; + return true; } diff --git a/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.c b/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.c index 9651604757..0e51eb7492 100644 --- a/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.c +++ b/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.c @@ -52,16 +52,16 @@ #include "state.h" float sweep = RECTANGLE_SURVEY_DEFAULT_SWEEP; -static bool nav_survey_rectangle_active = FALSE; +static bool nav_survey_rectangle_active = false; uint16_t rectangle_survey_sweep_num; -bool nav_in_segment = FALSE; -bool nav_in_circle = FALSE; +bool nav_in_segment = false; +bool nav_in_circle = false; bool interleave = USE_INTERLEAVE; static struct EnuCoor_f survey_from, survey_to; static struct EnuCoor_i survey_from_i, survey_to_i; -static bool survey_uturn __attribute__((unused)) = FALSE; +static bool survey_uturn __attribute__((unused)) = false; static survey_orientation_t survey_orientation = NS; float nav_survey_shift; @@ -137,8 +137,8 @@ bool nav_survey_rectangle_rotorcraft_setup(uint8_t wp1, uint8_t wp2, float grid, } } nav_survey_shift = grid; - survey_uturn = FALSE; - nav_survey_rectangle_active = FALSE; + survey_uturn = false; + nav_survey_rectangle_active = false; //go to start position ENU_BFP_OF_REAL(survey_from_i, survey_from); @@ -151,22 +151,22 @@ bool nav_survey_rectangle_rotorcraft_setup(uint8_t wp1, uint8_t wp2, float grid, } else { nav_set_heading_deg(90); } - return FALSE; + return false; } bool nav_survey_rectangle_rotorcraft_run(uint8_t wp1, uint8_t wp2) { - static bool is_last_half = FALSE; + static bool is_last_half = false; static float survey_radius; - nav_survey_active = TRUE; + nav_survey_active = true; /* entry scan */ // wait for start position and altitude be reached if (!nav_survey_rectangle_active && ((!nav_approaching_from(&survey_from_i, NULL, 0)) || (fabsf(stateGetPositionEnu_f()->z - waypoints[wp1].enu_f.z)) > 1.)) { } else { if (!nav_survey_rectangle_active) { - nav_survey_rectangle_active = TRUE; + nav_survey_rectangle_active = true; LINE_START_FUNCTION; } @@ -221,7 +221,7 @@ bool nav_survey_rectangle_rotorcraft_run(uint8_t wp1, uint8_t wp2) }else { survey_radius = nav_survey_shift /2.; } - is_last_half = FALSE; + is_last_half = false; } else { // last sweep not half nav_survey_shift = -nav_survey_shift; if (interleave) { @@ -233,7 +233,7 @@ bool nav_survey_rectangle_rotorcraft_run(uint8_t wp1, uint8_t wp2) rectangle_survey_sweep_num ++; } else { //room for half sweep after survey_radius = nav_survey_shift / 2.; - is_last_half = TRUE; + is_last_half = true; } } else {// room for full sweep after survey_radius = nav_survey_shift; @@ -270,7 +270,7 @@ bool nav_survey_rectangle_rotorcraft_run(uint8_t wp1, uint8_t wp2) }else { survey_radius = nav_survey_shift /2.; } - is_last_half = FALSE; + is_last_half = false; } else { // last sweep not half nav_survey_shift = -nav_survey_shift; if (interleave) { @@ -282,7 +282,7 @@ bool nav_survey_rectangle_rotorcraft_run(uint8_t wp1, uint8_t wp2) rectangle_survey_sweep_num ++; } else { //room for half sweep after survey_radius = nav_survey_shift / 2.; - is_last_half = TRUE; + is_last_half = true; } } else {// room for full sweep after survey_radius = nav_survey_shift; @@ -306,8 +306,8 @@ bool nav_survey_rectangle_rotorcraft_run(uint8_t wp1, uint8_t wp2) } } - nav_in_segment = FALSE; - survey_uturn = TRUE; + nav_in_segment = false; + survey_uturn = true; LINE_STOP_FUNCTION; #ifdef DIGITAL_CAM float temp; @@ -350,8 +350,8 @@ bool nav_survey_rectangle_rotorcraft_run(uint8_t wp1, uint8_t wp2) ENU_BFP_OF_REAL(survey_to_i, waypoints[0].enu_f); } if (nav_approaching_from(&survey_to_i, NULL, 0)) { - survey_uturn = FALSE; - nav_in_circle = FALSE; + survey_uturn = false; + nav_in_circle = false; LINE_START_FUNCTION; } else { @@ -369,7 +369,7 @@ bool nav_survey_rectangle_rotorcraft_run(uint8_t wp1, uint8_t wp2) } /* END turn */ } /* END entry scan */ - return TRUE; + return true; }// /* END survey_retangle */ diff --git a/sw/airborne/modules/nav/nav_survey_zamboni.c b/sw/airborne/modules/nav/nav_survey_zamboni.c index 1e7c2132f9..2cc5515443 100644 --- a/sw/airborne/modules/nav/nav_survey_zamboni.c +++ b/sw/airborne/modules/nav/nav_survey_zamboni.c @@ -118,7 +118,7 @@ bool nav_survey_zamboni_setup(uint8_t center_wp, uint8_t dir_wp, float sweep_len zs.stage = Z_ENTRY; - return FALSE; + return false; } /** @@ -211,8 +211,8 @@ bool nav_survey_zamboni_run(void) #ifdef DIGITAL_CAM LINE_STOP_FUNCTION; #endif - return FALSE; + return false; } else { - return TRUE; + return true; } } diff --git a/sw/airborne/modules/nav/nav_vertical_raster.c b/sw/airborne/modules/nav/nav_vertical_raster.c index abe24d7993..ad9b5e1f9b 100644 --- a/sw/airborne/modules/nav/nav_vertical_raster.c +++ b/sw/airborne/modules/nav/nav_vertical_raster.c @@ -43,7 +43,7 @@ static enum line_status line_status; bool nav_vertical_raster_setup(void) { line_status = LR12; - return FALSE; + return false; } bool nav_vertical_raster_run(uint8_t l1, uint8_t l2, float radius, float AltSweep) @@ -156,5 +156,5 @@ bool nav_vertical_raster_run(uint8_t l1, uint8_t l2, float radius, float AltSwee default: break; } - return TRUE; /* This pattern never ends */ + return true; /* This pattern never ends */ } diff --git a/sw/airborne/modules/nav/takeoff_detect.c b/sw/airborne/modules/nav/takeoff_detect.c index 71734bb9b3..e75895ad86 100644 --- a/sw/airborne/modules/nav/takeoff_detect.c +++ b/sw/airborne/modules/nav/takeoff_detect.c @@ -97,7 +97,7 @@ void takeoff_detect_periodic(void) } // if timer is finished, start launching if (takeoff_detect.timer > (int)(TAKEOFF_DETECT_PERIODIC_FREQ * TAKEOFF_DETECT_TIMER)) { - launch = TRUE; + launch = true; takeoff_detect.state = TO_DETECT_LAUNCHING; takeoff_detect.timer = 0; } @@ -107,7 +107,7 @@ void takeoff_detect_periodic(void) if (stateGetNedToBodyEulers_f()->theta < TAKEOFF_DETECT_ABORT_PITCH || pprz_mode != PPRZ_MODE_AUTO2) { // back to ARMED state - launch = FALSE; + launch = false; takeoff_detect.state = TO_DETECT_ARMED; } // increment timer and disable detection after some time diff --git a/sw/airborne/modules/optical_flow/px4flow.c b/sw/airborne/modules/optical_flow/px4flow.c index ac836f6d89..72f673e214 100644 --- a/sw/airborne/modules/optical_flow/px4flow.c +++ b/sw/airborne/modules/optical_flow/px4flow.c @@ -49,7 +49,7 @@ struct mavlink_msg_req req; // callback function on message reception static void decode_optical_flow_msg(struct mavlink_message *msg __attribute__((unused))) { - optical_flow_available = TRUE; + optical_flow_available = true; // Y negated to get to the body of the drone AbiSendMsgVELOCITY_ESTIMATE(PX4FLOW_VELOCITY_ID, 0, @@ -63,7 +63,7 @@ static void decode_optical_flow_msg(struct mavlink_message *msg __attribute__((u */ void px4flow_init(void) { - optical_flow_available = FALSE; + optical_flow_available = false; // register a mavlink message req.msg_id = MAVLINK_OPTICAL_FLOW_MSG_ID; diff --git a/sw/airborne/modules/orange_avoider/orange_avoider.c b/sw/airborne/modules/orange_avoider/orange_avoider.c index 3bff8c81a4..9726c35390 100644 --- a/sw/airborne/modules/orange_avoider/orange_avoider.c +++ b/sw/airborne/modules/orange_avoider/orange_avoider.c @@ -17,7 +17,7 @@ #include #include -uint8_t safeToGoForwards = FALSE; +uint8_t safeToGoForwards = false; int tresholdColorCount = 200; int32_t incrementForAvoidance; @@ -52,7 +52,7 @@ uint8_t increase_nav_heading(int32_t *heading, int32_t increment) *heading = *heading + increment; // Check if your turn made it go out of bounds... INT32_ANGLE_NORMALIZE(*heading); // HEADING HAS INT32_ANGLE_FRAC.... - return FALSE; + return false; } uint8_t moveWaypointForwards(uint8_t waypoint, float distanceMeters) { @@ -71,7 +71,7 @@ uint8_t moveWaypointForwards(uint8_t waypoint, float distanceMeters) // Set the waypoint to the calculated position waypoint_set_xy_i(waypoint, new_coor.x, new_coor.y); - return FALSE; + return false; } uint8_t chooseRandomIncrementAvoidance() @@ -83,6 +83,6 @@ uint8_t chooseRandomIncrementAvoidance() } else { incrementForAvoidance = -350; } - return FALSE; + return false; } diff --git a/sw/airborne/modules/sensors/airspeed_amsys.c b/sw/airborne/modules/sensors/airspeed_amsys.c index 22fb30fb1e..ea120435f1 100644 --- a/sw/airborne/modules/sensors/airspeed_amsys.c +++ b/sw/airborne/modules/sensors/airspeed_amsys.c @@ -96,9 +96,9 @@ void airspeed_amsys_init(void) airspeed_amsys_p = 0.0; airspeed_amsys_offset = 0; airspeed_amsys_offset_tmp = 0; - airspeed_amsys_i2c_done = TRUE; - airspeed_amsys_valid = TRUE; - airspeed_amsys_offset_init = FALSE; + airspeed_amsys_i2c_done = true; + airspeed_amsys_valid = true; + airspeed_amsys_offset_init = false; airspeed_scale = AIRSPEED_AMSYS_SCALE; airspeed_filter = AIRSPEED_AMSYS_FILTER; airspeed_amsys_i2c_trans.status = I2CTransDone; @@ -157,9 +157,9 @@ void airspeed_amsys_read_event(void) // Check if this is valid airspeed if (airspeed_amsys_raw == 0) { - airspeed_amsys_valid = FALSE; + airspeed_amsys_valid = false; } else { - airspeed_amsys_valid = TRUE; + airspeed_amsys_valid = true; } // Continue only if a new airspeed value was received @@ -185,7 +185,7 @@ void airspeed_amsys_read_event(void) if (airspeed_amsys_cnt == 0) { // Calculate average airspeed_amsys_offset = airspeed_amsys_offset_tmp / AIRSPEED_AMSYS_OFFSET_NBSAMPLES_AVRG; - airspeed_amsys_offset_init = TRUE; + airspeed_amsys_offset_init = true; } // Check if averaging needs to continue else if (airspeed_amsys_cnt <= AIRSPEED_AMSYS_OFFSET_NBSAMPLES_AVRG) { diff --git a/sw/airborne/modules/sensors/airspeed_ets.c b/sw/airborne/modules/sensors/airspeed_ets.c index 15b9629a19..a231d162d0 100644 --- a/sw/airborne/modules/sensors/airspeed_ets.c +++ b/sw/airborne/modules/sensors/airspeed_ets.c @@ -118,9 +118,9 @@ void airspeed_ets_init(void) airspeed_ets = 0.0; airspeed_ets_offset = 0; airspeed_ets_offset_tmp = 0; - airspeed_ets_i2c_done = TRUE; - airspeed_ets_valid = FALSE; - airspeed_ets_offset_init = FALSE; + airspeed_ets_i2c_done = true; + airspeed_ets_valid = false; + airspeed_ets_offset_init = false; airspeed_ets_cnt = AIRSPEED_ETS_OFFSET_NBSAMPLES_INIT + AIRSPEED_ETS_OFFSET_NBSAMPLES_AVRG; airspeed_ets_buffer_idx = 0; @@ -130,12 +130,12 @@ void airspeed_ets_init(void) airspeed_ets_i2c_trans.status = I2CTransDone; - airspeed_ets_delay_done = FALSE; + airspeed_ets_delay_done = false; SysTimeTimerStart(airspeed_ets_delay_time); #ifndef SITL #if AIRSPEED_ETS_SDLOG - log_airspeed_ets_started = FALSE; + log_airspeed_ets_started = false; #endif #endif } @@ -145,7 +145,7 @@ void airspeed_ets_read_periodic(void) #ifndef SITL if (!airspeed_ets_delay_done) { if (SysTimeTimer(airspeed_ets_delay_time) < USEC_OF_SEC(AIRSPEED_ETS_START_DELAY)) { return; } - else { airspeed_ets_delay_done = TRUE; } + else { airspeed_ets_delay_done = true; } } if (airspeed_ets_i2c_trans.status == I2CTransDone) { i2c_receive(&AIRSPEED_ETS_I2C_DEV, &airspeed_ets_i2c_trans, AIRSPEED_ETS_ADDR, 2); @@ -165,9 +165,9 @@ void airspeed_ets_read_event(void) airspeed_ets_raw = ((uint16_t)(airspeed_ets_i2c_trans.buf[1]) << 8) | (uint16_t)(airspeed_ets_i2c_trans.buf[0]); // Check if this is valid airspeed if (airspeed_ets_raw == 0) { - airspeed_ets_valid = FALSE; + airspeed_ets_valid = false; } else { - airspeed_ets_valid = TRUE; + airspeed_ets_valid = true; } // Continue only if a new airspeed value was received @@ -187,7 +187,7 @@ void airspeed_ets_read_event(void) if (airspeed_ets_offset > AIRSPEED_ETS_OFFSET_MAX) { airspeed_ets_offset = AIRSPEED_ETS_OFFSET_MAX; } - airspeed_ets_offset_init = TRUE; + airspeed_ets_offset_init = true; } // Check if averaging needs to continue else if (airspeed_ets_cnt <= AIRSPEED_ETS_OFFSET_NBSAMPLES_AVRG) { @@ -242,7 +242,7 @@ void airspeed_ets_read_event(void) if (pprzLogFile != -1) { if (!log_airspeed_ets_started) { sdLogWriteLog(pprzLogFile, "AIRSPEED_ETS: raw offset airspeed(m/s) GPS_fix TOW(ms) Week Lat(1e7deg) Lon(1e7deg) HMSL(mm) gpseed(cm/s) course(1e7rad) climb(cm/s)\n"); - log_airspeed_ets_started = TRUE; + log_airspeed_ets_started = true; } sdLogWriteLog(pprzLogFile, "airspeed_ets: %d %d %8.4f %d %d %d %d %d %d %d %d %d\n", airspeed_ets_raw, airspeed_ets_offset, airspeed_ets, diff --git a/sw/airborne/modules/sensors/alt_srf08.c b/sw/airborne/modules/sensors/alt_srf08.c index c7ec23666d..329ab3fab9 100644 --- a/sw/airborne/modules/sensors/alt_srf08.c +++ b/sw/airborne/modules/sensors/alt_srf08.c @@ -49,8 +49,8 @@ uint16_t srf08_range; void srf08_init(void) { - srf08_received = FALSE; - srf08_got = FALSE; + srf08_received = false; + srf08_got = false; srf_trans.buf[0] = 0x00; srf_trans.buf[1] = 0x51; @@ -78,14 +78,14 @@ void srf08_receive(void) { LED_OFF(2); srf_trans.buf[0] = SRF08_ECHO_1; - srf08_received = TRUE; + srf08_received = true; i2c_transmit(&SRF08_I2C_DEV, &srf_trans, SRF08_UNIT_0, 1); } /** Read values on the bus */ void srf08_read(void) { - srf08_got = TRUE; + srf08_got = true; i2c_receive(&SRF08_I2C_DEV, &srf_trans, SRF08_UNIT_0, 2); } @@ -144,10 +144,10 @@ void srf08_event(void) /** Handling of data sent by the device (initiated by srf08_receive() */ if (srf_trans.status == I2CTransSuccess) { if (srf08_received) { - srf08_received = FALSE; + srf08_received = false; srf08_read(); } else if (srf08_got) { - srf08_got = FALSE; + srf08_got = false; srf08_copy(); DOWNLINK_SEND_RANGEFINDER(DefaultChannel, DefaultDevice, &srf08_range, &f, &f, &f, &f, &f, &i); } diff --git a/sw/airborne/modules/sensors/aoa_pwm.c b/sw/airborne/modules/sensors/aoa_pwm.c index 0f1a25f9b6..fdbaf12c48 100644 --- a/sw/airborne/modules/sensors/aoa_pwm.c +++ b/sw/airborne/modules/sensors/aoa_pwm.c @@ -102,7 +102,7 @@ void aoa_pwm_init(void) aoa_pwm.angle = 0.0f; aoa_pwm.raw = 0.0f; #if LOG_AOA - log_started = FALSE; + log_started = false; #endif #if PERIODIC_TELEMETRY register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_AOA, send_aoa); @@ -136,7 +136,7 @@ void aoa_pwm_update(void) { if(pprzLogFile != -1) { if (!log_started) { sdLogWriteLog(pprzLogFile, "AOA_PWM: ANGLE(deg) RAW(int16)\n"); - log_started = TRUE; + log_started = true; } else { float angle = DegOfRad(aoa_pwm.angle); sdLogWriteLog(pprzLogFile, "AOA_PWM: %.3f %d\n", angle, aoa_pwm.raw); diff --git a/sw/airborne/modules/sensors/baro_MS5534A.c b/sw/airborne/modules/sensors/baro_MS5534A.c index 228e44545d..cbd51cef00 100644 --- a/sw/airborne/modules/sensors/baro_MS5534A.c +++ b/sw/airborne/modules/sensors/baro_MS5534A.c @@ -140,29 +140,29 @@ void baro_MS5534A_init(void) words[3] = BARO_MS5534A_W4; status = STATUS_MEASURE_PRESSURE; - status_read_data = FALSE; + status_read_data = false; calibration(); #else status = STATUS_INIT1; - status_read_data = FALSE; + status_read_data = false; #endif - baro_MS5534A_available = FALSE; - alt_baro_enabled = FALSE; + baro_MS5534A_available = false; + alt_baro_enabled = false; baro_MS5534A_ground_pressure = 101300; baro_MS5534A_r = 20.; baro_MS5534A_sigma2 = 1; - baro_MS5534A_do_reset = FALSE; + baro_MS5534A_do_reset = false; } void baro_MS5534A_reset(void) { status = STATUS_INIT1; - status_read_data = FALSE; + status_read_data = false; } /* To be called not faster than 30Hz */ @@ -240,7 +240,7 @@ void baro_MS5534A_event_task(void) uint16_t x = (sens * (d1 - 7168)) / (1 << 14) - off; // baro_MS5534A = ((x*10)>>5) + 250*10; baro_MS5534A_pressure = ((x * 100) >> 5) + 250 * 100; - baro_MS5534A_available = TRUE; + baro_MS5534A_available = true; break; case STATUS_RESET: @@ -264,10 +264,10 @@ void baro_MS5534A_event(void) { if (spi_message_received) { /* Got a message on SPI. */ - spi_message_received = FALSE; + spi_message_received = false; baro_MS5534A_event_task(); if (baro_MS5534A_available) { - baro_MS5534A_available = FALSE; + baro_MS5534A_available = false; baro_MS5534A_z = ground_alt + ((float)baro_MS5534A_ground_pressure - baro_MS5534A_pressure) * 0.084; #if SENSO_SYNC_SEND DOWNLINK_SEND_BARO_MS5534A(DefaultChannel, DefaultDevice, &baro_MS5534A_pressure, &baro_MS5534A_temp, &baro_MS5534A_z); diff --git a/sw/airborne/modules/sensors/baro_amsys.c b/sw/airborne/modules/sensors/baro_amsys.c index a1549dfa99..2d29747805 100644 --- a/sw/airborne/modules/sensors/baro_amsys.c +++ b/sw/airborne/modules/sensors/baro_amsys.c @@ -103,9 +103,9 @@ void baro_amsys_init(void) baro_amsys_p = 0.0; baro_amsys_offset = 0; baro_amsys_offset_tmp = 0; - baro_amsys_valid = TRUE; - baro_amsys_offset_init = FALSE; - baro_amsys_enabled = TRUE; + baro_amsys_valid = true; + baro_amsys_offset_init = false; + baro_amsys_enabled = true; baro_scale = BARO_AMSYS_SCALE; baro_amsys_cnt = BARO_AMSYS_OFFSET_NBSAMPLES_INIT + BARO_AMSYS_OFFSET_NBSAMPLES_AVRG; baro_amsys_r = BARO_AMSYS_R; @@ -150,9 +150,9 @@ void baro_amsys_read_event(void) #endif // Check if this is valid altimeter if (pBaroRaw == 0) { - baro_amsys_valid = FALSE; + baro_amsys_valid = false; } else { - baro_amsys_valid = TRUE; + baro_amsys_valid = true; } baro_amsys_adc = pBaroRaw; @@ -181,7 +181,7 @@ void baro_amsys_read_event(void) // Calculate average baro_amsys_offset = (float)(baro_amsys_offset_tmp / BARO_AMSYS_OFFSET_NBSAMPLES_AVRG); ref_alt_init = GROUND_ALT; - baro_amsys_offset_init = TRUE; + baro_amsys_offset_init = true; // hight over Sea level at init point //baro_amsys_offset_altitude = 288.15 / 0.0065 * (1 - pow((baro_amsys_p)/1013.25 , 1/5.255)); diff --git a/sw/airborne/modules/sensors/baro_bmp.c b/sw/airborne/modules/sensors/baro_bmp.c index 4ea1e406bd..34625761da 100644 --- a/sw/airborne/modules/sensors/baro_bmp.c +++ b/sw/airborne/modules/sensors/baro_bmp.c @@ -63,7 +63,7 @@ void baro_bmp_init(void) baro_bmp_r = BARO_BMP_R; baro_bmp_sigma2 = BARO_BMP_SIGMA2; - baro_bmp_enabled = TRUE; + baro_bmp_enabled = true; } @@ -93,7 +93,7 @@ void baro_bmp_event(void) AbiSendMsgBARO_ABS(BARO_BMP_SENDER_ID, pressure); float temp = baro_bmp.temperature / 10.0f; AbiSendMsgTEMPERATURE(BARO_BOARD_SENDER_ID, temp); - baro_bmp.data_available = FALSE; + baro_bmp.data_available = false; #ifdef SENSOR_SYNC_SEND DOWNLINK_SEND_BMP_STATUS(DefaultChannel, DefaultDevice, &baro_bmp.up, diff --git a/sw/airborne/modules/sensors/baro_ets.c b/sw/airborne/modules/sensors/baro_ets.c index c95171ed2a..b4d42943d5 100644 --- a/sw/airborne/modules/sensors/baro_ets.c +++ b/sw/airborne/modules/sensors/baro_ets.c @@ -123,16 +123,16 @@ void baro_ets_init(void) baro_ets_altitude = 0.0; baro_ets_offset = 0; baro_ets_offset_tmp = 0; - baro_ets_valid = FALSE; - baro_ets_offset_init = FALSE; - baro_ets_enabled = TRUE; + baro_ets_valid = false; + baro_ets_offset_init = false; + baro_ets_enabled = true; baro_ets_cnt = BARO_ETS_OFFSET_NBSAMPLES_INIT + BARO_ETS_OFFSET_NBSAMPLES_AVRG; baro_ets_r = BARO_ETS_R; baro_ets_sigma2 = BARO_ETS_SIGMA2; baro_ets_i2c_trans.status = I2CTransDone; - baro_ets_delay_done = FALSE; + baro_ets_delay_done = false; SysTimeTimerStart(baro_ets_delay_time); } @@ -141,7 +141,7 @@ void baro_ets_read_periodic(void) // Initiate next read if (!baro_ets_delay_done) { if (SysTimeTimer(baro_ets_delay_time) < USEC_OF_SEC(BARO_ETS_START_DELAY)) { return; } - else { baro_ets_delay_done = TRUE; } + else { baro_ets_delay_done = true; } } if (baro_ets_i2c_trans.status == I2CTransDone) { i2c_receive(&BARO_ETS_I2C_DEV, &baro_ets_i2c_trans, BARO_ETS_ADDR, 2); @@ -154,9 +154,9 @@ void baro_ets_read_event(void) baro_ets_adc = ((uint16_t)(baro_ets_i2c_trans.buf[1]) << 8) | (uint16_t)(baro_ets_i2c_trans.buf[0]); // Check if this is valid altimeter if (baro_ets_adc == 0) { - baro_ets_valid = FALSE; + baro_ets_valid = false; } else { - baro_ets_valid = TRUE; + baro_ets_valid = true; } // Continue only if a new altimeter value was received @@ -175,7 +175,7 @@ void baro_ets_read_event(void) if (baro_ets_offset > BARO_ETS_OFFSET_MAX) { baro_ets_offset = BARO_ETS_OFFSET_MAX; } - baro_ets_offset_init = TRUE; + baro_ets_offset_init = true; } // Check if averaging needs to continue else if (baro_ets_cnt <= BARO_ETS_OFFSET_NBSAMPLES_AVRG) { diff --git a/sw/airborne/modules/sensors/baro_hca.c b/sw/airborne/modules/sensors/baro_hca.c index 77415bab6d..98286e7f71 100644 --- a/sw/airborne/modules/sensors/baro_hca.c +++ b/sw/airborne/modules/sensors/baro_hca.c @@ -62,7 +62,7 @@ struct i2c_transaction baro_hca_i2c_trans; void baro_hca_init(void) { pBaroRaw = 0; - baro_hca_valid = TRUE; + baro_hca_valid = true; baro_hca_i2c_trans.status = I2CTransDone; } @@ -82,9 +82,9 @@ void baro_hca_read_event(void) pBaroRaw = ((uint16_t)baro_hca_i2c_trans.buf[0] << 8) | baro_hca_i2c_trans.buf[1]; if (pBaroRaw == 0) { - baro_hca_valid = FALSE; + baro_hca_valid = false; } else { - baro_hca_valid = TRUE; + baro_hca_valid = true; } diff --git a/sw/airborne/modules/sensors/baro_mpl3115.c b/sw/airborne/modules/sensors/baro_mpl3115.c index b8c35c54ec..0e1b633e72 100644 --- a/sw/airborne/modules/sensors/baro_mpl3115.c +++ b/sw/airborne/modules/sensors/baro_mpl3115.c @@ -70,7 +70,7 @@ void baro_mpl3115_read_event(void) #ifdef SENSOR_SYNC_SEND DOWNLINK_SEND_MPL3115_BARO(DefaultChannel, DefaultDevice, &baro_mpl.pressure, &baro_mpl.temperature, &baro_mpl.alt); #endif - baro_mpl.data_available = FALSE; + baro_mpl.data_available = false; } } diff --git a/sw/airborne/modules/sensors/baro_mpl3115.h b/sw/airborne/modules/sensors/baro_mpl3115.h index cb28ab4629..5c40040c68 100644 --- a/sw/airborne/modules/sensors/baro_mpl3115.h +++ b/sw/airborne/modules/sensors/baro_mpl3115.h @@ -33,6 +33,6 @@ extern void baro_mpl3115_init(void); extern void baro_mpl3115_read_periodic(void); extern void baro_mpl3115_read_event(void); -#define BaroMpl3115Update(_b, _h) { if (mpl3115_data_available) { _b = mpl3115_pressure; _h(); mpl3115_data_available = FALSE; } } +#define BaroMpl3115Update(_b, _h) { if (mpl3115_data_available) { _b = mpl3115_pressure; _h(); mpl3115_data_available = false; } } #endif diff --git a/sw/airborne/modules/sensors/baro_ms5611_i2c.c b/sw/airborne/modules/sensors/baro_ms5611_i2c.c index 3b710329c6..5a23371cc9 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_i2c.c +++ b/sw/airborne/modules/sensors/baro_ms5611_i2c.c @@ -61,8 +61,8 @@ void baro_ms5611_init(void) { ms5611_i2c_init(&baro_ms5611, &MS5611_I2C_DEV, MS5611_SLAVE_ADDR, FALSE); - baro_ms5611_enabled = TRUE; - baro_ms5611_alt_valid = FALSE; + baro_ms5611_enabled = true; + baro_ms5611_alt_valid = false; baro_ms5611_r = BARO_MS5611_R; baro_ms5611_sigma2 = BARO_MS5611_SIGMA2; @@ -97,10 +97,10 @@ void baro_ms5611_event(void) AbiSendMsgBARO_ABS(BARO_MS5611_SENDER_ID, pressure); float temp = baro_ms5611.data.temperature / 100.0f; AbiSendMsgTEMPERATURE(BARO_MS5611_SENDER_ID, temp); - baro_ms5611.data_available = FALSE; + baro_ms5611.data_available = false; baro_ms5611_alt = pprz_isa_altitude_of_pressure(pressure); - baro_ms5611_alt_valid = TRUE; + baro_ms5611_alt_valid = true; #ifdef SENSOR_SYNC_SEND fbaroms = baro_ms5611.data.pressure / 100.; diff --git a/sw/airborne/modules/sensors/baro_ms5611_spi.c b/sw/airborne/modules/sensors/baro_ms5611_spi.c index 0503f8c1e4..1f7ed49c28 100644 --- a/sw/airborne/modules/sensors/baro_ms5611_spi.c +++ b/sw/airborne/modules/sensors/baro_ms5611_spi.c @@ -60,8 +60,8 @@ void baro_ms5611_init(void) { ms5611_spi_init(&baro_ms5611, &MS5611_SPI_DEV, MS5611_SLAVE_IDX, FALSE); - baro_ms5611_enabled = TRUE; - baro_ms5611_alt_valid = FALSE; + baro_ms5611_enabled = true; + baro_ms5611_alt_valid = false; baro_ms5611_r = BARO_MS5611_R; baro_ms5611_sigma2 = BARO_MS5611_SIGMA2; @@ -97,10 +97,10 @@ void baro_ms5611_event(void) AbiSendMsgBARO_ABS(BARO_MS5611_SENDER_ID, pressure); float temp = baro_ms5611.data.temperature / 100.0f; AbiSendMsgTEMPERATURE(BARO_MS5611_SENDER_ID, temp); - baro_ms5611.data_available = FALSE; + baro_ms5611.data_available = false; baro_ms5611_alt = pprz_isa_altitude_of_pressure(pressure); - baro_ms5611_alt_valid = TRUE; + baro_ms5611_alt_valid = true; #ifdef SENSOR_SYNC_SEND fbaroms = baro_ms5611.data.pressure / 100.; diff --git a/sw/airborne/modules/sensors/baro_scp.c b/sw/airborne/modules/sensors/baro_scp.c index 6a3dbde434..b30653fb18 100644 --- a/sw/airborne/modules/sensors/baro_scp.c +++ b/sw/airborne/modules/sensors/baro_scp.c @@ -132,7 +132,7 @@ void SPI1_ISR(void) baro_scp_pressure += SSPDR; baro_scp_pressure += datard8; baro_scp_pressure *= 25; - baro_scp_available = TRUE; + baro_scp_available = true; foo1 = foo2; foo0 = foo2; } @@ -193,6 +193,6 @@ void baro_scp_event(void) #ifdef SENSOR_SYNC_SEND DOWNLINK_SEND_SCP_STATUS(DefaultChannel, DefaultDevice, &baro_scp_pressure, &baro_scp_temperature); #endif - baro_scp_available = FALSE; + baro_scp_available = false; } } diff --git a/sw/airborne/modules/sensors/imu_aspirin2.c b/sw/airborne/modules/sensors/imu_aspirin2.c index da5d39ddb3..669a975fac 100644 --- a/sw/airborne/modules/sensors/imu_aspirin2.c +++ b/sw/airborne/modules/sensors/imu_aspirin2.c @@ -228,7 +228,7 @@ void aspirin2_subsystem_event(void) VECT3_ASSIGN(imu.accel_unscaled, -x, y, -z); #endif - acc_valid = TRUE; + acc_valid = true; ppzuavimu_adxl345.status = I2CTransDone; } @@ -245,7 +245,7 @@ void aspirin2_subsystem_event(void) VECT3_ASSIGN(imu.mag_unscaled, -y, -x, -z); #endif - mag_valid = TRUE; + mag_valid = true; ppzuavimu_hmc5843.status = I2CTransDone; } */ diff --git a/sw/airborne/modules/sensors/mag_hmc58xx.c b/sw/airborne/modules/sensors/mag_hmc58xx.c index 53eea05649..f38e046fbb 100644 --- a/sw/airborne/modules/sensors/mag_hmc58xx.c +++ b/sw/airborne/modules/sensors/mag_hmc58xx.c @@ -83,7 +83,7 @@ void mag_hmc58xx_module_event(void) mag_hmc58xx_report(); #endif #if MODULE_HMC58XX_UPDATE_AHRS || MODULE_HMC58XX_SYNC_SEND - mag_hmc58xx.data_available = FALSE; + mag_hmc58xx.data_available = false; #endif } } diff --git a/sw/airborne/modules/sensors/pressure_board_navarro.c b/sw/airborne/modules/sensors/pressure_board_navarro.c index 532e257149..26e8a8eaa9 100644 --- a/sw/airborne/modules/sensors/pressure_board_navarro.c +++ b/sw/airborne/modules/sensors/pressure_board_navarro.c @@ -86,7 +86,7 @@ void pbn_init(void) pbn.airspeed_offset = 0; pbn.airspeed_adc = 0; pbn.altitude_adc = 0; - pbn.data_valid = TRUE; + pbn.data_valid = true; offset_cnt = OFFSET_NBSAMPLES_AVRG; pbn.airspeed = 0.; pbn.altitude = 0.; @@ -119,9 +119,9 @@ void pbn_read_event(void) // Consider 0 as a wrong value if (pbn.airspeed_adc == 0 || pbn.altitude_adc == 0) { - pbn.data_valid = FALSE; + pbn.data_valid = false; } else { - pbn.data_valid = TRUE; + pbn.data_valid = true; if (offset_cnt > 0) { // IIR filter to compute an initial offset diff --git a/sw/airborne/modules/sensors/trigger_ext.c b/sw/airborne/modules/sensors/trigger_ext.c index b8581429c3..ad03829cc8 100644 --- a/sw/airborne/modules/sensors/trigger_ext.c +++ b/sw/airborne/modules/sensors/trigger_ext.c @@ -58,7 +58,7 @@ void trigger_ext_periodic(void) &turb_id, &sync_itow, &cycle_time); - trig_ext_valid = FALSE; + trig_ext_valid = false; } } diff --git a/sw/airborne/modules/servo_switch/servo_switch.c b/sw/airborne/modules/servo_switch/servo_switch.c index 5054870fad..aa13e080b2 100644 --- a/sw/airborne/modules/servo_switch/servo_switch.c +++ b/sw/airborne/modules/servo_switch/servo_switch.c @@ -31,7 +31,7 @@ bool servo_switch_on; void servo_switch_init(void) { - servo_switch_on = FALSE; + servo_switch_on = false; servo_switch_periodic(); } diff --git a/sw/airborne/modules/servo_switch/servo_switch.h b/sw/airborne/modules/servo_switch/servo_switch.h index 1d7bf0bc70..9704e9af7d 100644 --- a/sw/airborne/modules/servo_switch/servo_switch.h +++ b/sw/airborne/modules/servo_switch/servo_switch.h @@ -43,8 +43,8 @@ extern int16_t servo_switch_value; extern void servo_switch_init(void); extern void servo_switch_periodic(void); -#define ServoSwitchOn() ({ servo_switch_on = TRUE; FALSE; }) -#define ServoSwitchOff() ({ servo_switch_on = FALSE; FALSE; }) +#define ServoSwitchOn() ({ servo_switch_on = true; false; }) +#define ServoSwitchOff() ({ servo_switch_on = false; false; }) #endif //SERVO_SWITCH_H diff --git a/sw/airborne/modules/sonar/agl_dist.c b/sw/airborne/modules/sonar/agl_dist.c index 724f864e5a..10d3d28f85 100644 --- a/sw/airborne/modules/sonar/agl_dist.c +++ b/sw/airborne/modules/sonar/agl_dist.c @@ -54,7 +54,7 @@ static void sonar_cb(uint8_t sender_id, float distance); void agl_dist_init(void) { - agl_dist_valid = FALSE; + agl_dist_valid = false; agl_dist_value = 0.; agl_dist_value_filtered = 0.; @@ -67,11 +67,11 @@ static void sonar_cb(uint8_t __attribute__((unused)) sender_id, float distance) { if (distance < AGL_DIST_SONAR_MAX_RANGE && distance > AGL_DIST_SONAR_MIN_RANGE) { agl_dist_value = distance; - agl_dist_valid = TRUE; + agl_dist_valid = true; agl_dist_value_filtered = (AGL_DIST_SONAR_FILTER * agl_dist_value_filtered + agl_dist_value) / (AGL_DIST_SONAR_FILTER + 1); } else { - agl_dist_valid = FALSE; + agl_dist_valid = false; } } diff --git a/sw/airborne/modules/stereocam/droplet/stereocam_droplet.c b/sw/airborne/modules/stereocam/droplet/stereocam_droplet.c index 06383b2a2f..5c6a6da15b 100644 --- a/sw/airborne/modules/stereocam/droplet/stereocam_droplet.c +++ b/sw/airborne/modules/stereocam/droplet/stereocam_droplet.c @@ -113,13 +113,13 @@ void stereocam_droplet_periodic(void) // Results DOWNLINK_SEND_PAYLOAD(DefaultChannel, DefaultDevice, 1, avoid_navigation_data.stereo_bin); - volatile bool once = TRUE; + volatile bool once = true; // Move waypoint with constant speed in current direction if ( (avoid_navigation_data.stereo_bin[0] == 97) || (avoid_navigation_data.stereo_bin[0] == 100) ) { - once = TRUE; + once = true; struct EnuCoor_f enu; enu.x = waypoint_get_x(WP_GOAL); enu.y = waypoint_get_y(WP_GOAL); @@ -133,10 +133,10 @@ void stereocam_droplet_periodic(void) // STOP!!! if (once) { NavSetWaypointHere(WP_GOAL); - once = FALSE; + once = false; } } else { - once = TRUE; + once = true; } diff --git a/sw/airborne/modules/stereocam/nav_line_avoid/avoid_navigation.c b/sw/airborne/modules/stereocam/nav_line_avoid/avoid_navigation.c index 0912145d02..a2148cb4db 100644 --- a/sw/airborne/modules/stereocam/nav_line_avoid/avoid_navigation.c +++ b/sw/airborne/modules/stereocam/nav_line_avoid/avoid_navigation.c @@ -54,7 +54,7 @@ struct AvoidNavigationStruct avoid_navigation_data; -bool obstacle_detected = FALSE; +bool obstacle_detected = false; int32_t counter = 0; // Called once on paparazzi autopilot start @@ -78,7 +78,7 @@ void run_avoid_navigation_onvision(void) if (counter > 1) { counter = 0; //Obstacle detected, go to turn until clear mode - obstacle_detected = TRUE; + obstacle_detected = true; avoid_navigation_data.mode = 1; } } else { @@ -100,7 +100,7 @@ void run_avoid_navigation_onvision(void) new_coor.y = pos->y + POS_BFP_OF_REAL(cos_heading * (NAV_LINE_AVOID_SEGMENT_LENGTH)); new_coor.z = pos->z; waypoint_set_xy_i(WP_W1, new_coor.x, new_coor.y); - obstacle_detected = FALSE; + obstacle_detected = false; avoid_navigation_data.mode = 0; } } else { diff --git a/sw/airborne/modules/vehicle_interface/vi.c b/sw/airborne/modules/vehicle_interface/vi.c index 78a52c2bea..9506ff5b37 100644 --- a/sw/airborne/modules/vehicle_interface/vi.c +++ b/sw/airborne/modules/vehicle_interface/vi.c @@ -36,8 +36,8 @@ struct VehicleInterface vi; void vi_init(void) { - vi.enabled = FALSE; - vi.timeouted = TRUE; + vi.enabled = false; + vi.timeouted = true; vi.last_msg = VI_TIMEOUT; vi.input.h_mode = GUIDANCE_H_MODE_ATTITUDE; @@ -54,7 +54,7 @@ void vi_periodic(void) if (vi.last_msg < VI_TIMEOUT) { vi.last_msg++; } else { - vi.timeouted = TRUE; + vi.timeouted = true; vi.input.h_mode = GUIDANCE_H_MODE_ATTITUDE; INT_EULERS_ZERO(vi.input.h_sp.attitude); vi.input.v_mode = GUIDANCE_V_MODE_CLIMB; diff --git a/sw/airborne/peripherals/ads1114.c b/sw/airborne/peripherals/ads1114.c index 55867bfeaa..c33899698a 100644 --- a/sw/airborne/peripherals/ads1114.c +++ b/sw/airborne/peripherals/ads1114.c @@ -43,8 +43,8 @@ void ads1114_init(void) ads1114_1.trans.buf[1] = ADS1114_1_CONFIG_MSB; ads1114_1.trans.buf[2] = ADS1114_1_CONFIG_LSB; i2c_transmit(&ADS1114_I2C_DEV, &ads1114_1.trans, ADS1114_1_I2C_ADDR, 3); - ads1114_1.config_done = FALSE; - ads1114_1.data_available = FALSE; + ads1114_1.config_done = false; + ads1114_1.data_available = false; #endif /* configure the ads1114_2 */ @@ -54,8 +54,8 @@ void ads1114_init(void) ads1114_2.trans.buf[1] = ADS1114_2_CONFIG_MSB; ads1114_2.trans.buf[2] = ADS1114_2_CONFIG_LSB; i2c_transmit(&ADS1114_I2C_DEV, &ads1114_2.trans, ADS1114_2_I2C_ADDR, 3); - ads1114_2.config_done = FALSE; - ads1114_2.data_available = FALSE; + ads1114_2.config_done = false; + ads1114_2.data_available = false; #endif } diff --git a/sw/airborne/peripherals/ads1114.h b/sw/airborne/peripherals/ads1114.h index 96b1d2eb42..291b2839fd 100644 --- a/sw/airborne/peripherals/ads1114.h +++ b/sw/airborne/peripherals/ads1114.h @@ -134,10 +134,10 @@ extern void ads1114_read(struct ads1114_periph *p); // Generic Event Macro #define _Ads1114Event(_p) {\ if (!_p.config_done) { \ - if (_p.trans.status == I2CTransSuccess) { _p.config_done = TRUE; _p.trans.status = I2CTransDone; } \ + if (_p.trans.status == I2CTransSuccess) { _p.config_done = true; _p.trans.status = I2CTransDone; } \ if (_p.trans.status == I2CTransFailed) { _p.trans.status = I2CTransDone; } \ } else { \ - if (_p.trans.status == I2CTransSuccess) { _p.data_available = TRUE; _p.trans.status = I2CTransDone; } \ + if (_p.trans.status == I2CTransSuccess) { _p.data_available = true; _p.trans.status = I2CTransDone; } \ if (_p.trans.status == I2CTransFailed) { _p.trans.status = I2CTransDone; } \ } \ } diff --git a/sw/airborne/peripherals/ads1220.c b/sw/airborne/peripherals/ads1220.c index 25dc1336d7..6ffcb2ded1 100644 --- a/sw/airborne/peripherals/ads1220.c +++ b/sw/airborne/peripherals/ads1220.c @@ -71,7 +71,7 @@ void ads1220_init(struct Ads1220 *ads, struct spi_periph *spi_p, uint8_t slave_i ads->spi_trans.status = SPITransDone; ads->data = 0; - ads->data_available = FALSE; + ads->data_available = false; ads->config.status = ADS1220_UNINIT; } @@ -135,7 +135,7 @@ void ads1220_event(struct Ads1220 *ads) } else if (ads->spi_trans.status == SPITransSuccess) { // Successfull reading of 24bits adc ads->data = (uint32_t)(((uint32_t)(ads->rx_buf[0]) << 16) | ((uint32_t)(ads->rx_buf[1]) << 8) | (ads->rx_buf[2])); - ads->data_available = TRUE; + ads->data_available = true; ads->spi_trans.status = SPITransDone; } } else if (ads->config.status == ADS1220_SEND_RESET) { // Reset ads1220 before configuring diff --git a/sw/airborne/peripherals/adxl345.h b/sw/airborne/peripherals/adxl345.h index ec8ed86805..5c0688957d 100644 --- a/sw/airborne/peripherals/adxl345.h +++ b/sw/airborne/peripherals/adxl345.h @@ -55,12 +55,12 @@ struct Adxl345Config { static inline void adxl345_set_default_config(struct Adxl345Config *c) { - c->drdy_int_enable = FALSE; - c->int_invert = TRUE; - c->full_res = TRUE; - c->justify_msb = FALSE; - c->self_test = FALSE; - c->spi_3_wire = FALSE; + c->drdy_int_enable = false; + c->int_invert = true; + c->full_res = true; + c->justify_msb = false; + c->self_test = false; + c->spi_3_wire = false; c->rate = ADXL345_RATE_100HZ; c->range = ADXL345_RANGE_16G; diff --git a/sw/airborne/peripherals/adxl345_i2c.c b/sw/airborne/peripherals/adxl345_i2c.c index 5732a0ae16..0e94bafe0f 100644 --- a/sw/airborne/peripherals/adxl345_i2c.c +++ b/sw/airborne/peripherals/adxl345_i2c.c @@ -42,7 +42,7 @@ void adxl345_i2c_init(struct Adxl345_I2c *adxl, struct i2c_periph *i2c_p, uint8_ adxl->i2c_trans.status = I2CTransDone; /* set default config options */ adxl345_set_default_config(&(adxl->config)); - adxl->initialized = FALSE; + adxl->initialized = false; adxl->init_status = ADXL_CONF_UNINIT; } @@ -78,7 +78,7 @@ static void adxl345_i2c_send_config(struct Adxl345_I2c *adxl) adxl->init_status++; break; case ADXL_CONF_DONE: - adxl->initialized = TRUE; + adxl->initialized = true; adxl->i2c_trans.status = I2CTransDone; break; default: @@ -121,7 +121,7 @@ void adxl345_i2c_event(struct Adxl345_I2c *adxl) adxl->data.vect.x = Int16FromBuf(adxl->i2c_trans.buf, 0); adxl->data.vect.y = Int16FromBuf(adxl->i2c_trans.buf, 2); adxl->data.vect.z = Int16FromBuf(adxl->i2c_trans.buf, 4); - adxl->data_available = TRUE; + adxl->data_available = true; adxl->i2c_trans.status = I2CTransDone; } } else if (adxl->init_status != ADXL_CONF_UNINIT) { // Configuring but not yet initialized diff --git a/sw/airborne/peripherals/adxl345_spi.c b/sw/airborne/peripherals/adxl345_spi.c index 6447b29adb..f2b8021d89 100644 --- a/sw/airborne/peripherals/adxl345_spi.c +++ b/sw/airborne/peripherals/adxl345_spi.c @@ -60,8 +60,8 @@ void adxl345_spi_init(struct Adxl345_Spi *adxl, struct spi_periph *spi_p, uint8_ /* set default ADXL345 config options */ adxl345_set_default_config(&(adxl->config)); - adxl->initialized = FALSE; - adxl->data_available = FALSE; + adxl->initialized = false; + adxl->data_available = false; adxl->init_status = ADXL_CONF_UNINIT; } @@ -97,7 +97,7 @@ static void adxl345_spi_send_config(struct Adxl345_Spi *adxl) adxl->init_status++; break; case ADXL_CONF_DONE: - adxl->initialized = TRUE; + adxl->initialized = true; adxl->spi_trans.status = SPITransDone; break; default: @@ -138,7 +138,7 @@ void adxl345_spi_event(struct Adxl345_Spi *adxl) adxl->data.vect.x = Int16FromBuf(adxl->rx_buf, 1); adxl->data.vect.y = Int16FromBuf(adxl->rx_buf, 3); adxl->data.vect.z = Int16FromBuf(adxl->rx_buf, 5); - adxl->data_available = TRUE; + adxl->data_available = true; adxl->spi_trans.status = SPITransDone; } } else if (adxl->init_status != ADXL_CONF_UNINIT) { // Configuring but not yet initialized diff --git a/sw/airborne/peripherals/ak8963.c b/sw/airborne/peripherals/ak8963.c index 3033048e7a..db9f1af394 100644 --- a/sw/airborne/peripherals/ak8963.c +++ b/sw/airborne/peripherals/ak8963.c @@ -38,9 +38,9 @@ void ak8963_init(struct Ak8963 *ak, struct i2c_periph *i2c_p, uint8_t addr) /* set i2c address */ ak->i2c_trans.slave_addr = addr; ak->i2c_trans.status = I2CTransDone; - ak->initialized = FALSE; + ak->initialized = false; ak->init_status = AK_CONF_UNINIT; - ak->data_available = FALSE; + ak->data_available = false; } void ak8963_configure(struct Ak8963 *ak) @@ -75,7 +75,7 @@ void ak8963_configure(struct Ak8963 *ak) // Initialization done default: - ak->initialized = TRUE; + ak->initialized = true; break; } } @@ -114,7 +114,7 @@ void ak8963_event(struct Ak8963 *ak) ak->data.vect.x = Int16FromBuf(ak->i2c_trans.buf, 0); ak->data.vect.y = Int16FromBuf(ak->i2c_trans.buf, 2); ak->data.vect.z = Int16FromBuf(ak->i2c_trans.buf, 4); - ak->data_available = TRUE; + ak->data_available = true; // Read second status register to be ready for reading again ak->i2c_trans.buf[0] = AK8963_REG_ST2; @@ -132,9 +132,9 @@ void ak8963_event(struct Ak8963 *ak) ak->status = AK_STATUS_IDLE; // check overrun //if (bit_is_set(ak->i2c_trans.buf[0], 3)) { - // ak->data_available = FALSE; + // ak->data_available = false; //} else { - // ak->data_available = TRUE; + // ak->data_available = true; //} } break; diff --git a/sw/airborne/peripherals/ak8975.c b/sw/airborne/peripherals/ak8975.c index 800bd00aaa..e73b2fe3df 100644 --- a/sw/airborne/peripherals/ak8975.c +++ b/sw/airborne/peripherals/ak8975.c @@ -53,10 +53,10 @@ void ak8975_init(struct Ak8975 *ak, struct i2c_periph *i2c_p, uint8_t addr) ak->i2c_trans.status = I2CTransDone; - ak->initialized = FALSE; + ak->initialized = false; ak->status = AK_STATUS_IDLE; ak->init_status = AK_CONF_UNINIT; - ak->data_available = FALSE; + ak->data_available = false; } // Configure @@ -102,7 +102,7 @@ void ak8975_configure(struct Ak8975 *ak) break; case AK_CONF_REQUESTED: - ak->initialized = TRUE; + ak->initialized = true; break; default: @@ -178,7 +178,7 @@ void ak8975_event(struct Ak8975 *ak) ak->data.vect.y = Int16FromRaw(val); val = RawFromBuf(ak->i2c_trans.buf, 5); ak->data.vect.z = Int16FromRaw(val); - ak->data_available = TRUE; + ak->data_available = true; // End reading, back to idle ak->status = AK_STATUS_IDLE; break; diff --git a/sw/airborne/peripherals/bmp085.c b/sw/airborne/peripherals/bmp085.c index d88e6818b6..74a2aa082c 100644 --- a/sw/airborne/peripherals/bmp085.c +++ b/sw/airborne/peripherals/bmp085.c @@ -66,14 +66,14 @@ static int32_t bmp085_compensated_pressure(struct Bmp085Calib *calib, int32_t ra */ static bool bmp085_eoc_true(void) { - return TRUE; + return true; } void bmp085_read_eeprom_calib(struct Bmp085 *bmp) { if (bmp->status == BMP085_STATUS_UNINIT && bmp->i2c_trans.status == I2CTransDone) { - bmp->initialized = FALSE; + bmp->initialized = false; bmp->i2c_trans.buf[0] = BMP085_EEPROM_AC1; i2c_transceive(bmp->i2c_p, &(bmp->i2c_trans), bmp->i2c_trans.slave_addr, 1, 22); } @@ -90,8 +90,8 @@ void bmp085_init(struct Bmp085 *bmp, struct i2c_periph *i2c_p, uint8_t addr) /* set initial status: Success or Done */ bmp->i2c_trans.status = I2CTransDone; - bmp->data_available = FALSE; - bmp->initialized = FALSE; + bmp->data_available = false; + bmp->initialized = false; bmp->status = BMP085_STATUS_UNINIT; /* by default assign EOC function that always returns TRUE @@ -156,7 +156,7 @@ void bmp085_event(struct Bmp085 *bmp) bmp->calib.mc = (bmp->i2c_trans.buf[18] << 8) | bmp->i2c_trans.buf[19]; bmp->calib.md = (bmp->i2c_trans.buf[20] << 8) | bmp->i2c_trans.buf[21]; bmp->status = BMP085_STATUS_IDLE; - bmp->initialized = TRUE; + bmp->initialized = true; break; case BMP085_STATUS_READ_TEMP: @@ -177,7 +177,7 @@ void bmp085_event(struct Bmp085 *bmp) bmp->i2c_trans.buf[2]; bmp->up = bmp->up >> (8 - BMP085_OSS); bmp->pressure = bmp085_compensated_pressure(&(bmp->calib), bmp->up); - bmp->data_available = TRUE; + bmp->data_available = true; bmp->status = BMP085_STATUS_IDLE; break; diff --git a/sw/airborne/peripherals/cyrf6936.c b/sw/airborne/peripherals/cyrf6936.c index 0431a9950d..33e73f3e60 100644 --- a/sw/airborne/peripherals/cyrf6936.c +++ b/sw/airborne/peripherals/cyrf6936.c @@ -50,7 +50,7 @@ void cyrf6936_init(struct Cyrf6936 *cyrf, struct spi_periph *spi_p, const uint8_ /* Set spi_peripheral and the status */ cyrf->spi_p = spi_p; cyrf->status = CYRF6936_UNINIT; - cyrf->has_irq = FALSE; + cyrf->has_irq = false; /* Set the spi transaction */ cyrf->spi_t.cpol = SPICpolIdleLow; @@ -223,7 +223,7 @@ void cyrf6936_event(struct Cyrf6936 *cyrf) cyrf->rx_packet[i] = cyrf->input_buf[i + 1]; } - cyrf->has_irq = TRUE; + cyrf->has_irq = true; cyrf->status = CYRF6936_IDLE; break; } @@ -281,7 +281,7 @@ static bool cyrf6936_write_block(struct Cyrf6936 *cyrf, const uint8_t addr, cons uint8_t i; /* Check if there is already a SPI transaction busy */ if (cyrf->spi_t.status != SPITransDone) { - return FALSE; + return false; } /* Set the buffer and commit the transaction */ @@ -312,7 +312,7 @@ static bool cyrf6936_read_register(struct Cyrf6936 *cyrf, const uint8_t addr) static bool cyrf6936_read_block(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t length) { if (cyrf->spi_t.status != SPITransDone) { - return FALSE; + return false; } /* Set the buffer and commit the transaction */ @@ -343,7 +343,7 @@ bool cyrf6936_multi_write(struct Cyrf6936 *cyrf, const uint8_t data[][2], const uint8_t i; /* Check if the cyrf6936 isn't busy */ if (cyrf->status != CYRF6936_IDLE) { - return FALSE; + return false; } // Set the status @@ -364,7 +364,7 @@ bool cyrf6936_multi_write(struct Cyrf6936 *cyrf, const uint8_t data[][2], const cyrf6936_write_register(cyrf, data[0][0], data[0][1]); } - return TRUE; + return true; } /** @@ -376,7 +376,7 @@ bool cyrf6936_write_chan_sop_data_crc(struct Cyrf6936 *cyrf, const uint8_t chan, uint8_t i; /* Check if the cyrf6936 isn't busy */ if (cyrf->status != CYRF6936_IDLE) { - return FALSE; + return false; } // Set the status @@ -403,7 +403,7 @@ bool cyrf6936_write_chan_sop_data_crc(struct Cyrf6936 *cyrf, const uint8_t chan, cyrf->buffer_idx = 0; cyrf6936_write_register(cyrf, CYRF_CRC_SEED_LSB, cyrf->buffer[0]); - return TRUE; + return true; } /** @@ -413,7 +413,7 @@ bool cyrf6936_read_rx_irq_status_packet(struct Cyrf6936 *cyrf) { /* Check if the cyrf6936 isn't busy */ if (cyrf->status != CYRF6936_IDLE) { - return FALSE; + return false; } // Set the status @@ -423,7 +423,7 @@ bool cyrf6936_read_rx_irq_status_packet(struct Cyrf6936 *cyrf) cyrf->buffer_idx = 0; cyrf6936_read_register(cyrf, CYRF_RX_IRQ_STATUS); - return TRUE; + return true; } /** @@ -435,7 +435,7 @@ bool cyrf6936_send(struct Cyrf6936 *cyrf, const uint8_t data[], const uint8_t le /* Check if the cyrf6936 isn't busy */ if (cyrf->status != CYRF6936_IDLE) { - return FALSE; + return false; } // Set the status @@ -451,5 +451,5 @@ bool cyrf6936_send(struct Cyrf6936 *cyrf, const uint8_t data[], const uint8_t le cyrf->buffer_idx = 0; cyrf6936_write_register(cyrf, CYRF_TX_LENGTH, cyrf->buffer[0]); - return TRUE; + return true; } diff --git a/sw/airborne/peripherals/eeprom25AA256.c b/sw/airborne/peripherals/eeprom25AA256.c index 895b22ae58..f4cda0bd88 100644 --- a/sw/airborne/peripherals/eeprom25AA256.c +++ b/sw/airborne/peripherals/eeprom25AA256.c @@ -94,7 +94,7 @@ void eeprom25AA256_event(struct Eeprom25AA256 *eeprom) eeprom->spi_trans.status = SPITransDone; } else if (eeprom->spi_trans.status == SPITransSuccess) { // Successfull reading - eeprom->data_available = TRUE; + eeprom->data_available = true; eeprom->spi_trans.status = SPITransDone; } } diff --git a/sw/airborne/peripherals/hmc5843.c b/sw/airborne/peripherals/hmc5843.c index 5ef98a5782..56d112622a 100644 --- a/sw/airborne/peripherals/hmc5843.c +++ b/sw/airborne/peripherals/hmc5843.c @@ -92,7 +92,7 @@ void hmc5843_idle_task(void) hmc5843.sent_rx = 0; hmc5843.sent_tx = 0; hmc5843.timeout = 0; - hmc5843.data_available = TRUE; + hmc5843.data_available = true; memcpy(hmc5843.data.buf, (const void *) hmc5843.i2c_trans.buf, 6); for (int i = 0; i < 3; i++) { hmc5843.data.value[i] = bswap_16(hmc5843.data.value[i]); @@ -104,7 +104,7 @@ void hmc5843_periodic(void) { if (!hmc5843.initialized) { send_config(); - hmc5843.initialized = TRUE; + hmc5843.initialized = true; } else if (hmc5843.timeout++ > HMC5843_TIMEOUT && HMC5843_I2C_DEV.status == I2CIdle && i2c_idle(&HMC5843_I2C_DEV)) { #ifdef USE_HMC59843_ARCH_RESET hmc5843_arch_reset(); diff --git a/sw/airborne/peripherals/hmc58xx.c b/sw/airborne/peripherals/hmc58xx.c index fe2f05c00d..3db8446110 100644 --- a/sw/airborne/peripherals/hmc58xx.c +++ b/sw/airborne/peripherals/hmc58xx.c @@ -82,7 +82,7 @@ void hmc58xx_init(struct Hmc58xx *hmc, struct i2c_periph *i2c_p, uint8_t addr) /* set default config options */ hmc58xx_set_default_config(&(hmc->config)); hmc->type = HMC_TYPE_5883; - hmc->initialized = FALSE; + hmc->initialized = false; hmc->init_status = HMC_CONF_UNINIT; hmc->adc_overflow_cnt = 0; } @@ -114,7 +114,7 @@ static void hmc58xx_send_config(struct Hmc58xx *hmc) hmc->init_status++; break; case HMC_CONF_DONE: - hmc->initialized = TRUE; + hmc->initialized = true; hmc->i2c_trans.status = I2CTransDone; break; default: @@ -169,7 +169,7 @@ void hmc58xx_event(struct Hmc58xx *hmc) /* only set available if measurements valid: -4096 if ADC under/overflow in sensor */ if (hmc->data.vect.x != -4096 && hmc->data.vect.y != -4096 && hmc->data.vect.z != -4096) { - hmc->data_available = TRUE; + hmc->data_available = true; } else { hmc->adc_overflow_cnt++; diff --git a/sw/airborne/peripherals/itg3200.c b/sw/airborne/peripherals/itg3200.c index 758b3276d2..08d05d5662 100644 --- a/sw/airborne/peripherals/itg3200.c +++ b/sw/airborne/peripherals/itg3200.c @@ -55,7 +55,7 @@ void itg3200_init(struct Itg3200 *itg, struct i2c_periph *i2c_p, uint8_t addr) itg->i2c_trans.status = I2CTransDone; /* set default config options */ itg3200_set_default_config(&(itg->config)); - itg->initialized = FALSE; + itg->initialized = false; itg->init_status = ITG_CONF_UNINIT; } @@ -90,7 +90,7 @@ static void itg3200_send_config(struct Itg3200 *itg) itg->init_status++; break; case ITG_CONF_DONE: - itg->initialized = TRUE; + itg->initialized = true; itg->i2c_trans.status = I2CTransDone; break; default: @@ -135,7 +135,7 @@ void itg3200_event(struct Itg3200 *itg) itg->data.rates.p = Int16FromBuf(itg->i2c_trans.buf, 3); itg->data.rates.q = Int16FromBuf(itg->i2c_trans.buf, 5); itg->data.rates.r = Int16FromBuf(itg->i2c_trans.buf, 7); - itg->data_available = TRUE; + itg->data_available = true; } itg->i2c_trans.status = I2CTransDone; } diff --git a/sw/airborne/peripherals/l3g4200.c b/sw/airborne/peripherals/l3g4200.c index f9f133bf27..c4691dc0ae 100644 --- a/sw/airborne/peripherals/l3g4200.c +++ b/sw/airborne/peripherals/l3g4200.c @@ -53,7 +53,7 @@ void l3g4200_init(struct L3g4200 *l3g, struct i2c_periph *i2c_p, uint8_t addr) l3g->i2c_trans.status = I2CTransDone; /* set default config options */ l3g4200_set_default_config(&(l3g->config)); - l3g->initialized = FALSE; + l3g->initialized = false; l3g->init_status = L3G_CONF_UNINIT; } @@ -81,7 +81,7 @@ static void l3g4200_send_config(struct L3g4200 *l3g) l3g->init_status++; break; case L3G_CONF_DONE: - l3g->initialized = TRUE; + l3g->initialized = true; l3g->i2c_trans.status = I2CTransDone; break; default: @@ -123,7 +123,7 @@ void l3g4200_event(struct L3g4200 *l3g) l3g->data.rates.p = Int16FromBuf(l3g->i2c_trans.buf, 1); l3g->data.rates.q = Int16FromBuf(l3g->i2c_trans.buf, 3); l3g->data.rates.r = Int16FromBuf(l3g->i2c_trans.buf, 5); - l3g->data_available = TRUE; + l3g->data_available = true; } l3g->i2c_trans.status = I2CTransDone; } diff --git a/sw/airborne/peripherals/l3gd20.h b/sw/airborne/peripherals/l3gd20.h index d0843a310d..93e5afe475 100644 --- a/sw/airborne/peripherals/l3gd20.h +++ b/sw/airborne/peripherals/l3gd20.h @@ -49,7 +49,7 @@ struct L3gd20Config { static inline void l3gd20_set_default_config(struct L3gd20Config *c) { - c->spi_3_wire = FALSE; + c->spi_3_wire = false; c->drbw = L3GD20_DRBW_760Hz_100BW; c->full_scale = L3GD20_FS_2000dps2; diff --git a/sw/airborne/peripherals/l3gd20_spi.c b/sw/airborne/peripherals/l3gd20_spi.c index c774adaa74..674398ac04 100644 --- a/sw/airborne/peripherals/l3gd20_spi.c +++ b/sw/airborne/peripherals/l3gd20_spi.c @@ -55,8 +55,8 @@ void l3gd20_spi_init(struct L3gd20_Spi *l3g, struct spi_periph *spi_p, uint8_t s /* set default L3GD20 config options */ l3gd20_set_default_config(&(l3g->config)); - l3g->initialized = FALSE; - l3g->data_available = FALSE; + l3g->initialized = false; + l3g->data_available = false; l3g->init_status = L3G_CONF_UNINIT; } @@ -101,7 +101,7 @@ static void l3gd20_spi_send_config(struct L3gd20_Spi *l3g) l3g->init_status++; break; case L3G_CONF_DONE: - l3g->initialized = TRUE; + l3g->initialized = true; l3g->spi_trans.status = SPITransDone; break; default: @@ -144,7 +144,7 @@ void l3gd20_spi_event(struct L3gd20_Spi *l3g) l3g->data_rates.rates.p = Int16FromBuf(l3g->rx_buf, 2); l3g->data_rates.rates.q = Int16FromBuf(l3g->rx_buf, 4); l3g->data_rates.rates.r = Int16FromBuf(l3g->rx_buf, 6); - l3g->data_available = TRUE; + l3g->data_available = true; } l3g->spi_trans.status = SPITransDone; } diff --git a/sw/airborne/peripherals/lis302dl.h b/sw/airborne/peripherals/lis302dl.h index 114b68e123..275fe2229c 100644 --- a/sw/airborne/peripherals/lis302dl.h +++ b/sw/airborne/peripherals/lis302dl.h @@ -55,9 +55,9 @@ struct Lis302dlConfig { static inline void lis302dl_set_default_config(struct Lis302dlConfig *c) { - c->int_invert = TRUE; - c->filt_data = FALSE; - c->spi_3_wire = FALSE; + c->int_invert = true; + c->filt_data = false; + c->spi_3_wire = false; c->rate = LIS302DL_RATE_100HZ; c->range = LIS302DL_RANGE_2G; diff --git a/sw/airborne/peripherals/lis302dl_spi.c b/sw/airborne/peripherals/lis302dl_spi.c index cc765197c6..a4c43450db 100644 --- a/sw/airborne/peripherals/lis302dl_spi.c +++ b/sw/airborne/peripherals/lis302dl_spi.c @@ -55,8 +55,8 @@ void lis302dl_spi_init(struct Lis302dl_Spi *lis, struct spi_periph *spi_p, uint8 /* set default LIS302DL config options */ lis302dl_set_default_config(&(lis->config)); - lis->initialized = FALSE; - lis->data_available = FALSE; + lis->initialized = false; + lis->data_available = false; lis->init_status = LIS_CONF_UNINIT; } @@ -107,7 +107,7 @@ static void lis302dl_spi_send_config(struct Lis302dl_Spi *lis) lis->init_status++; break; case LIS_CONF_DONE: - lis->initialized = TRUE; + lis->initialized = true; lis->spi_trans.status = SPITransDone; break; default: @@ -148,7 +148,7 @@ void lis302dl_spi_event(struct Lis302dl_Spi *lis) lis->data.vect.x = lis->rx_buf[3]; lis->data.vect.y = lis->rx_buf[5]; lis->data.vect.z = lis->rx_buf[7]; - lis->data_available = TRUE; + lis->data_available = true; } lis->spi_trans.status = SPITransDone; } diff --git a/sw/airborne/peripherals/lsm303dlhc.c b/sw/airborne/peripherals/lsm303dlhc.c index 639737056e..aa34d312c6 100644 --- a/sw/airborne/peripherals/lsm303dlhc.c +++ b/sw/airborne/peripherals/lsm303dlhc.c @@ -94,7 +94,7 @@ void lsm303dlhc_init(struct Lsm303dlhc *lsm, struct i2c_periph *i2c_p, uint8_t a lsm303dlhc_mag_set_default_config(&(lsm->config.mag)); lsm->init_status.mag = LSM_CONF_MAG_UNINIT; } - lsm->initialized = FALSE; + lsm->initialized = false; } static void lsm303dlhc_i2c_tx_reg(struct Lsm303dlhc *lsm, uint8_t reg, uint8_t val) @@ -130,7 +130,7 @@ static void lsm303dlhc_send_config(struct Lsm303dlhc *lsm) lsm->init_status.acc++; break; case LSM_CONF_ACC_DONE: - lsm->initialized = TRUE; + lsm->initialized = true; lsm->i2c_trans.status = I2CTransDone; lsm303dlhc_read(lsm); break; @@ -152,7 +152,7 @@ static void lsm303dlhc_send_config(struct Lsm303dlhc *lsm) lsm->init_status.mag++; break; case LSM_CONF_MAG_DONE: - lsm->initialized = TRUE; + lsm->initialized = true; lsm->i2c_trans.status = I2CTransDone; break; default: @@ -215,7 +215,7 @@ void lsm303dlhc_event(struct Lsm303dlhc *lsm) lsm->data.vect.x = Int16FromBuf(lsm->i2c_trans.buf, 0); lsm->data.vect.y = Int16FromBuf(lsm->i2c_trans.buf, 2); lsm->data.vect.z = Int16FromBuf(lsm->i2c_trans.buf, 4); - lsm->data_available = TRUE; + lsm->data_available = true; lsm->i2c_trans.status = I2CTransDone; } else { } diff --git a/sw/airborne/peripherals/mcp355x.c b/sw/airborne/peripherals/mcp355x.c index 5d38d2aaf3..f296168140 100644 --- a/sw/airborne/peripherals/mcp355x.c +++ b/sw/airborne/peripherals/mcp355x.c @@ -35,7 +35,7 @@ struct spi_transaction mcp355x_spi_trans; void mcp355x_init(void) { - mcp355x_data_available = FALSE; + mcp355x_data_available = false; mcp355x_data = 0; mcp355x_spi_trans.input_length = 4; @@ -66,7 +66,7 @@ void mcp355x_event(void) ((uint32_t)mcp355x_spi_trans.input_buf[1] << 9) | ((uint32_t)mcp355x_spi_trans.input_buf[2] << 1) | (mcp355x_spi_trans.input_buf[3] >> 7)); - mcp355x_data_available = TRUE; + mcp355x_data_available = true; } mcp355x_spi_trans.status = SPITransDone; } diff --git a/sw/airborne/peripherals/mpl3115.c b/sw/airborne/peripherals/mpl3115.c index 9132912dec..1abb33ebd8 100644 --- a/sw/airborne/peripherals/mpl3115.c +++ b/sw/airborne/peripherals/mpl3115.c @@ -39,12 +39,12 @@ void mpl3115_init(struct Mpl3115 *mpl, struct i2c_periph *i2c_p, uint8_t addr) mpl->trans.status = I2CTransDone; mpl->req_trans.status = I2CTransDone; - mpl->initialized = FALSE; + mpl->initialized = false; mpl->init_status = MPL_CONF_UNINIT; /* by default disable raw mode and set pressure mode */ - mpl->raw_mode = FALSE; - mpl->alt_mode = FALSE; + mpl->raw_mode = false; + mpl->alt_mode = false; mpl->pressure = 0; mpl->temperature = 0; @@ -69,7 +69,7 @@ static void mpl3115_send_config(struct Mpl3115 *mpl) mpl->init_status++; break; case MPL_CONF_DONE: - mpl->initialized = TRUE; + mpl->initialized = true; mpl->trans.status = I2CTransDone; break; default: @@ -130,7 +130,7 @@ void mpl3115_event(struct Mpl3115 *mpl) tmp = ((int16_t)mpl->trans.buf[4] << 8) | mpl->trans.buf[5]; mpl->temperature = (tmp >> 4); } - mpl->data_available = TRUE; + mpl->data_available = true; } mpl->trans.status = I2CTransDone; } diff --git a/sw/airborne/peripherals/mpu60x0.c b/sw/airborne/peripherals/mpu60x0.c index 4bfb5ffdff..9c7098b44a 100644 --- a/sw/airborne/peripherals/mpu60x0.c +++ b/sw/airborne/peripherals/mpu60x0.c @@ -36,7 +36,7 @@ void mpu60x0_set_default_config(struct Mpu60x0Config *c) c->dlpf_cfg = MPU60X0_DEFAULT_DLPF_CFG; c->gyro_range = MPU60X0_DEFAULT_FS_SEL; c->accel_range = MPU60X0_DEFAULT_AFS_SEL; - c->drdy_int_enable = FALSE; + c->drdy_int_enable = false; /* Number of bytes to read starting with MPU60X0_REG_INT_STATUS * By default read only gyro and accel data -> 15 bytes. @@ -46,7 +46,7 @@ void mpu60x0_set_default_config(struct Mpu60x0Config *c) c->nb_slaves = 0; c->nb_slave_init = 0; - c->i2c_bypass = FALSE; + c->i2c_bypass = false; } void mpu60x0_send_config(Mpu60x0ConfigSet mpu_set, void *mpu, struct Mpu60x0Config *config) @@ -106,7 +106,7 @@ void mpu60x0_send_config(Mpu60x0ConfigSet mpu_set, void *mpu, struct Mpu60x0Conf config->init_status++; break; case MPU60X0_CONF_DONE: - config->initialized = TRUE; + config->initialized = true; break; default: break; diff --git a/sw/airborne/peripherals/mpu60x0_i2c.c b/sw/airborne/peripherals/mpu60x0_i2c.c index b2e1a40bcf..80ec85cd8c 100644 --- a/sw/airborne/peripherals/mpu60x0_i2c.c +++ b/sw/airborne/peripherals/mpu60x0_i2c.c @@ -41,8 +41,8 @@ void mpu60x0_i2c_init(struct Mpu60x0_I2c *mpu, struct i2c_periph *i2c_p, uint8_t /* set default MPU60X0 config options */ mpu60x0_set_default_config(&(mpu->config)); - mpu->data_available = FALSE; - mpu->config.initialized = FALSE; + mpu->data_available = false; + mpu->config.initialized = false; mpu->config.init_status = MPU60X0_CONF_UNINIT; mpu->slave_init_status = MPU60X0_I2C_CONF_UNINIT; @@ -109,7 +109,7 @@ void mpu60x0_i2c_event(struct Mpu60x0_I2c *mpu) #pragma GCC diagnostic pop } - mpu->data_available = TRUE; + mpu->data_available = true; } mpu->i2c_trans.status = I2CTransDone; } @@ -194,9 +194,9 @@ bool mpu60x0_configure_i2c_slaves(Mpu60x0ConfigSet mpu_set, void *mpu) mpu_i2c->slave_init_status++; break; case MPU60X0_I2C_CONF_DONE: - return TRUE; + return true; default: break; } - return FALSE; + return false; } diff --git a/sw/airborne/peripherals/mpu60x0_spi.c b/sw/airborne/peripherals/mpu60x0_spi.c index e3611d6e2d..40f28e1cbd 100644 --- a/sw/airborne/peripherals/mpu60x0_spi.c +++ b/sw/airborne/peripherals/mpu60x0_spi.c @@ -55,8 +55,8 @@ void mpu60x0_spi_init(struct Mpu60x0_Spi *mpu, struct spi_periph *spi_p, uint8_t /* set default MPU60X0 config options */ mpu60x0_set_default_config(&(mpu->config)); - mpu->data_available = FALSE; - mpu->config.initialized = FALSE; + mpu->data_available = false; + mpu->config.initialized = false; mpu->config.init_status = MPU60X0_CONF_UNINIT; mpu->slave_init_status = MPU60X0_SPI_CONF_UNINIT; @@ -127,7 +127,7 @@ void mpu60x0_spi_event(struct Mpu60x0_Spi *mpu) #pragma GCC diagnostic pop } - mpu->data_available = TRUE; + mpu->data_available = true; } mpu->spi_trans.status = SPITransDone; } @@ -188,9 +188,9 @@ bool mpu60x0_configure_i2c_slaves(Mpu60x0ConfigSet mpu_set, void *mpu) } break; case MPU60X0_SPI_CONF_DONE: - return TRUE; + return true; default: break; } - return FALSE; + return false; } diff --git a/sw/airborne/peripherals/mpu9250.c b/sw/airborne/peripherals/mpu9250.c index a65f65ca62..8adac4a30a 100644 --- a/sw/airborne/peripherals/mpu9250.c +++ b/sw/airborne/peripherals/mpu9250.c @@ -37,7 +37,7 @@ void mpu9250_set_default_config(struct Mpu9250Config *c) c->dlpf_accel_cfg = MPU9250_DEFAULT_DLPF_ACCEL_CFG; c->gyro_range = MPU9250_DEFAULT_FS_SEL; c->accel_range = MPU9250_DEFAULT_AFS_SEL; - c->drdy_int_enable = FALSE; + c->drdy_int_enable = false; /* Number of bytes to read starting with MPU9250_REG_INT_STATUS * By default read only gyro and accel data -> 15 bytes. @@ -47,7 +47,7 @@ void mpu9250_set_default_config(struct Mpu9250Config *c) c->nb_slaves = 0; c->nb_slave_init = 0; - c->i2c_bypass = FALSE; + c->i2c_bypass = false; } void mpu9250_send_config(Mpu9250ConfigSet mpu_set, void *mpu, struct Mpu9250Config *config) @@ -112,7 +112,7 @@ void mpu9250_send_config(Mpu9250ConfigSet mpu_set, void *mpu, struct Mpu9250Conf config->init_status++; break; case MPU9250_CONF_DONE: - config->initialized = TRUE; + config->initialized = true; break; default: break; diff --git a/sw/airborne/peripherals/mpu9250_i2c.c b/sw/airborne/peripherals/mpu9250_i2c.c index eaeb610d0f..e547c8b6c1 100644 --- a/sw/airborne/peripherals/mpu9250_i2c.c +++ b/sw/airborne/peripherals/mpu9250_i2c.c @@ -43,8 +43,8 @@ void mpu9250_i2c_init(struct Mpu9250_I2c *mpu, struct i2c_periph *i2c_p, uint8_t /* set default MPU9250 config options */ mpu9250_set_default_config(&(mpu->config)); - mpu->data_available = FALSE; - mpu->config.initialized = FALSE; + mpu->data_available = false; + mpu->config.initialized = false; mpu->config.init_status = MPU9250_CONF_UNINIT; /* "internal" ak8963 magnetometer */ @@ -56,7 +56,7 @@ void mpu9250_i2c_init(struct Mpu9250_I2c *mpu, struct i2c_periph *i2c_p, uint8_t /* set callback function to configure mag */ mpu->config.slaves[0].configure = &imu_mpu9250_configure_mag_slave; /* read the mag directly for now */ - mpu->config.i2c_bypass = TRUE; + mpu->config.i2c_bypass = true; mpu->slave_init_status = MPU9250_I2C_CONF_UNINIT; } @@ -125,7 +125,7 @@ void mpu9250_i2c_event(struct Mpu9250_I2c *mpu) #pragma GCC diagnostic pop } - mpu->data_available = TRUE; + mpu->data_available = true; } mpu->i2c_trans.status = I2CTransDone; } @@ -157,9 +157,9 @@ bool imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set __attribute__((unu ak8963_configure(&mpu_i2c->akm); if (mpu_i2c->akm.initialized) { - return TRUE; + return true; } else { - return FALSE; + return false; } } @@ -227,9 +227,9 @@ bool mpu9250_configure_i2c_slaves(Mpu9250ConfigSet mpu_set, void *mpu) mpu_i2c->slave_init_status++; break; case MPU9250_I2C_CONF_DONE: - return TRUE; + return true; default: break; } - return FALSE; + return false; } diff --git a/sw/airborne/peripherals/mpu9250_spi.c b/sw/airborne/peripherals/mpu9250_spi.c index 2b02d57407..5ca9b1ab60 100644 --- a/sw/airborne/peripherals/mpu9250_spi.c +++ b/sw/airborne/peripherals/mpu9250_spi.c @@ -55,8 +55,8 @@ void mpu9250_spi_init(struct Mpu9250_Spi *mpu, struct spi_periph *spi_p, uint8_t /* set default MPU9250 config options */ mpu9250_set_default_config(&(mpu->config)); - mpu->data_available = FALSE; - mpu->config.initialized = FALSE; + mpu->data_available = false; + mpu->config.initialized = false; mpu->config.init_status = MPU9250_CONF_UNINIT; mpu->slave_init_status = MPU9250_SPI_CONF_UNINIT; @@ -124,7 +124,7 @@ void mpu9250_spi_event(struct Mpu9250_Spi *mpu) #pragma GCC diagnostic pop } - mpu->data_available = TRUE; + mpu->data_available = true; } mpu->spi_trans.status = SPITransDone; } @@ -185,9 +185,9 @@ bool mpu9250_configure_i2c_slaves(Mpu9250ConfigSet mpu_set, void *mpu) } break; case MPU9250_SPI_CONF_DONE: - return TRUE; + return true; default: break; } - return FALSE; + return false; } diff --git a/sw/airborne/peripherals/ms5611.c b/sw/airborne/peripherals/ms5611.c index 27894cf892..79f4c0784d 100644 --- a/sw/airborne/peripherals/ms5611.c +++ b/sw/airborne/peripherals/ms5611.c @@ -54,9 +54,9 @@ bool ms5611_prom_crc_ok(uint16_t *prom) } prom[7] |= crc; if (crc == ((res >> 12) & 0xF)) { - return TRUE; + return true; } else { - return FALSE; + return false; } } @@ -97,9 +97,9 @@ bool ms5611_calc(struct Ms5611Data *ms) /* temperature in deg Celsius with 0.01 degC resolultion */ ms->temperature = (int32_t)tempms; ms->pressure = p; - return TRUE; + return true; } - return FALSE; + return false; } /** @@ -140,7 +140,7 @@ bool ms5607_calc(struct Ms5611Data *ms) /* temperature in deg Celsius with 0.01 degC resolultion */ ms->temperature = (int32_t)tempms; ms->pressure = p; - return TRUE; + return true; } - return FALSE; + return false; } diff --git a/sw/airborne/peripherals/ms5611_i2c.c b/sw/airborne/peripherals/ms5611_i2c.c index 32827f87d0..b4c068e812 100644 --- a/sw/airborne/peripherals/ms5611_i2c.c +++ b/sw/airborne/peripherals/ms5611_i2c.c @@ -41,8 +41,8 @@ void ms5611_i2c_init(struct Ms5611_I2c *ms, struct i2c_periph *i2c_p, uint8_t ad /* set initial status: Success or Done */ ms->i2c_trans.status = I2CTransDone; - ms->data_available = FALSE; - ms->initialized = FALSE; + ms->data_available = false; + ms->initialized = false; ms->status = MS5611_STATUS_UNINIT; ms->prom_cnt = 0; ms->is_ms5607 = is_ms5607; @@ -51,7 +51,7 @@ void ms5611_i2c_init(struct Ms5611_I2c *ms, struct i2c_periph *i2c_p, uint8_t ad void ms5611_i2c_start_configure(struct Ms5611_I2c *ms) { if (ms->status == MS5611_STATUS_UNINIT) { - ms->initialized = FALSE; + ms->initialized = false; ms->prom_cnt = 0; ms->i2c_trans.buf[0] = MS5611_SOFT_RESET; i2c_transmit(ms->i2c_p, &(ms->i2c_trans), ms->i2c_trans.slave_addr, 1); @@ -191,7 +191,7 @@ void ms5611_i2c_event(struct Ms5611_I2c *ms) } else { /* done reading prom, check prom crc */ if (ms5611_prom_crc_ok(ms->data.c)) { - ms->initialized = TRUE; + ms->initialized = true; ms->status = MS5611_STATUS_IDLE; } else { /* checksum error, try again */ diff --git a/sw/airborne/peripherals/ms5611_spi.c b/sw/airborne/peripherals/ms5611_spi.c index 983d38f6bd..eeebcc1ab1 100644 --- a/sw/airborne/peripherals/ms5611_spi.c +++ b/sw/airborne/peripherals/ms5611_spi.c @@ -55,8 +55,8 @@ void ms5611_spi_init(struct Ms5611_Spi *ms, struct spi_periph *spi_p, uint8_t sl /* set initial status: Success or Done */ ms->spi_trans.status = SPITransDone; - ms->data_available = FALSE; - ms->initialized = FALSE; + ms->data_available = false; + ms->initialized = false; ms->status = MS5611_STATUS_UNINIT; ms->prom_cnt = 0; ms->is_ms5607 = is_ms5607; @@ -65,7 +65,7 @@ void ms5611_spi_init(struct Ms5611_Spi *ms, struct spi_periph *spi_p, uint8_t sl void ms5611_spi_start_configure(struct Ms5611_Spi *ms) { if (ms->status == MS5611_STATUS_UNINIT) { - ms->initialized = FALSE; + ms->initialized = false; ms->prom_cnt = 0; ms->tx_buf[0] = MS5611_SOFT_RESET; spi_submit(ms->spi_p, &(ms->spi_trans)); @@ -202,7 +202,7 @@ void ms5611_spi_event(struct Ms5611_Spi *ms) } else { /* done reading prom, check prom crc */ if (ms5611_prom_crc_ok(ms->data.c)) { - ms->initialized = TRUE; + ms->initialized = true; ms->status = MS5611_STATUS_IDLE; } else { /* checksum error, try again */ diff --git a/sw/airborne/peripherals/vn200_serial.c b/sw/airborne/peripherals/vn200_serial.c index c82dbdb062..b796f5cbca 100644 --- a/sw/airborne/peripherals/vn200_serial.c +++ b/sw/airborne/peripherals/vn200_serial.c @@ -123,10 +123,10 @@ void vn200_parse(struct VNPacket *vnp, uint8_t c) vnp->msg_idx++; if (vnp->msg_idx == (vnp->datalength + 2)) { if (verify_chk(vnp->msg_buf, vnp->datalength, &(vnp->calc_chk), &(vnp->rec_chk))) { - vnp->msg_available = TRUE; + vnp->msg_available = true; vnp->counter++; } else { - vnp->msg_available = FALSE; + vnp->msg_available = false; vnp->chksm_error++; } vnp->status = VNMsgSync; diff --git a/sw/airborne/state.c b/sw/airborne/state.c index 45b5ae0833..ade27cd0a4 100644 --- a/sw/airborne/state.c +++ b/sw/airborne/state.c @@ -48,9 +48,9 @@ void stateInit(void) state.ned_to_body_orientation.status = 0; state.rate_status = 0; state.wind_air_status = 0; - state.ned_initialized_i = FALSE; - state.ned_initialized_f = FALSE; - state.utm_initialized_f = FALSE; + state.ned_initialized_i = false; + state.ned_initialized_f = false; + state.utm_initialized_f = false; } diff --git a/sw/airborne/state.h b/sw/airborne/state.h index 5a70e723ea..17b13bc2aa 100644 --- a/sw/airborne/state.h +++ b/sw/airborne/state.h @@ -452,15 +452,15 @@ static inline void stateSetLocalOrigin_i(struct LtpDef_i *ltp_def) ClearBit(state.accel_status, ACCEL_NED_I); ClearBit(state.accel_status, ACCEL_NED_F); - state.ned_initialized_i = TRUE; - state.ned_initialized_f = TRUE; + state.ned_initialized_i = true; + state.ned_initialized_f = true; } /// Set the local (flat earth) coordinate frame origin from UTM (float). static inline void stateSetLocalUtmOrigin_f(struct UtmCoor_f *utm_def) { state.utm_origin_f = *utm_def; - state.utm_initialized_f = TRUE; + state.utm_initialized_f = true; /* clear bits for all local frame representations */ state.pos_status &= ~(POS_LOCAL_COORD); diff --git a/sw/airborne/subsystems/actuators.c b/sw/airborne/subsystems/actuators.c index 17ac5a1903..c79a434e4b 100644 --- a/sw/airborne/subsystems/actuators.c +++ b/sw/airborne/subsystems/actuators.c @@ -39,10 +39,10 @@ void actuators_init(void) { #if defined ACTUATORS_START_DELAY && ! defined SITL - actuators_delay_done = FALSE; + actuators_delay_done = false; SysTimeTimerStart(actuators_delay_time); #else - actuators_delay_done = TRUE; + actuators_delay_done = true; actuators_delay_time = 0; #endif diff --git a/sw/airborne/subsystems/actuators/actuators_asctec.c b/sw/airborne/subsystems/actuators/actuators_asctec.c index b93566b1ce..5627cf17f1 100644 --- a/sw/airborne/subsystems/actuators/actuators_asctec.c +++ b/sw/airborne/subsystems/actuators/actuators_asctec.c @@ -58,7 +58,7 @@ void actuators_asctec_set(bool motors_on) #if defined ACTUATORS_START_DELAY && ! defined SITL if (!actuators_delay_done) { if (SysTimeTimer(actuators_delay_time) < USEC_OF_SEC(ACTUATORS_START_DELAY)) { return; } - else { actuators_delay_done = TRUE; } + else { actuators_delay_done = true; } } #endif diff --git a/sw/airborne/subsystems/actuators/actuators_asctec_v2.c b/sw/airborne/subsystems/actuators/actuators_asctec_v2.c index 3c274eb11b..b2b03cab6a 100644 --- a/sw/airborne/subsystems/actuators/actuators_asctec_v2.c +++ b/sw/airborne/subsystems/actuators/actuators_asctec_v2.c @@ -59,7 +59,7 @@ void actuators_asctec_v2_set(void) i2c1_init(); #endif return; - } else { actuators_delay_done = TRUE; } + } else { actuators_delay_done = true; } } #endif diff --git a/sw/airborne/subsystems/actuators/actuators_asctec_v2_new.c b/sw/airborne/subsystems/actuators/actuators_asctec_v2_new.c index fd1ca2ed8b..5da0658e97 100644 --- a/sw/airborne/subsystems/actuators/actuators_asctec_v2_new.c +++ b/sw/airborne/subsystems/actuators/actuators_asctec_v2_new.c @@ -61,7 +61,7 @@ void actuators_asctec_v2_set(void) i2c1_init(); #endif return; - } else { actuators_delay_done = TRUE; } + } else { actuators_delay_done = true; } } #endif diff --git a/sw/airborne/subsystems/actuators/actuators_esc32.c b/sw/airborne/subsystems/actuators/actuators_esc32.c index 08d6d304cb..44fbca5a7c 100644 --- a/sw/airborne/subsystems/actuators/actuators_esc32.c +++ b/sw/airborne/subsystems/actuators/actuators_esc32.c @@ -290,10 +290,10 @@ static bool actuators_esc32_play_melody(uint32_t tt, uint8_t tid, uint32_t *stat } *status_sub = *status_sub + (1 << 24); } else if (counter == length && SysTimeTimer(timer) > timeout) { - return TRUE; + return true; } - return FALSE; + return false; } /** When the CAN bus receives a message */ diff --git a/sw/airborne/subsystems/actuators/actuators_mkk.c b/sw/airborne/subsystems/actuators/actuators_mkk.c index d1651e730a..ca893b183d 100644 --- a/sw/airborne/subsystems/actuators/actuators_mkk.c +++ b/sw/airborne/subsystems/actuators/actuators_mkk.c @@ -50,7 +50,7 @@ void actuators_mkk_set(void) if (SysTimeTimer(actuators_delay_time) < USEC_OF_SEC(ACTUATORS_START_DELAY)) { return; } else { - actuators_delay_done = TRUE; + actuators_delay_done = true; } } #endif diff --git a/sw/airborne/subsystems/actuators/actuators_mkk_v2.c b/sw/airborne/subsystems/actuators/actuators_mkk_v2.c index 8e7ecab0c1..392a61da07 100644 --- a/sw/airborne/subsystems/actuators/actuators_mkk_v2.c +++ b/sw/airborne/subsystems/actuators/actuators_mkk_v2.c @@ -69,7 +69,7 @@ void actuators_mkk_v2_set(void) #if defined ACTUATORS_START_DELAY && ! defined SITL if (!actuators_delay_done) { if (SysTimeTimer(actuators_delay_time) < USEC_OF_SEC(ACTUATORS_START_DELAY)) { return; } - else { actuators_delay_done = TRUE; } + else { actuators_delay_done = true; } } #endif diff --git a/sw/airborne/subsystems/actuators/actuators_skiron.c b/sw/airborne/subsystems/actuators/actuators_skiron.c index 05028ad095..082e52f8d5 100644 --- a/sw/airborne/subsystems/actuators/actuators_skiron.c +++ b/sw/airborne/subsystems/actuators/actuators_skiron.c @@ -49,7 +49,7 @@ void actuators_skiron_set(void) #if defined ACTUATORS_START_DELAY && ! defined SITL if (!actuators_delay_done) { if (SysTimeTimer(actuators_delay_time) < USEC_OF_SEC(ACTUATORS_START_DELAY)) { return; } - else { actuators_delay_done = TRUE; } + else { actuators_delay_done = true; } } #endif diff --git a/sw/airborne/subsystems/actuators/motor_mixing.c b/sw/airborne/subsystems/actuators/motor_mixing.c index b23dd707bf..0e15e9e6b3 100644 --- a/sw/airborne/subsystems/actuators/motor_mixing.c +++ b/sw/airborne/subsystems/actuators/motor_mixing.c @@ -102,7 +102,7 @@ void motor_mixing_init(void) roll_coef[i] * MOTOR_MIXING_TRIM_ROLL + pitch_coef[i] * MOTOR_MIXING_TRIM_PITCH + yaw_coef[i] * MOTOR_MIXING_TRIM_YAW; - motor_mixing.override_enabled[i] = FALSE; + motor_mixing.override_enabled[i] = false; motor_mixing.override_value[i] = MOTOR_MIXING_STOP_MOTOR; } motor_mixing.nb_failure = 0; diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c index 643790ebaf..c27ec7f856 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c @@ -86,10 +86,10 @@ struct AhrsFloatCmpl ahrs_fc; void ahrs_fc_init(void) { ahrs_fc.status = AHRS_FC_UNINIT; - ahrs_fc.is_aligned = FALSE; + ahrs_fc.is_aligned = false; - ahrs_fc.ltp_vel_norm_valid = FALSE; - ahrs_fc.heading_aligned = FALSE; + ahrs_fc.ltp_vel_norm_valid = false; + ahrs_fc.heading_aligned = false; /* init ltp_to_imu quaternion as zero/identity rotation */ float_quat_identity(&ahrs_fc.ltp_to_imu_quat); @@ -106,9 +106,9 @@ void ahrs_fc_init(void) ahrs_fc.mag_zeta = AHRS_MAG_ZETA; #if AHRS_GRAVITY_UPDATE_COORDINATED_TURN - ahrs_fc.correct_gravity = TRUE; + ahrs_fc.correct_gravity = true; #else - ahrs_fc.correct_gravity = FALSE; + ahrs_fc.correct_gravity = false; #endif ahrs_fc.gravity_heuristic_factor = AHRS_GRAVITY_HEURISTIC_FACTOR; @@ -126,11 +126,11 @@ bool ahrs_fc_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel, #if USE_MAGNETOMETER /* Compute an initial orientation from accel and mag directly as quaternion */ ahrs_float_get_quat_from_accel_mag(&ahrs_fc.ltp_to_imu_quat, lp_accel, lp_mag); - ahrs_fc.heading_aligned = TRUE; + ahrs_fc.heading_aligned = true; #else /* Compute an initial orientation from accel and just set heading to zero */ ahrs_float_get_quat_from_accel(&ahrs_fc.ltp_to_imu_quat, lp_accel); - ahrs_fc.heading_aligned = FALSE; + ahrs_fc.heading_aligned = false; #endif /* Convert initial orientation from quat to rotation matrix representations. */ @@ -140,9 +140,9 @@ bool ahrs_fc_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel, ahrs_fc.gyro_bias = *lp_gyro; ahrs_fc.status = AHRS_FC_RUNNING; - ahrs_fc.is_aligned = TRUE; + ahrs_fc.is_aligned = true; - return TRUE; + return true; } @@ -395,9 +395,9 @@ void ahrs_fc_update_gps(struct GpsState *gps_s __attribute__((unused))) #if AHRS_GRAVITY_UPDATE_COORDINATED_TURN && USE_GPS if (gps_s->fix >= GPS_FIX_3D) { ahrs_fc.ltp_vel_norm = gps_s->speed_3d / 100.; - ahrs_fc.ltp_vel_norm_valid = TRUE; + ahrs_fc.ltp_vel_norm_valid = true; } else { - ahrs_fc.ltp_vel_norm_valid = FALSE; + ahrs_fc.ltp_vel_norm_valid = false; } #endif @@ -498,7 +498,7 @@ void ahrs_fc_realign_heading(float heading) float_quat_comp(&ahrs_fc.ltp_to_imu_quat, &q, body_to_imu_quat); float_rmat_of_quat(&ahrs_fc.ltp_to_imu_rmat, &ahrs_fc.ltp_to_imu_quat); - ahrs_fc.heading_aligned = TRUE; + ahrs_fc.heading_aligned = true; } void ahrs_fc_set_body_to_imu(struct OrientationReps *body_to_imu) diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c index cc27684fb0..d7afd6a593 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c @@ -99,7 +99,7 @@ static inline void set_dcm_matrix_from_rmat(struct FloatRMat *rmat) void ahrs_dcm_init(void) { ahrs_dcm.status = AHRS_DCM_UNINIT; - ahrs_dcm.is_aligned = FALSE; + ahrs_dcm.is_aligned = false; /* init ltp_to_imu euler with zero */ FLOAT_EULERS_ZERO(ahrs_dcm.ltp_to_imu_euler); @@ -112,7 +112,7 @@ void ahrs_dcm_init(void) ahrs_dcm.gps_speed = 0; ahrs_dcm.gps_acceleration = 0; ahrs_dcm.gps_course = 0; - ahrs_dcm.gps_course_valid = FALSE; + ahrs_dcm.gps_course_valid = false; ahrs_dcm.gps_age = 100; } @@ -133,9 +133,9 @@ bool ahrs_dcm_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel, ahrs_dcm.gyro_bias = *lp_gyro; ahrs_dcm.status = AHRS_DCM_RUNNING; - ahrs_dcm.is_aligned = TRUE; + ahrs_dcm.is_aligned = true; - return TRUE; + return true; } @@ -177,9 +177,9 @@ void ahrs_dcm_update_gps(struct GpsState *gps_s) if (gps_s->gspeed >= 500) { //got a 3d fix and ground speed is more than 5.0 m/s ahrs_dcm.gps_course = ((float)gps_s->course) / 1.e7; - ahrs_dcm.gps_course_valid = TRUE; + ahrs_dcm.gps_course_valid = true; } else { - ahrs_dcm.gps_course_valid = FALSE; + ahrs_dcm.gps_course_valid = false; } } else { ahrs_dcm.gps_age = 100; @@ -282,7 +282,7 @@ void Normalize(void) float error = 0; float temporary[3][3]; float renorm = 0; - uint8_t problem = FALSE; + uint8_t problem = false; // Find the non-orthogonality of X wrt Y error = -Vector_Dot_Product(&DCM_Matrix[0][0], &DCM_Matrix[1][0]) * .5; //eq.19 @@ -309,7 +309,7 @@ void Normalize(void) renorm_sqrt_count++; #endif } else { - problem = TRUE; + problem = true; #if PERFORMANCE_REPORTING == 1 renorm_blowup_count++; #endif @@ -326,7 +326,7 @@ void Normalize(void) renorm_sqrt_count++; #endif } else { - problem = TRUE; + problem = true; #if PERFORMANCE_REPORTING == 1 renorm_blowup_count++; #endif @@ -343,7 +343,7 @@ void Normalize(void) renorm_sqrt_count++; #endif } else { - problem = TRUE; + problem = true; #if PERFORMANCE_REPORTING == 1 renorm_blowup_count++; #endif @@ -353,7 +353,7 @@ void Normalize(void) // Reset on trouble if (problem) { // Our solution is blowing up and we will force back to initial condition. Hope we are not upside down! set_dcm_matrix_from_rmat(orientationGetRMat_f(&ahrs_dcm.body_to_imu)); - problem = FALSE; + problem = false; } } diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_invariant.c b/sw/airborne/subsystems/ahrs/ahrs_float_invariant.c index 9473bac8f0..e93425bdf0 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_invariant.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_invariant.c @@ -150,8 +150,8 @@ void ahrs_float_invariant_init(void) ahrs_float_inv.gains.n = AHRS_INV_N; ahrs_float_inv.gains.o = AHRS_INV_O; - ahrs_float_inv.is_aligned = FALSE; - ahrs_float_inv.reset = FALSE; + ahrs_float_inv.is_aligned = false; + ahrs_float_inv.reset = false; } void ahrs_float_invariant_align(struct FloatRates *lp_gyro, @@ -165,7 +165,7 @@ void ahrs_float_invariant_align(struct FloatRates *lp_gyro, ahrs_float_inv.state.bias = *lp_gyro; // ins and ahrs are now running - ahrs_float_inv.is_aligned = TRUE; + ahrs_float_inv.is_aligned = true; } void ahrs_float_invariant_propagate(struct FloatRates* gyro, float dt) @@ -173,8 +173,8 @@ void ahrs_float_invariant_propagate(struct FloatRates* gyro, float dt) // realign all the filter if needed // a complete init cycle is required if (ahrs_float_inv.reset) { - ahrs_float_inv.reset = FALSE; - ahrs_float_inv.is_aligned = FALSE; + ahrs_float_inv.reset = false; + ahrs_float_inv.is_aligned = false; init_invariant_state(); } diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c index bc69cd5773..f7c6be557b 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c @@ -62,7 +62,7 @@ struct AhrsMlkf ahrs_mlkf; void ahrs_mlkf_init(void) { - ahrs_mlkf.is_aligned = FALSE; + ahrs_mlkf.is_aligned = false; /* init ltp_to_imu quaternion as zero/identity rotation */ float_quat_identity(&ahrs_mlkf.ltp_to_imu_quat); @@ -114,9 +114,9 @@ bool ahrs_mlkf_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel, /* used averaged gyro as initial value for bias */ ahrs_mlkf.gyro_bias = *lp_gyro; - ahrs_mlkf.is_aligned = TRUE; + ahrs_mlkf.is_aligned = true; - return TRUE; + return true; } void ahrs_mlkf_propagate(struct FloatRates *gyro, float dt) diff --git a/sw/airborne/subsystems/ahrs/ahrs_gx3.c b/sw/airborne/subsystems/ahrs/ahrs_gx3.c index 3a96a97efe..293e59ce3b 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_gx3.c +++ b/sw/airborne/subsystems/ahrs/ahrs_gx3.c @@ -74,7 +74,7 @@ static inline bool gx3_verify_chk(volatile uint8_t *buff_add) void ahrs_gx3_align(void) { - ahrs_gx3.is_aligned = FALSE; + ahrs_gx3.is_aligned = false; //make the gyros zero, takes 10s (specified in Byte 4 and 5) uart_put_byte(&GX3_PORT, 0xcd); @@ -83,7 +83,7 @@ void ahrs_gx3_align(void) uart_put_byte(&GX3_PORT, 0x27); uart_put_byte(&GX3_PORT, 0x10); - ahrs_gx3.is_aligned = TRUE; + ahrs_gx3.is_aligned = true; } #if PERIODIC_TELEMETRY @@ -106,12 +106,12 @@ static void send_gx3(struct transport_tx *trans, struct link_device *dev) void imu_impl_init(void) { // Initialize variables - ahrs_gx3.is_aligned = FALSE; + ahrs_gx3.is_aligned = false; // Initialize packet ahrs_gx3.packet.status = GX3PacketWaiting; ahrs_gx3.packet.msg_idx = 0; - ahrs_gx3.packet.msg_available = FALSE; + ahrs_gx3.packet.msg_available = false; ahrs_gx3.packet.chksm_error = 0; ahrs_gx3.packet.hdr_error = 0; @@ -309,9 +309,9 @@ void gx3_packet_parse(uint8_t c) ahrs_gx3.packet.msg_idx++; if (ahrs_gx3.packet.msg_idx == GX3_MSG_LEN) { if (gx3_verify_chk(ahrs_gx3.packet.msg_buf)) { - ahrs_gx3.packet.msg_available = TRUE; + ahrs_gx3.packet.msg_available = true; } else { - ahrs_gx3.packet.msg_available = FALSE; + ahrs_gx3.packet.msg_available = false; ahrs_gx3.packet.chksm_error++; } ahrs_gx3.packet.status = 0; @@ -334,7 +334,7 @@ void ahrs_gx3_init(void) #else ahrs_gx3.mag_offset = 0.0; #endif - ahrs_gx3.is_aligned = FALSE; + ahrs_gx3.is_aligned = false; } void ahrs_gx3_register(void) diff --git a/sw/airborne/subsystems/ahrs/ahrs_gx3.h b/sw/airborne/subsystems/ahrs/ahrs_gx3.h index be1dca4003..b444c8a5e9 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_gx3.h +++ b/sw/airborne/subsystems/ahrs/ahrs_gx3.h @@ -108,7 +108,7 @@ static inline void ImuEvent(void) if (ahrs_gx3.packet.msg_available) { gx3_packet_read_message(); ahrs_gx3_publish_imu(); - ahrs_gx3.packet.msg_available = FALSE; + ahrs_gx3.packet.msg_available = false; } } diff --git a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.c b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.c index ef688c14b9..3497b5fae3 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.c +++ b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.c @@ -63,7 +63,7 @@ static inline void get_psi_measurement_from_mag(int32_t *psi_meas, int32_t phi_e void ahrs_ice_init(void) { ahrs_ice.status = AHRS_ICE_UNINIT; - ahrs_ice.is_aligned = FALSE; + ahrs_ice.is_aligned = false; /* init ltp_to_imu to zero */ INT_EULERS_ZERO(ahrs_ice.ltp_to_imu_euler) @@ -94,9 +94,9 @@ bool ahrs_ice_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel, RATES_COPY(ahrs_ice.gyro_bias, *lp_gyro); ahrs_ice.status = AHRS_ICE_RUNNING; - ahrs_ice.is_aligned = TRUE; + ahrs_ice.is_aligned = true; - return TRUE; + return true; } //#define USE_NOISE_CUT 1 @@ -112,9 +112,9 @@ static inline bool cut_rates(struct Int32Rates i1, struct Int32Rates i2, int32_t if (diff.p < -threshold || diff.p > threshold || diff.q < -threshold || diff.q > threshold || diff.r < -threshold || diff.r > threshold) { - return TRUE; + return true; } else { - return FALSE; + return false; } } #define RATE_CUT_THRESHOLD RATE_BFP_OF_REAL(1) @@ -127,10 +127,10 @@ static inline bool cut_accel(struct Int32Vect3 i1, struct Int32Vect3 i2, int32_t diff.y < -threshold || diff.y > threshold || diff.z < -threshold || diff.z > threshold) { LED_ON(4); - return TRUE; + return true; } else { LED_OFF(4); - return FALSE; + return false; } } #define ACCEL_CUT_THRESHOLD ACCEL_BFP_OF_REAL(20) diff --git a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.c b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.c index 7339986924..52e01aab98 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.c +++ b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.c @@ -109,10 +109,10 @@ void ahrs_icq_init(void) { ahrs_icq.status = AHRS_ICQ_UNINIT; - ahrs_icq.is_aligned = FALSE; + ahrs_icq.is_aligned = false; - ahrs_icq.ltp_vel_norm_valid = FALSE; - ahrs_icq.heading_aligned = FALSE; + ahrs_icq.ltp_vel_norm_valid = false; + ahrs_icq.heading_aligned = false; /* init ltp_to_imu quaternion as zero/identity rotation */ int32_quat_identity(&ahrs_icq.ltp_to_imu_quat); @@ -135,9 +135,9 @@ void ahrs_icq_init(void) ahrs_icq.gravity_heuristic_factor = AHRS_GRAVITY_HEURISTIC_FACTOR; #if AHRS_GRAVITY_UPDATE_COORDINATED_TURN - ahrs_icq.correct_gravity = TRUE; + ahrs_icq.correct_gravity = true; #else - ahrs_icq.correct_gravity = FALSE; + ahrs_icq.correct_gravity = false; #endif VECT3_ASSIGN(ahrs_icq.mag_h, MAG_BFP_OF_REAL(AHRS_H_X), @@ -156,11 +156,11 @@ bool ahrs_icq_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel, /* Compute an initial orientation from accel and mag directly as quaternion */ ahrs_int_get_quat_from_accel_mag(&ahrs_icq.ltp_to_imu_quat, lp_accel, lp_mag); - ahrs_icq.heading_aligned = TRUE; + ahrs_icq.heading_aligned = true; #else /* Compute an initial orientation from accel and just set heading to zero */ ahrs_int_get_quat_from_accel(&ahrs_icq.ltp_to_imu_quat, lp_accel); - ahrs_icq.heading_aligned = FALSE; + ahrs_icq.heading_aligned = false; // supress unused arg warning lp_mag = lp_mag; #endif @@ -171,9 +171,9 @@ bool ahrs_icq_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel, INT_RATES_LSHIFT(ahrs_icq.high_rez_bias, ahrs_icq.high_rez_bias, 28); ahrs_icq.status = AHRS_ICQ_RUNNING; - ahrs_icq.is_aligned = TRUE; + ahrs_icq.is_aligned = true; - return TRUE; + return true; } @@ -516,9 +516,9 @@ void ahrs_icq_update_gps(struct GpsState *gps_s __attribute__((unused))) #if AHRS_GRAVITY_UPDATE_COORDINATED_TURN && USE_GPS if (gps_s->fix >= GPS_FIX_3D) { ahrs_icq.ltp_vel_norm = SPEED_BFP_OF_REAL(gps_s->speed_3d / 100.); - ahrs_icq.ltp_vel_norm_valid = TRUE; + ahrs_icq.ltp_vel_norm_valid = true; } else { - ahrs_icq.ltp_vel_norm_valid = FALSE; + ahrs_icq.ltp_vel_norm_valid = false; } #endif @@ -641,7 +641,7 @@ void ahrs_icq_realign_heading(int32_t heading) /* compute ltp to imu rotations */ int32_quat_comp(&ahrs_icq.ltp_to_imu_quat, <p_to_body_quat, body_to_imu_quat); - ahrs_icq.heading_aligned = TRUE; + ahrs_icq.heading_aligned = true; } void ahrs_icq_set_body_to_imu(struct OrientationReps *body_to_imu) diff --git a/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c b/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c index 764138489c..d5c32997e1 100644 --- a/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c +++ b/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c @@ -66,7 +66,7 @@ static void launchBatterySurveyThread (void) // Functions for the generic device API static int sdlog_check_free_space(struct chibios_sdlog* p __attribute__((unused)), uint8_t len __attribute__((unused))) { - return TRUE; + return true; } static void sdlog_transmit(struct chibios_sdlog* p, uint8_t byte) @@ -115,10 +115,10 @@ bool chibios_logInit(void) launchBatterySurveyThread (); - return TRUE; + return true; error: - return FALSE; + return false; } diff --git a/sw/airborne/subsystems/chibios-libopencm3/printf.c b/sw/airborne/subsystems/chibios-libopencm3/printf.c index 6bdfedeccf..771267e22b 100644 --- a/sw/airborne/subsystems/chibios-libopencm3/printf.c +++ b/sw/airborne/subsystems/chibios-libopencm3/printf.c @@ -52,7 +52,7 @@ static bool writeBufferWithinSize (char **buffer, const char c, size_t *size) (*buffer)++; return (--(*size) == 0); } else { - return TRUE; + return true; } } @@ -154,10 +154,10 @@ void chvprintf(BaseSequentialStream *chp, const char *fmt, va_list ap) { } p = tmpbuf; s = tmpbuf; - left_align = FALSE; + left_align = false; if (*fmt == '-') { fmt++; - left_align = TRUE; + left_align = true; } filler = ' '; if (*fmt == '.') { @@ -198,7 +198,7 @@ void chvprintf(BaseSequentialStream *chp, const char *fmt, va_list ap) { } /* Long modifier.*/ if (c == 'l' || c == 'L') { - is_long = TRUE; + is_long = true; if (*fmt) c = *fmt++; } @@ -314,10 +314,10 @@ void chvsnprintf(char *buffer, size_t size, const char *fmt, va_list ap) { } p = tmpbuf; s = tmpbuf; - left_align = FALSE; + left_align = false; if (*fmt == '-') { fmt++; - left_align = TRUE; + left_align = true; } filler = ' '; if (*fmt == '.') { @@ -357,7 +357,7 @@ void chvsnprintf(char *buffer, size_t size, const char *fmt, va_list ap) { } /* Long modifier.*/ if (c == 'l' || c == 'L') { - is_long = TRUE; + is_long = true; if (*fmt) c = *fmt++; } diff --git a/sw/airborne/subsystems/chibios-libopencm3/sdio.c b/sw/airborne/subsystems/chibios-libopencm3/sdio.c index 8144b683b9..10d68f52c2 100644 --- a/sw/airborne/subsystems/chibios-libopencm3/sdio.c +++ b/sw/airborne/subsystems/chibios-libopencm3/sdio.c @@ -55,11 +55,11 @@ static enum {STOP, CONNECT} cnxState = STOP; bool sdioConnect (void) { if (!sdc_lld_is_card_inserted (NULL)) { - return FALSE; + return false; } if (cnxState == CONNECT) { - return TRUE; + return true; } /* @@ -85,20 +85,20 @@ bool sdioConnect (void) } cnxState = CONNECT; - return TRUE; + return true; } bool sdioDisconnect (void) { if (cnxState == STOP) - return TRUE; + return true; if (sdcDisconnect(&SDCD1)) { - return FALSE; + return false; } sdcStop (&SDCD1); cnxState = STOP; - return TRUE; + return true; } bool isCardInserted (void) @@ -179,10 +179,10 @@ bool badblocks(uint32_t start, uint32_t end, uint32_t blockatonce, uint8_t patte goto ERROR; position += blockatonce; } - return FALSE; + return false; ERROR: - return TRUE; + return true; } /** @@ -209,7 +209,7 @@ void fillbuffers(uint8_t pattern){ void cmd_sdiotest(void) { uint32_t i = 0; FRESULT err = 0; - bool format = FALSE; + bool format = false; chThdSleepMilliseconds(100); diff --git a/sw/airborne/subsystems/chibios-libopencm3/usb_msd.c b/sw/airborne/subsystems/chibios-libopencm3/usb_msd.c index e3be6d159c..b6a9e9f622 100644 --- a/sw/airborne/subsystems/chibios-libopencm3/usb_msd.c +++ b/sw/airborne/subsystems/chibios-libopencm3/usb_msd.c @@ -192,7 +192,7 @@ bool msdRequestsHook(USBDriver *usbp) { /* check that the request is for interface 0 */ if (MSD_SETUP_INDEX(usbp->setup) != 0) - return FALSE; + return false; /* act depending on bRequest = setup[1] */ switch (usbp->setup[1]) { @@ -202,7 +202,7 @@ bool msdRequestsHook(USBDriver *usbp) { (MSD_SETUP_LENGTH(usbp->setup) != 0) || (MSD_SETUP_VALUE(usbp->setup) != 0)) { - return FALSE; + return false; } /* reset all endpoints */ @@ -210,27 +210,27 @@ bool msdRequestsHook(USBDriver *usbp) { /* The device shall NAK the status stage of the device request until * the Bulk-Only Mass Storage Reset is complete. */ - return TRUE; + return true; case MSD_GET_MAX_LUN: /* check that it is a DEV2HOST request */ if (((usbp->setup[0] & USB_RTYPE_DIR_MASK) != USB_RTYPE_DIR_DEV2HOST) || (MSD_SETUP_LENGTH(usbp->setup) != 1) || (MSD_SETUP_VALUE(usbp->setup) != 0)) { - return FALSE; + return false; } static uint8_t len_buf[1] = {0}; /* stall to indicate that we don't support LUN */ usbSetupTransfer(usbp, len_buf, 1, NULL); - return TRUE; + return true; default: - return FALSE; + return false; break; } } - return FALSE; + return false; } /** @@ -305,10 +305,10 @@ bool msd_scsi_process_inquiry(USBMassStorageDriver *msdp) { case 0x80: { uint8_t response[] = {'0'}; /* TODO */ msd_start_transmit(msdp, response, sizeof(response)); - msdp->result = TRUE; + msdp->result = true; /* wait for ISR */ - return TRUE; + return true; } /* unhandled */ @@ -317,16 +317,16 @@ bool msd_scsi_process_inquiry(USBMassStorageDriver *msdp) { SCSI_SENSE_KEY_ILLEGAL_REQUEST, SCSI_ASENSE_INVALID_FIELD_IN_CDB, SCSI_ASENSEQ_NO_QUALIFIER); - return FALSE; + return false; } } else { msd_start_transmit(msdp, (const uint8_t *)&msdp->inquiry, sizeof(msdp->inquiry)); - msdp->result = TRUE; + msdp->result = true; /* wait for ISR */ - return TRUE; + return true; } } @@ -336,13 +336,13 @@ bool msd_scsi_process_inquiry(USBMassStorageDriver *msdp) { bool msd_scsi_process_request_sense(USBMassStorageDriver *msdp) { msd_start_transmit(msdp, (const uint8_t *)&msdp->sense, sizeof(msdp->sense)); - msdp->result = TRUE; + msdp->result = true; /* wait for ISR immediately, otherwise the caller may reset the sense bytes before they are sent to the host! */ msd_wait_for_isr(msdp); /* ... don't wait for ISR, we just did it */ - return FALSE; + return false; } /** @@ -356,10 +356,10 @@ bool msd_scsi_process_read_capacity_10(USBMassStorageDriver *msdp) { response.last_block_addr = swap_uint32(msdp->block_dev_info.blk_num-1); msd_start_transmit(msdp, (const uint8_t *)&response, sizeof(response)); - msdp->result = TRUE; + msdp->result = true; /* wait for ISR */ - return TRUE; + return true; } /** @@ -375,15 +375,15 @@ bool msd_scsi_process_send_diagnostic(USBMassStorageDriver *msdp) { SCSI_SENSE_KEY_ILLEGAL_REQUEST, SCSI_ASENSE_INVALID_FIELD_IN_CDB, SCSI_ASENSEQ_NO_QUALIFIER); - msdp->result = FALSE; - return FALSE; + msdp->result = false; + return false; } /* TODO: actually perform the test */ - msdp->result = TRUE; + msdp->result = true; /* don't wait for ISR */ - return FALSE; + return false; } /** @@ -400,10 +400,10 @@ bool msd_scsi_process_start_read_write_10(USBMassStorageDriver *msdp) { SCSI_SENSE_KEY_DATA_PROTECT, SCSI_ASENSE_WRITE_PROTECTED, SCSI_ASENSEQ_NO_QUALIFIER); - msdp->result = FALSE; + msdp->result = false; /* don't wait for ISR */ - return FALSE; + return false; } uint32_t rw_block_address = swap_uint32(*(DWORD *)&cbw->scsi_cmd_data[2]); @@ -416,10 +416,10 @@ bool msd_scsi_process_start_read_write_10(USBMassStorageDriver *msdp) { SCSI_SENSE_KEY_ILLEGAL_REQUEST, SCSI_ASENSE_LOGICAL_BLOCK_ADDRESS_OUT_OF_RANGE, SCSI_ASENSEQ_NO_QUALIFIER); - msdp->result = FALSE; + msdp->result = false; /* don't wait for ISR */ - return FALSE; + return false; } if (cbw->scsi_cmd_data[0] == SCSI_CMD_WRITE_10) { @@ -445,10 +445,10 @@ bool msd_scsi_process_start_read_write_10(USBMassStorageDriver *msdp) { SCSI_SENSE_KEY_MEDIUM_ERROR, SCSI_ASENSE_WRITE_FAULT, SCSI_ASENSEQ_NO_QUALIFIER); - msdp->result = FALSE; + msdp->result = false; /* don't wait for ISR */ - return FALSE; + return false; } if (i < (total - 1)) { @@ -468,10 +468,10 @@ bool msd_scsi_process_start_read_write_10(USBMassStorageDriver *msdp) { SCSI_SENSE_KEY_MEDIUM_ERROR, SCSI_ASENSE_READ_ERROR, SCSI_ASENSEQ_NO_QUALIFIER); - msdp->result = FALSE; + msdp->result = false; /* don't wait for ISR */ - return FALSE; + return false; } /* loop over each block */ @@ -488,10 +488,10 @@ bool msd_scsi_process_start_read_write_10(USBMassStorageDriver *msdp) { SCSI_SENSE_KEY_MEDIUM_ERROR, SCSI_ASENSE_READ_ERROR, SCSI_ASENSEQ_NO_QUALIFIER); - msdp->result = FALSE; + msdp->result = false; /* wait for ISR (the previous transmission is still running) */ - return TRUE; + return true; } } @@ -500,10 +500,10 @@ bool msd_scsi_process_start_read_write_10(USBMassStorageDriver *msdp) { } } - msdp->result = TRUE; + msdp->result = true; /* don't wait for ISR */ - return FALSE; + return false; } /** @@ -517,10 +517,10 @@ bool msd_scsi_process_start_stop_unit(USBMassStorageDriver *msdp) { msdp->state = MSD_EJECTED; } - msdp->result = TRUE; + msdp->result = true; /* don't wait for ISR */ - return FALSE; + return false; } /** @@ -536,10 +536,10 @@ bool msd_scsi_process_mode_sense_6(USBMassStorageDriver *msdp) { }; msd_start_transmit(msdp, response, sizeof(response)); - msdp->result = TRUE; + msdp->result = true; /* wait for ISR */ - return TRUE; + return true; } /** @@ -553,10 +553,10 @@ bool msd_scsi_process_read_format_capacities(USBMassStorageDriver *msdp) { response.desc_and_block_length = swap_uint32((0x02 << 24) | (msdp->block_dev_info.blk_size & 0x00FFFFFF)); msd_start_transmit(msdp, (const uint8_t*)&response, sizeof(response)); - msdp->result = TRUE; + msdp->result = true; /* wait for ISR */ - return TRUE; + return true; } /** @@ -566,18 +566,18 @@ bool msd_scsi_process_test_unit_ready(USBMassStorageDriver *msdp) { if (blkIsInserted(msdp->config->bbdp)) { /* device inserted and ready */ - msdp->result = TRUE; + msdp->result = true; } else { /* device not present or not ready */ msd_scsi_set_sense(msdp, SCSI_SENSE_KEY_NOT_READY, SCSI_ASENSE_MEDIUM_NOT_PRESENT, SCSI_ASENSEQ_NO_QUALIFIER); - msdp->result = FALSE; + msdp->result = false; } /* don't wait for ISR */ - return FALSE; + return false; } /** @@ -589,7 +589,7 @@ bool msd_wait_for_command_block(USBMassStorageDriver *msdp) { msdp->state = MSD_READ_COMMAND_BLOCK; /* wait for ISR */ - return TRUE; + return true; } /** @@ -616,10 +616,10 @@ bool msd_read_command_block(USBMassStorageDriver *msdp) { chSysUnlock(); /* don't wait for ISR */ - return FALSE; + return false; } - bool sleep = FALSE; + bool sleep = false; /* check the command */ switch (cbw->scsi_cmd_data[0]) { @@ -657,15 +657,15 @@ bool msd_read_command_block(USBMassStorageDriver *msdp) { break; case SCSI_CMD_FORMAT_UNIT: /* don't handle */ - msdp->result = TRUE; + msdp->result = true; break; case SCSI_CMD_PREVENT_ALLOW_MEDIUM_REMOVAL: /* don't handle */ - msdp->result = TRUE; + msdp->result = true; break; case SCSI_CMD_VERIFY_10: /* don't handle */ - msdp->result = TRUE; + msdp->result = true; break; default: msd_scsi_set_sense(msdp, @@ -678,7 +678,7 @@ bool msd_read_command_block(USBMassStorageDriver *msdp) { usbStallTransmitI(msdp->config->usbp, msdp->config->bulk_ep); chSysUnlock(); - return FALSE; + return false; } if (msdp->result) { @@ -705,7 +705,7 @@ bool msd_read_command_block(USBMassStorageDriver *msdp) { usbStallTransmitI(msdp->config->usbp, msdp->config->bulk_ep); chSysUnlock(); - /*return FALSE;*/ + /*return false;*/ } /* update the command status wrapper and send it to the host */ @@ -717,7 +717,7 @@ bool msd_read_command_block(USBMassStorageDriver *msdp) { msd_start_transmit(msdp, (const uint8_t *)csw, sizeof(*csw)); /* wait for ISR */ - return TRUE; + return true; } /** @@ -730,13 +730,13 @@ static msg_t mass_storage_thread(void *arg) { chRegSetThreadName("USB-MSD"); - bool wait_for_isr = FALSE; + bool wait_for_isr = false; /* wait for the usb to be initialised */ msd_wait_for_isr(msdp); while (!chThdShouldTerminate()) { - wait_for_isr = FALSE; + wait_for_isr = false; /* wait on data depending on the current state */ switch (msdp->state) { diff --git a/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.c b/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.c index 002be05c23..c2620d950b 100644 --- a/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.c +++ b/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.c @@ -152,7 +152,7 @@ int32_t varLenMsgQueuePopTimeout (VarLenMsgQueue* que, void* msg, // OUT OF BAND CONDITION pushSparseChunkMap (que, mpl); // DebugTrace ("pushSparseChunkMap (ptr=%d len=%d)", mpl.ptr, mpl.len); - // oobCondition=TRUE; + // oobCondition=true; const uint16_t sizeToCopy = msgLen < mpl.len ? msgLen : mpl.len; retVal = ringBufferCopyFromAddr(&que->circBuf, mpl.ptr, msg, sizeToCopy); } else { @@ -393,31 +393,31 @@ static uint16_t popSparseChunkMap (VarLenMsgQueue* que, const uint16_t mplAddr) bool varLenMsgQueueTestIntegrityIfEmpty(VarLenMsgQueue* que) { - bool retVal = TRUE; + bool retVal = true; varLenMsgQueueLock(que); int32_t status; if ((status = chMBGetUsedCountI (&que->mb)) > 0) { DebugTrace ("Error: mailbox not empty : [%d]", status); - retVal=FALSE; + retVal=false; goto unlockAndExit; } if (! ringBufferIsEmpty (&que->circBuf)) { DebugTrace ("Error: circular buffer not empty"); - retVal=FALSE; + retVal=false; goto unlockAndExit; } if (que->sparseChunkNumber != 0) { DebugTrace ("Error: sparseChunkNumber not NULL"); - retVal=FALSE; + retVal=false; goto unlockAndExit; } if (que->mbReservedSlot != 0) { DebugTrace ("Error: mbReservedSlot not NULL"); - retVal=FALSE; + retVal=false; goto unlockAndExit; } @@ -425,7 +425,7 @@ bool varLenMsgQueueTestIntegrityIfEmpty(VarLenMsgQueue* que) for (uint16_t i=0; i< que->mbAndSparseChunkSize; i++) { if (que->sparseChunkMap[i].len != 0) { DebugTrace ("Error: sparseChunkMap not erased"); - retVal=FALSE; + retVal=false; goto unlockAndExit; } } diff --git a/sw/airborne/subsystems/datalink/bluegiga.c b/sw/airborne/subsystems/datalink/bluegiga.c index ba851ffd75..b7135a1532 100644 --- a/sw/airborne/subsystems/datalink/bluegiga.c +++ b/sw/airborne/subsystems/datalink/bluegiga.c @@ -77,10 +77,10 @@ static int dev_check_free_space(struct bluegiga_periph *p, uint8_t len) // check if there is enough space for message // NB if BLUEGIGA_BUFFER_SIZE is smaller than 256 then an additional check is needed that len < BLUEGIGA_BUFFER_SIZE if (len - 1 <= ((p->tx_extract_idx - p->tx_insert_idx - 1 + BLUEGIGA_BUFFER_SIZE) % BLUEGIGA_BUFFER_SIZE)) { - return TRUE; + return true; } - return FALSE; + return false; } static void dev_put_byte(struct bluegiga_periph *p, uint8_t byte) { diff --git a/sw/airborne/subsystems/datalink/datalink.c b/sw/airborne/subsystems/datalink/datalink.c index bdaaf8be11..986168c011 100644 --- a/sw/airborne/subsystems/datalink/datalink.c +++ b/sw/airborne/subsystems/datalink/datalink.c @@ -59,7 +59,7 @@ #define MOfCm(_x) (((float)(_x))/100.) #if USE_NPS -bool datalink_enabled = TRUE; +bool datalink_enabled = true; #endif void dl_parse_msg(void) diff --git a/sw/airborne/subsystems/datalink/datalink.h b/sw/airborne/subsystems/datalink/datalink.h index 61fa4a710c..e8c77a6915 100644 --- a/sw/airborne/subsystems/datalink/datalink.h +++ b/sw/airborne/subsystems/datalink/datalink.h @@ -75,7 +75,7 @@ EXTERN bool datalink_enabled; for (_i = 0; _i < _len; _i++) { \ dl_buffer[_i] = _buf[_i]; \ } \ - dl_msg_available = TRUE; \ + dl_msg_available = true; \ } /** Check for new message and parse */ @@ -92,7 +92,7 @@ static inline void DlCheckAndParse(void) datalink_time = 0; datalink_nb_msgs++; dl_parse_msg(); - dl_msg_available = FALSE; + dl_msg_available = false; } } @@ -106,7 +106,7 @@ static inline void DlCheckAndParse(void) #elif defined DATALINK && DATALINK == XBEE #define DatalinkEvent() { \ - xbee_check_and_parse(&(XBEE_UART).device, &xbee_tp, dl_buffer, (uint8_t*)(&dl_msg_available)); \ + xbee_check_and_parse(&(XBEE_UART).device, &xbee_tp, dl_buffer, &dl_msg_available); \ DlCheckAndParse(); \ } diff --git a/sw/airborne/subsystems/datalink/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c index 2bc0f94dcf..9bfd074e13 100644 --- a/sw/airborne/subsystems/datalink/superbitrf.c +++ b/sw/airborne/subsystems/datalink/superbitrf.c @@ -289,7 +289,7 @@ void superbitrf_event(void) { uint8_t i, pn_row, data_code[16]; static uint8_t packet_size, tx_packet[16]; - static bool start_transfer = TRUE; + static bool start_transfer = true; #ifdef RADIO_CONTROL_LED static uint32_t slowLedCpt = 0; @@ -317,7 +317,7 @@ void superbitrf_event(void) superbitrf.rx_packet_count++; // Reset the packet receiving - superbitrf.cyrf6936.has_irq = FALSE; + superbitrf.cyrf6936.has_irq = false; } /* Check if it has a valid send */ @@ -327,7 +327,7 @@ void superbitrf_event(void) superbitrf.tx_packet_count++; // Reset the packet receiving - superbitrf.cyrf6936.has_irq = FALSE; + superbitrf.cyrf6936.has_irq = false; } } @@ -340,7 +340,7 @@ void superbitrf_event(void) if (cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_stratup_config, 11)) { // Check if need to go to bind or transfer if (gpio_get(SPEKTRUM_BIND_PIN_PORT, SPEKTRUM_BIND_PIN) == 0) { - start_transfer = FALSE; + start_transfer = false; } superbitrf.status = SUPERBITRF_INIT_BINDING; @@ -379,7 +379,7 @@ void superbitrf_event(void) // Try to write the transfer config if (cyrf6936_multi_write(&superbitrf.cyrf6936, cyrf_transfer_config, 4)) { superbitrf.resync_count = 0; - superbitrf.packet_loss = FALSE; + superbitrf.packet_loss = false; superbitrf.packet_loss_bit = 0; superbitrf.status = SUPERBITRF_SYNCING_A; superbitrf.state = 1; @@ -611,7 +611,7 @@ void superbitrf_event(void) case 0: // Fixing timer overflow if (superbitrf.timer_overflow && get_sys_time_usec() <= superbitrf.timer) { - superbitrf.timer_overflow = FALSE; + superbitrf.timer_overflow = false; } // When there is a timeout @@ -636,9 +636,9 @@ void superbitrf_event(void) // Set the timer superbitrf.timer = (get_sys_time_usec() + SUPERBITRF_DATARECV_TIME) % 0xFFFFFFFF; if (superbitrf.timer < get_sys_time_usec()) { - superbitrf.timer_overflow = TRUE; + superbitrf.timer_overflow = true; } else { - superbitrf.timer_overflow = FALSE; + superbitrf.timer_overflow = false; } // Only send on channel 2 @@ -694,7 +694,7 @@ void superbitrf_event(void) case 6: // Fixing timer overflow if (superbitrf.timer_overflow && get_sys_time_usec() <= superbitrf.timer) { - superbitrf.timer_overflow = FALSE; + superbitrf.timer_overflow = false; } // Waiting for data receive @@ -736,9 +736,9 @@ void superbitrf_event(void) superbitrf.timer = (superbitrf.timer - SUPERBITRF_DATARECV_TIME + SUPERBITRF_RECV_SHORT_TIME) % 0xFFFFFFFF; } if (superbitrf.timer < get_sys_time_usec()) { - superbitrf.timer_overflow = TRUE; + superbitrf.timer_overflow = true; } else { - superbitrf.timer_overflow = FALSE; + superbitrf.timer_overflow = false; } superbitrf.state = 0; @@ -851,9 +851,9 @@ static inline void superbitrf_receive_packet_cb(bool error, uint8_t status, uint // Check if it is a data loss packet if (packet[1] != (~superbitrf.bind_mfg_id[3] + 1 + superbitrf.packet_loss_bit) % 0xFF && packet[1] != (superbitrf.bind_mfg_id[3] + 1 + superbitrf.packet_loss_bit) % 0xFF) { - superbitrf.packet_loss = TRUE; + superbitrf.packet_loss = true; } else { - superbitrf.packet_loss = FALSE; + superbitrf.packet_loss = false; } // When it is a data packet, parse the packet if not busy already @@ -864,7 +864,7 @@ static inline void superbitrf_receive_packet_cb(bool error, uint8_t status, uint // When we have a full message if (superbitrf.rx_transport.trans_rx.msg_received) { DatalinkFillDlBuffer(superbitrf.rx_transport.trans_rx.payload, superbitrf.rx_transport.trans_rx.payload_len); - superbitrf.rx_transport.trans_rx.msg_received = FALSE; + superbitrf.rx_transport.trans_rx.msg_received = false; } } } @@ -924,7 +924,7 @@ static inline void superbitrf_receive_packet_cb(bool error, uint8_t status, uint // When we have a full message if (superbitrf.rx_transport.trans_rx.msg_received) { DatalinkFillDlBuffer(superbitrf.rx_transport.trans_rx.payload, superbitrf.rx_transport.trans_rx.payload_len); - superbitrf.rx_transport.trans_rx.msg_received = FALSE; + superbitrf.rx_transport.trans_rx.msg_received = false; } } } @@ -977,7 +977,7 @@ static inline void superbitrf_receive_packet_cb(bool error, uint8_t status, uint // Parse the packet superbitrf_radio_to_channels(&packet[2], superbitrf.num_channels, superbitrf.resolution, superbitrf.rc_values); - superbitrf.rc_frame_available = TRUE; + superbitrf.rc_frame_available = true; // Calculate the timing (seperately for the channel switches) if (superbitrf.crc_seed != ((superbitrf.bind_mfg_id[0] << 8) + superbitrf.bind_mfg_id[1])) { @@ -995,12 +995,12 @@ static inline void superbitrf_receive_packet_cb(bool error, uint8_t status, uint // Check if it is a data loss packet if (packet[1] != (~superbitrf.bind_mfg_id[3] + 1 + superbitrf.packet_loss_bit) && packet[1] != (superbitrf.bind_mfg_id[3] + 1 + superbitrf.packet_loss_bit)) { - superbitrf.packet_loss = TRUE; + superbitrf.packet_loss = true; } else { - superbitrf.packet_loss = FALSE; + superbitrf.packet_loss = false; } - superbitrf.packet_loss = FALSE; + superbitrf.packet_loss = false; // When it is a data packet, parse the packet if not busy already if (!dl_msg_available && !superbitrf.packet_loss) { @@ -1010,7 +1010,7 @@ static inline void superbitrf_receive_packet_cb(bool error, uint8_t status, uint // When we have a full message if (superbitrf.rx_transport.trans_rx.msg_received) { DatalinkFillDlBuffer(superbitrf.rx_transport.trans_rx.payload, superbitrf.rx_transport.trans_rx.payload_len); - superbitrf.rx_transport.trans_rx.msg_received = FALSE; + superbitrf.rx_transport.trans_rx.msg_received = false; } } } diff --git a/sw/airborne/subsystems/datalink/w5100.c b/sw/airborne/subsystems/datalink/w5100.c index ccdb06a8d1..30df7d696b 100644 --- a/sw/airborne/subsystems/datalink/w5100.c +++ b/sw/airborne/subsystems/datalink/w5100.c @@ -169,7 +169,7 @@ static inline uint16_t w5100_sock_get16(uint8_t _sock, uint16_t _reg) } // Functions for the generic device API -static int true_function(struct w5100_periph *p __attribute__((unused)), uint8_t len __attribute__((unused))) { return TRUE; } +static int true_function(struct w5100_periph *p __attribute__((unused)), uint8_t len __attribute__((unused))) { return true; } static void dev_transmit(struct w5100_periph *p __attribute__((unused)), uint8_t byte) { w5100_transmit(byte); } static void dev_send(struct w5100_periph *p __attribute__((unused))) { w5100_send(); } static int dev_char_available(struct w5100_periph *p __attribute__((unused))) { return w5100_ch_available; } @@ -364,9 +364,9 @@ static void configure_socket(uint8_t _s, uint8_t _flag, uint16_t _lport, uint16_ bool w5100_ch_available() { if (w5100_rx_size(CMD_SOCKET) > 0) { - return TRUE; + return true; } - return FALSE; + return false; } uint16_t w5100_receive(uint8_t *buf, uint16_t len __attribute__((unused))) diff --git a/sw/airborne/subsystems/datalink/w5100.h b/sw/airborne/subsystems/datalink/w5100.h index aa0464f04d..9dd888831e 100644 --- a/sw/airborne/subsystems/datalink/w5100.h +++ b/sw/airborne/subsystems/datalink/w5100.h @@ -96,7 +96,7 @@ static inline void w5100_check_and_parse(struct link_device *dev, struct pprz_tr w5100_read_buffer(trans); if (trans->trans_rx.msg_received) { DatalinkFillDlBuffer(trans->trans_rx.payload, trans->trans_rx.payload_len); - trans->trans_rx.msg_received = FALSE; + trans->trans_rx.msg_received = false; } } } diff --git a/sw/airborne/subsystems/electrical.c b/sw/airborne/subsystems/electrical.c index 3d3295aef6..649f55e679 100644 --- a/sw/airborne/subsystems/electrical.c +++ b/sw/airborne/subsystems/electrical.c @@ -102,8 +102,8 @@ void electrical_init(void) electrical.current = 0; electrical.energy = 0; - electrical.bat_low = FALSE; - electrical.bat_critical = FALSE; + electrical.bat_low = false; + electrical.bat_critical = false; #if defined ADC_CHANNEL_VSUPPLY adc_buf_channel(ADC_CHANNEL_VSUPPLY, &electrical_priv.vsupply_adc_buf, DEFAULT_AV_NB_SAMPLE); @@ -122,7 +122,7 @@ void electrical_periodic(void) { static uint32_t bat_low_counter = 0; static uint32_t bat_critical_counter = 0; - static bool vsupply_check_started = FALSE; + static bool vsupply_check_started = false; #if defined(ADC_CHANNEL_VSUPPLY) && !defined(SITL) electrical.vsupply = 10 * VoltageOfAdc((electrical_priv.vsupply_adc_buf.sum / @@ -183,7 +183,7 @@ void electrical_periodic(void) /*if valid voltage is seen then start checking. Set min level to 0 to always start*/ if (electrical.vsupply >= MIN_BAT_LEVEL * 10) { - vsupply_check_started = TRUE; + vsupply_check_started = true; } if (vsupply_check_started) { @@ -192,12 +192,12 @@ void electrical_periodic(void) bat_low_counter--; } if (bat_low_counter == 0) { - electrical.bat_low = TRUE; + electrical.bat_low = true; } } else { // reset battery low status and counter bat_low_counter = BAT_CHECKER_DELAY * ELECTRICAL_PERIODIC_FREQ; - electrical.bat_low = FALSE; + electrical.bat_low = false; } if (electrical.vsupply < CRITIC_BAT_LEVEL * 10) { @@ -205,12 +205,12 @@ void electrical_periodic(void) bat_critical_counter--; } if (bat_critical_counter == 0) { - electrical.bat_critical = TRUE; + electrical.bat_critical = true; } } else { // reset battery critical status and counter bat_critical_counter = BAT_CHECKER_DELAY * ELECTRICAL_PERIODIC_FREQ; - electrical.bat_critical = FALSE; + electrical.bat_critical = false; } } diff --git a/sw/airborne/subsystems/gps.h b/sw/airborne/subsystems/gps.h index 58c8ce550f..6295f27943 100644 --- a/sw/airborne/subsystems/gps.h +++ b/sw/airborne/subsystems/gps.h @@ -151,9 +151,9 @@ extern void gps_inject_data(uint8_t packet_id, uint8_t length, uint8_t *data); static inline bool gps_has_been_good(void) { - static bool gps_had_valid_fix = FALSE; + static bool gps_had_valid_fix = false; if (GpsFixValid()) { - gps_had_valid_fix = TRUE; + gps_had_valid_fix = true; } return gps_had_valid_fix; } diff --git a/sw/airborne/subsystems/gps/gps_furuno.c b/sw/airborne/subsystems/gps/gps_furuno.c index 7927baa5b8..bd3413946d 100644 --- a/sw/airborne/subsystems/gps/gps_furuno.c +++ b/sw/airborne/subsystems/gps/gps_furuno.c @@ -83,7 +83,7 @@ void nmea_configure(void) return; } } - gps_nmea.is_configured = TRUE; + gps_nmea.is_configured = true; } void nmea_parse_prop_init(void) diff --git a/sw/airborne/subsystems/gps/gps_mtk.c b/sw/airborne/subsystems/gps/gps_mtk.c index 56c1686af0..693b311f4b 100644 --- a/sw/airborne/subsystems/gps/gps_mtk.c +++ b/sw/airborne/subsystems/gps/gps_mtk.c @@ -111,12 +111,12 @@ void gps_mtk_msg(void); void gps_mtk_init(void) { gps_mtk.status = UNINIT; - gps_mtk.msg_available = FALSE; + gps_mtk.msg_available = false; gps_mtk.error_cnt = 0; gps_mtk.error_last = GPS_MTK_ERR_NONE; #ifdef GPS_CONFIGURE gps_status_config = 0; - gps_configuring = TRUE; + gps_configuring = true; #endif } @@ -157,7 +157,7 @@ void gps_mtk_msg(void) } AbiSendMsgGPS(GPS_MTK_ID, now_ts, &gps_mtk.state); } - gps_mtk.msg_available = FALSE; + gps_mtk.msg_available = false; } static void gps_mtk_time2itow(uint32_t gps_date, uint32_t gps_time, @@ -394,7 +394,7 @@ void gps_mtk_parse(uint8_t c) gps_mtk.error_last = GPS_MTK_ERR_CHECKSUM; goto error; } - gps_mtk.msg_available = TRUE; + gps_mtk.msg_available = true; goto restart; break; default: @@ -450,11 +450,11 @@ static bool user_gps_configure(bool cpt) break; case 1: MtkSend_CFG(MTK_DIY_OUTPUT_RATE); - return FALSE; + return false; default: break; } - return TRUE; /* Continue, except for the last case */ + return true; /* Continue, except for the last case */ } #endif // ! USER_GPS_CONFIGURE diff --git a/sw/airborne/subsystems/gps/gps_nmea.c b/sw/airborne/subsystems/gps/gps_nmea.c index 2c6dbd1058..4d5de67ab2 100644 --- a/sw/airborne/subsystems/gps/gps_nmea.c +++ b/sw/airborne/subsystems/gps/gps_nmea.c @@ -66,10 +66,10 @@ static void nmea_parse_GSV(void); void gps_nmea_init(void) { gps_nmea.state.nb_channels = GPS_NMEA_NB_CHANNELS; - gps_nmea.is_configured = FALSE; - gps_nmea.msg_available = FALSE; - gps_nmea.pos_available = FALSE; - gps_nmea.have_gsv = FALSE; + gps_nmea.is_configured = false; + gps_nmea.msg_available = false; + gps_nmea.pos_available = false; + gps_nmea.have_gsv = false; gps_nmea.gps_nb_ovrn = 0; gps_nmea.msg_len = 0; nmea_parse_prop_init(); @@ -107,12 +107,12 @@ void nmea_gps_msg(void) } AbiSendMsgGPS(GPS_NMEA_ID, now_ts, &gps); } - gps_nmea.msg_available = FALSE; + gps_nmea.msg_available = false; } void WEAK nmea_configure(void) { - gps_nmea.is_configured = TRUE; + gps_nmea.is_configured = true; } void WEAK nmea_parse_prop_init(void) @@ -145,7 +145,7 @@ void nmea_parse_msg(void) nmea_parse_GSA(); } else if (gps_nmea.msg_len > 5 && !strncmp(&gps_nmea.msg_buf[2] , "GSV", 3)) { gps_nmea.msg_buf[gps_nmea.msg_len] = 0; - gps_nmea.have_gsv = TRUE; + gps_nmea.have_gsv = true; NMEA_PRINT("GSV: \"%s\" \n\r", gps_nmea.msg_buf); nmea_parse_GSV(); } else { @@ -189,7 +189,7 @@ void nmea_parse_char(uint8_t c) else { // TODO: check for CRC before setting msg as available gps_nmea.status = GOT_END; - gps_nmea.msg_available = TRUE; + gps_nmea.msg_available = true; } break; @@ -424,10 +424,10 @@ static void nmea_parse_GGA(void) // 0 = Invalid, 1 = Valid SPS, 2 = Valid DGPS, 3 = Valid PPS // check for good position fix if ((gps_nmea.msg_buf[i] != '0') && (gps_nmea.msg_buf[i] != ',')) { - gps_nmea.pos_available = TRUE; + gps_nmea.pos_available = true; NMEA_PRINT("p_GGA() - POS_AVAILABLE == TRUE\n\r"); } else { - gps_nmea.pos_available = FALSE; + gps_nmea.pos_available = false; NMEA_PRINT("p_GGA() - gps_pos_available == false\n\r"); } @@ -492,9 +492,9 @@ static void nmea_parse_GSV(void) // check what satellites this messages contains // GPGSV -> GPS // GLGSV -> GLONASS - bool is_glonass = FALSE; + bool is_glonass = false; if (!strncmp(&gps_nmea.msg_buf[0] , "GL", 2)) { - is_glonass = TRUE; + is_glonass = true; } // total sentences diff --git a/sw/airborne/subsystems/gps/gps_sim_hitl.c b/sw/airborne/subsystems/gps/gps_sim_hitl.c index 1d11261992..6ab0a24832 100644 --- a/sw/airborne/subsystems/gps/gps_sim_hitl.c +++ b/sw/airborne/subsystems/gps/gps_sim_hitl.c @@ -74,7 +74,7 @@ void gps_sim_hitl_event(void) gps.fix = GPS_FIX_3D; gps.last_3dfix_ticks = sys_time.nb_sec_rem; gps.last_3dfix_time = sys_time.nb_sec; - gps_available = TRUE; + gps_available = true; } else { struct Int32Vect2 zero_vector; diff --git a/sw/airborne/subsystems/gps/gps_sim_nps.c b/sw/airborne/subsystems/gps/gps_sim_nps.c index e6a88ee679..b5bddfbb63 100644 --- a/sw/airborne/subsystems/gps/gps_sim_nps.c +++ b/sw/airborne/subsystems/gps/gps_sim_nps.c @@ -89,7 +89,7 @@ void gps_feed_value(void) void gps_nps_init(void) { - gps_has_fix = TRUE; + gps_has_fix = true; } /* diff --git a/sw/airborne/subsystems/gps/gps_sirf.c b/sw/airborne/subsystems/gps/gps_sirf.c index c3b9da13e0..ca8625b45f 100644 --- a/sw/airborne/subsystems/gps/gps_sirf.c +++ b/sw/airborne/subsystems/gps/gps_sirf.c @@ -121,8 +121,8 @@ void sirf_parse_41(void); void gps_sirf_init(void) { - gps_sirf.msg_available = FALSE; - gps_sirf.pos_available = FALSE; + gps_sirf.msg_available = false; + gps_sirf.pos_available = false; gps_sirf.msg_len = 0; gps_sirf.read_state = 0; } @@ -141,7 +141,7 @@ void gps_sirf_msg(void) } AbiSendMsgGPS(GPS_SIRF_ID, now_ts, &gps); } - gps_sirf.msg_available = FALSE; + gps_sirf.msg_available = false; } void sirf_parse_char(uint8_t c) @@ -175,7 +175,7 @@ void sirf_parse_char(uint8_t c) if (c == 0xB3) { gps_sirf.msg_buf[gps_sirf.msg_len] = c; gps_sirf.msg_len++; - gps_sirf.msg_available = TRUE; + gps_sirf.msg_available = true; } else { goto restart; } @@ -228,7 +228,7 @@ void sirf_parse_41(void) //Let gps_sirf know we have a position update - gps_sirf.pos_available = TRUE; + gps_sirf.pos_available = true; } void sirf_parse_2(void) @@ -262,7 +262,7 @@ void sirf_parse_2(void) void sirf_parse_msg(void) { //Set position available to false and check if it is a valid message - gps_sirf.pos_available = FALSE; + gps_sirf.pos_available = false; if (gps_sirf.msg_len < 8) { return; } diff --git a/sw/airborne/subsystems/gps/gps_skytraq.c b/sw/airborne/subsystems/gps/gps_skytraq.c index 555de3837e..ff59378570 100644 --- a/sw/airborne/subsystems/gps/gps_skytraq.c +++ b/sw/airborne/subsystems/gps/gps_skytraq.c @@ -109,7 +109,7 @@ void gps_skytraq_msg(void) } AbiSendMsgGPS(GPS_SKYTRAQ_ID, now_ts, &gps); } - gps_skytraq.msg_available = FALSE; + gps_skytraq.msg_available = false; } void gps_skytraq_event(void) @@ -256,7 +256,7 @@ void gps_skytraq_parse(uint8_t c) gps_skytraq.status = GOT_SYNC3; break; case GOT_SYNC3: - gps_skytraq.msg_available = TRUE; + gps_skytraq.msg_available = true; goto restart; default: gps_skytraq.error_last = GPS_SKYTRAQ_ERR_UNEXPECTED; @@ -274,18 +274,18 @@ static int distance_too_great(struct EcefCoor_i *ecef_ref, struct EcefCoor_i *ec { int32_t xdiff = abs(ecef_ref->x - ecef_pos->x); if (xdiff > MAX_DISTANCE) { - return TRUE; + return true; } int32_t ydiff = abs(ecef_ref->y - ecef_pos->y); if (ydiff > MAX_DISTANCE) { - return TRUE; + return true; } int32_t zdiff = abs(ecef_ref->z - ecef_pos->z); if (zdiff > MAX_DISTANCE) { - return TRUE; + return true; } - return FALSE; + return false; } /* diff --git a/sw/airborne/subsystems/gps/gps_ubx.c b/sw/airborne/subsystems/gps/gps_ubx.c index 6914de5b49..57462f693e 100644 --- a/sw/airborne/subsystems/gps/gps_ubx.c +++ b/sw/airborne/subsystems/gps/gps_ubx.c @@ -60,7 +60,7 @@ struct GpsTimeSync gps_ubx_time_sync; void gps_ubx_init(void) { gps_ubx.status = UNINIT; - gps_ubx.msg_available = FALSE; + gps_ubx.msg_available = false; gps_ubx.error_cnt = 0; gps_ubx.error_last = GPS_UBX_ERR_NONE; @@ -263,7 +263,7 @@ void gps_ubx_parse(uint8_t c) gps_ubx.error_last = GPS_UBX_ERR_CHECKSUM; goto error; } - gps_ubx.msg_available = TRUE; + gps_ubx.msg_available = true; goto restart; break; default: @@ -344,7 +344,7 @@ void gps_ubx_msg(void) } AbiSendMsgGPS(GPS_UBX_ID, now_ts, &gps_ubx.state); } - gps_ubx.msg_available = FALSE; + gps_ubx.msg_available = false; } void gps_ubx_register(void) diff --git a/sw/airborne/subsystems/imu.c b/sw/airborne/subsystems/imu.c index 61275b96a6..5f33bcb3e9 100644 --- a/sw/airborne/subsystems/imu.c +++ b/sw/airborne/subsystems/imu.c @@ -192,7 +192,7 @@ void imu_SetBodyToImuCurrent(float set) AbiSendMsgBODY_TO_IMU_QUAT(1, orientationGetQuat_f(&imu.body_to_imu)); } else { // indicate that we couldn't set to current roll/pitch - imu.b2i_set_current = FALSE; + imu.b2i_set_current = false; } } else { // reset to BODY_TO_IMU as defined in airframe file diff --git a/sw/airborne/subsystems/imu/imu_aspirin.c b/sw/airborne/subsystems/imu/imu_aspirin.c index 1e228c446a..60a659553e 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin.c +++ b/sw/airborne/subsystems/imu/imu_aspirin.c @@ -67,16 +67,16 @@ struct ImuAspirin imu_aspirin; void imu_impl_init(void) { - imu_aspirin.accel_valid = FALSE; - imu_aspirin.gyro_valid = FALSE; - imu_aspirin.mag_valid = FALSE; + imu_aspirin.accel_valid = false; + imu_aspirin.gyro_valid = false; + imu_aspirin.mag_valid = false; /* Set accel configuration */ adxl345_spi_init(&imu_aspirin.acc_adxl, &(ASPIRIN_SPI_DEV), ASPIRIN_SPI_SLAVE_IDX); // set the data rate imu_aspirin.acc_adxl.config.rate = ASPIRIN_ACCEL_RATE; /// @todo drdy int handling for adxl345 - //imu_aspirin.acc_adxl.config.drdy_int_enable = TRUE; + //imu_aspirin.acc_adxl.config.drdy_int_enable = true; /* Gyro configuration and initalization */ itg3200_init(&imu_aspirin.gyro_itg, &(ASPIRIN_I2C_DEV), ITG3200_ADDR); @@ -122,16 +122,16 @@ void imu_aspirin_event(void) adxl345_spi_event(&imu_aspirin.acc_adxl); if (imu_aspirin.acc_adxl.data_available) { VECT3_COPY(imu.accel_unscaled, imu_aspirin.acc_adxl.data.vect); - imu_aspirin.acc_adxl.data_available = FALSE; - imu_aspirin.accel_valid = TRUE; + imu_aspirin.acc_adxl.data_available = false; + imu_aspirin.accel_valid = true; } /* If the itg3200 I2C transaction has succeeded: convert the data */ itg3200_event(&imu_aspirin.gyro_itg); if (imu_aspirin.gyro_itg.data_available) { RATES_COPY(imu.gyro_unscaled, imu_aspirin.gyro_itg.data.rates); - imu_aspirin.gyro_itg.data_available = FALSE; - imu_aspirin.gyro_valid = TRUE; + imu_aspirin.gyro_itg.data_available = false; + imu_aspirin.gyro_valid = true; } /* HMC58XX event task */ @@ -144,22 +144,22 @@ void imu_aspirin_event(void) imu.mag_unscaled.y = -imu_aspirin.mag_hmc.data.vect.x; imu.mag_unscaled.z = imu_aspirin.mag_hmc.data.vect.z; #endif - imu_aspirin.mag_hmc.data_available = FALSE; - imu_aspirin.mag_valid = TRUE; + imu_aspirin.mag_hmc.data_available = false; + imu_aspirin.mag_valid = true; } if (imu_aspirin.gyro_valid) { - imu_aspirin.gyro_valid = FALSE; + imu_aspirin.gyro_valid = false; imu_scale_gyro(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_ASPIRIN_ID, now_ts, &imu.gyro); } if (imu_aspirin.accel_valid) { - imu_aspirin.accel_valid = FALSE; + imu_aspirin.accel_valid = false; imu_scale_accel(&imu); AbiSendMsgIMU_ACCEL_INT32(IMU_ASPIRIN_ID, now_ts, &imu.accel); } if (imu_aspirin.mag_valid) { - imu_aspirin.mag_valid = FALSE; + imu_aspirin.mag_valid = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_ASPIRIN_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c index b24a6593e0..16435fad1c 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c +++ b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c @@ -146,7 +146,7 @@ void imu_impl_init(void) imu_aspirin2.wait_slave4_trans.output_buf = &(imu_aspirin2.wait_slave4_tx_buf[0]); imu_aspirin2.wait_slave4_trans.status = SPITransDone; - imu_aspirin2.slave4_ready = FALSE; + imu_aspirin2.slave4_ready = false; #endif } @@ -233,7 +233,7 @@ void imu_aspirin2_event(void) #endif #endif - imu_aspirin2.mpu.data_available = FALSE; + imu_aspirin2.mpu.data_available = false; imu_scale_gyro(&imu); imu_scale_accel(&imu); @@ -261,7 +261,7 @@ bool imu_aspirin2_configure_mag_slave(Mpu60x0ConfigSet mpu_set, void *mpu) // wait before starting the configuration of the HMC58xx mag // doing to early may void the mode configuration if (get_sys_time_float() < ASPIRIN_2_MAG_STARTUP_DELAY) { - return FALSE; + return false; } mpu_set_and_wait(mpu_set, mpu, MPU60X0_REG_I2C_SLV4_ADDR, (HMC58XX_ADDR >> 1)); @@ -290,7 +290,7 @@ bool imu_aspirin2_configure_mag_slave(Mpu60x0ConfigSet mpu_set, void *mpu) (1 << 7) | // Slave 0 enable (6 << 0)); // Read 6 bytes - return TRUE; + return true; } void mpu_wait_slave4_ready(void) @@ -306,9 +306,9 @@ void mpu_wait_slave4_ready(void) void mpu_wait_slave4_ready_cb(struct spi_transaction *t) { if (bit_is_set(t->input_buf[1], MPU60X0_I2C_SLV4_DONE)) { - imu_aspirin2.slave4_ready = TRUE; + imu_aspirin2.slave4_ready = true; } else { - imu_aspirin2.slave4_ready = FALSE; + imu_aspirin2.slave4_ready = false; } t->status = SPITransDone; } diff --git a/sw/airborne/subsystems/imu/imu_aspirin_i2c.c b/sw/airborne/subsystems/imu/imu_aspirin_i2c.c index 4b6fbaddb8..a5d7fb1bbd 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin_i2c.c +++ b/sw/airborne/subsystems/imu/imu_aspirin_i2c.c @@ -87,7 +87,7 @@ void imu_impl_init(void) // set the data rate imu_aspirin.acc_adxl.config.rate = ASPIRIN_ACCEL_RATE; /// @todo drdy int handling for adxl345 - //imu_aspirin.acc_adxl.config.drdy_int_enable = TRUE; + //imu_aspirin.acc_adxl.config.drdy_int_enable = true; // With CS tied high to VDD I/O, the ADXL345 is in I2C mode #ifdef ASPIRIN_I2C_CS_PORT @@ -133,7 +133,7 @@ void imu_aspirin_i2c_event(void) adxl345_i2c_event(&imu_aspirin.acc_adxl); if (imu_aspirin.acc_adxl.data_available) { VECT3_COPY(imu.accel_unscaled, imu_aspirin.acc_adxl.data.vect); - imu_aspirin.acc_adxl.data_available = FALSE; + imu_aspirin.acc_adxl.data_available = false; imu_scale_accel(&imu); AbiSendMsgIMU_ACCEL_INT32(IMU_ASPIRIN_ID, now_ts, &imu.accel); } @@ -142,7 +142,7 @@ void imu_aspirin_i2c_event(void) itg3200_event(&imu_aspirin.gyro_itg); if (imu_aspirin.gyro_itg.data_available) { RATES_COPY(imu.gyro_unscaled, imu_aspirin.gyro_itg.data.rates); - imu_aspirin.gyro_itg.data_available = FALSE; + imu_aspirin.gyro_itg.data_available = false; imu_scale_gyro(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_ASPIRIN_ID, now_ts, &imu.gyro); } @@ -157,7 +157,7 @@ void imu_aspirin_i2c_event(void) imu.mag_unscaled.y = -imu_aspirin.mag_hmc.data.vect.x; imu.mag_unscaled.z = imu_aspirin.mag_hmc.data.vect.z; #endif - imu_aspirin.mag_hmc.data_available = FALSE; + imu_aspirin.mag_hmc.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_ASPIRIN_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/subsystems/imu/imu_b2.c b/sw/airborne/subsystems/imu/imu_b2.c index 21ca2d1d43..0a556b47f1 100644 --- a/sw/airborne/subsystems/imu/imu_b2.c +++ b/sw/airborne/subsystems/imu/imu_b2.c @@ -128,7 +128,7 @@ static inline void ImuMagEvent(void) imu.mag_unscaled.z = hmc5843.data.value[IMU_MAG_Z_CHAN]; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_B2_ID, get_sys_time_usec(), &imu.mag); - hmc5843.data_available = FALSE; + hmc5843.data_available = false; } } #elif defined IMU_B2_MAG_TYPE && IMU_B2_MAG_TYPE == IMU_B2_MAG_HMC58XX @@ -141,7 +141,7 @@ static inline void ImuMagEvent(void) imu.mag_unscaled.z = imu_b2.mag_hmc.data.value[IMU_MAG_Z_CHAN]; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_B2_ID, get_sys_time_usec(), &imu.mag); - imu_b2.mag_hmc.data_available = FALSE; + imu_b2.mag_hmc.data_available = false; } } #else diff --git a/sw/airborne/subsystems/imu/imu_bebop.c b/sw/airborne/subsystems/imu/imu_bebop.c index 8bbe51bfdc..3c8ac8e37f 100644 --- a/sw/airborne/subsystems/imu/imu_bebop.c +++ b/sw/airborne/subsystems/imu/imu_bebop.c @@ -120,7 +120,7 @@ void imu_bebop_event(void) VECT3_ASSIGN(imu.accel_unscaled, imu_bebop.mpu.data_accel.vect.x, -imu_bebop.mpu.data_accel.vect.y, -imu_bebop.mpu.data_accel.vect.z); - imu_bebop.mpu.data_available = FALSE; + imu_bebop.mpu.data_available = false; imu_scale_gyro(&imu); imu_scale_accel(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_BOARD_ID, now_ts, &imu.gyro); @@ -138,7 +138,7 @@ void imu_bebop_event(void) VECT3_ASSIGN(imu.mag_unscaled, -imu_bebop.ak.data.vect.y, imu_bebop.ak.data.vect.x, imu_bebop.ak.data.vect.z); #endif - imu_bebop.ak.data_available = FALSE; + imu_bebop.ak.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_BOARD_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/subsystems/imu/imu_crista.c b/sw/airborne/subsystems/imu/imu_crista.c index 1234fc9135..7e8215939c 100644 --- a/sw/airborne/subsystems/imu/imu_crista.c +++ b/sw/airborne/subsystems/imu/imu_crista.c @@ -28,7 +28,7 @@ uint16_t ADS8344_values[ADS8344_NB_CHANNELS]; void imu_impl_init(void) { - ADS8344_available = FALSE; + ADS8344_available = false; imu_crista_arch_init(); @@ -79,7 +79,7 @@ static inline void ImuMagEvent(void) imu.mag_unscaled.x = hmc5843.data.value[IMU_MAG_X_CHAN]; imu.mag_unscaled.y = hmc5843.data.value[IMU_MAG_Y_CHAN]; imu.mag_unscaled.z = hmc5843.data.value[IMU_MAG_Z_CHAN]; - hmc5843.data_available = FALSE; + hmc5843.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_CRISTA_ID, now_ts, &imu.mag); } @@ -91,7 +91,7 @@ static inline void ImuMagEvent(void) void imu_christa_event(void) { if (ADS8344_available) { - ADS8344_available = FALSE; + ADS8344_available = false; imu.gyro_unscaled.p = ADS8344_values[IMU_GYRO_P_CHAN]; imu.gyro_unscaled.q = ADS8344_values[IMU_GYRO_Q_CHAN]; imu.gyro_unscaled.r = ADS8344_values[IMU_GYRO_R_CHAN]; diff --git a/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.c b/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.c index a67275083d..f9cfe9fb9e 100644 --- a/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.c +++ b/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.c @@ -100,7 +100,7 @@ void imu_impl_init(void) imu_drotek2.mpu.config.slaves[0].configure = &imu_drotek2_configure_mag_slave; // use hmc mag via passthrough - imu_drotek2.mpu.config.i2c_bypass = TRUE; + imu_drotek2.mpu.config.i2c_bypass = true; } void imu_periodic(void) @@ -136,7 +136,7 @@ void imu_drotek2_event(void) VECT3_COPY(imu.accel_unscaled, imu_drotek2.mpu.data_accel.vect); #endif - imu_drotek2.mpu.data_available = FALSE; + imu_drotek2.mpu.data_available = false; imu_scale_gyro(&imu); imu_scale_accel(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_DROTEK_ID, now_ts, &imu.gyro); @@ -153,7 +153,7 @@ void imu_drotek2_event(void) #else VECT3_COPY(imu.mag_unscaled, imu_drotek2.hmc.data.vect); #endif - imu_drotek2.hmc.data_available = FALSE; + imu_drotek2.hmc.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_DROTEK_ID, now_ts, &imu.mag); } @@ -167,8 +167,8 @@ bool imu_drotek2_configure_mag_slave(Mpu60x0ConfigSet mpu_set __attribute__((unu { hmc58xx_start_configure(&imu_drotek2.hmc); if (imu_drotek2.hmc.initialized) { - return TRUE; + return true; } else { - return FALSE; + return false; } } diff --git a/sw/airborne/subsystems/imu/imu_gl1.c b/sw/airborne/subsystems/imu/imu_gl1.c index 476beed67b..0fa158a4e1 100644 --- a/sw/airborne/subsystems/imu/imu_gl1.c +++ b/sw/airborne/subsystems/imu/imu_gl1.c @@ -84,7 +84,7 @@ void imu_impl_init(void) // set the data rate imu_gl1.acc_adxl.config.rate = GL1_ACCEL_RATE; /// @todo drdy int handling for adxl345 - //imu_aspirin.acc_adxl.config.drdy_int_enable = TRUE; + //imu_aspirin.acc_adxl.config.drdy_int_enable = true; /* Gyro configuration and initalization */ @@ -125,7 +125,7 @@ void imu_gl1_i2c_event(void) imu.accel_unscaled.x = imu_gl1.acc_adxl.data.vect.y; imu.accel_unscaled.y = imu_gl1.acc_adxl.data.vect.x; imu.accel_unscaled.z = -imu_gl1.acc_adxl.data.vect.z; - imu_gl1.acc_adxl.data_available = FALSE; + imu_gl1.acc_adxl.data_available = false; imu_scale_accel(&imu); AbiSendMsgIMU_ACCEL_INT32(IMU_GL1_ID, now_ts, &imu.accel); } @@ -137,7 +137,7 @@ void imu_gl1_i2c_event(void) imu.gyro_unscaled.p = imu_gl1.gyro_l3g.data.rates.q; imu.gyro_unscaled.q = imu_gl1.gyro_l3g.data.rates.p; imu.gyro_unscaled.r = -imu_gl1.gyro_l3g.data.rates.r; - imu_gl1.gyro_l3g.data_available = FALSE; + imu_gl1.gyro_l3g.data_available = false; imu_scale_gyro(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_GL1_ID, now_ts, &imu.gyro); } @@ -149,7 +149,7 @@ void imu_gl1_i2c_event(void) imu.mag_unscaled.y = imu_gl1.mag_hmc.data.vect.x; imu.mag_unscaled.x = imu_gl1.mag_hmc.data.vect.y; imu.mag_unscaled.z = -imu_gl1.mag_hmc.data.vect.z; - imu_gl1.mag_hmc.data_available = FALSE; + imu_gl1.mag_hmc.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_GL1_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/subsystems/imu/imu_mpu6000.c b/sw/airborne/subsystems/imu/imu_mpu6000.c index f1d8e57cb6..baafbde5e0 100644 --- a/sw/airborne/subsystems/imu/imu_mpu6000.c +++ b/sw/airborne/subsystems/imu/imu_mpu6000.c @@ -92,7 +92,7 @@ void imu_mpu_spi_event(void) uint32_t now_ts = get_sys_time_usec(); RATES_COPY(imu.gyro_unscaled, imu_mpu_spi.mpu.data_rates.rates); VECT3_COPY(imu.accel_unscaled, imu_mpu_spi.mpu.data_accel.vect); - imu_mpu_spi.mpu.data_available = FALSE; + imu_mpu_spi.mpu.data_available = false; imu_scale_gyro(&imu); imu_scale_accel(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_MPU6000_ID, now_ts, &imu.gyro); diff --git a/sw/airborne/subsystems/imu/imu_mpu6000_hmc5883.c b/sw/airborne/subsystems/imu/imu_mpu6000_hmc5883.c index c14f92a61b..7b8924fe21 100644 --- a/sw/airborne/subsystems/imu/imu_mpu6000_hmc5883.c +++ b/sw/airborne/subsystems/imu/imu_mpu6000_hmc5883.c @@ -104,7 +104,7 @@ void imu_mpu_hmc_event(void) if (imu_mpu_hmc.mpu.data_available) { RATES_COPY(imu.gyro_unscaled, imu_mpu_hmc.mpu.data_rates.rates); VECT3_COPY(imu.accel_unscaled, imu_mpu_hmc.mpu.data_accel.vect); - imu_mpu_hmc.mpu.data_available = FALSE; + imu_mpu_hmc.mpu.data_available = false; imu_scale_gyro(&imu); imu_scale_accel(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_MPU6000_HMC_ID, now_ts, &imu.gyro); @@ -118,7 +118,7 @@ void imu_mpu_hmc_event(void) imu.mag_unscaled.x = imu_mpu_hmc.hmc.data.vect.y; imu.mag_unscaled.y = -imu_mpu_hmc.hmc.data.vect.x; imu.mag_unscaled.z = imu_mpu_hmc.hmc.data.vect.z; - imu_mpu_hmc.hmc.data_available = FALSE; + imu_mpu_hmc.hmc.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_MPU6000_HMC_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/subsystems/imu/imu_mpu60x0_i2c.c b/sw/airborne/subsystems/imu/imu_mpu60x0_i2c.c index ad88ed290c..93a5f5a02c 100644 --- a/sw/airborne/subsystems/imu/imu_mpu60x0_i2c.c +++ b/sw/airborne/subsystems/imu/imu_mpu60x0_i2c.c @@ -93,7 +93,7 @@ void imu_mpu_i2c_event(void) if (imu_mpu_i2c.mpu.data_available) { RATES_COPY(imu.gyro_unscaled, imu_mpu_i2c.mpu.data_rates.rates); VECT3_COPY(imu.accel_unscaled, imu_mpu_i2c.mpu.data_accel.vect); - imu_mpu_i2c.mpu.data_available = FALSE; + imu_mpu_i2c.mpu.data_available = false; imu_scale_gyro(&imu); imu_scale_accel(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_MPU60X0_ID, now_ts, &imu.gyro); diff --git a/sw/airborne/subsystems/imu/imu_mpu9250_i2c.c b/sw/airborne/subsystems/imu/imu_mpu9250_i2c.c index 661400d964..0beadef58f 100644 --- a/sw/airborne/subsystems/imu/imu_mpu9250_i2c.c +++ b/sw/airborne/subsystems/imu/imu_mpu9250_i2c.c @@ -133,7 +133,7 @@ void imu_mpu9250_event(void) VECT3_COPY(imu.accel_unscaled, accel); RATES_COPY(imu.gyro_unscaled, rates); - imu_mpu9250.mpu.data_available = FALSE; + imu_mpu9250.mpu.data_available = false; imu_scale_gyro(&imu); imu_scale_accel(&imu); @@ -149,7 +149,7 @@ void imu_mpu9250_event(void) -(int32_t)(imu_mpu9250.mpu.akm.data.value[IMU_MPU9250_CHAN_Z]) }; VECT3_COPY(imu.mag_unscaled, mag); - imu_mpu9250.mpu.akm.data_available = FALSE; + imu_mpu9250.mpu.akm.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_MPU9250_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/subsystems/imu/imu_mpu9250_spi.c b/sw/airborne/subsystems/imu/imu_mpu9250_spi.c index f32fe6b290..612302a288 100644 --- a/sw/airborne/subsystems/imu/imu_mpu9250_spi.c +++ b/sw/airborne/subsystems/imu/imu_mpu9250_spi.c @@ -162,7 +162,7 @@ void imu_impl_init(void) imu_mpu9250.wait_slave4_trans.output_buf = &(imu_mpu9250.wait_slave4_tx_buf[0]); imu_mpu9250.wait_slave4_trans.status = SPITransDone; - imu_mpu9250.slave4_ready = FALSE; + imu_mpu9250.slave4_ready = false; } void imu_periodic(void) @@ -207,7 +207,7 @@ void imu_mpu9250_event(void) } #endif - imu_mpu9250.mpu.data_available = FALSE; + imu_mpu9250.mpu.data_available = false; imu_scale_gyro(&imu); imu_scale_accel(&imu); @@ -232,7 +232,7 @@ bool imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set, void *mpu) // wait before starting the configuration of the mag // doing to early may void the mode configuration if (get_sys_time_float() < IMU_MPU9250_MAG_STARTUP_DELAY) { - return FALSE; + return false; } //config AK8963 soft reset @@ -259,7 +259,7 @@ bool imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set, void *mpu) (1 << 7) | // Slave 0 enable (7 << 0)); // Read 7 bytes (mag x,y,z + status) - return TRUE; + return true; } void mpu_wait_slave4_ready(void) @@ -275,9 +275,9 @@ void mpu_wait_slave4_ready(void) void mpu_wait_slave4_ready_cb(struct spi_transaction *t) { if (bit_is_set(t->input_buf[1], MPU9250_I2C_SLV4_DONE)) { - imu_mpu9250.slave4_ready = TRUE; + imu_mpu9250.slave4_ready = true; } else { - imu_mpu9250.slave4_ready = FALSE; + imu_mpu9250.slave4_ready = false; } t->status = SPITransDone; } diff --git a/sw/airborne/subsystems/imu/imu_navstik.c b/sw/airborne/subsystems/imu/imu_navstik.c index 7a1001b5ef..4f172ce3ba 100644 --- a/sw/airborne/subsystems/imu/imu_navstik.c +++ b/sw/airborne/subsystems/imu/imu_navstik.c @@ -118,7 +118,7 @@ void imu_navstik_event(void) RATES_COPY(imu.gyro_unscaled, imu_navstik.mpu.data_rates.rates); VECT3_COPY(imu.accel_unscaled, imu_navstik.mpu.data_accel.vect); - imu_navstik.mpu.data_available = FALSE; + imu_navstik.mpu.data_available = false; imu_scale_gyro(&imu); imu_scale_accel(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_BOARD_ID, now_ts, &imu.gyro); @@ -131,7 +131,7 @@ void imu_navstik_event(void) imu.mag_unscaled.x = imu_navstik.hmc.data.vect.y; imu.mag_unscaled.y = -imu_navstik.hmc.data.vect.x; imu.mag_unscaled.z = imu_navstik.hmc.data.vect.z; - imu_navstik.hmc.data_available = FALSE; + imu_navstik.hmc.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_BOARD_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/subsystems/imu/imu_nps.c b/sw/airborne/subsystems/imu/imu_nps.c index e3d453390d..49d8c0aecb 100644 --- a/sw/airborne/subsystems/imu/imu_nps.c +++ b/sw/airborne/subsystems/imu/imu_nps.c @@ -30,9 +30,9 @@ struct ImuNps imu_nps; void imu_impl_init(void) { - imu_nps.gyro_available = FALSE; - imu_nps.mag_available = FALSE; - imu_nps.accel_available = FALSE; + imu_nps.gyro_available = false; + imu_nps.mag_available = false; + imu_nps.accel_available = false; } @@ -48,8 +48,8 @@ void imu_feed_gyro_accel(void) VECT3_ASSIGN(imu.accel_unscaled, sensors.accel.value.x, sensors.accel.value.y, sensors.accel.value.z); // set availability flags... - imu_nps.accel_available = TRUE; - imu_nps.gyro_available = TRUE; + imu_nps.accel_available = true; + imu_nps.gyro_available = true; } @@ -58,7 +58,7 @@ void imu_feed_mag(void) { VECT3_ASSIGN(imu.mag_unscaled, sensors.mag.value.x, sensors.mag.value.y, sensors.mag.value.z); - imu_nps.mag_available = TRUE; + imu_nps.mag_available = true; } @@ -66,17 +66,17 @@ void imu_nps_event(void) { uint32_t now_ts = get_sys_time_usec(); if (imu_nps.gyro_available) { - imu_nps.gyro_available = FALSE; + imu_nps.gyro_available = false; imu_scale_gyro(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_BOARD_ID, now_ts, &imu.gyro); } if (imu_nps.accel_available) { - imu_nps.accel_available = FALSE; + imu_nps.accel_available = false; imu_scale_accel(&imu); AbiSendMsgIMU_ACCEL_INT32(IMU_BOARD_ID, now_ts, &imu.accel); } if (imu_nps.mag_available) { - imu_nps.mag_available = FALSE; + imu_nps.mag_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_BOARD_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/subsystems/imu/imu_ppzuav.c b/sw/airborne/subsystems/imu/imu_ppzuav.c index 16d7a76f39..a4ee049183 100644 --- a/sw/airborne/subsystems/imu/imu_ppzuav.c +++ b/sw/airborne/subsystems/imu/imu_ppzuav.c @@ -118,7 +118,7 @@ void imu_ppzuav_event(void) imu.accel_unscaled.x = -imu_ppzuav.acc_adxl.data.vect.x; imu.accel_unscaled.y = imu_ppzuav.acc_adxl.data.vect.y; imu.accel_unscaled.z = -imu_ppzuav.acc_adxl.data.vect.z; - imu_ppzuav.acc_adxl.data_available = FALSE; + imu_ppzuav.acc_adxl.data_available = false; imu_scale_accel(&imu); AbiSendMsgIMU_ACCEL_INT32(IMU_PPZUAV_ID, now_ts, &imu.accel); } @@ -129,7 +129,7 @@ void imu_ppzuav_event(void) imu.gyro_unscaled.p = -imu_ppzuav.gyro_itg.data.rates.p; imu.gyro_unscaled.q = imu_ppzuav.gyro_itg.data.rates.q; imu.gyro_unscaled.r = -imu_ppzuav.gyro_itg.data.rates.r; - imu_ppzuav.gyro_itg.data_available = FALSE; + imu_ppzuav.gyro_itg.data_available = false; imu_scale_gyro(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_PPZUAV_ID, now_ts, &imu.gyro); } @@ -140,7 +140,7 @@ void imu_ppzuav_event(void) imu.mag_unscaled.x = -imu_ppzuav.mag_hmc.data.vect.y; imu.mag_unscaled.y = -imu_ppzuav.mag_hmc.data.vect.x; imu.mag_unscaled.z = -imu_ppzuav.mag_hmc.data.vect.z; - imu_ppzuav.mag_hmc.data_available = FALSE; + imu_ppzuav.mag_hmc.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_PPZUAV_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/subsystems/imu/imu_px4fmu.c b/sw/airborne/subsystems/imu/imu_px4fmu.c index c5d50fe68d..6656895d93 100644 --- a/sw/airborne/subsystems/imu/imu_px4fmu.c +++ b/sw/airborne/subsystems/imu/imu_px4fmu.c @@ -102,7 +102,7 @@ void imu_px4fmu_event(void) imu_px4fmu.mpu.data_accel.vect.y, imu_px4fmu.mpu.data_accel.vect.x, -imu_px4fmu.mpu.data_accel.vect.z); - imu_px4fmu.mpu.data_available = FALSE; + imu_px4fmu.mpu.data_available = false; imu_scale_gyro(&imu); imu_scale_accel(&imu); AbiSendMsgIMU_GYRO_INT32(IMU_BOARD_ID, now_ts, &imu.gyro); @@ -115,7 +115,7 @@ void imu_px4fmu_event(void) imu.mag_unscaled.x = imu_px4fmu.hmc.data.vect.y; imu.mag_unscaled.y = imu_px4fmu.hmc.data.vect.x; imu.mag_unscaled.z = -imu_px4fmu.hmc.data.vect.z; - imu_px4fmu.hmc.data_available = FALSE; + imu_px4fmu.hmc.data_available = false; imu_scale_mag(&imu); AbiSendMsgIMU_MAG_INT32(IMU_BOARD_ID, now_ts, &imu.mag); } diff --git a/sw/airborne/subsystems/imu/imu_um6.c b/sw/airborne/subsystems/imu/imu_um6.c index 77b1d858de..a4a1efb372 100644 --- a/sw/airborne/subsystems/imu/imu_um6.c +++ b/sw/airborne/subsystems/imu/imu_um6.c @@ -140,7 +140,7 @@ void imu_impl_init(void) // Initialize packet UM6_packet.status = UM6PacketWaiting; UM6_packet.msg_idx = 0; - UM6_packet.msg_available = FALSE; + UM6_packet.msg_available = false; UM6_packet.chksm_error = 0; UM6_packet.hdr_error = 0; @@ -345,9 +345,9 @@ void UM6_packet_parse(uint8_t c) UM6_packet.msg_idx++; if (UM6_packet.msg_idx == PacketLength) { if (UM6_verify_chk(UM6_packet.msg_buf, PacketLength)) { - UM6_packet.msg_available = TRUE; + UM6_packet.msg_available = true; } else { - UM6_packet.msg_available = FALSE; + UM6_packet.msg_available = false; UM6_packet.chksm_error++; } UM6_packet.status = UM6PacketWaiting; diff --git a/sw/airborne/subsystems/imu/imu_um6.h b/sw/airborne/subsystems/imu/imu_um6.h index a8fbf532b2..68f5c39c29 100644 --- a/sw/airborne/subsystems/imu/imu_um6.h +++ b/sw/airborne/subsystems/imu/imu_um6.h @@ -106,7 +106,7 @@ static inline void imu_um6_event(void) UM6_packet_parse(uart_getch(&(UM6_LINK))); } if (UM6_packet.msg_available) { - UM6_packet.msg_available = FALSE; + UM6_packet.msg_available = false; UM6_packet_read_message(); imu_um6_publish(); } diff --git a/sw/airborne/subsystems/ins/hf_float.c b/sw/airborne/subsystems/ins/hf_float.c index d2062edf33..9f817cc3e0 100644 --- a/sw/airborne/subsystems/ins/hf_float.c +++ b/sw/airborne/subsystems/ins/hf_float.c @@ -278,7 +278,7 @@ void b2_hff_init(float init_x, float init_xdot, float init_y, float init_ydot) acc_buf_n = 0; b2_hff_rb_put = b2_hff_rb; b2_hff_rb_last = b2_hff_rb; - b2_hff_rb_last->rollback = FALSE; + b2_hff_rb_last->rollback = false; b2_hff_rb_last->lag_counter = 0; b2_hff_state.lag_counter = GPS_LAG_N; #ifdef SITL @@ -293,7 +293,7 @@ void b2_hff_init(float init_x, float init_xdot, float init_y, float init_ydot) b2_hff_state.lag_counter = 0; #endif b2_hff_rb_n = 0; - b2_hff_state.rollback = FALSE; + b2_hff_state.rollback = false; lag_counter_err = 0; save_counter = -1; past_save_counter = SAVE_DONE; @@ -381,7 +381,7 @@ static void b2_hff_rb_put_state(struct HfilterFloat *source) /* copy state from source into buffer */ b2_hff_set_state(b2_hff_rb_put, source); b2_hff_rb_put->lag_counter = 0; - b2_hff_rb_put->rollback = FALSE; + b2_hff_rb_put->rollback = false; /* forward write pointer */ INC_RB_POINTER(b2_hff_rb_put); @@ -403,7 +403,7 @@ static void b2_hff_rb_drop_last(void) } else { PRINT_DBG(2, ("hff ringbuffer empty!\n")); b2_hff_rb_last->lag_counter = 0; - b2_hff_rb_last->rollback = FALSE; + b2_hff_rb_last->rollback = false; } PRINT_DBG(2, ("drop last state. fill count now: %d\n", b2_hff_rb_n)); } @@ -565,7 +565,7 @@ void b2_hff_update_gps(struct FloatVect2 *pos_ned, struct FloatVect2 *speed_ned) PRINT_DBG(2, ("update. rb_n: %d lag_counter: %d lag_cnt_err: %d\n", b2_hff_rb_n, b2_hff_rb_last->lag_counter, lag_counter_err)); if (abs(lag_counter_err) <= GPS_LAG_TOL_N) { - b2_hff_rb_last->rollback = TRUE; + b2_hff_rb_last->rollback = true; b2_hff_update_x(b2_hff_rb_last, pos_ned->x, Rgps_pos); b2_hff_update_y(b2_hff_rb_last, pos_ned->y, Rgps_pos); #if HFF_UPDATE_SPEED diff --git a/sw/airborne/subsystems/ins/ins_alt_float.c b/sw/airborne/subsystems/ins/ins_alt_float.c index 0725b7844d..e14b08c81e 100644 --- a/sw/airborne/subsystems/ins/ins_alt_float.c +++ b/sw/airborne/subsystems/ins/ins_alt_float.c @@ -102,11 +102,11 @@ void ins_alt_float_init(void) #if USE_INS_NAV_INIT struct UtmCoor_f utm0 = { nav_utm_north0, nav_utm_east0, ground_alt, nav_utm_zone0 }; stateSetLocalUtmOrigin_f(&utm0); - ins_altf.origin_initialized = TRUE; + ins_altf.origin_initialized = true; stateSetPositionUtm_f(&utm0); #else - ins_altf.origin_initialized = FALSE; + ins_altf.origin_initialized = false; #endif // set initial body to imu to 0 @@ -117,10 +117,10 @@ void ins_alt_float_init(void) #if USE_BAROMETER ins_altf.qfe = 0.0f; - ins_altf.baro_initialized = FALSE; + ins_altf.baro_initialized = false; ins_altf.baro_alt = 0.0f; #endif - ins_altf.reset_alt_ref = FALSE; + ins_altf.reset_alt_ref = false; // why do we have this here? alt_kalman(0.0f, 0.1); @@ -138,10 +138,10 @@ void ins_reset_local_origin(void) // reset state UTM ref stateSetLocalUtmOrigin_f(&utm); - ins_altf.origin_initialized = TRUE; + ins_altf.origin_initialized = true; // reset filter flag - ins_altf.reset_alt_ref = TRUE; + ins_altf.reset_alt_ref = true; } void ins_reset_altitude_ref(void) @@ -152,7 +152,7 @@ void ins_reset_altitude_ref(void) // reset state UTM ref stateSetLocalUtmOrigin_f(&utm); // reset filter flag - ins_altf.reset_alt_ref = TRUE; + ins_altf.reset_alt_ref = true; } #if USE_BAROMETER @@ -171,10 +171,10 @@ void ins_alt_float_update_baro(float pressure) if (!ins_altf.baro_initialized) { ins_altf.qfe = pressure; - ins_altf.baro_initialized = TRUE; + ins_altf.baro_initialized = true; } if (ins_altf.reset_alt_ref) { - ins_altf.reset_alt_ref = FALSE; + ins_altf.reset_alt_ref = false; ins_altf.alt = ground_alt; ins_altf.alt_dot = 0.0f; ins_altf.qfe = pressure; @@ -232,7 +232,7 @@ void ins_alt_float_update_gps(struct GpsState *gps_s) float falt = gps_s->hmsl / 1000.0f; if (ins_altf.reset_alt_ref) { - ins_altf.reset_alt_ref = FALSE; + ins_altf.reset_alt_ref = false; ins_altf.alt = falt; ins_altf.alt_dot = 0.0f; alt_kalman_reset(); diff --git a/sw/airborne/subsystems/ins/ins_float_invariant.c b/sw/airborne/subsystems/ins/ins_float_invariant.c index 870201f604..d2ac7ab269 100644 --- a/sw/airborne/subsystems/ins/ins_float_invariant.c +++ b/sw/airborne/subsystems/ins/ins_float_invariant.c @@ -55,7 +55,7 @@ #if LOG_INVARIANT_FILTER #include "sdLog.h" #include "subsystems/chibios-libopencm3/chibios_sdlog.h" -bool log_started = FALSE; +bool log_started = false; #endif /*------------- =*= Invariant Observers =*= -------------* @@ -182,8 +182,8 @@ static inline void init_invariant_state(void) ins_float_inv.meas.baro_alt = 0.0f; // init baro - ins_baro_initialized = FALSE; - ins_gps_fix_once = FALSE; + ins_baro_initialized = false; + ins_gps_fix_once = false; } #if SEND_INVARIANT_FILTER || PERIODIC_TELEMETRY @@ -261,8 +261,8 @@ void ins_float_invariant_init(void) ins_float_inv.gains.rh = INS_INV_RH; ins_float_inv.gains.sh = INS_INV_SH; - ins_float_inv.is_aligned = FALSE; - ins_float_inv.reset = FALSE; + ins_float_inv.is_aligned = false; + ins_float_inv.reset = false; #if PERIODIC_TELEMETRY register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_INV_FILTER, send_inv_filter); @@ -319,7 +319,7 @@ void ins_float_invariant_align(struct FloatRates *lp_gyro, stateSetNedToBodyQuat_f(&ins_float_inv.state.quat); // ins and ahrs are now running - ins_float_inv.is_aligned = TRUE; + ins_float_inv.is_aligned = true; } void ins_float_invariant_propagate(struct FloatRates* gyro, struct FloatVect3* accel, float dt) @@ -329,8 +329,8 @@ void ins_float_invariant_propagate(struct FloatRates* gyro, struct FloatVect3* a // realign all the filter if needed // a complete init cycle is required if (ins_float_inv.reset) { - ins_float_inv.reset = FALSE; - ins_float_inv.is_aligned = FALSE; + ins_float_inv.reset = false; + ins_float_inv.is_aligned = false; init_invariant_state(); } @@ -380,7 +380,7 @@ void ins_float_invariant_propagate(struct FloatRates* gyro, struct FloatVect3* a // log file header sdLogWriteLog(pprzLogFile, "p q r ax ay az gx gy gz gvx gvy gvz mx my mz b qi qx qy qz bp bq br vx vy vz px py pz hb as\n"); - log_started = TRUE; + log_started = true; } else { sdLogWriteLog(pprzLogFile, "%.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f %.3f\n", @@ -424,7 +424,7 @@ void ins_float_invariant_update_gps(struct GpsState *gps_s) { if (gps_s->fix >= GPS_FIX_3D && ins_float_inv.is_aligned) { - ins_gps_fix_once = TRUE; + ins_gps_fix_once = true; #if INS_FINV_USE_UTM if (state.utm_initialized_f) { @@ -473,11 +473,11 @@ void ins_float_invariant_update_baro(float pressure) // test stop condition if (fabs(alpha) < 0.005f) { ins_qfe = baro_moy; - ins_baro_initialized = TRUE; + ins_baro_initialized = true; } if (i == 250) { ins_qfe = pressure; - ins_baro_initialized = TRUE; + ins_baro_initialized = true; } i++; } else { /* normal update with baro measurement */ diff --git a/sw/airborne/subsystems/ins/ins_gps_passthrough.c b/sw/airborne/subsystems/ins/ins_gps_passthrough.c index 534e127ecb..8a24c76ebf 100644 --- a/sw/airborne/subsystems/ins/ins_gps_passthrough.c +++ b/sw/airborne/subsystems/ins/ins_gps_passthrough.c @@ -105,9 +105,9 @@ void ins_gps_passthrough_init(void) ins_gp.ltp_def.hmsl = NAV_ALT0; stateSetLocalOrigin_i(&ins_gp.ltp_def); - ins_gp.ltp_initialized = TRUE; + ins_gp.ltp_initialized = true; #else - ins_gp.ltp_initialized = FALSE; + ins_gp.ltp_initialized = false; #endif INT32_VECT3_ZERO(ins_gp.ltp_pos); @@ -127,7 +127,7 @@ void ins_reset_local_origin(void) ins_gp.ltp_def.lla.alt = gps.lla_pos.alt; ins_gp.ltp_def.hmsl = gps.hmsl; stateSetLocalOrigin_i(&ins_gp.ltp_def); - ins_gp.ltp_initialized = TRUE; + ins_gp.ltp_initialized = true; } void ins_reset_altitude_ref(void) diff --git a/sw/airborne/subsystems/ins/ins_int.c b/sw/airborne/subsystems/ins/ins_int.c index c9fc0b9c6b..49529ecbec 100644 --- a/sw/airborne/subsystems/ins/ins_int.c +++ b/sw/airborne/subsystems/ins/ins_int.c @@ -195,9 +195,9 @@ void ins_int_init(void) #if USE_INS_NAV_INIT ins_init_origin_from_flightplan(); - ins_int.ltp_initialized = TRUE; + ins_int.ltp_initialized = true; #else - ins_int.ltp_initialized = FALSE; + ins_int.ltp_initialized = false; #endif /* we haven't had any measurement updates yet, so set the counter to max */ @@ -205,7 +205,7 @@ void ins_int_init(void) // Bind to BARO_ABS message AbiBindMsgBARO_ABS(INS_BARO_ID, &baro_ev, baro_cb); - ins_int.baro_initialized = FALSE; + ins_int.baro_initialized = false; #if USE_SONAR ins_int.update_on_agl = INS_SONAR_UPDATE_ON_AGL; @@ -213,8 +213,8 @@ void ins_int_init(void) AbiBindMsgAGL(INS_SONAR_ID, &sonar_ev, sonar_cb); #endif - ins_int.vf_reset = FALSE; - ins_int.hf_realign = FALSE; + ins_int.vf_reset = false; + ins_int.hf_realign = false; /* init vertical and horizontal filters */ vff_init_zero(); @@ -240,19 +240,19 @@ void ins_reset_local_origin(void) ltp_def_from_ecef_i(&ins_int.ltp_def, &gps.ecef_pos); ins_int.ltp_def.lla.alt = gps.lla_pos.alt; ins_int.ltp_def.hmsl = gps.hmsl; - ins_int.ltp_initialized = TRUE; + ins_int.ltp_initialized = true; stateSetLocalOrigin_i(&ins_int.ltp_def); } else { - ins_int.ltp_initialized = FALSE; + ins_int.ltp_initialized = false; } #else - ins_int.ltp_initialized = FALSE; + ins_int.ltp_initialized = false; #endif #if USE_HFF - ins_int.hf_realign = TRUE; + ins_int.hf_realign = true; #endif - ins_int.vf_reset = TRUE; + ins_int.vf_reset = true; } void ins_reset_altitude_ref(void) @@ -267,7 +267,7 @@ void ins_reset_altitude_ref(void) ins_int.ltp_def.hmsl = gps.hmsl; stateSetLocalOrigin_i(&ins_int.ltp_def); #endif - ins_int.vf_reset = TRUE; + ins_int.vf_reset = true; } void ins_int_propagate(struct Int32Vect3 *accel, float dt) @@ -319,12 +319,12 @@ static void baro_cb(uint8_t __attribute__((unused)) sender_id, float pressure) if (!ins_int.baro_initialized && pressure > 1e-7) { // wait for a first positive value ins_int.qfe = pressure; - ins_int.baro_initialized = TRUE; + ins_int.baro_initialized = true; } if (ins_int.baro_initialized) { if (ins_int.vf_reset) { - ins_int.vf_reset = FALSE; + ins_int.vf_reset = false; ins_int.qfe = pressure; vff_realign(0.); ins_update_from_vff(); @@ -397,7 +397,7 @@ void ins_int_update_gps(struct GpsState *gps_s) VECT2_SDIV(gps_speed_m_s_ned, gps_speed_m_s_ned, 100.); if (ins_int.hf_realign) { - ins_int.hf_realign = FALSE; + ins_int.hf_realign = false; const struct FloatVect2 zero = {0.0f, 0.0f}; b2_hff_realign(gps_pos_m_ned, zero); } diff --git a/sw/airborne/subsystems/ins/ins_vectornav.c b/sw/airborne/subsystems/ins/ins_vectornav.c index e22211e5eb..dba77614bd 100644 --- a/sw/airborne/subsystems/ins/ins_vectornav.c +++ b/sw/airborne/subsystems/ins/ins_vectornav.c @@ -112,7 +112,7 @@ void ins_vectornav_event(void) // read message if (ins_vn.vn_packet.msg_available) { ins_vectornav_read_message(); - ins_vn.vn_packet.msg_available = FALSE; + ins_vn.vn_packet.msg_available = false; } } @@ -129,7 +129,7 @@ void ins_vectornav_init(void) // Initialize packet ins_vn.vn_packet.status = VNMsgSync; ins_vn.vn_packet.msg_idx = 0; - ins_vn.vn_packet.msg_available = FALSE; + ins_vn.vn_packet.msg_available = false; ins_vn.vn_packet.chksm_error = 0; ins_vn.vn_packet.hdr_error = 0; ins_vn.vn_packet.overrun_error = 0; @@ -146,9 +146,9 @@ void ins_vectornav_init(void) #if USE_INS_NAV_INIT ins_init_origin_from_flightplan(); - ins_vn.ltp_initialized = TRUE; + ins_vn.ltp_initialized = true; #else - ins_vn.ltp_initialized = FALSE; + ins_vn.ltp_initialized = false; #endif struct FloatEulers body_to_imu_eulers = diff --git a/sw/airborne/subsystems/intermcu/intermcu_ap.c b/sw/airborne/subsystems/intermcu/intermcu_ap.c index 678595428f..3ce6e576b8 100644 --- a/sw/airborne/subsystems/intermcu/intermcu_ap.c +++ b/sw/airborne/subsystems/intermcu/intermcu_ap.c @@ -120,7 +120,7 @@ static inline void intermcu_parse_msg(struct transport_rx *trans, void (*rc_fram } // Set to receive another message - trans->msg_received = FALSE; + trans->msg_received = false; } void RadioControlEvent(void (*frame_handler)(void)) diff --git a/sw/airborne/subsystems/intermcu/intermcu_fbw.c b/sw/airborne/subsystems/intermcu/intermcu_fbw.c index 7b32f62107..5c3654e2b2 100644 --- a/sw/airborne/subsystems/intermcu/intermcu_fbw.c +++ b/sw/airborne/subsystems/intermcu/intermcu_fbw.c @@ -37,8 +37,8 @@ #include "mcu_periph/sys_time.h" static uint8_t px4RebootSequence[] = {0x41, 0xd7, 0x32, 0x0a, 0x46, 0x39}; static uint8_t px4RebootSequenceCount = 0; -static bool px4RebootTimeout = FALSE; -uint8_t autopilot_motors_on = FALSE; +static bool px4RebootTimeout = false; +uint8_t autopilot_motors_on = false; tid_t px4bl_tid; ///< id for time out of the px4 bootloader reset #endif @@ -150,7 +150,7 @@ static void intermcu_parse_msg(struct transport_rx *trans, void (*commands_frame } // Set to receive another message - trans->msg_received = FALSE; + trans->msg_received = false; } void InterMcuEvent(void (*frame_handler)(void)) diff --git a/sw/airborne/subsystems/navigation/common_nav.h b/sw/airborne/subsystems/navigation/common_nav.h index 4d7895533c..3f78ba13b8 100644 --- a/sw/airborne/subsystems/navigation/common_nav.h +++ b/sw/airborne/subsystems/navigation/common_nav.h @@ -68,21 +68,21 @@ unit_t nav_update_waypoints_alt(void) __attribute__((unused)); void common_nav_periodic_task_4Hz(void); -#define NavSetGroundReferenceHere() ({ nav_reset_reference(); nav_update_waypoints_alt(); FALSE; }) +#define NavSetGroundReferenceHere() ({ nav_reset_reference(); nav_update_waypoints_alt(); false; }) -#define NavSetAltitudeReferenceHere() ({ nav_reset_alt(); nav_update_waypoints_alt(); FALSE; }) +#define NavSetAltitudeReferenceHere() ({ nav_reset_alt(); nav_update_waypoints_alt(); false; }) #define NavSetWaypointHere(_wp) ({ \ waypoints[_wp].x = stateGetPositionEnu_f()->x; \ waypoints[_wp].y = stateGetPositionEnu_f()->y; \ - FALSE; \ + false; \ }) #define NavSetWaypointPosAndAltHere(_wp) ({ \ waypoints[_wp].x = stateGetPositionEnu_f()->x; \ waypoints[_wp].y = stateGetPositionEnu_f()->y; \ waypoints[_wp].a = stateGetPositionEnu_f()->z + ground_alt; \ - FALSE; \ + false; \ }) #endif /* COMMON_NAV_H */ diff --git a/sw/airborne/subsystems/navigation/nav_survey_rectangle.c b/sw/airborne/subsystems/navigation/nav_survey_rectangle.c index c05c8cde6e..f6c62c1bc6 100644 --- a/sw/airborne/subsystems/navigation/nav_survey_rectangle.c +++ b/sw/airborne/subsystems/navigation/nav_survey_rectangle.c @@ -32,7 +32,7 @@ static struct point survey_from; static struct point survey_to; -static bool survey_uturn __attribute__((unused)) = FALSE; +static bool survey_uturn __attribute__((unused)) = false; static survey_orientation_t survey_orientation = NS; #define SurveyGoingNorth() ((survey_orientation == NS) && (survey_to.y > survey_from.y)) @@ -82,7 +82,7 @@ void nav_survey_rectangle_init(uint8_t wp1, uint8_t wp2, float grid, survey_orie } } nav_survey_shift = grid; - survey_uturn = FALSE; + survey_uturn = false; LINE_START_FUNCTION; } @@ -91,7 +91,7 @@ void nav_survey_rectangle(uint8_t wp1, uint8_t wp2) { static float survey_radius; - nav_survey_active = TRUE; + nav_survey_active = true; nav_survey_west = Min(WaypointX(wp1), WaypointX(wp2)); nav_survey_east = Max(WaypointX(wp1), WaypointX(wp2)); @@ -174,8 +174,8 @@ void nav_survey_rectangle(uint8_t wp1, uint8_t wp2) } } - nav_in_segment = FALSE; - survey_uturn = TRUE; + nav_in_segment = false; + survey_uturn = true; LINE_STOP_FUNCTION; } } else { /* U-turn */ @@ -184,8 +184,8 @@ void nav_survey_rectangle(uint8_t wp1, uint8_t wp2) (SurveyGoingEast() && NavCourseCloseTo(90)) || (SurveyGoingWest() && NavCourseCloseTo(270))) { /* U-turn finished, back on a segment */ - survey_uturn = FALSE; - nav_in_circle = FALSE; + survey_uturn = false; + nav_in_circle = false; LINE_START_FUNCTION; } else { NavCircleWaypoint(0, survey_radius); diff --git a/sw/airborne/subsystems/navigation/waypoints.c b/sw/airborne/subsystems/navigation/waypoints.c index 11a398f662..4bf4f627fa 100644 --- a/sw/airborne/subsystems/navigation/waypoints.c +++ b/sw/airborne/subsystems/navigation/waypoints.c @@ -57,7 +57,7 @@ bool waypoint_is_global(uint8_t wp_id) if (wp_id < nb_waypoint) { return bit_is_set(waypoints[wp_id].flags, WP_FLAG_GLOBAL); } - return FALSE; + return false; } void waypoint_set_global_flag(uint8_t wp_id) diff --git a/sw/airborne/subsystems/radio_control/ppm.c b/sw/airborne/subsystems/radio_control/ppm.c index 22b58e1e6b..255d16063e 100644 --- a/sw/airborne/subsystems/radio_control/ppm.c +++ b/sw/airborne/subsystems/radio_control/ppm.c @@ -65,10 +65,10 @@ static void send_ppm(struct transport_tx *trans, struct link_device *dev) void radio_control_impl_init(void) { - ppm_frame_available = FALSE; + ppm_frame_available = false; ppm_last_pulse_time = 0; ppm_cur_pulse = RADIO_CTL_NB; - ppm_data_valid = FALSE; + ppm_data_valid = false; ppm_arch_init(); @@ -89,7 +89,7 @@ void radio_control_impl_event(void (* _received_frame_handler)(void)) NormalizePpmIIR(ppm_pulses, radio_control); _received_frame_handler(); } - ppm_frame_available = FALSE; + ppm_frame_available = false; } } @@ -109,12 +109,12 @@ void ppm_decode_frame(uint32_t ppm_time) if (length > RC_PPM_TICKS_OF_USEC(PPM_SYNC_MIN_LEN) && length < RC_PPM_TICKS_OF_USEC(PPM_SYNC_MAX_LEN)) { if (ppm_data_valid && RssiValid()) { - ppm_frame_available = TRUE; - ppm_data_valid = FALSE; + ppm_frame_available = true; + ppm_data_valid = false; } ppm_cur_pulse = 0; } else { - ppm_data_valid = FALSE; + ppm_data_valid = false; } } else { if (length > RC_PPM_TICKS_OF_USEC(PPM_DATA_MIN_LEN) && @@ -122,11 +122,11 @@ void ppm_decode_frame(uint32_t ppm_time) ppm_pulses[ppm_cur_pulse] = length; ppm_cur_pulse++; if (ppm_cur_pulse == RADIO_CTL_NB) { - ppm_data_valid = TRUE; + ppm_data_valid = true; } } else { ppm_cur_pulse = RADIO_CTL_NB; - ppm_data_valid = FALSE; + ppm_data_valid = false; } } } diff --git a/sw/airborne/subsystems/radio_control/rc_datalink.c b/sw/airborne/subsystems/radio_control/rc_datalink.c index d059bbafa3..dbef64e21a 100644 --- a/sw/airborne/subsystems/radio_control/rc_datalink.c +++ b/sw/airborne/subsystems/radio_control/rc_datalink.c @@ -33,7 +33,7 @@ volatile bool rc_dl_frame_available; void radio_control_impl_init(void) { - rc_dl_frame_available = FALSE; + rc_dl_frame_available = false; } @@ -50,7 +50,7 @@ void parse_rc_3ch_datalink(uint8_t throttle_mode, rc_dl_values[RADIO_MODE] = (int8_t)mode; rc_dl_values[RADIO_YAW] = 0; - rc_dl_frame_available = TRUE; + rc_dl_frame_available = true; } void parse_rc_4ch_datalink( @@ -66,7 +66,7 @@ void parse_rc_4ch_datalink( rc_dl_values[RADIO_PITCH] = pitch; rc_dl_values[RADIO_YAW] = yaw; - rc_dl_frame_available = TRUE; + rc_dl_frame_available = true; } /** @@ -95,6 +95,6 @@ void radio_control_impl_event(void (* _received_frame_handler)(void)) radio_control.status = RC_OK; rc_datalink_normalize(rc_dl_values, radio_control.values); _received_frame_handler(); - rc_dl_frame_available = FALSE; + rc_dl_frame_available = false; } } diff --git a/sw/airborne/subsystems/radio_control/sbus.c b/sw/airborne/subsystems/radio_control/sbus.c index 991bca1cc5..a9dbb2663d 100644 --- a/sw/airborne/subsystems/radio_control/sbus.c +++ b/sw/airborne/subsystems/radio_control/sbus.c @@ -76,6 +76,6 @@ void radio_control_impl_event(void (* _received_frame_handler)(void)) NormalizePpmIIR(sbus.pulses, radio_control); _received_frame_handler(); } - sbus.frame_available = FALSE; + sbus.frame_available = false; } } diff --git a/sw/airborne/subsystems/radio_control/sbus_common.c b/sw/airborne/subsystems/radio_control/sbus_common.c index 929bee1670..d893982bf6 100644 --- a/sw/airborne/subsystems/radio_control/sbus_common.c +++ b/sw/airborne/subsystems/radio_control/sbus_common.c @@ -56,7 +56,7 @@ void sbus_common_init(struct Sbus *sbus_p, struct uart_periph *dev) { - sbus_p->frame_available = FALSE; + sbus_p->frame_available = false; sbus_p->status = SBUS_STATUS_UNINIT; // Set UART parameters (100K, 8 bits, 2 stops, even parity) diff --git a/sw/airborne/subsystems/radio_control/sbus_dual.c b/sw/airborne/subsystems/radio_control/sbus_dual.c index 5d5bc1ffe2..84320c0643 100644 --- a/sw/airborne/subsystems/radio_control/sbus_dual.c +++ b/sw/airborne/subsystems/radio_control/sbus_dual.c @@ -78,7 +78,7 @@ void radio_control_impl_event(void (* _received_frame_handler)(void)) NormalizePpmIIR(sbus2.pulses, radio_control); _received_frame_handler(); } - sbus2.frame_available = FALSE; + sbus2.frame_available = false; } if (sbus1.frame_available) { radio_control.frame_cpt++; @@ -90,6 +90,6 @@ void radio_control_impl_event(void (* _received_frame_handler)(void)) NormalizePpmIIR(sbus1.pulses, radio_control); _received_frame_handler(); } - sbus1.frame_available = FALSE; + sbus1.frame_available = false; } } diff --git a/sw/airborne/subsystems/radio_control/superbitrf_rc.c b/sw/airborne/subsystems/radio_control/superbitrf_rc.c index b8bb946e89..638db5efc0 100644 --- a/sw/airborne/subsystems/radio_control/superbitrf_rc.c +++ b/sw/airborne/subsystems/radio_control/superbitrf_rc.c @@ -67,6 +67,6 @@ void radio_control_impl_event(void (* _received_frame_handler)(void)) superbitrf_rc_normalize(superbitrf.rc_values, radio_control.values, superbitrf.num_channels); _received_frame_handler(); - superbitrf.rc_frame_available = FALSE; + superbitrf.rc_frame_available = false; } } diff --git a/sw/airborne/subsystems/sensors/infrared_i2c.c b/sw/airborne/subsystems/sensors/infrared_i2c.c index 09f253f586..ff6b29c5ef 100644 --- a/sw/airborne/subsystems/sensors/infrared_i2c.c +++ b/sw/airborne/subsystems/sensors/infrared_i2c.c @@ -86,12 +86,12 @@ void infrared_event(void) */ void infrared_i2c_init(void) { - ir_i2c_data_hor_available = FALSE; - ir_i2c_data_ver_available = FALSE; + ir_i2c_data_hor_available = false; + ir_i2c_data_ver_available = false; ir_i2c_hor_status = IR_I2C_IDLE; ir_i2c_conf_word = IR_I2C_DEFAULT_CONF; - ir_i2c_conf_hor_done = FALSE; - ir_i2c_conf_ver_done = FALSE; + ir_i2c_conf_hor_done = false; + ir_i2c_conf_ver_done = false; irh_trans.status = I2CTransDone; irv_trans.status = I2CTransDone; @@ -110,7 +110,7 @@ void infrared_i2c_update(void) } else { // Read next values i2c_receive(&i2c0, &irh_trans, IR_HOR_I2C_ADDR, 3); - ir_i2c_data_hor_available = FALSE; + ir_i2c_data_hor_available = false; ir_i2c_hor_status = IR_I2C_READ_IR1; } } @@ -122,7 +122,7 @@ void infrared_i2c_update(void) } else { // Read next values i2c_receive(&i2c0, &irv_trans, IR_VER_I2C_ADDR, 2); - ir_i2c_data_ver_available = FALSE; + ir_i2c_data_ver_available = false; } } #endif /* SITL || HITL */ @@ -166,11 +166,11 @@ void infrared_i2c_hor_event(void) ir2 = ir2 - (IR_I2C_IR2_NEUTRAL << ir_i2c_conf_word); ir_i2c.ir2 = FilterIR(ir_i2c.ir2, ir2); // Update estimator - ir_i2c_data_hor_available = TRUE; + ir_i2c_data_hor_available = true; #ifndef IR_I2C_READ_ONLY if (ir_i2c_data_ver_available) { - ir_i2c_data_hor_available = FALSE; - ir_i2c_data_ver_available = FALSE; + ir_i2c_data_hor_available = false; + ir_i2c_data_ver_available = false; UpdateIRValue(ir_i2c); } #endif @@ -185,7 +185,7 @@ void infrared_i2c_hor_event(void) break; case IR_I2C_CONFIGURE_HOR : // End conf cycle - ir_i2c_conf_hor_done = TRUE; + ir_i2c_conf_hor_done = true; ir_i2c_hor_status = IR_I2C_IDLE; break; } @@ -201,17 +201,17 @@ void infrared_i2c_ver_event(void) int16_t ir3 = (irv_trans.buf[0] << 8) | irv_trans.buf[1]; ir3 = ir3 - (IR_I2C_TOP_NEUTRAL << ir_i2c_conf_word); ir_i2c.ir3 = FilterIR(ir_i2c.ir3, ir3); - ir_i2c_data_ver_available = TRUE; + ir_i2c_data_ver_available = true; #ifndef IR_I2C_READ_ONLY if (ir_i2c_data_hor_available) { - ir_i2c_data_hor_available = FALSE; - ir_i2c_data_ver_available = FALSE; + ir_i2c_data_hor_available = false; + ir_i2c_data_ver_available = false; UpdateIRValue(ir_i2c); } #endif } if (irv_trans.type == I2CTransTx) { - ir_i2c_conf_ver_done = TRUE; + ir_i2c_conf_ver_done = true; } #endif /* !SITL && !HITL */ } diff --git a/sw/airborne/subsystems/sensors/infrared_i2c.h b/sw/airborne/subsystems/sensors/infrared_i2c.h index 214fc9cd29..92a9f237f1 100644 --- a/sw/airborne/subsystems/sensors/infrared_i2c.h +++ b/sw/airborne/subsystems/sensors/infrared_i2c.h @@ -52,8 +52,8 @@ extern void infrared_i2c_ver_event(void); #define infrared_i2cDownlink() DOWNLINK_SEND_DEBUG_IR_I2C(DefaultChannel, DefaultDevice, &ir_i2c.ir1, &ir_i2c.ir2, &ir_i2c.ir3) #define infrared_i2c_SetConfWord(_v) { \ - ir_i2c_conf_hor_done = FALSE; \ - ir_i2c_conf_ver_done = FALSE; \ + ir_i2c_conf_hor_done = false; \ + ir_i2c_conf_ver_done = false; \ ir_i2c_conf_word = _v; \ } diff --git a/sw/airborne/subsystems/settings.c b/sw/airborne/subsystems/settings.c index 3897b84ab3..00740bd3e3 100644 --- a/sw/airborne/subsystems/settings.c +++ b/sw/airborne/subsystems/settings.c @@ -62,12 +62,12 @@ int32_t settings_store(void) persistent_settings_store(); if (!persistent_write((void *)&pers_settings, sizeof(struct PersistentSettings))) { /* persistent write was successful */ - settings_store_flag = TRUE; + settings_store_flag = true; return 0; } } #endif - settings_store_flag = FALSE; + settings_store_flag = false; return -1; } @@ -80,11 +80,11 @@ int32_t settings_clear(void) if (settings_clear_flag) { if (!persistent_clear()) { /* clearing all persistent settings was successful */ - settings_clear_flag = TRUE; + settings_clear_flag = true; return 0; } } #endif - settings_clear_flag = FALSE; + settings_clear_flag = false; return -1; } diff --git a/sw/airborne/test/ahrs/ahrs_on_synth.c b/sw/airborne/test/ahrs/ahrs_on_synth.c index 6c2a77ee5f..5b8db8f1fc 100644 --- a/sw/airborne/test/ahrs/ahrs_on_synth.c +++ b/sw/airborne/test/ahrs/ahrs_on_synth.c @@ -215,11 +215,11 @@ void aos_compute_sensors(void) #ifdef AHRS_GRAVITY_UPDATE_COORDINATED_TURN #if AHRS_TYPE == AHRS_TYPE_FCQ || AHRS_TYPE == AHRS_TYPE_FLQ ahrs_impl.ltp_vel_norm = FLOAT_VECT3_NORM(aos.ltp_vel); - ahrs_impl.ltp_vel_norm_valid = TRUE; + ahrs_impl.ltp_vel_norm_valid = true; #endif #if AHRS_TYPE == AHRS_TYPE_FCR2 ahrs_impl.ltp_vel_norm = FLOAT_VECT3_NORM(aos.ltp_vel); - ahrs_impl.ltp_vel_norm_valid = TRUE; + ahrs_impl.ltp_vel_norm_valid = true; #endif #if AHRS_TYPE == AHRS_TYPE_FCR ahrs_impl.gps_speed = FLOAT_VECT3_NORM(aos.ltp_vel); @@ -229,7 +229,7 @@ void aos_compute_sensors(void) #endif #if AHRS_TYPE == AHRS_TYPE_ICQ ahrs_impl.ltp_vel_norm = SPEED_BFP_OF_REAL(FLOAT_VECT3_NORM(aos.ltp_vel)); - ahrs_impl.ltp_vel_norm_valid = TRUE; + ahrs_impl.ltp_vel_norm_valid = true; #endif #endif @@ -276,7 +276,7 @@ void aos_run(void) #if AHRS_TYPE == AHRS_TYPE_FCR ahrs_impl.gps_course = aos.heading_meas; - ahrs_impl.gps_course_valid = TRUE; + ahrs_impl.gps_course_valid = true; #else if (aos.time > 10) { if (!ahrs_impl.heading_aligned) { diff --git a/sw/airborne/test/ahrs/run_ahrs_on_synth.c b/sw/airborne/test/ahrs/run_ahrs_on_synth.c index 0ef81f3c17..62573fb9da 100644 --- a/sw/airborne/test/ahrs/run_ahrs_on_synth.c +++ b/sw/airborne/test/ahrs/run_ahrs_on_synth.c @@ -37,8 +37,8 @@ int main(int argc, char **argv) static void report(void) { - int output_sensors = FALSE; - int output_pos = FALSE; + int output_sensors = false; + int output_pos = false; printf("%f ", aos.time); diff --git a/sw/airborne/test/ahrs/run_ahrs_on_synth_ivy.c b/sw/airborne/test/ahrs/run_ahrs_on_synth_ivy.c index 9e21128ded..a12185cd9e 100644 --- a/sw/airborne/test/ahrs/run_ahrs_on_synth_ivy.c +++ b/sw/airborne/test/ahrs/run_ahrs_on_synth_ivy.c @@ -73,7 +73,7 @@ gboolean timeout_callback(gpointer data) DegOfRad(aos.gyro_bias.q), DegOfRad(aos.gyro_bias.r)); - return TRUE; + return true; } diff --git a/sw/airborne/test/peripherals/test_lis302dl_spi.c b/sw/airborne/test/peripherals/test_lis302dl_spi.c index a87f2c2ee2..22c2418b63 100644 --- a/sw/airborne/test/peripherals/test_lis302dl_spi.c +++ b/sw/airborne/test/peripherals/test_lis302dl_spi.c @@ -98,7 +98,7 @@ static inline void main_event_task(void) if (lis302.data_available) { struct Int32Vect3 accel; VECT3_COPY(accel, lis302.data.vect); - lis302.data_available = FALSE; + lis302.data_available = false; RunOnceEvery(10, { DOWNLINK_SEND_IMU_ACCEL_RAW(DefaultChannel, DefaultDevice, diff --git a/sw/airborne/test/test_manual.c b/sw/airborne/test/test_manual.c index 6d43a9f3ba..e241d6a8d3 100644 --- a/sw/airborne/test/test_manual.c +++ b/sw/airborne/test/test_manual.c @@ -91,7 +91,7 @@ static inline void main_init(void) // just to make it usable in a standard rotorcraft airframe file // with // in the command_laws section - autopilot_motors_on = TRUE; + autopilot_motors_on = true; } static inline void main_periodic(void)