diff --git a/conf/HB/hb_conf_speedy_opticflow.xml b/conf/HB/hb_conf_speedy_opticflow.xml
deleted file mode 100644
index 030ac1611b..0000000000
--- a/conf/HB/hb_conf_speedy_opticflow.xml
+++ /dev/null
@@ -1,13 +0,0 @@
-
-
-
diff --git a/conf/HB/hb_control_panel_speedy_opticflow.xml b/conf/HB/hb_control_panel_speedy_opticflow.xml
deleted file mode 100644
index c3150d8b66..0000000000
--- a/conf/HB/hb_control_panel_speedy_opticflow.xml
+++ /dev/null
@@ -1,248 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/conf/airframes/CDW/cdw_classix.xml b/conf/airframes/CDW/cdw_classix.xml
index a3fb9fd86a..e107c0fdad 100644
--- a/conf/airframes/CDW/cdw_classix.xml
+++ b/conf/airframes/CDW/cdw_classix.xml
@@ -216,9 +216,9 @@
-
-
-
+
+
+
diff --git a/conf/airframes/CDW/cdw_twoseastwenty.xml b/conf/airframes/CDW/cdw_twoseastwenty.xml
index e6bc58c9d3..333d4e24f1 100644
--- a/conf/airframes/CDW/cdw_twoseastwenty.xml
+++ b/conf/airframes/CDW/cdw_twoseastwenty.xml
@@ -36,10 +36,10 @@
-
-
-
-
+
+
+
+
@@ -70,10 +70,10 @@
-
-
-
-
+
+
+
+
diff --git a/conf/airframes/CDW/cdw_yapa_xsens.xml b/conf/airframes/CDW/cdw_yapa_xsens.xml
index e34c994ff9..9253102bb7 100644
--- a/conf/airframes/CDW/cdw_yapa_xsens.xml
+++ b/conf/airframes/CDW/cdw_yapa_xsens.xml
@@ -25,10 +25,10 @@
-
-
-
-
+
+
+
+
diff --git a/conf/airframes/FLIXR/flixr_lisa_mx.xml b/conf/airframes/FLIXR/flixr_lisa_mx.xml
index 8b43115b0f..7f838f559e 100644
--- a/conf/airframes/FLIXR/flixr_lisa_mx.xml
+++ b/conf/airframes/FLIXR/flixr_lisa_mx.xml
@@ -96,6 +96,7 @@
+
diff --git a/conf/airframes/HB/hb_ardrone2_opticflowtest.xml b/conf/airframes/HB/hb_ardrone2_opticflowtest.xml
deleted file mode 100644
index 9cc875028c..0000000000
--- a/conf/airframes/HB/hb_ardrone2_opticflowtest.xml
+++ /dev/null
@@ -1,218 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/conf/airframes/TUDELFT/tudelft_heli450.xml b/conf/airframes/TUDELFT/tudelft_heli450.xml
index ecd2f554d6..b9ef473ed0 100644
--- a/conf/airframes/TUDELFT/tudelft_heli450.xml
+++ b/conf/airframes/TUDELFT/tudelft_heli450.xml
@@ -37,10 +37,10 @@
-
-
-
-
+
+
+
+
@@ -61,7 +61,7 @@
-
+
@@ -71,9 +71,9 @@
-
-
-
+
+
+
diff --git a/conf/airframes/examples/microjet.xml b/conf/airframes/examples/microjet.xml
index c26ab5689c..314594c7d6 100644
--- a/conf/airframes/examples/microjet.xml
+++ b/conf/airframes/examples/microjet.xml
@@ -180,7 +180,7 @@
-
+
diff --git a/conf/airframes/examples/microjet_imu_xsens.xml b/conf/airframes/examples/microjet_imu_xsens.xml
index 1ab3a1316b..92d91d3b86 100644
--- a/conf/airframes/examples/microjet_imu_xsens.xml
+++ b/conf/airframes/examples/microjet_imu_xsens.xml
@@ -21,10 +21,10 @@
-
-
-
-
+
+
+
+
diff --git a/conf/airframes/examples/microjet_lisa_m_xsens.xml b/conf/airframes/examples/microjet_lisa_m_xsens.xml
index ee9ddd2269..7278c17917 100644
--- a/conf/airframes/examples/microjet_lisa_m_xsens.xml
+++ b/conf/airframes/examples/microjet_lisa_m_xsens.xml
@@ -21,10 +21,10 @@
-
-
-
-
+
+
+
+
diff --git a/conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile b/conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile
index c7fd2abd9e..9942dfdb66 100644
--- a/conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile
+++ b/conf/firmwares/subsystems/fixedwing/gps_ublox_utm.makefile
@@ -1,3 +1 @@
-include $(CFG_SHARED)/gps_ublox.makefile
-
-$(info Please replace with )
+$(error Please replace with )
diff --git a/conf/firmwares/subsystems/fixedwing/imu_xsens.makefile b/conf/firmwares/subsystems/fixedwing/imu_xsens.makefile
index b18ab3bd5f..67d4ac948e 100644
--- a/conf/firmwares/subsystems/fixedwing/imu_xsens.makefile
+++ b/conf/firmwares/subsystems/fixedwing/imu_xsens.makefile
@@ -1,68 +1 @@
-# Hey Emacs, this is a -*- makefile -*-
-
-# XSens Mti just providing IMU measurements
-
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-#
-
-
-#########################################
-## IMU
-
-ap.CFLAGS += -DUSE_IMU
-ap.CFLAGS += -DIMU_TYPE_H=\"modules/ins/ins_xsens.h\"
-ap.srcs += $(SRC_MODULES)/ins/ins_xsens.c
-ap.srcs += $(SRC_SUBSYSTEMS)/imu.c
-
-ifndef XSENS_UART_BAUD
- XSENS_UART_BAUD = B115200
-endif
-
-ap.CFLAGS += -DUSE_UART$(XSENS_UART_NR)
-ap.CFLAGS += -DINS_LINK=uart$(XSENS_UART_NR)
-ap.CFLAGS += -DUART$(XSENS_UART_NR)_BAUD=$(XSENS_UART_BAUD)
-ap.CFLAGS += -DXSENS_OUTPUT_MODE=0x1836
+$(error Error: The imu xsens subsystem has been converted to a module, replace by )
diff --git a/conf/firmwares/subsystems/fixedwing/ins_xsens.makefile b/conf/firmwares/subsystems/fixedwing/ins_xsens.makefile
index c243ad9f96..038ff5b548 100644
--- a/conf/firmwares/subsystems/fixedwing/ins_xsens.makefile
+++ b/conf/firmwares/subsystems/fixedwing/ins_xsens.makefile
@@ -1,70 +1 @@
-# Hey Emacs, this is a -*- makefile -*-
-
-# XSens Mti-G
-
-#
-#
-#
-#
-
-
-
-#########################################
-## ATTITUDE
-
-ap.CFLAGS += -DUSE_INS_MODULE
-
-# AHRS Results
-ap.CFLAGS += -DINS_TYPE_H=\"modules/ins/ins_xsens.h\"
-
-ifndef XSENS_UART_BAUD
- XSENS_UART_BAUD = B115200
-endif
-
-#B230400
-#B115200
-
-ap.CFLAGS += -DUSE_UART$(XSENS_UART_NR)
-ap.CFLAGS += -DINS_LINK=uart$(XSENS_UART_NR)
-ap.CFLAGS += -DUART$(XSENS_UART_NR)_BAUD=$(XSENS_UART_BAUD)
-ap.CFLAGS += -DXSENS_OUTPUT_MODE=0x1836
-ap.srcs += $(SRC_SUBSYSTEMS)/ins.c
-ap.srcs += $(SRC_MODULES)/ins/ins_xsens.c
-ap.CFLAGS += -DAHRS_TRIGGERED_ATTITUDE_LOOP
-
-
-
-#########################################
-## GPS
-
-ap.CFLAGS += -DUSE_GPS_XSENS
-ap.CFLAGS += -DUSE_GPS_XSENS_RAW_DATA
-ap.CFLAGS += -DGPS_NB_CHANNELS=16
-ap.CFLAGS += -DUSE_GPS
-ap.CFLAGS += -DGPS_TYPE_H=\"modules/ins/ins_xsens.h\"
-ap.srcs += $(SRC_SUBSYSTEMS)/gps.c
-
-
-#########################################
-## Simulator
-SIM_TARGETS = sim nps
-
-ifneq (,$(findstring $(TARGET),$(SIM_TARGETS)))
-
-$(TARGET).CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\"
-$(TARGET).CFLAGS += -DUSE_AHRS
-
-$(TARGET).srcs += $(SRC_SUBSYSTEMS)/ahrs.c
-$(TARGET).srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_sim.c
-
-$(TARGET).srcs += $(SRC_SUBSYSTEMS)/ins.c
-$(TARGET).CFLAGS += -DINS_TYPE_H=\"subsystems/ins/ins_gps_passthrough_utm.h\"
-$(TARGET).srcs += $(SRC_SUBSYSTEMS)/ins/ins_gps_passthrough_utm.c
-
-$(TARGET).CFLAGS += -DUSE_GPS
-$(TARGET).CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\"
-$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c
-$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps.c
-
-endif
-
+$(error Error: The ins xsens subsystem has been converted to a module, replace by )
diff --git a/conf/firmwares/subsystems/shared/ins_xsens700.makefile b/conf/firmwares/subsystems/shared/ins_xsens700.makefile
index 58be4d9d3f..bf4eb71b37 100644
--- a/conf/firmwares/subsystems/shared/ins_xsens700.makefile
+++ b/conf/firmwares/subsystems/shared/ins_xsens700.makefile
@@ -1,64 +1 @@
-# Hey Emacs, this is a -*- makefile -*-
-
-# XSens Mti-G
-
-#
-#
-#
-#
-
-
-#########################################
-## ATTITUDE
-
-ap.CFLAGS += -DUSE_INS_MODULE
-
-# AHRS Results
-ap.CFLAGS += -DINS_TYPE_H=\"modules/ins/ins_xsens.h\"
-
-ifndef XSENS_UART_BAUD
- XSENS_UART_BAUD = B115200
-endif
-
-ap.CFLAGS += -DUSE_UART$(XSENS_UART_NR)
-ap.CFLAGS += -DINS_LINK=uart$(XSENS_UART_NR)
-ap.CFLAGS += -DUART$(XSENS_UART_NR)_BAUD=$(XSENS_UART_BAUD)
-ap.CFLAGS += -DXSENS_OUTPUT_MODE=0x1836
-ap.srcs += $(SRC_SUBSYSTEMS)/ins.c
-ap.srcs += $(SRC_MODULES)/ins/ins_xsens700.c
-ap.CFLAGS += -DAHRS_TRIGGERED_ATTITUDE_LOOP
-
-
-#########################################
-## GPS
-
-ap.CFLAGS += -DUSE_GPS_XSENS
-ap.CFLAGS += -DGPS_NB_CHANNELS=50
-ap.CFLAGS += -DUSE_GPS
-ap.CFLAGS += -DGPS_TYPE_H=\"modules/ins/ins_xsens.h\"
-ap.srcs += $(SRC_SUBSYSTEMS)/gps.c
-
-
-#########################################
-## Simulator
-SIM_TARGETS = sim nps
-
-ifneq (,$(findstring $(TARGET),$(SIM_TARGETS)))
-
-$(TARGET).CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\"
-$(TARGET).CFLAGS += -DUSE_AHRS
-
-$(TARGET).srcs += $(SRC_SUBSYSTEMS)/ahrs.c
-$(TARGET).srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_sim.c
-
-$(TARGET).srcs += $(SRC_SUBSYSTEMS)/ins.c
-$(TARGET).CFLAGS += -DINS_TYPE_H=\"subsystems/ins/ins_gps_passthrough_utm.h\"
-$(TARGET).srcs += $(SRC_SUBSYSTEMS)/ins/ins_gps_passthrough_utm.c
-
-$(TARGET).CFLAGS += -DUSE_GPS
-$(TARGET).CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\"
-$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c
-$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps.c
-
-endif
-
+$(error Error: The ins xsens700 subsystem has been converted to a module, replace by )
diff --git a/conf/flight_plans/HB/hb_cyberzoo.xml b/conf/flight_plans/HB/hb_cyberzoo.xml
deleted file mode 100644
index 9490062a65..0000000000
--- a/conf/flight_plans/HB/hb_cyberzoo.xml
+++ /dev/null
@@ -1,123 +0,0 @@
-
-
-
-
-#include "autopilot.h"
-#include "subsystems/ahrs.h"
-#include "subsystems/electrical.h"
-#include "subsystems/datalink/datalink.h"
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/conf/flight_plans/rotorcraft_basic.xml b/conf/flight_plans/rotorcraft_basic.xml
index 6adc56ef56..34c4cd72e5 100644
--- a/conf/flight_plans/rotorcraft_basic.xml
+++ b/conf/flight_plans/rotorcraft_basic.xml
@@ -61,6 +61,9 @@
+
+
+
diff --git a/conf/flight_plans/rotorcraft_optitrack.xml b/conf/flight_plans/rotorcraft_optitrack.xml
index 6e22f60c05..1d3261047d 100644
--- a/conf/flight_plans/rotorcraft_optitrack.xml
+++ b/conf/flight_plans/rotorcraft_optitrack.xml
@@ -74,6 +74,9 @@
+
+
+
diff --git a/conf/modules/gps_i2c.xml b/conf/modules/gps_i2c.xml
deleted file mode 100644
index 5db107fc91..0000000000
--- a/conf/modules/gps_i2c.xml
+++ /dev/null
@@ -1,21 +0,0 @@
-
-
-
-
-
- U-blox GPS (I2C)
- (apparently currently broken)
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/conf/modules/gps_ubx_i2c.xml b/conf/modules/gps_ubx_i2c.xml
new file mode 100644
index 0000000000..ab1e733f3c
--- /dev/null
+++ b/conf/modules/gps_ubx_i2c.xml
@@ -0,0 +1,30 @@
+
+
+
+
+
+ U-blox GPS (I2C)
+
+
+
+
+ gps_ublox
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/conf/modules/imu_xsens.xml b/conf/modules/imu_xsens.xml
new file mode 100644
index 0000000000..8e464f0d13
--- /dev/null
+++ b/conf/modules/imu_xsens.xml
@@ -0,0 +1,49 @@
+
+
+
+
+
+ XSens IMU
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ ap.CFLAGS += -DIMU_TYPE_H=\"modules/ins/imu_xsens.h\"
+
+
+
+
+
+
+
+
+ sim.CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\"
+
+
+
+
+
+
+
+ nps.CFLAGS += -DIMU_TYPE_H=\"subsystems/imu/imu_nps.h\"
+
+
+
+
diff --git a/conf/modules/ins_xsens.xml b/conf/modules/ins_xsens.xml
index 6ec0d450ef..4c93bdcfa8 100644
--- a/conf/modules/ins_xsens.xml
+++ b/conf/modules/ins_xsens.xml
@@ -1,16 +1,77 @@
-
+
- XSens
+
+ XSens Mti-G INS
+
+
+
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ ap.CFLAGS += -DGPS_TYPE_H=\"modules/ins/ins_xsens.h\"
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ sim.CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\"
+ sim.CFLAGS += -DINS_TYPE_H=\"subsystems/ins/ins_gps_passthrough_utm.h\"
+ sim.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\"
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ nps.CFLAGS += -DINS_TYPE_H=\"subsystems/ins/ins_gps_passthrough_utm.h\"
+ nps.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim_nps.h\"
+
diff --git a/conf/modules/ins_xsens700.xml b/conf/modules/ins_xsens700.xml
new file mode 100644
index 0000000000..4247003015
--- /dev/null
+++ b/conf/modules/ins_xsens700.xml
@@ -0,0 +1,76 @@
+
+
+
+
+
+ XSens Mti-G 700 INS
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ ap.CFLAGS += -DGPS_TYPE_H=\"modules/ins/ins_xsens700.h\"
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ sim.CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\"
+ sim.CFLAGS += -DINS_TYPE_H=\"subsystems/ins/ins_gps_passthrough_utm.h\"
+ sim.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\"
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ nps.CFLAGS += -DINS_TYPE_H=\"subsystems/ins/ins_gps_passthrough_utm.h\"
+ nps.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim_nps.h\"
+
+
+
+
diff --git a/conf/modules/ins_xsens_MTiG_Uart0.xml b/conf/modules/ins_xsens_MTiG_Uart0.xml
deleted file mode 100644
index 0438e3776a..0000000000
--- a/conf/modules/ins_xsens_MTiG_Uart0.xml
+++ /dev/null
@@ -1,26 +0,0 @@
-
-
-
-
- XSens MTiG
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/conf/modules/ins_xsens_MTi_Uart0.xml b/conf/modules/ins_xsens_MTi_Uart0.xml
deleted file mode 100644
index 8bcb60694c..0000000000
--- a/conf/modules/ins_xsens_MTi_Uart0.xml
+++ /dev/null
@@ -1,24 +0,0 @@
-
-
-
-
- XSens MTi
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/conf/modules/usb_serial_stm32_example1.xml b/conf/modules/usb_serial_stm32_example1.xml
index 463e29677b..2c7dd7fe8f 100644
--- a/conf/modules/usb_serial_stm32_example1.xml
+++ b/conf/modules/usb_serial_stm32_example1.xml
@@ -17,10 +17,8 @@
-
-
- ap.srcs += $(SRC_ARCH)/usb_ser_hw.c
-
+
+
diff --git a/conf/modules/usb_serial_stm32_example2.xml b/conf/modules/usb_serial_stm32_example2.xml
index c92642f4e9..df0a3b4276 100644
--- a/conf/modules/usb_serial_stm32_example2.xml
+++ b/conf/modules/usb_serial_stm32_example2.xml
@@ -1,17 +1,17 @@
-
+
-
+
-
- STM32 USB-serial example.
- Example of USB-serial module on STM32 architecture, using libopencm3 library.
- This example tests the capability of USB-serial port by sending a lots of data.
- To be used with Lisa M/MX 2.1
-
+
+ STM32 USB-serial example.
+ Example of USB-serial module on STM32 architecture, using libopencm3 library.
+ This example tests the capability of USB-serial port by sending a lots of data.
+ To be used with Lisa M/MX 2.1
+
@@ -20,11 +20,9 @@
-
-
- ap.srcs += $(SRC_ARCH)/usb_ser_hw.c
-
-
-
+
+
+
+
-
+
diff --git a/sw/airborne/arch/linux/mcu_periph/i2c_arch.c b/sw/airborne/arch/linux/mcu_periph/i2c_arch.c
index 46617bb147..4fcf70e470 100644
--- a/sw/airborne/arch/linux/mcu_periph/i2c_arch.c
+++ b/sw/airborne/arch/linux/mcu_periph/i2c_arch.c
@@ -42,14 +42,14 @@ void i2c_setbitrate(struct i2c_periph *p __attribute__((unused)), int bitrate _
{
}
-bool_t i2c_idle(struct i2c_periph *p __attribute__((unused)))
+bool i2c_idle(struct i2c_periph *p __attribute__((unused)))
{
- return TRUE;
+ return true;
}
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wcast-qual"
-bool_t i2c_submit(struct i2c_periph *p, struct i2c_transaction *t)
+bool i2c_submit(struct i2c_periph *p, struct i2c_transaction *t)
{
int file = (int)p->reg_addr;
@@ -68,7 +68,7 @@ bool_t 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_t 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_t 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_t 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 1fe3dd0927..a835b95bc1 100644
--- a/sw/airborne/arch/linux/mcu_periph/spi_arch.c
+++ b/sw/airborne/arch/linux/mcu_periph/spi_arch.c
@@ -45,7 +45,7 @@ void spi_init_slaves(void)
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wcast-qual"
-bool_t spi_submit(struct spi_periph *p, struct spi_transaction *t)
+bool spi_submit(struct spi_periph *p, struct spi_transaction *t)
{
int fd = (int)p->reg_addr;
@@ -89,7 +89,7 @@ bool_t 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_t spi_submit(struct spi_periph *p, struct spi_transaction *t)
}
t->status = SPITransSuccess;
- return TRUE;
+ return true;
}
#pragma GCC diagnostic pop
-bool_t spi_lock(struct spi_periph *p, uint8_t slave)
+bool spi_lock(struct spi_periph *p, uint8_t slave)
{
// not implemented
- return FALSE;
+ return false;
}
-bool_t spi_resume(struct spi_periph *p, uint8_t slave)
+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/linux/mcu_periph/udp_arch.c b/sw/airborne/arch/linux/mcu_periph/udp_arch.c
index 4308a0e493..d020bcbc3f 100644
--- a/sw/airborne/arch/linux/mcu_periph/udp_arch.c
+++ b/sw/airborne/arch/linux/mcu_periph/udp_arch.c
@@ -66,7 +66,7 @@ void udp_arch_init(void)
* Initialize the UDP peripheral.
* Allocate UdpSocket struct and create and bind the UDP socket.
*/
-void udp_arch_periph_init(struct udp_periph *p, char *host, int port_out, int port_in, bool_t broadcast)
+void udp_arch_periph_init(struct udp_periph *p, char *host, int port_out, int port_in, bool broadcast)
{
struct UdpSocket *sock = malloc(sizeof(struct UdpSocket));
udp_socket_create(sock, host, port_out, port_in, broadcast);
diff --git a/sw/airborne/arch/linux/udp_socket.c b/sw/airborne/arch/linux/udp_socket.c
index 93b7b8c76b..ae61cdd3c0 100644
--- a/sw/airborne/arch/linux/udp_socket.c
+++ b/sw/airborne/arch/linux/udp_socket.c
@@ -46,7 +46,7 @@
* @param[in] broadcast if TRUE enable broadcasting
* @return -1 on error, otherwise 0
*/
-int udp_socket_create(struct UdpSocket *sock, char *host, int port_out, int port_in, bool_t broadcast)
+int udp_socket_create(struct UdpSocket *sock, char *host, int port_out, int port_in, bool broadcast)
{
if (sock == NULL) {
return -1;
diff --git a/sw/airborne/arch/linux/udp_socket.h b/sw/airborne/arch/linux/udp_socket.h
index 89bdbe62c9..2f26886985 100644
--- a/sw/airborne/arch/linux/udp_socket.h
+++ b/sw/airborne/arch/linux/udp_socket.h
@@ -46,7 +46,7 @@ struct UdpSocket {
* @param[in] broadcast if TRUE enable broadcasting
* @return -1 on error, otherwise 0
*/
-extern int udp_socket_create(struct UdpSocket *sock, char *host, int port_out, int port_in, bool_t broadcast);
+extern int udp_socket_create(struct UdpSocket *sock, char *host, int port_out, int port_in, bool broadcast);
/**
* Send a packet from buffer, blocking.
diff --git a/sw/airborne/arch/lpc21/ADS8344.c b/sw/airborne/arch/lpc21/ADS8344.c
index 685094a546..0953c73e3f 100644
--- a/sw/airborne/arch/lpc21/ADS8344.c
+++ b/sw/airborne/arch/lpc21/ADS8344.c
@@ -35,7 +35,7 @@
#define ADS8344Select() SetBit(ADS8344_SS_IOCLR,ADS8344_SS_PIN)
#define ADS8344Unselect() SetBit(ADS8344_SS_IOSET,ADS8344_SS_PIN)
-bool_t ADS8344_available;
+bool ADS8344_available;
uint16_t ADS8344_values[NB_CHANNELS];
#define POWER_MODE (1 << 1 | 1)
@@ -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/ADS8344.h b/sw/airborne/arch/lpc21/ADS8344.h
index 186b00802c..8e7131787f 100644
--- a/sw/airborne/arch/lpc21/ADS8344.h
+++ b/sw/airborne/arch/lpc21/ADS8344.h
@@ -28,7 +28,7 @@
#define NB_CHANNELS 8
extern uint16_t ADS8344_values[NB_CHANNELS];
-extern bool_t ADS8344_available;
+extern bool ADS8344_available;
void ADS8344_init(void);
void ADS8344_start(void);
diff --git a/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c b/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c
index 9940fc6e62..5e7d024814 100644
--- a/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c
+++ b/sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c
@@ -85,7 +85,7 @@ __attribute__((always_inline)) static inline void I2cSendByte(void *reg, uint8_t
((i2cRegs_t *)reg)->dat = b;
}
-__attribute__((always_inline)) static inline void I2cReceive(void *reg, bool_t ack)
+__attribute__((always_inline)) static inline void I2cReceive(void *reg, bool ack)
{
if (ack) { ((i2cRegs_t *)reg)->conset = _BV(AA); }
else { ((i2cRegs_t *)reg)->conclr = _BV(AAC); }
@@ -341,12 +341,12 @@ void i2c1_hw_init(void)
#endif /* USE_I2C1 */
-bool_t i2c_idle(struct i2c_periph *p)
+bool i2c_idle(struct i2c_periph *p)
{
return p->status == I2CIdle;
}
-bool_t i2c_submit(struct i2c_periph *p, struct i2c_transaction *t)
+bool i2c_submit(struct i2c_periph *p, struct i2c_transaction *t)
{
uint8_t idx;
@@ -356,7 +356,7 @@ bool_t 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_t 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 548e588a9a..ad76c5433d 100644
--- a/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c
+++ b/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c
@@ -490,7 +490,7 @@ void spi1_arch_init(void)
#endif
-bool_t spi_submit(struct spi_periph *p, struct spi_transaction *t)
+bool spi_submit(struct spi_periph *p, struct spi_transaction *t)
{
//unsigned cpsr;
@@ -499,7 +499,7 @@ bool_t 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_t spi_submit(struct spi_periph *p, struct spi_transaction *t)
//VICIntEnable = VIC_BIT(*vic);
//restoreIRQ(cpsr); // restore global interrupts
enableIRQ();
- return TRUE;
+ return true;
}
@@ -560,20 +560,20 @@ void spi_slave_unselect(uint8_t slave)
SpiSlaveUnselect(slave);
}
-bool_t spi_lock(struct spi_periph *p, uint8_t slave)
+bool spi_lock(struct spi_periph *p, uint8_t slave)
{
uint8_t *vic = (uint8_t *)(p->init_struct);
VICIntEnClear = VIC_BIT(*vic);
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_t spi_resume(struct spi_periph *p, uint8_t slave)
+bool spi_resume(struct spi_periph *p, uint8_t slave)
{
uint8_t *vic = (uint8_t *)(p->init_struct);
VICIntEnClear = VIC_BIT(*vic);
@@ -584,10 +584,10 @@ bool_t 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 */
@@ -676,12 +676,12 @@ void spi1_slave_arch_init(void)
#endif
/** Register one (and only one) transaction to use spi as slave */
-bool_t spi_slave_register(struct spi_periph *p, struct spi_transaction *t)
+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_t spi_slave_register(struct spi_periph *p, struct spi_transaction *t)
SpiSetDataSize(p, t->dss);
- return TRUE;
+ return true;
}
-bool_t spi_slave_wait(struct spi_periph *p)
+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 bd51061a9d..e0ede7b4ca 100644
--- a/sw/airborne/arch/lpc21/modules/sensors/trig_ext_hw.c
+++ b/sw/airborne/arch/lpc21/modules/sensors/trig_ext_hw.c
@@ -7,7 +7,7 @@
uint32_t trigger_t0;
uint32_t delta_t0;
-volatile bool_t trig_ext_valid;
+volatile bool trig_ext_valid;
void TRIG_ISR()
@@ -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/modules/sensors/trig_ext_hw.h b/sw/airborne/arch/lpc21/modules/sensors/trig_ext_hw.h
index 8a03f4935b..b06f0801c4 100644
--- a/sw/airborne/arch/lpc21/modules/sensors/trig_ext_hw.h
+++ b/sw/airborne/arch/lpc21/modules/sensors/trig_ext_hw.h
@@ -11,7 +11,7 @@
extern uint32_t trigger_t0;
extern uint32_t delta_t0;
-extern volatile bool_t trig_ext_valid;
+extern volatile bool trig_ext_valid;
void TRIG_ISR(void);
void trig_ext_init(void);
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/lpc21/subsystems/radio_control/spektrum_arch.c b/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.c
index d2d89cedc2..5a49f7303c 100644
--- a/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.c
+++ b/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.c
@@ -22,7 +22,7 @@
#include "subsystems/radio_control.h"
#include "subsystems/radio_control/spektrum_arch.h"
-bool_t rc_spk_parser_status;
+bool rc_spk_parser_status;
uint8_t rc_spk_parser_idx;
uint8_t rc_spk_parser_buf[RADIO_CONTROL_NB_CHANNEL * 2];
const int16_t rc_spk_throw[RADIO_CONTROL_NB_CHANNEL] = RC_SPK_THROWS;
diff --git a/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.h b/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.h
index 50601186ae..f3f9c7cf85 100644
--- a/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.h
+++ b/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.h
@@ -34,7 +34,7 @@
#define RC_SPK_STA_GOT_SYNC_1 1
#define RC_SPK_STA_GOT_SYNC_2 2
-extern bool_t rc_spk_parser_status;
+extern bool rc_spk_parser_status;
extern uint8_t rc_spk_parser_idx;
extern uint8_t rc_spk_parser_buf[RADIO_CONTROL_NB_CHANNEL * 2];
diff --git a/sw/airborne/arch/lpc21/usb_ser_hw.c b/sw/airborne/arch/lpc21/usb_ser_hw.c
index 973db68984..471fb7bfe4 100644
--- a/sw/airborne/arch/lpc21/usb_ser_hw.c
+++ b/sw/airborne/arch/lpc21/usb_ser_hw.c
@@ -406,7 +406,7 @@ int VCOM_getchar(void)
@returns TRUE if len bytes are free
*/
-bool_t VCOM_check_free_space(uint8_t len)
+bool VCOM_check_free_space(uint8_t len)
{
return (fifo_free(&txfifo) >= len ? TRUE : FALSE);
}
diff --git a/sw/airborne/arch/sim/baro_MS5534A.h b/sw/airborne/arch/sim/baro_MS5534A.h
index d4b5444316..50db3a05ed 100644
--- a/sw/airborne/arch/sim/baro_MS5534A.h
+++ b/sw/airborne/arch/sim/baro_MS5534A.h
@@ -34,11 +34,11 @@
#if USE_BARO_MS5534A
-extern bool_t spi_message_received;
-extern bool_t baro_MS5534A_available;
+extern bool spi_message_received;
+extern bool baro_MS5534A_available;
extern uint32_t baro_MS5534A_pressure;
extern uint16_t baro_MS5534A_temp;
-extern bool_t alt_baro_enabled;
+extern bool alt_baro_enabled;
extern uint32_t baro_MS5534A_ground_pressure;
extern float baro_MS5534A_r;
extern float baro_MS5534A_sigma2;
diff --git a/sw/airborne/arch/sim/mcu_periph/i2c_arch.c b/sw/airborne/arch/sim/mcu_periph/i2c_arch.c
index e84743c9aa..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_t i2c_idle(struct i2c_periph *p __attribute__((unused))) { return TRUE; }
-bool_t 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 bd5b72659f..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_t 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_t 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_t 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/modules/ins/ins_arduimu_basic.c b/sw/airborne/arch/sim/modules/ins/ins_arduimu_basic.c
index 010fd189f1..88d744b739 100644
--- a/sw/airborne/arch/sim/modules/ins/ins_arduimu_basic.c
+++ b/sw/airborne/arch/sim/modules/ins/ins_arduimu_basic.c
@@ -15,7 +15,7 @@ struct FloatVect3 arduimu_accel;
float ins_roll_neutral;
float ins_pitch_neutral;
-bool_t arduimu_calibrate_neutrals;
+bool arduimu_calibrate_neutrals;
// Updates from Ocaml sim
extern float sim_phi;
diff --git a/sw/airborne/arch/sim/sim_ap.c b/sw/airborne/arch/sim/sim_ap.c
index ad6e5a39f4..64b71d95e1 100644
--- a/sw/airborne/arch/sim/sim_ap.c
+++ b/sw/airborne/arch/sim/sim_ap.c
@@ -35,8 +35,8 @@
uint8_t ir_estim_mode;
uint8_t vertical_mode;
uint8_t inflight_calib_mode;
-bool_t rc_event_1, rc_event_2;
-bool_t launch;
+bool rc_event_1, rc_event_2;
+bool launch;
uint8_t gps_nb_ovrn, link_fbw_fbw_nb_err, link_fbw_nb_err;
float alt_roll_pgain;
float roll_rate_pgain;
@@ -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 805d54eb77..3480ecd2b3 100644
--- a/sw/airborne/arch/sim/subsystems/radio_control/spektrum_arch.c
+++ b/sw/airborne/arch/sim/subsystems/radio_control/spektrum_arch.c
@@ -37,13 +37,13 @@
#include
#endif
-static bool_t spektrum_available;
+static bool spektrum_available;
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; _cnt 20;
+ const bool shouldAccumulateValue = timeStampDiff > 20;
if (shouldAccumulateValue) {
adc_watchdog.timeStamp = get_sys_time_msec();
}
diff --git a/sw/airborne/arch/stm32/mcu_periph/gpio_arch.c b/sw/airborne/arch/stm32/mcu_periph/gpio_arch.c
index f05b23970d..dfe2cd8693 100644
--- a/sw/airborne/arch/stm32/mcu_periph/gpio_arch.c
+++ b/sw/airborne/arch/stm32/mcu_periph/gpio_arch.c
@@ -103,7 +103,7 @@ void gpio_setup_input_pulldown(uint32_t port, uint16_t gpios)
gpio_set_mode(port, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, gpios);
}
-void gpio_setup_pin_af(uint32_t port, uint16_t pin, uint32_t af, bool_t is_output)
+void gpio_setup_pin_af(uint32_t port, uint16_t pin, uint32_t af, bool is_output)
{
gpio_enable_clock(port);
/* remap alternate function if needed */
@@ -150,7 +150,7 @@ void gpio_setup_input_pulldown(uint32_t port, uint16_t gpios)
gpio_mode_setup(port, GPIO_MODE_INPUT, GPIO_PUPD_PULLDOWN, gpios);
}
-void gpio_setup_pin_af(uint32_t port, uint16_t pin, uint8_t af, bool_t is_output __attribute__((unused)))
+void gpio_setup_pin_af(uint32_t port, uint16_t pin, uint8_t af, bool is_output __attribute__((unused)))
{
gpio_enable_clock(port);
gpio_set_af(port, af, pin);
diff --git a/sw/airborne/arch/stm32/mcu_periph/gpio_arch.h b/sw/airborne/arch/stm32/mcu_periph/gpio_arch.h
index 35a9a9918f..ee8e7b48f2 100644
--- a/sw/airborne/arch/stm32/mcu_periph/gpio_arch.h
+++ b/sw/airborne/arch/stm32/mcu_periph/gpio_arch.h
@@ -66,9 +66,9 @@ extern void gpio_setup_input_pulldown(uint32_t port, uint16_t gpios);
* This is an STM32 specific helper funtion and should only be used in stm32 arch code.
*/
#if defined(STM32F1)
-extern void gpio_setup_pin_af(uint32_t port, uint16_t pin, uint32_t af, bool_t is_output);
+extern void gpio_setup_pin_af(uint32_t port, uint16_t pin, uint32_t af, bool is_output);
#else
-extern void gpio_setup_pin_af(uint32_t port, uint16_t pin, uint8_t af, bool_t is_output);
+extern void gpio_setup_pin_af(uint32_t port, uint16_t pin, uint8_t af, bool is_output);
#endif
/**
diff --git a/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c b/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c
index ef4b29b758..ce827d2da3 100644
--- a/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c
+++ b/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c
@@ -1283,9 +1283,9 @@ static inline void i2c_scl_toggle(uint32_t i2c)
#endif
}
-static inline bool_t i2c_sda_get(uint32_t i2c)
+static inline bool i2c_sda_get(uint32_t i2c)
{
- bool_t res = FALSE;
+ bool res = false;
#if USE_I2C1
if (i2c == I2C1) {
res = gpio_get(I2C1_GPIO_PORT, I2C1_GPIO_SDA);
@@ -1415,10 +1415,10 @@ void i2c_event(void)
/////////////////////////////////////////////////////////
// Implement Interface Functions
-bool_t i2c_submit(struct i2c_periph *periph, struct i2c_transaction *t)
+bool i2c_submit(struct i2c_periph *periph, struct i2c_transaction *t)
{
if (periph->watchdog > WD_DELAY) {
- return FALSE;
+ return false;
}
uint8_t temp;
@@ -1428,7 +1428,7 @@ bool_t 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,10 +1462,10 @@ bool_t 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_t i2c_idle(struct i2c_periph *periph)
+bool i2c_idle(struct i2c_periph *periph)
{
// This is actually a difficult function:
// -simply reading the status flags can clear bits and corrupt the transaction
@@ -1475,7 +1475,7 @@ bool_t 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_t 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 011ff21082..521a4e93da 100644
--- a/sw/airborne/arch/stm32/mcu_periph/spi_arch.c
+++ b/sw/airborne/arch/stm32/mcu_periph/spi_arch.c
@@ -97,9 +97,9 @@ struct spi_periph_dma {
uint8_t rx_nvic_irq; ///< receive interrupt
uint8_t tx_nvic_irq; ///< transmit interrupt
uint16_t tx_dummy_buf; ///< dummy tx buffer for receive only cases
- bool_t tx_extra_dummy_dma; ///< extra tx dummy dma flag for tx_len < rx_len
+ bool tx_extra_dummy_dma; ///< extra tx dummy dma flag for tx_len < rx_len
uint16_t rx_dummy_buf; ///< dummy rx buffer for receive only cases
- bool_t rx_extra_dummy_dma; ///< extra rx dummy dma flag for tx_len > rx_len
+ bool rx_extra_dummy_dma; ///< extra rx dummy dma flag for tx_len > rx_len
struct locm3_spi_comm comm; ///< current communication parameters
uint8_t comm_sig; ///< comm config signature used to check for changes
};
@@ -121,7 +121,7 @@ static struct spi_periph_dma spi3_dma;
static void spi_start_dma_transaction(struct spi_periph *periph, struct spi_transaction *_trans);
static void spi_next_transaction(struct spi_periph *periph);
static void spi_configure_dma(uint32_t dma, uint32_t rcc_dma, uint8_t chan, uint32_t periph_addr, uint32_t buf_addr,
- uint16_t len, enum SPIDataSizeSelect dss, bool_t increment);
+ uint16_t len, enum SPIDataSizeSelect dss, bool increment);
static void __attribute__((unused)) process_rx_dma_interrupt(struct spi_periph *periph);
static void __attribute__((unused)) process_tx_dma_interrupt(struct spi_periph *periph);
static void spi_arch_int_enable(struct spi_periph *spi);
@@ -260,14 +260,14 @@ void spi_init_slaves(void)
* Implementation of the generic SPI functions
*
*****************************************************************************/
-bool_t spi_submit(struct spi_periph *p, struct spi_transaction *t)
+bool spi_submit(struct spi_periph *p, struct spi_transaction *t)
{
uint8_t idx;
idx = p->trans_insert_idx + 1;
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,22 +287,22 @@ bool_t spi_submit(struct spi_periph *p, struct spi_transaction *t)
}
//FIXME
spi_arch_int_enable(p);
- return TRUE;
+ return true;
}
-bool_t spi_lock(struct spi_periph *p, uint8_t slave)
+bool spi_lock(struct spi_periph *p, uint8_t slave)
{
spi_arch_int_disable(p);
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_t spi_resume(struct spi_periph *p, uint8_t slave)
+bool spi_resume(struct spi_periph *p, uint8_t slave)
{
spi_arch_int_disable(p);
if (p->suspend == slave + 1) {
@@ -312,10 +312,10 @@ bool_t 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;
}
@@ -456,7 +456,7 @@ static void set_comm_from_transaction(struct locm3_spi_comm *c, struct spi_trans
*
*****************************************************************************/
static void spi_configure_dma(uint32_t dma, uint32_t rcc_dma, uint8_t chan, uint32_t periph_addr, uint32_t buf_addr,
- uint16_t len, enum SPIDataSizeSelect dss, bool_t increment)
+ uint16_t len, enum SPIDataSizeSelect dss, bool increment)
{
rcc_periph_clock_enable(rcc_dma);
#ifdef STM32F1
@@ -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);
@@ -1621,7 +1621,7 @@ static void spi_slave_set_config(struct spi_periph * periph, struct spi_transact
* Therefore, to ensure that the first byte of your data will be set, you have to set the transmit buffer before you call
* this function
*/
-bool_t spi_slave_register(struct spi_periph * periph, struct spi_transaction * trans) {
+bool spi_slave_register(struct spi_periph * periph, struct spi_transaction * trans) {
struct spi_periph_dma *dma = periph->init_struct;
/* Store local copy to notify of the results */
@@ -1687,7 +1687,7 @@ bool_t spi_slave_register(struct spi_periph * periph, struct spi_transaction * t
/* 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 861a942323..8a17599095 100644
--- a/sw/airborne/arch/stm32/mcu_periph/uart_arch.c
+++ b/sw/airborne/arch/stm32/mcu_periph/uart_arch.c
@@ -89,7 +89,7 @@ void uart_periph_set_bits_stop_parity(struct uart_periph *p, uint8_t bits, uint8
}
}
-void uart_periph_set_mode(struct uart_periph *p, bool_t tx_enabled, bool_t rx_enabled, bool_t hw_flow_control)
+void uart_periph_set_mode(struct uart_periph *p, bool tx_enabled, bool rx_enabled, bool hw_flow_control)
{
uint32_t mode = 0;
if (tx_enabled) {
@@ -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/subsystems/radio_control/spektrum_arch.c b/sw/airborne/arch/stm32/subsystems/radio_control/spektrum_arch.c
index 65fddebf4c..e016973889 100644
--- a/sw/airborne/arch/stm32/subsystems/radio_control/spektrum_arch.c
+++ b/sw/airborne/arch/stm32/subsystems/radio_control/spektrum_arch.c
@@ -324,7 +324,7 @@ void radio_control_impl_init(void)
*
*****************************************************************************/
-static inline void SpektrumParser(uint8_t _c, SpektrumStateType *spektrum_state, bool_t secondary_receiver)
+static inline void SpektrumParser(uint8_t _c, SpektrumStateType *spektrum_state, bool secondary_receiver)
{
@@ -530,6 +530,8 @@ void RadioControlEventImp(void (*frame_handler)(void))
*/
for (int i = 0; i < Min(RADIO_CONTROL_NB_CHANNEL, (MaxChannelNum + 1)); i++) {
radio_control.values[i] = SpektrumBuf[i];
+ //Only values between +-MAX_PPRZ are allowed
+ Bound(radio_control.values[i], -MAX_PPRZ, MAX_PPRZ);
if (i == RADIO_THROTTLE) {
radio_control.values[i] += MAX_PPRZ;
radio_control.values[i] /= 2;
diff --git a/sw/airborne/arch/stm32/usb_ser_hw.c b/sw/airborne/arch/stm32/usb_ser_hw.c
index 02b5d44fa0..c2c30d2e76 100644
--- a/sw/airborne/arch/stm32/usb_ser_hw.c
+++ b/sw/airborne/arch/stm32/usb_ser_hw.c
@@ -61,8 +61,8 @@ static fifo_t txfifo;
static fifo_t rxfifo;
void fifo_init(fifo_t *fifo, uint8_t *buf);
-bool_t fifo_put(fifo_t *fifo, uint8_t c);
-bool_t fifo_get(fifo_t *fifo, uint8_t *pc);
+bool fifo_put(fifo_t *fifo, uint8_t c);
+bool fifo_get(fifo_t *fifo, uint8_t *pc);
int fifo_avail(fifo_t *fifo);
int fifo_free(fifo_t *fifo);
int tx_timeout; // tmp work around for usbd_ep_stall_get from, this function does not always seem to work
@@ -286,12 +286,12 @@ static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep)
}
// store USB connection status
-static bool_t usb_connected;
+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);
}
@@ -326,7 +326,7 @@ void fifo_init(fifo_t *fifo, uint8_t *buf)
-bool_t fifo_put(fifo_t *fifo, uint8_t c)
+bool fifo_put(fifo_t *fifo, uint8_t c)
{
int next;
@@ -334,23 +334,23 @@ bool_t 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;
}
-bool_t fifo_get(fifo_t *fifo, uint8_t *pc)
+bool fifo_get(fifo_t *fifo, uint8_t *pc)
{
int next;
// 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_t fifo_get(fifo_t *fifo, uint8_t *pc)
*pc = fifo->buf[fifo->tail];
fifo->tail = next;
- return TRUE;
+ return true;
}
@@ -423,7 +423,7 @@ int VCOM_getchar(void)
* Checks if buffer free in VCOM buffer
* @returns TRUE if len bytes are free
*/
-bool_t VCOM_check_free_space(uint8_t len)
+bool VCOM_check_free_space(uint8_t len)
{
return (fifo_free(&txfifo) >= len ? TRUE : FALSE);
}
@@ -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 00d1368b86..4f751321f4 100644
--- a/sw/airborne/boards/apogee/baro_board.c
+++ b/sw/airborne/boards/apogee/baro_board.c
@@ -41,7 +41,7 @@
#include "sdLog.h"
#include "subsystems/chibios-libopencm3/chibios_sdlog.h"
#include "subsystems/gps.h"
-bool_t log_apogee_baro_started;
+bool log_apogee_baro_started;
#endif
@@ -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 760b3fc302..f202fbf86b 100644
--- a/sw/airborne/boards/apogee/chibios-libopencm3/board.c
+++ b/sw/airborne/boards/apogee/chibios-libopencm3/board.c
@@ -64,15 +64,15 @@ void __early_init(void) {
/**
*
*/
-bool_t sdc_lld_is_write_protected(SDCDriver *sdcp) {
+bool sdc_lld_is_write_protected(SDCDriver *sdcp) {
(void)sdcp;
- return FALSE;
+ return false;
}
/**
*
*/
-bool_t sdc_lld_is_card_inserted(SDCDriver *sdcp) {
+bool sdc_lld_is_card_inserted(SDCDriver *sdcp) {
(void)sdcp;
return !palReadPad(GPIOB, GPIOB_SDIO_DETECT);
}
@@ -86,21 +86,21 @@ bool_t sdc_lld_is_card_inserted(SDCDriver *sdcp) {
/**
* @brief MMC_SPI card detection.
*/
-bool_t mmc_lld_is_card_inserted(MMCDriver *mmcp) {
+bool mmc_lld_is_card_inserted(MMCDriver *mmcp) {
(void)mmcp;
/* TODO: Fill the implementation.*/
- return TRUE;
+ return true;
}
/**
* @brief MMC_SPI card write protection detection.
*/
-bool_t mmc_lld_is_write_protected(MMCDriver *mmcp) {
+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/chibios-libopencm3/chconf.h b/sw/airborne/boards/apogee/chibios-libopencm3/chconf.h
index e7929309ba..34158a3b85 100644
--- a/sw/airborne/boards/apogee/chibios-libopencm3/chconf.h
+++ b/sw/airborne/boards/apogee/chibios-libopencm3/chconf.h
@@ -511,7 +511,7 @@
#define SYSTEM_TICK_EVENT_HOOK() { \
/* System tick event code here.*/ \
void sys_tick_handler (void); \
- extern bool_t pprzReady; \
+ extern bool pprzReady; \
if (pprzReady == TRUE) sys_tick_handler (); \
}
#endif
diff --git a/sw/airborne/boards/apogee/imu_apogee.c b/sw/airborne/boards/apogee/imu_apogee.c
index 19b6fdfe1c..8ca65bac7e 100644
--- a/sw/airborne/boards/apogee/imu_apogee.c
+++ b/sw/airborne/boards/apogee/imu_apogee.c
@@ -81,10 +81,10 @@ PRINT_CONFIG_VAR(APOGEE_MAG_FREQ)
PRINT_CONFIG_VAR(MAG_PRESCALER)
// mag config will be done later in bypass mode
-bool_t configure_mag_slave(Mpu60x0ConfigSet mpu_set, void *mpu);
-bool_t configure_mag_slave(Mpu60x0ConfigSet mpu_set __attribute__((unused)), void *mpu __attribute__((unused)))
+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
@@ -92,10 +92,10 @@ bool_t configure_mag_slave(Mpu60x0ConfigSet mpu_set __attribute__((unused)), voi
struct ImuApogee imu_apogee;
// baro config will be done later in bypass mode
-bool_t configure_baro_slave(Mpu60x0ConfigSet mpu_set, void *mpu);
-bool_t configure_baro_slave(Mpu60x0ConfigSet mpu_set __attribute__((unused)), void *mpu __attribute__((unused)))
+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 3ce4531815..98e6bcd0ee 100644
--- a/sw/airborne/boards/ardrone/actuators.c
+++ b/sw/airborne/boards/ardrone/actuators.c
@@ -169,10 +169,10 @@ 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_t last_motor_on = FALSE;
+ static bool last_motor_on = false;
// Reset Flipflop sequence
- static bool_t reset_flipflop_counter = 0;
+ static bool reset_flipflop_counter = 0;
if (reset_flipflop_counter > 0) {
reset_flipflop_counter--;
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 ec816bad16..0f6eeadee2 100644
--- a/sw/airborne/boards/ardrone/navdata.c
+++ b/sw/airborne/boards/ardrone/navdata.c
@@ -51,7 +51,7 @@
/* Internal used functions */
static void *navdata_read(void *data __attribute__((unused)));
static void navdata_cmd_send(uint8_t cmd);
-static bool_t navdata_baro_calib(void);
+static bool navdata_baro_calib(void);
static void mag_freeze_check(void);
static void baro_update_logic(void);
@@ -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_t navdata_available = FALSE;
+static bool navdata_available = false;
/* syncronization variables */
static pthread_mutex_t navdata_mutex = PTHREAD_MUTEX_INITIALIZER;
@@ -168,7 +168,7 @@ static void send_navdata(struct transport_tx *trans, struct link_device *dev)
/**
* Initialize the navdata board
*/
-bool_t navdata_init()
+bool navdata_init()
{
assert(sizeof(struct navdata_measure_t) == NAVDATA_PACKET_SIZE);
@@ -178,7 +178,7 @@ bool_t 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_t 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_t 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_t 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_t 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);
@@ -413,7 +413,7 @@ static void navdata_cmd_send(uint8_t cmd)
/**
* Try to receive the baro calibration from the navdata board
*/
-static bool_t navdata_baro_calib(void)
+static bool navdata_baro_calib(void)
{
/* Start baro calibration acquisition */
navdata_cmd_send(NAVDATA_CMD_BARO_CALIB);
@@ -422,7 +422,7 @@ static bool_t 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_t 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/ardrone/navdata.h b/sw/airborne/boards/ardrone/navdata.h
index 6df78b6a2b..256ab7b20b 100644
--- a/sw/airborne/boards/ardrone/navdata.h
+++ b/sw/airborne/boards/ardrone/navdata.h
@@ -112,7 +112,7 @@ struct bmp180_calib_t {
/* Main navdata structure */
struct navdata_t {
- bool_t is_initialized; ///< Check if the navdata board is initialized
+ bool is_initialized; ///< Check if the navdata board is initialized
int fd; ///< The navdata file pointer
uint32_t totalBytesRead;
@@ -124,14 +124,14 @@ struct navdata_t {
struct navdata_measure_t measure; ///< Main navdata packet receieved from navboard
struct bmp180_calib_t bmp180_calib; ///< BMP180 calibration receieved from navboard
- bool_t baro_calibrated; ///< Whenever the baro is calibrated
- bool_t baro_available; ///< Whenever the baro is available
- bool_t imu_lost; ///< Whenever the imu is lost
+ bool baro_calibrated; ///< Whenever the baro is calibrated
+ bool baro_available; ///< Whenever the baro is available
+ bool imu_lost; ///< Whenever the imu is lost
};
extern struct navdata_t navdata;
-bool_t navdata_init(void);
+bool navdata_init(void);
void navdata_update(void);
int16_t navdata_height(void);
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/board.c b/sw/airborne/boards/bebop/board.c
index 432a53ed2c..cd5213e337 100644
--- a/sw/airborne/boards/bebop/board.c
+++ b/sw/airborne/boards/bebop/board.c
@@ -26,13 +26,65 @@
*/
#include
+#include
+#include
+#include
#include "video.h"
#include "mcu.h"
+int KillGracefully(char *process_name);
+
+int KillGracefully(char *process_name)
+ {
+ /* "pidof" always in /bin on Bebop firmware tested 1.98, 2.0.57, no need for "which" */
+ char pidof_commandline[200] = "/bin/pidof ";
+ strcat(pidof_commandline, process_name);
+ /* Bebop Busybox a
+ $ cat /proc/sys/kernel/pid_max
+ Gives max 32768, makes sure it never kills existing other process
+ */
+ char pid[7] = "";
+ int ret = 0; /* Return code of kill system call */
+ FILE *fp;
+
+ while (ret == 0) {
+ fp = popen(pidof_commandline, "r");
+ if (fp != NULL) { /* Could open the pidof with line */
+ if (fgets(pid, sizeof(pid) - 1, fp) != NULL) {
+ //printf("Process ID deducted: \"%s\"\n", pid);
+ if (atoi(pid) > 0) { /* To make sure we end 0 > There is a real process id found */
+ char kill_command_and_process[200] = "kill -9 "; /* BTW there is no pkill on this Busybox */
+ strcat(kill_command_and_process, pid);
+ ret = system(kill_command_and_process);
+ /* No need to wait, since if it is not closed the next pidof scan still will still find it and try to kill it */
+ }
+ } else {
+ ret = 256; /* Could not get handle */
+ pclose(fp);
+ }
+ } else {
+ ret = 256; /* fp NULL, so no process, just return */
+ return 0;
+ }
+ } /* end while */
+ return 0;
+}
void board_init(void)
{
- // First we try to kill the dragon-prog and its respawner if it is running
- int ret __attribute__((unused)) = system("killall -q -9 watchdog.sh; killall -q -9 dragon-prog");
+ /*
+ * Process running by default for firmware >= v1.98
+ *
+ * - /bin/sh - /usr/bin/DragonStarter.sh -out2null
+ * - //usr/bin/dragon-prog
+ *
+ * Thus two process to kill, the DragonStarter first
+ * This to make sure OEM program does not get re-started
+ *
+ */
+ int ret __attribute__((unused)) = system("killall -q -15 DragonStarter.sh");
+ usleep(50000); /* Give DragonStarter 50ms time to end on a busy system */
+ KillGracefully("dragon-prog");
+ (void) ret;
// We also try to initialize the video CMOS chips here (Bottom and front)
mt9v117_init();
diff --git a/sw/airborne/boards/bebop/video.c b/sw/airborne/boards/bebop/video.c
index 7940705445..04d8f19f15 100644
--- a/sw/airborne/boards/bebop/video.c
+++ b/sw/airborne/boards/bebop/video.c
@@ -59,18 +59,18 @@ struct video_config_t front_camera = {
.filters = VIDEO_FILTER_DEBAYER
};
-static bool_t write_reg(int fd, char *addr_val, uint8_t cnt)
+static bool write_reg(int fd, char *addr_val, uint8_t cnt)
{
char resp[cnt - 2];
uint8_t i;
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,15 +79,15 @@ static bool_t write_reg(int fd, char *addr_val, uint8_t cnt)
return write_reg(fd, addr_val, cnt);
}
}
- return TRUE;
+ return true;
}
-static bool_t _write(int fd, char *data, uint8_t cnt)
+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.h b/sw/airborne/boards/krooz/imu_krooz.h
index 88136fb680..ef06085db9 100644
--- a/sw/airborne/boards/krooz/imu_krooz.h
+++ b/sw/airborne/boards/krooz/imu_krooz.h
@@ -105,8 +105,8 @@
#endif
struct ImuKrooz {
- volatile bool_t mpu_eoc;
- volatile bool_t hmc_eoc;
+ volatile bool mpu_eoc;
+ volatile bool hmc_eoc;
struct Mpu60x0_I2c mpu;
struct Hmc58xx hmc;
struct Int32Rates rates_sum;
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/krooz/imu_krooz_memsic.h b/sw/airborne/boards/krooz/imu_krooz_memsic.h
index fc110b874d..f384639de7 100644
--- a/sw/airborne/boards/krooz/imu_krooz_memsic.h
+++ b/sw/airborne/boards/krooz/imu_krooz_memsic.h
@@ -108,8 +108,8 @@
#endif
struct ImuKrooz {
- volatile bool_t mpu_eoc;
- volatile bool_t hmc_eoc;
+ volatile bool mpu_eoc;
+ volatile bool hmc_eoc;
struct Mpu60x0_I2c mpu;
struct spi_transaction ad7689_trans;
volatile uint8_t ad7689_spi_tx_buffer[2];
diff --git a/sw/airborne/boards/lisa_l/baro_board.c b/sw/airborne/boards/lisa_l/baro_board.c
index 0722d18512..2c44511285 100644
--- a/sw/airborne/boards/lisa_l/baro_board.c
+++ b/sw/airborne/boards/lisa_l/baro_board.c
@@ -42,7 +42,7 @@ enum LisaBaroStatus {
struct BaroBoard {
enum LisaBaroStatus status;
- bool_t running;
+ bool running;
};
@@ -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 43b272e484..daf96d61df 100644
--- a/sw/airborne/boards/lisa_m/baro_board.c
+++ b/sw/airborne/boards/lisa_m/baro_board.c
@@ -36,7 +36,7 @@
struct Bmp085 baro_bmp085;
-static bool_t baro_eoc(void)
+static bool baro_eoc(void)
{
return gpio_get(GPIOB, GPIO0);
}
@@ -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 244a689502..6bcfc273e0 100644
--- a/sw/airborne/boards/lisa_mx/baro_board.c
+++ b/sw/airborne/boards/lisa_mx/baro_board.c
@@ -36,7 +36,7 @@
struct Bmp085 baro_bmp085;
-static bool_t baro_eoc(void)
+static bool baro_eoc(void)
{
return gpio_get(GPIOB, GPIO0);
}
@@ -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/boards/umarim/imu_umarim.h b/sw/airborne/boards/umarim/imu_umarim.h
index d3155d2ccf..13edc9a149 100644
--- a/sw/airborne/boards/umarim/imu_umarim.h
+++ b/sw/airborne/boards/umarim/imu_umarim.h
@@ -102,8 +102,8 @@
#define IMU_ACCEL_Z_NEUTRAL 0
#endif
-extern volatile bool_t gyr_valid;
-extern volatile bool_t acc_valid;
+extern volatile bool gyr_valid;
+extern volatile bool acc_valid;
struct ImuUmarim {
struct Itg3200 itg;
diff --git a/sw/airborne/firmwares/fixedwing/autopilot.c b/sw/airborne/firmwares/fixedwing/autopilot.c
index 2994f4678c..e499c99b81 100644
--- a/sw/airborne/firmwares/fixedwing/autopilot.c
+++ b/sw/airborne/firmwares/fixedwing/autopilot.c
@@ -39,10 +39,10 @@
#include "pprz_version.h"
uint8_t pprz_mode;
-bool_t kill_throttle;
+bool kill_throttle;
uint8_t mcu1_status;
-bool_t launch;
+bool launch;
/** flight time in seconds. */
uint16_t autopilot_flight_time;
@@ -53,9 +53,9 @@ uint16_t vsupply;
int32_t current;
float energy;
-bool_t gps_lost;
+bool gps_lost;
-bool_t power_switch;
+bool power_switch;
#if PERIODIC_TELEMETRY
#include "subsystems/datalink/telemetry.h"
@@ -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 bc823b8cd6..2a7aa3d2eb 100644
--- a/sw/airborne/firmwares/fixedwing/autopilot.h
+++ b/sw/airborne/firmwares/fixedwing/autopilot.h
@@ -59,14 +59,14 @@ extern void autopilot_init(void);
(pprz > THRESHOLD1 ? PPRZ_MODE_AUTO1 : PPRZ_MODE_MANUAL))
extern uint8_t pprz_mode;
-extern bool_t kill_throttle;
+extern bool kill_throttle;
extern uint8_t mcu1_status;
/** flight time in seconds. */
extern uint16_t autopilot_flight_time;
#define autopilot_ResetFlightTimeAndLaunch(_) { \
- autopilot_flight_time = 0; launch = FALSE; \
+ autopilot_flight_time = 0; launch = false; \
}
@@ -98,9 +98,9 @@ extern int32_t current; // milliAmpere
*/
extern float energy;
-extern bool_t launch;
+extern bool launch;
-extern bool_t gps_lost;
+extern bool gps_lost;
/** Assignment, returning _old_value != _value
* Using GCC expression statements */
@@ -115,7 +115,7 @@ extern void autopilot_send_mode(void);
/** Power switch control.
*/
-extern bool_t power_switch;
+extern bool power_switch;
#ifdef POWER_SWITCH_GPIO
#include "mcu_periph/gpio.h"
diff --git a/sw/airborne/firmwares/fixedwing/chibios-libopencm3/chibios_init.c b/sw/airborne/firmwares/fixedwing/chibios-libopencm3/chibios_init.c
index a81759e64c..09b2de413f 100644
--- a/sw/airborne/firmwares/fixedwing/chibios-libopencm3/chibios_init.c
+++ b/sw/airborne/firmwares/fixedwing/chibios-libopencm3/chibios_init.c
@@ -56,14 +56,14 @@ Thread *pprzThdPtr = NULL;
static WORKING_AREA(wa_thd_heartbeat, 2048);
void chibios_launch_heartbeat (void);
-bool_t sdOk = FALSE;
+bool sdOk = false;
/*
* Init ChibiOS HAL and Sys
*/
-bool_t chibios_init(void) {
+bool chibios_init(void) {
halInit();
chSysInit();
diff --git a/sw/airborne/firmwares/fixedwing/chibios-libopencm3/chibios_init.h b/sw/airborne/firmwares/fixedwing/chibios-libopencm3/chibios_init.h
index 7660a5360f..6b8aa79308 100644
--- a/sw/airborne/firmwares/fixedwing/chibios-libopencm3/chibios_init.h
+++ b/sw/airborne/firmwares/fixedwing/chibios-libopencm3/chibios_init.h
@@ -31,7 +31,7 @@
#include "std.h"
extern Thread *pprzThdPtr;
-extern bool_t chibios_init(void);
+extern bool chibios_init(void);
extern void launch_pprz_thd (int32_t (*thd) (void *arg));
#endif
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 ded4e50f93..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
@@ -361,11 +361,11 @@ static inline uint8_t mcu1_status_update(void)
{
uint8_t new_status = fbw_state->status;
if (mcu1_status != new_status) {
- bool_t changed = ((mcu1_status & MASK_FBW_CHANGED) != (new_status & MASK_FBW_CHANGED));
+ bool changed = ((mcu1_status & MASK_FBW_CHANGED) != (new_status & MASK_FBW_CHANGED));
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,18 +400,18 @@ 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)) {
- bool_t pprz_mode_changed = pprz_mode_update();
+ bool pprz_mode_changed = pprz_mode_update();
mode_changed |= pprz_mode_changed;
#if defined RADIO_CALIB && defined RADIO_CONTROL_SETTINGS
- bool_t calib_mode_changed = RcSettingsModeUpdate(fbw_state->channels);
+ bool calib_mode_changed = RcSettingsModeUpdate(fbw_state->channels);
rc_settings(calib_mode_changed || pprz_mode_changed);
mode_changed |= calib_mode_changed;
#endif
@@ -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 2452c6ccfa..01ee2fe249 100644
--- a/sw/airborne/firmwares/fixedwing/main_chibios_libopencm3.c
+++ b/sw/airborne/firmwares/fixedwing/main_chibios_libopencm3.c
@@ -47,8 +47,8 @@
static int32_t pprz_thd(void *arg);
-static bool_t sdlogOk ;
-bool_t pprzReady = FALSE;
+static bool sdlogOk ;
+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/main_fbw.h b/sw/airborne/firmwares/fixedwing/main_fbw.h
index 67752e7d0d..b3b715d176 100644
--- a/sw/airborne/firmwares/fixedwing/main_fbw.h
+++ b/sw/airborne/firmwares/fixedwing/main_fbw.h
@@ -37,7 +37,7 @@
#define FBW_MODE_OF_PPRZ(mode) ((mode) < THRESHOLD_MANUAL_PPRZ ? FBW_MODE_MANUAL : FBW_MODE_AUTO)
extern uint8_t fbw_mode;
-extern bool_t failsafe_mode;
+extern bool failsafe_mode;
void init_fbw(void);
void handle_periodic_tasks_fbw(void);
diff --git a/sw/airborne/firmwares/fixedwing/nav.c b/sw/airborne/firmwares/fixedwing/nav.c
index c48fea15b5..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_t nav_in_circle = FALSE;
-bool_t 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;
@@ -87,7 +87,7 @@ float nav_ground_speed_setpoint, nav_ground_speed_pgain;
/* Used in nav_survey_rectangle. Defined here for downlink and uplink */
float nav_survey_shift;
float nav_survey_west, nav_survey_east, nav_survey_north, nav_survey_south;
-bool_t nav_survey_active;
+bool nav_survey_active;
int nav_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;
@@ -216,7 +216,7 @@ static void nav_ground_speed_loop(void)
#endif
float baseleg_out_qdr;
-bool_t nav_compute_baseleg(uint8_t wp_af, uint8_t wp_td, uint8_t wp_baseleg, float radius)
+bool nav_compute_baseleg(uint8_t wp_af, uint8_t wp_td, uint8_t wp_baseleg, float radius)
{
nav_radius = radius;
@@ -236,10 +236,10 @@ bool_t nav_compute_baseleg(uint8_t wp_af, uint8_t wp_td, uint8_t wp_baseleg, flo
baseleg_out_qdr += M_PI;
}
- return FALSE;
+ return false;
}
-bool_t nav_compute_final_from_glide(uint8_t wp_af, uint8_t wp_td, float glide)
+bool nav_compute_final_from_glide(uint8_t wp_af, uint8_t wp_td, float glide)
{
float x_0 = waypoints[wp_td].x - waypoints[wp_af].x;
@@ -255,14 +255,14 @@ bool_t 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;
}
/* For a landing UPWIND.
Computes Top Of Descent waypoint from Touch Down and Approach Fix
waypoints, using glide airspeed, glide vertical speed and wind */
-static inline bool_t compute_TOD(uint8_t _af, uint8_t _td, uint8_t _tod, float glide_airspeed, float glide_vspeed)
+static inline bool compute_TOD(uint8_t _af, uint8_t _td, uint8_t _tod, float glide_airspeed, float glide_vspeed)
{
struct FloatVect2 *wind = stateGetHorizontalWindspeed_f();
float td_af_x = WaypointX(_af) - WaypointX(_td);
@@ -273,7 +273,7 @@ static inline bool_t compute_TOD(uint8_t _af, uint8_t _td, uint8_t _tod, float g
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;
}
@@ -321,7 +321,7 @@ float fp_climb; /* m/s */
*
* @return true if the position (x, y) is reached
*/
-bool_t nav_approaching_xy(float x, float y, float from_x, float from_y, float approaching_time)
+bool nav_approaching_xy(float x, float y, float from_x, float from_y, float approaching_time)
{
/** distance to waypoint in x */
float pw_x = x - stateGetPositionEnu_f()->x;
@@ -341,7 +341,7 @@ bool_t nav_approaching_xy(float x, float y, float from_x, float from_y, float ap
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.;
@@ -481,10 +481,10 @@ static void send_wp_moved(struct transport_tx *trans, struct link_device *dev)
DownlinkSendWp(trans, dev, i);
}
-bool_t DownlinkSendWpNr(uint8_t _wp)
+bool DownlinkSendWpNr(uint8_t _wp)
{
DownlinkSendWp(&(DefaultChannel).trans_tx, &(DefaultDevice).device, _wp);
- return FALSE;
+ return false;
}
diff --git a/sw/airborne/firmwares/fixedwing/nav.h b/sw/airborne/firmwares/fixedwing/nav.h
index 3e8848498b..f80821c2a6 100644
--- a/sw/airborne/firmwares/fixedwing/nav.h
+++ b/sw/airborne/firmwares/fixedwing/nav.h
@@ -68,8 +68,8 @@ extern float carrot_x, carrot_y;
extern float nav_circle_radians; /* Cumulated */
extern float nav_circle_radians_no_rewind; /* Cumulated */
-extern bool_t nav_in_circle;
-extern bool_t nav_in_segment;
+extern bool nav_in_circle;
+extern bool nav_in_segment;
extern float nav_circle_x, nav_circle_y, nav_circle_radius; /* m */
extern float nav_segment_x_1, nav_segment_y_1, nav_segment_x_2, nav_segment_y_2; /* m */
@@ -112,7 +112,7 @@ extern float nav_ground_speed_pgain, nav_ground_speed_setpoint;
extern float nav_survey_shift;
extern float nav_survey_west, nav_survey_east, nav_survey_north, nav_survey_south;
-extern bool_t nav_survey_active;
+extern bool nav_survey_active;
extern void nav_periodic_task(void);
extern void nav_home(void);
@@ -123,8 +123,8 @@ extern float nav_circle_trigo_qdr; /** Angle from center to mobile */
extern void nav_circle_XY(float x, float y, float radius);
extern float baseleg_out_qdr;
-extern bool_t nav_compute_baseleg(uint8_t wp_af, uint8_t wp_td, uint8_t wp_baseleg, float radius);
-extern bool_t nav_compute_final_from_glide(uint8_t wp_af, uint8_t wp_td, float glide);
+extern bool nav_compute_baseleg(uint8_t wp_af, uint8_t wp_td, uint8_t wp_baseleg, float radius);
+extern bool nav_compute_final_from_glide(uint8_t wp_af, uint8_t wp_td, float glide);
#define RCLost() bit_is_set(fbw_state->status, STATUS_RADIO_REALLY_LOST)
@@ -160,7 +160,7 @@ extern void nav_route_xy(float last_wp_x, float last_wp_y, float wp_x, float wp_
#define NavSegment(_start, _end) \
nav_route_xy(waypoints[_start].x, waypoints[_start].y, waypoints[_end].x, waypoints[_end].y)
-bool_t nav_approaching_xy(float x, float y, float from_x, float from_y, float approaching_time);
+bool nav_approaching_xy(float x, float y, float from_x, float from_y, float approaching_time);
#define NavApproaching(wp, time) nav_approaching_xy(waypoints[wp].x, waypoints[wp].y, last_x, last_y, time)
#define NavApproachingFrom(wp, from, time) nav_approaching_xy(waypoints[wp].x, waypoints[wp].y, waypoints[from].x, waypoints[from].y, time)
@@ -230,7 +230,7 @@ bool_t nav_approaching_xy(float x, float y, float from_x, float from_y, float ap
pprz_msg_send_NAVIGATION(_trans, _dev, AC_ID, &nav_block, &nav_stage, &(pos->x), &(pos->y), &dist_wp, &dist_home, &_circle_count, &nav_oval_count); \
}
-extern bool_t DownlinkSendWpNr(uint8_t _wp);
+extern bool DownlinkSendWpNr(uint8_t _wp);
#define DownlinkSendWp(_trans, _dev, i) { \
float x = nav_utm_east0 + waypoints[i].x; \
diff --git a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.c b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.c
index da86184584..85a2d8caae 100644
--- a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.c
+++ b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.c
@@ -85,10 +85,10 @@ float h_ctl_course_dgain;
float h_ctl_roll_max_setpoint;
/* roll and pitch disabling */
-bool_t h_ctl_disabled;
+bool h_ctl_disabled;
/* AUTO1 rate mode */
-bool_t h_ctl_auto1_rate;
+bool h_ctl_auto1_rate;
struct HCtlAdaptRef {
float roll_angle;
@@ -196,7 +196,7 @@ float h_ctl_aileron_of_throttle;
float h_ctl_elevator_of_roll;
float h_ctl_pitch_of_roll; // Should be used instead of elevator_of_roll
-bool_t use_airspeed_ratio;
+bool use_airspeed_ratio;
float airspeed_ratio2;
#define AIRSPEED_RATIO_MIN 0.5
#define AIRSPEED_RATIO_MAX 2.
@@ -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_adaptive.h b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.h
index aaa2bfc72d..5175ef7a26 100644
--- a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.h
+++ b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.h
@@ -63,6 +63,6 @@ extern float h_ctl_yaw_ny_igain;
h_ctl_pitch_igain = _gain; \
}
-extern bool_t use_airspeed_ratio;
+extern bool use_airspeed_ratio;
#endif /* FW_H_CTL_A_H */
diff --git a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.c b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.c
index 724dd9647c..02994c0e70 100644
--- a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.c
+++ b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.c
@@ -44,10 +44,10 @@ float h_ctl_course_dgain;
float h_ctl_roll_max_setpoint;
/* roll and pitch disabling */
-bool_t h_ctl_disabled;
+bool h_ctl_disabled;
/* AUTO1 rate mode */
-bool_t h_ctl_auto1_rate;
+bool h_ctl_auto1_rate;
/* inner roll loop parameters */
@@ -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/fixedwing/stabilization/stabilization_attitude.h b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.h
index 42c1f7b605..e583f27169 100644
--- a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.h
+++ b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.h
@@ -48,10 +48,10 @@ extern float v_ctl_auto_throttle_dash_trim;
#endif
/* roll and pitch disabling */
-extern bool_t h_ctl_disabled;
+extern bool h_ctl_disabled;
/* AUTO1 rate mode */
-extern bool_t h_ctl_auto1_rate;
+extern bool h_ctl_auto1_rate;
/* inner roll loop parameters */
extern float h_ctl_roll_setpoint;
diff --git a/sw/airborne/firmwares/motor_bench/main_motor_bench.c b/sw/airborne/firmwares/motor_bench/main_motor_bench.c
index 011407ed5a..9fcf98f742 100644
--- a/sw/airborne/firmwares/motor_bench/main_motor_bench.c
+++ b/sw/airborne/firmwares/motor_bench/main_motor_bench.c
@@ -101,16 +101,16 @@ 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;
}
}
-bool_t dl_msg_available;
+bool dl_msg_available;
#define MSG_SIZE 128
uint8_t dl_buffer[MSG_SIZE] __attribute__((aligned));
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 1a77ff92d7..e23f4e8aa9 100644
--- a/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.c
+++ b/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.c
@@ -5,7 +5,7 @@
#include "led.h"
-bool_t mb_twi_controller_asctech_command;
+bool mb_twi_controller_asctech_command;
uint8_t mb_twi_controller_asctech_command_type;
#define MB_TWI_CONTROLLER_ASCTECH_ADDR_FRONT 0
@@ -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 b65af55d57..69eb13c43a 100644
--- a/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.h
+++ b/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.h
@@ -13,18 +13,18 @@ extern void mb_twi_controller_set_raw(uint8_t throttle);
#define MB_TWI_CONTROLLER_COMMAND_SET_ADDR 3
-extern bool_t mb_twi_controller_asctech_command;
+extern bool mb_twi_controller_asctech_command;
extern uint8_t mb_twi_controller_asctech_command_type;
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 374f1f5865..7377040e07 100644
--- a/sw/airborne/firmwares/rotorcraft/autopilot.c
+++ b/sw/airborne/firmwares/rotorcraft/autopilot.c
@@ -69,18 +69,18 @@
uint8_t autopilot_mode;
uint8_t autopilot_mode_auto2;
-bool_t autopilot_in_flight;
+bool autopilot_in_flight;
uint32_t autopilot_in_flight_counter;
uint16_t autopilot_flight_time;
-bool_t autopilot_motors_on;
-bool_t kill_throttle;
+bool autopilot_motors_on;
+bool kill_throttle;
-bool_t autopilot_rc;
-bool_t autopilot_power_switch;
+bool autopilot_rc;
+bool autopilot_power_switch;
-bool_t autopilot_ground_detected;
-bool_t autopilot_detect_ground_once;
+bool autopilot_ground_detected;
+bool autopilot_detect_ground_once;
/** time steps for in_flight detection (at 20Hz, so 20=1second) */
#ifndef AUTOPILOT_IN_FLIGHT_TIME
@@ -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
@@ -194,12 +194,13 @@ static void send_status(struct transport_tx *trans, struct link_device *dev)
#else
uint8_t fix = 0;
#endif
+ uint8_t in_flight = autopilot_in_flight;
+ uint8_t motors_on = autopilot_motors_on;
uint16_t time_sec = sys_time.nb_sec;
pprz_msg_send_ROTORCRAFT_STATUS(trans, dev, AC_ID,
&imu_nb_err, &_motor_nb_err,
&radio_control.status, &radio_control.frame_rate,
- &fix, &autopilot_mode,
- &autopilot_in_flight, &autopilot_motors_on,
+ &fix, &autopilot_mode, &in_flight, &motors_on,
&guidance_h.mode, &guidance_v_mode,
&electrical.vsupply, &time_sec);
}
@@ -287,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
@@ -379,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.
@@ -416,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;
@@ -521,18 +522,18 @@ void autopilot_set_mode(uint8_t new_autopilot_mode)
}
-bool_t autopilot_guided_goto_ned(float x, float y, float z, float heading)
+bool autopilot_guided_goto_ned(float x, float y, float z, float heading)
{
if (autopilot_mode == AP_MODE_GUIDED) {
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_t autopilot_guided_goto_ned_relative(float dx, float dy, float dz, float dyaw)
+bool autopilot_guided_goto_ned_relative(float dx, float dy, float dz, float dyaw)
{
if (autopilot_mode == AP_MODE_GUIDED && stateIsLocalCoordinateValid()) {
float x = stateGetPositionNed_f()->x + dx;
@@ -541,10 +542,10 @@ bool_t autopilot_guided_goto_ned_relative(float dx, float dy, float dz, float dy
float heading = stateGetNedToBodyEulers_f()->psi + dyaw;
return autopilot_guided_goto_ned(x, y, z, heading);
}
- return FALSE;
+ return false;
}
-bool_t autopilot_guided_goto_body_relative(float dx, float dy, float dz, float dyaw)
+bool autopilot_guided_goto_body_relative(float dx, float dy, float dz, float dyaw)
{
if (autopilot_mode == AP_MODE_GUIDED && stateIsLocalCoordinateValid()) {
float psi = stateGetNedToBodyEulers_f()->psi;
@@ -554,21 +555,21 @@ bool_t autopilot_guided_goto_body_relative(float dx, float dy, float dz, float d
float heading = psi + dyaw;
return autopilot_guided_goto_ned(x, y, z, heading);
}
- return FALSE;
+ return false;
}
-bool_t autopilot_guided_move_ned(float vx, float vy, float vz, float heading)
+bool autopilot_guided_move_ned(float vx, float vy, float vz, float heading)
{
if (autopilot_mode == AP_MODE_GUIDED) {
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_t motors_on)
+void autopilot_check_in_flight(bool motors_on)
{
if (autopilot_in_flight) {
if (autopilot_in_flight_counter > 0) {
@@ -578,7 +579,7 @@ void autopilot_check_in_flight(bool_t 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;
@@ -593,7 +594,7 @@ void autopilot_check_in_flight(bool_t 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;
@@ -603,12 +604,12 @@ void autopilot_check_in_flight(bool_t motors_on)
}
-void autopilot_set_motors_on(bool_t 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 7e1ddeeace..a64f774a9c 100644
--- a/sw/airborne/firmwares/rotorcraft/autopilot.h
+++ b/sw/airborne/firmwares/rotorcraft/autopilot.h
@@ -56,22 +56,22 @@
extern uint8_t autopilot_mode;
extern uint8_t autopilot_mode_auto2;
-extern bool_t autopilot_motors_on;
-extern bool_t autopilot_in_flight;
-extern bool_t kill_throttle;
-extern bool_t autopilot_rc;
+extern bool autopilot_motors_on;
+extern bool autopilot_in_flight;
+extern bool kill_throttle;
+extern bool autopilot_rc;
-extern bool_t autopilot_power_switch;
+extern bool autopilot_power_switch;
extern void autopilot_init(void);
extern void autopilot_periodic(void);
extern void autopilot_on_rc_frame(void);
extern void autopilot_set_mode(uint8_t new_autopilot_mode);
-extern void autopilot_set_motors_on(bool_t motors_on);
-extern void autopilot_check_in_flight(bool_t motors_on);
+extern void autopilot_set_motors_on(bool motors_on);
+extern void autopilot_check_in_flight(bool motors_on);
-extern bool_t autopilot_ground_detected;
-extern bool_t autopilot_detect_ground_once;
+extern bool autopilot_ground_detected;
+extern bool autopilot_detect_ground_once;
extern uint16_t autopilot_flight_time;
@@ -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;
}
}
}
@@ -190,7 +190,7 @@ extern void send_autopilot_version(struct transport_tx *trans, struct link_devic
* @param heading Setpoint in radians.
* @return TRUE if setpoint was set (currently in AP_MODE_GUIDED)
*/
-extern bool_t autopilot_guided_goto_ned(float x, float y, float z, float heading);
+extern bool autopilot_guided_goto_ned(float x, float y, float z, float heading);
/** Set position and heading setpoints wrt. current position in GUIDED mode.
* @param dx Offset relative to current north position (local NED frame) in meters.
@@ -199,7 +199,7 @@ extern bool_t autopilot_guided_goto_ned(float x, float y, float z, float heading
* @param dyaw Offset relative to current heading setpoint in radians.
* @return TRUE if setpoint was set (currently in AP_MODE_GUIDED)
*/
-extern bool_t autopilot_guided_goto_ned_relative(float dx, float dy, float dz, float dyaw);
+extern bool autopilot_guided_goto_ned_relative(float dx, float dy, float dz, float dyaw);
/** Set position and heading setpoints wrt. current position AND heading in GUIDED mode.
* @param dx relative position (body frame, forward) in meters.
@@ -208,7 +208,7 @@ extern bool_t autopilot_guided_goto_ned_relative(float dx, float dy, float dz, f
* @param dyaw Offset relative to current heading setpoint in radians.
* @return TRUE if setpoint was set (currently in AP_MODE_GUIDED)
*/
-extern bool_t autopilot_guided_goto_body_relative(float dx, float dy, float dz, float dyaw);
+extern bool autopilot_guided_goto_body_relative(float dx, float dy, float dz, float dyaw);
/** Set velocity and heading setpoints in GUIDED mode.
* @param vx North velocity (local NED frame) in meters/sec.
@@ -217,6 +217,6 @@ extern bool_t autopilot_guided_goto_body_relative(float dx, float dy, float dz,
* @param heading Setpoint in radians.
* @return TRUE if setpoint was set (currently in AP_MODE_GUIDED)
*/
-extern bool_t autopilot_guided_move_ned(float vx, float vy, float vz, float heading);
+extern bool autopilot_guided_move_ned(float vx, float vy, float vz, float heading);
#endif /* AUTOPILOT_H */
diff --git a/sw/airborne/firmwares/rotorcraft/autopilot_arming_switch.h b/sw/airborne/firmwares/rotorcraft/autopilot_arming_switch.h
index 015165793a..fcdeef6fb7 100644
--- a/sw/airborne/firmwares/rotorcraft/autopilot_arming_switch.h
+++ b/sw/airborne/firmwares/rotorcraft/autopilot_arming_switch.h
@@ -43,15 +43,15 @@ enum arming_state {
};
enum arming_state autopilot_arming_state;
-bool_t autopilot_unarmed_in_auto;
+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_t motors_on)
+static inline void autopilot_arming_set(bool motors_on)
{
if (motors_on) {
autopilot_arming_state = STATE_MOTORS_ON;
@@ -61,9 +61,9 @@ static inline void autopilot_arming_set(bool_t 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 9ba5021f5e..99ad493d07 100644
--- a/sw/airborne/firmwares/rotorcraft/autopilot_arming_throttle.h
+++ b/sw/airborne/firmwares/rotorcraft/autopilot_arming_throttle.h
@@ -44,16 +44,16 @@ enum arming_throttle_state {
enum arming_throttle_state autopilot_arming_state;
uint8_t autopilot_arming_delay_counter;
-bool_t autopilot_unarmed_in_auto;
+bool autopilot_unarmed_in_auto;
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_t motors_on)
+static inline void autopilot_arming_set(bool motors_on)
{
if (motors_on) {
autopilot_arming_state = STATE_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 25ad60e9c9..d7bfc72ac4 100644
--- a/sw/airborne/firmwares/rotorcraft/autopilot_arming_yaw.h
+++ b/sw/airborne/firmwares/rotorcraft/autopilot_arming_yaw.h
@@ -65,7 +65,7 @@ static inline void autopilot_arming_init(void)
/** Update the status of the check_motors state machine.
*/
-static inline void autopilot_arming_set(bool_t motors_on)
+static inline void autopilot_arming_set(bool motors_on)
{
if (motors_on) {
autopilot_check_motor_status = STATUS_MOTORS_ON;
@@ -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 43482ccb1a..bd9ca01467 100644
--- a/sw/airborne/firmwares/rotorcraft/autopilot_rc_helpers.h
+++ b/sw/airborne/firmwares/rotorcraft/autopilot_rc_helpers.h
@@ -52,24 +52,24 @@
(radio_control.values[RADIO_ROLL] < AUTOPILOT_STICK_CENTER_THRESHOLD && \
radio_control.values[RADIO_ROLL] > -AUTOPILOT_STICK_CENTER_THRESHOLD)
-static inline bool_t rc_attitude_sticks_centered(void)
+static inline bool rc_attitude_sticks_centered(void)
{
return ROLL_STICK_CENTERED() && PITCH_STICK_CENTERED() && YAW_STICK_CENTERED();
}
#ifdef RADIO_KILL_SWITCH
-static inline bool_t kill_switch_is_on(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_t kill_switch_is_on(void)
+static inline bool kill_switch_is_on(void)
{
- return FALSE;
+ return false;
}
#endif
diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_flip.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_flip.c
index e28bf47c92..7ee46e8ba2 100644
--- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_flip.c
+++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_flip.c
@@ -48,7 +48,7 @@
uint32_t flip_counter;
uint8_t flip_state;
-bool_t flip_rollout;
+bool flip_rollout;
int32_t heading_save;
uint8_t autopilot_mode_old;
struct Int32Vect2 flip_cmd_earth;
diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c
index 99ab607898..14ab2564d1 100644
--- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c
+++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c
@@ -96,12 +96,12 @@ struct Int32Vect2 guidance_h_cmd_earth;
static void guidance_h_update_reference(void);
#if !GUIDANCE_INDI
-static void guidance_h_traj_run(bool_t in_flight);
+static void guidance_h_traj_run(bool in_flight);
#endif
static void guidance_h_hover_enter(void);
static void guidance_h_nav_enter(void);
static inline void transition_run(void);
-static void read_rc_setpoint_speed_i(struct Int32Vect2 *speed_sp, bool_t in_flight);
+static void read_rc_setpoint_speed_i(struct Int32Vect2 *speed_sp, bool in_flight);
#if PERIODIC_TELEMETRY
#include "subsystems/datalink/telemetry.h"
@@ -292,7 +292,7 @@ void guidance_h_mode_changed(uint8_t new_mode)
}
-void guidance_h_read_rc(bool_t in_flight)
+void guidance_h_read_rc(bool in_flight)
{
switch (guidance_h.mode) {
@@ -352,7 +352,7 @@ void guidance_h_read_rc(bool_t in_flight)
}
-void guidance_h_run(bool_t in_flight)
+void guidance_h_run(bool in_flight)
{
switch (guidance_h.mode) {
@@ -490,7 +490,7 @@ static void guidance_h_update_reference(void)
#define GH_GAIN_SCALE 2
#if !GUIDANCE_INDI
-static void guidance_h_traj_run(bool_t in_flight)
+static void guidance_h_traj_run(bool in_flight)
{
/* maximum bank angle: default 20 deg, max 40 deg*/
static const int32_t traj_max_bank = Min(BFP_OF_REAL(GUIDANCE_H_MAX_BANK, INT32_ANGLE_FRAC),
@@ -600,7 +600,7 @@ static inline void transition_run(void)
}
/// read speed setpoint from RC
-static void read_rc_setpoint_speed_i(struct Int32Vect2 *speed_sp, bool_t in_flight)
+static void read_rc_setpoint_speed_i(struct Int32Vect2 *speed_sp, bool in_flight)
{
if (in_flight) {
// negative pitch is forward
@@ -636,37 +636,37 @@ void guidance_h_set_igain(uint32_t igain)
INT_VECT2_ZERO(guidance_h_trim_att_integrator);
}
-bool_t guidance_h_set_guided_pos(float x, float y)
+bool guidance_h_set_guided_pos(float x, float y)
{
if (guidance_h.mode == GUIDANCE_H_MODE_GUIDED) {
ClearBit(guidance_h.sp.mask, 4);
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_t guidance_h_set_guided_heading(float heading)
+bool guidance_h_set_guided_heading(float heading)
{
if (guidance_h.mode == GUIDANCE_H_MODE_GUIDED) {
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_t guidance_h_set_guided_vel(float vx, float vy)
+bool guidance_h_set_guided_vel(float vx, float vy)
{
if (guidance_h.mode == GUIDANCE_H_MODE_GUIDED) {
SetBit(guidance_h.sp.mask, 4);
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_h.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.h
index 22344e3f75..3a592a1e2b 100644
--- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.h
+++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.h
@@ -90,8 +90,8 @@ struct HorizontalGuidanceGains {
struct HorizontalGuidance {
uint8_t mode;
/* configuration options */
- bool_t use_ref;
- bool_t approx_force_by_thrust;
+ bool use_ref;
+ bool approx_force_by_thrust;
/* gains */
struct HorizontalGuidanceGains gains;
@@ -108,8 +108,8 @@ extern int32_t transition_theta_offset;
extern void guidance_h_init(void);
extern void guidance_h_mode_changed(uint8_t new_mode);
-extern void guidance_h_read_rc(bool_t in_flight);
-extern void guidance_h_run(bool_t in_flight);
+extern void guidance_h_read_rc(bool in_flight);
+extern void guidance_h_run(bool in_flight);
extern void guidance_h_set_igain(uint32_t igain);
@@ -118,20 +118,20 @@ extern void guidance_h_set_igain(uint32_t igain);
* @param y East position (local NED frame) in meters.
* @return TRUE if setpoints were set (currently in GUIDANCE_H_MODE_GUIDED)
*/
-extern bool_t guidance_h_set_guided_pos(float x, float y);
+extern bool guidance_h_set_guided_pos(float x, float y);
/** Set heading setpoint in GUIDED mode.
* @param heading Setpoint in radians.
* @return TRUE if setpoint was set (currently in GUIDANCE_H_MODE_GUIDED)
*/
-extern bool_t guidance_h_set_guided_heading(float heading);
+extern bool guidance_h_set_guided_heading(float heading);
/** Set horizontal velocity setpoint in GUIDED mode.
* @param x North velocity (local NED frame) in meters/sec.
* @param y East velocity (local NED frame) in meters/sec.
* @return TRUE if setpoints were set (currently in GUIDANCE_H_MODE_GUIDED)
*/
-extern bool_t guidance_h_set_guided_vel(float vx, float vy);
+extern bool guidance_h_set_guided_vel(float vx, float vy);
/* Make sure that ref can only be temporarily disabled for testing,
* but not enabled if GUIDANCE_H_USE_REF was defined to FALSE.
diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_indi.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_indi.c
index 1a78882800..e2d3ebe7ae 100644
--- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_indi.c
+++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_indi.c
@@ -82,7 +82,7 @@ void guidance_indi_enter(void) {
FLOAT_VECT3_ZERO(filt_accel_ned_dd);
}
-void guidance_indi_run(bool_t in_flight, int32_t heading) {
+void guidance_indi_run(bool in_flight, int32_t heading) {
//filter accel to get rid of noise
//filter attitude to synchronize with accel
@@ -184,7 +184,7 @@ void guidance_indi_calcG(struct FloatMat33 *Gmat) {
RMAT_ELMT(*Gmat, 2, 2) = cphi*ctheta;
}
-void stabilization_attitude_set_setpoint_rp_quat_f(bool_t in_flight, int32_t heading)
+void stabilization_attitude_set_setpoint_rp_quat_f(bool in_flight, int32_t heading)
{
struct FloatQuat q_rp_cmd;
float_quat_of_eulers(&q_rp_cmd, &guidance_euler_cmd); //TODO this is a quaternion without yaw! add the desired yaw before you use it!
diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_indi.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_indi.h
index eeca34b5c7..5eac0f542d 100644
--- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_indi.h
+++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_indi.h
@@ -35,10 +35,10 @@
#include "math/pprz_algebra_float.h"
extern void guidance_indi_enter(void);
-extern void guidance_indi_run(bool_t in_flight, int32_t heading);
+extern void guidance_indi_run(bool in_flight, int32_t heading);
extern void guidance_indi_filter_attitude(void);
extern void guidance_indi_calcG(struct FloatMat33 *Gmat);
extern void guidance_indi_filter_accel(void);
-extern void stabilization_attitude_set_setpoint_rp_quat_f(bool_t in_flight, int32_t heading);
+extern void stabilization_attitude_set_setpoint_rp_quat_f(bool in_flight, int32_t heading);
#endif /* GUIDANCE_INDI_H */
diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_module.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_module.h
index d24eda6d8a..125e6aa2ec 100644
--- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_module.h
+++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_module.h
@@ -36,12 +36,12 @@
* - void guidance_h_module_init(void);
* - void guidance_h_module_enter(void);
* - void guidance_h_module_read_rc(void);
- * - void guidance_h_module_run(bool_t in_flight);
+ * - void guidance_h_module_run(bool in_flight);
*
*
* b) Implement own Vertical loops when GUIDANCE_V_MODE_MODULE_SETTING is set to GUIDANCE_V_MODE_MODULE
* - void guidance_v_module_enter(void);
- * - void guidance_v_module_run(bool_t in_flight);
+ * - void guidance_v_module_run(bool in_flight);
*
* If the module implements both V and H mode, take into account that the H is called first and later V
*
diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c
index d11416d693..4f48c23cee 100644
--- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c
+++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c
@@ -101,8 +101,8 @@ int32_t guidance_v_fb_cmd;
int32_t guidance_v_delta_t;
float guidance_v_nominal_throttle;
-bool_t guidance_v_adapt_throttle_enabled;
-bool_t guidance_v_guided_vel_enabled;
+bool guidance_v_adapt_throttle_enabled;
+bool guidance_v_guided_vel_enabled;
/** Direct throttle from radio control.
* range 0:#MAX_PPRZ
@@ -138,7 +138,7 @@ int32_t guidance_v_thrust_coeff;
}
static int32_t get_vertical_thrust_coeff(void);
-static void run_hover_loop(bool_t in_flight);
+static void run_hover_loop(bool in_flight);
#if PERIODIC_TELEMETRY
#include "subsystems/datalink/telemetry.h"
@@ -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();
@@ -262,7 +262,7 @@ void guidance_v_mode_changed(uint8_t new_mode)
}
-void guidance_v_notify_in_flight(bool_t in_flight)
+void guidance_v_notify_in_flight(bool in_flight)
{
if (in_flight) {
gv_adapt_init();
@@ -270,7 +270,7 @@ void guidance_v_notify_in_flight(bool_t in_flight)
}
-void guidance_v_run(bool_t in_flight)
+void guidance_v_run(bool in_flight)
{
// FIXME... SATURATIONS NOT TAKEN INTO ACCOUNT
@@ -311,7 +311,7 @@ void guidance_v_run(bool_t 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);
@@ -406,7 +406,7 @@ static int32_t get_vertical_thrust_coeff(void)
#define FF_CMD_FRAC 18
-static void run_hover_loop(bool_t in_flight)
+static void run_hover_loop(bool in_flight)
{
/* convert our reference to generic representation */
@@ -460,22 +460,22 @@ static void run_hover_loop(bool_t in_flight)
}
-bool_t guidance_v_set_guided_z(float z)
+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_t guidance_v_set_guided_vz(float vz)
+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/guidance/guidance_v.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h
index f38f55046c..3803faee81 100644
--- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h
+++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h
@@ -92,9 +92,9 @@ extern float guidance_v_nominal_throttle;
/** Use adaptive throttle command estimation.
*/
-extern bool_t guidance_v_adapt_throttle_enabled;
+extern bool guidance_v_adapt_throttle_enabled;
-extern bool_t guidance_v_guided_vel_enabled;
+extern bool guidance_v_guided_vel_enabled;
extern int32_t guidance_v_thrust_coeff;
@@ -105,20 +105,20 @@ extern int32_t guidance_v_ki; ///< vertical control I-gain
extern void guidance_v_init(void);
extern void guidance_v_read_rc(void);
extern void guidance_v_mode_changed(uint8_t new_mode);
-extern void guidance_v_notify_in_flight(bool_t in_flight);
-extern void guidance_v_run(bool_t in_flight);
+extern void guidance_v_notify_in_flight(bool in_flight);
+extern void guidance_v_run(bool in_flight);
/** Set z setpoint in GUIDED mode.
* @param z Setpoint (down is positive) in meters.
* @return TRUE if setpoint was set (currently in GUIDANCE_V_MODE_GUIDED)
*/
-extern bool_t guidance_v_set_guided_z(float z);
+extern bool guidance_v_set_guided_z(float z);
/** Set z velocity setpoint in GUIDED mode.
* @param vz Setpoint (down is positive) in meters/second.
* @return TRUE if setpoint was set (currently in GUIDANCE_V_MODE_GUIDED)
*/
-extern bool_t guidance_v_set_guided_vz(float vz);
+extern bool guidance_v_set_guided_vz(float vz);
#define guidance_v_SetKi(_val) { \
guidance_v_ki = _val; \
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 35c758c5a5..a47037c7af 100644
--- a/sw/airborne/firmwares/rotorcraft/main_fbw.c
+++ b/sw/airborne/firmwares/rotorcraft/main_fbw.c
@@ -152,8 +152,8 @@ STATIC_INLINE void main_periodic(void)
intermcu_periodic();
/* Safety logic */
- bool_t ap_lost = (inter_mcu.status == INTERMCU_LOST);
- bool_t rc_lost = (radio_control.status == RC_REALLY_LOST);
+ bool ap_lost = (inter_mcu.status == INTERMCU_LOST);
+ bool rc_lost = (radio_control.status == RC_REALLY_LOST);
if (rc_lost) {
if (ap_lost) {
// Both are lost
@@ -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 eeeb26f462..0389d22fe4 100644
--- a/sw/airborne/firmwares/rotorcraft/navigation.c
+++ b/sw/airborne/firmwares/rotorcraft/navigation.c
@@ -64,9 +64,9 @@ const float max_dist_from_home = MAX_DIST_FROM_HOME;
const float max_dist2_from_home = MAX_DIST_FROM_HOME * MAX_DIST_FROM_HOME;
float failsafe_mode_dist2 = FAILSAFE_MODE_DISTANCE * FAILSAFE_MODE_DISTANCE;
float dist2_to_home;
-bool_t too_far_from_home;
+bool too_far_from_home;
-bool_t exception_flag[10] = {0}; //exception flags that can be used in the flight plan
+bool exception_flag[10] = {0}; //exception flags that can be used in the flight plan
float dist2_to_wp;
@@ -78,7 +78,7 @@ int32_t nav_circle_radius, nav_circle_qdr, nav_circle_radians;
int32_t nav_leg_progress;
uint32_t nav_leg_length;
-bool_t nav_survey_active;
+bool nav_survey_active;
int32_t nav_roll, nav_pitch;
int32_t nav_heading;
@@ -105,8 +105,8 @@ float flight_altitude;
static inline void nav_set_altitude(void);
-#define CLOSE_TO_WAYPOINT (15 << 8)
-#define CARROT_DIST (12 << 8)
+#define CLOSE_TO_WAYPOINT (15 << INT32_POS_FRAC)
+#define CARROT_DIST (12 << INT32_POS_FRAC)
/** minimum horizontal distance to waypoint to mark as arrived */
#ifndef ARRIVED_AT_WAYPOINT
@@ -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;
@@ -300,7 +300,7 @@ void nav_route(struct EnuCoor_i *wp_start, struct EnuCoor_i *wp_end)
dist2_to_wp = get_dist2_to_point(wp_end);
}
-bool_t nav_approaching_from(struct EnuCoor_i *wp, struct EnuCoor_i *from, int16_t approaching_time)
+bool nav_approaching_from(struct EnuCoor_i *wp, struct EnuCoor_i *from, int16_t approaching_time)
{
int32_t dist_to_point;
struct Int32Vect2 diff;
@@ -328,7 +328,7 @@ bool_t nav_approaching_from(struct EnuCoor_i *wp, struct EnuCoor_i *from, int16_
/* 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,20 +340,20 @@ bool_t nav_approaching_from(struct EnuCoor_i *wp, struct EnuCoor_i *from, int16_
return (diff.x * from_diff.x + diff.y * from_diff.y < 0);
}
- return FALSE;
+ return false;
}
-bool_t nav_check_wp_time(struct EnuCoor_i *wp, uint16_t stay_time)
+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_t 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_t 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_t 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;
@@ -452,14 +452,14 @@ void navigation_update_wp_from_speed(uint8_t wp, struct Int16Vect3 speed_sp, int
&(waypoints[wp].enu_i.z)));
}
-bool_t nav_detect_ground(void)
+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_t nav_is_in_flight(void)
+bool nav_is_in_flight(void)
{
return autopilot_in_flight;
}
@@ -506,21 +506,21 @@ void compute_dist2_to_home(void)
}
/** Set nav_heading in degrees. */
-bool_t nav_set_heading_rad(float rad)
+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. */
-bool_t nav_set_heading_deg(float deg)
+bool nav_set_heading_deg(float deg)
{
return nav_set_heading_rad(RadOfDeg(deg));
}
/** Set heading to point towards x,y position in local coordinates */
-bool_t nav_set_heading_towards(float x, float y)
+bool nav_set_heading_towards(float x, float y)
{
struct FloatVect2 target = {x, y};
struct FloatVect2 pos_diff;
@@ -532,18 +532,129 @@ bool_t 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 */
-bool_t nav_set_heading_towards_waypoint(uint8_t wp)
+bool nav_set_heading_towards_waypoint(uint8_t wp)
{
return nav_set_heading_towards(WaypointX(wp), WaypointY(wp));
}
/** Set heading to the current yaw angle */
-bool_t nav_set_heading_current(void)
+bool nav_set_heading_current(void)
{
nav_heading = stateGetNedToBodyEulers_i()->psi;
- return FALSE;
+ return false;
+}
+
+/************** Oval Navigation **********************************************/
+
+/** Navigation along a figure O. One side leg is defined by waypoints [p1] and
+ [p2].
+ The navigation goes through 4 states: OC1 (half circle next to [p1]),
+ OR21 (route [p2] to [p1], OC2 (half circle next to [p2]) and OR12
+ (opposite leg).
+
+ Initial state is the route along the desired segment (OC2).
+*/
+
+#ifndef LINE_START_FUNCTION
+#define LINE_START_FUNCTION {}
+#endif
+#ifndef LINE_STOP_FUNCTION
+#define LINE_STOP_FUNCTION {}
+#endif
+
+enum oval_status oval_status;
+uint8_t nav_oval_count;
+
+void nav_oval_init(void)
+{
+ oval_status = OC2;
+ nav_oval_count = 0;
+}
+
+void nav_oval(uint8_t p1, uint8_t p2, float radius)
+{
+ radius = - radius; /* Historical error ? */
+ int32_t alt = waypoints[p1].enu_i.z;
+ waypoints[p2].enu_i.z = alt;
+
+ float p2_p1_x = waypoints[p1].enu_f.x - waypoints[p2].enu_f.x;
+ float p2_p1_y = waypoints[p1].enu_f.y - waypoints[p2].enu_f.y;
+ float d = sqrtf(p2_p1_x * p2_p1_x + p2_p1_y * p2_p1_y);
+
+ /* Unit vector from p1 to p2 */
+ int32_t u_x = POS_BFP_OF_REAL(p2_p1_x / d);
+ int32_t u_y = POS_BFP_OF_REAL(p2_p1_y / d);
+
+ /* The half circle centers and the other leg */
+ struct EnuCoor_i p1_center = { waypoints[p1].enu_i.x + radius * -u_y,
+ waypoints[p1].enu_i.y + radius * u_x,
+ alt
+ };
+ struct EnuCoor_i p1_out = { waypoints[p1].enu_i.x + 2 * radius * -u_y,
+ waypoints[p1].enu_i.y + 2 * radius * u_x,
+ alt
+ };
+
+ struct EnuCoor_i p2_in = { waypoints[p2].enu_i.x + 2 * radius * -u_y,
+ waypoints[p2].enu_i.y + 2 * radius * u_x,
+ alt
+ };
+ struct EnuCoor_i p2_center = { waypoints[p2].enu_i.x + radius * -u_y,
+ waypoints[p2].enu_i.y + radius * u_x,
+ alt
+ };
+
+ int32_t qdr_out_2 = INT32_ANGLE_PI - int32_atan2_2(u_y, u_x);
+ int32_t qdr_out_1 = qdr_out_2 + INT32_ANGLE_PI;
+ if (radius < 0) {
+ qdr_out_2 += INT32_ANGLE_PI;
+ qdr_out_1 += INT32_ANGLE_PI;
+ }
+ int32_t qdr_anticipation = ANGLE_BFP_OF_REAL(radius > 0 ? -15 : 15);
+
+ switch (oval_status) {
+ case OC1 :
+ nav_circle(&p1_center, POS_BFP_OF_REAL(-radius));
+ if (NavQdrCloseTo(INT32_DEG_OF_RAD(qdr_out_1) - qdr_anticipation)) {
+ oval_status = OR12;
+ InitStage();
+ LINE_START_FUNCTION;
+ }
+ return;
+
+ case OR12:
+ nav_route(&p1_out, &p2_in);
+ if (nav_approaching_from(&p2_in, &p1_out, CARROT)) {
+ oval_status = OC2;
+ nav_oval_count++;
+ InitStage();
+ LINE_STOP_FUNCTION;
+ }
+ return;
+
+ case OC2 :
+ nav_circle(&p2_center, POS_BFP_OF_REAL(-radius));
+ if (NavQdrCloseTo(INT32_DEG_OF_RAD(qdr_out_2) - qdr_anticipation)) {
+ oval_status = OR21;
+ InitStage();
+ LINE_START_FUNCTION;
+ }
+ return;
+
+ case OR21:
+ nav_route(&waypoints[p2].enu_i, &waypoints[p1].enu_i);
+ if (nav_approaching_from(&waypoints[p1].enu_i, &waypoints[p2].enu_i, CARROT)) {
+ oval_status = OC1;
+ InitStage();
+ LINE_STOP_FUNCTION;
+ }
+ return;
+
+ default: /* Should not occur !!! Doing nothing */
+ return;
+ }
}
diff --git a/sw/airborne/firmwares/rotorcraft/navigation.h b/sw/airborne/firmwares/rotorcraft/navigation.h
index e7dfb04702..cacf10767b 100644
--- a/sw/airborne/firmwares/rotorcraft/navigation.h
+++ b/sw/airborne/firmwares/rotorcraft/navigation.h
@@ -60,7 +60,7 @@ extern float nav_climb_vspeed, nav_descend_vspeed;
extern int32_t nav_leg_progress;
extern uint32_t nav_leg_length;
-extern bool_t nav_survey_active;
+extern bool nav_survey_active;
extern uint8_t vertical_mode;
extern uint32_t nav_throttle; ///< direct throttle from 0:MAX_PPRZ, used in VERTICAL_MODE_MANUAL
@@ -71,7 +71,7 @@ extern float flight_altitude;
#define VERTICAL_MODE_ALT 2
extern float dist2_to_home; ///< squared distance to home waypoint
-extern bool_t too_far_from_home;
+extern bool too_far_from_home;
extern float failsafe_mode_dist2; ///< maximum squared distance to home wp before going to failsafe mode
extern float dist2_to_wp; ///< squared distance to next waypoint
@@ -84,33 +84,33 @@ extern void nav_home(void);
unit_t nav_reset_reference(void) __attribute__((unused));
unit_t nav_reset_alt(void) __attribute__((unused));
void nav_periodic_task(void);
-bool_t nav_detect_ground(void);
-bool_t nav_is_in_flight(void);
+bool nav_detect_ground(void);
+bool nav_is_in_flight(void);
-extern bool_t exception_flag[10];
+extern bool exception_flag[10];
extern void set_exception_flag(uint8_t flag_num);
-extern bool_t nav_set_heading_rad(float rad);
-extern bool_t nav_set_heading_deg(float deg);
-extern bool_t nav_set_heading_towards(float x, float y);
-extern bool_t nav_set_heading_towards_waypoint(uint8_t wp);
-extern bool_t nav_set_heading_current(void);
+extern bool nav_set_heading_rad(float rad);
+extern bool nav_set_heading_deg(float deg);
+extern bool nav_set_heading_towards(float x, float y);
+extern bool nav_set_heading_towards_waypoint(uint8_t wp);
+extern bool nav_set_heading_current(void);
/** default approaching_time for a wp */
#ifndef CARROT
#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) { \
@@ -133,12 +133,20 @@ extern void nav_circle(struct EnuCoor_i *wp_center, int32_t radius);
}
#define NavCircleCount() ((float)abs(nav_circle_radians) / INT32_ANGLE_2_PI)
-#define NavCircleQdr() ({ int32_t qdr = INT32_DEG_OF_RAD(INT32_ANGLE_2_PI_2 - nav_circle_qdr) >> INT32_ANGLE_FRAC; NormCourse(qdr); qdr; })
+#define NavCircleQdr() ({ int32_t qdr = INT32_DEG_OF_RAD(INT32_ANGLE_PI_2 - nav_circle_qdr) >> INT32_ANGLE_FRAC; NormCourse(qdr); qdr; })
+#define CloseDegAngles(_c1, _c2) ({ int32_t _diff = _c1 - _c2; NormCourse(_diff); 350 < _diff || _diff < 10; })
/** True if x (in degrees) is close to the current QDR (less than 10 degrees)*/
-#define NavQdrCloseTo(x) {}
+#define NavQdrCloseTo(x) CloseDegAngles(((x) >> INT32_ANGLE_FRAC), NavCircleQdr())
#define NavCourseCloseTo(x) {}
+enum oval_status { OR12, OC2, OR21, OC1 };
+
+extern void nav_oval_init(void);
+extern void nav_oval(uint8_t, uint8_t, float);
+extern uint8_t nav_oval_count;
+#define Oval(a, b, c) nav_oval((b), (a), (c))
+
/*********** Navigation along a line *************************************/
extern void nav_route(struct EnuCoor_i *wp_start, struct EnuCoor_i *wp_end);
#define NavSegment(_start, _end) { \
@@ -155,12 +163,12 @@ extern void nav_route(struct EnuCoor_i *wp_start, struct EnuCoor_i *wp_end);
}
/** Proximity tests on approaching a wp */
-bool_t nav_approaching_from(struct EnuCoor_i *wp, struct EnuCoor_i *from, int16_t approaching_time);
+bool nav_approaching_from(struct EnuCoor_i *wp, struct EnuCoor_i *from, int16_t approaching_time);
#define NavApproaching(wp, time) nav_approaching_from(&waypoints[wp].enu_i, NULL, time)
#define NavApproachingFrom(wp, from, time) nav_approaching_from(&waypoints[wp].enu_i, &waypoints[from].enu_i, time)
/** Check the time spent in a radius of 'ARRIVED_AT_WAYPOINT' around a wp */
-bool_t nav_check_wp_time(struct EnuCoor_i *wp, uint16_t stay_time);
+bool nav_check_wp_time(struct EnuCoor_i *wp, uint16_t stay_time);
#define NavCheckWaypointTime(wp, time) nav_check_wp_time(&waypoints[wp].enu_i, time)
/** Set the climb control to auto-throttle with the specified pitch
@@ -200,7 +208,7 @@ bool_t 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/rotorcraft/stabilization/stabilization_attitude.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude.h
index 8faecf40e2..6fe498da21 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude.h
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude.h
@@ -32,12 +32,12 @@
#include STABILIZATION_ATTITUDE_TYPE_H
extern void stabilization_attitude_init(void);
-extern void stabilization_attitude_read_rc(bool_t in_flight, bool_t in_carefree, bool_t coordinated_turn);
+extern void stabilization_attitude_read_rc(bool in_flight, bool in_carefree, bool coordinated_turn);
extern void stabilization_attitude_enter(void);
extern void stabilization_attitude_set_failsafe_setpoint(void);
extern void stabilization_attitude_set_rpy_setpoint_i(struct Int32Eulers *rpy);
extern void stabilization_attitude_set_earth_cmd_i(struct Int32Vect2 *cmd, int32_t heading);
-extern void stabilization_attitude_run(bool_t in_flight);
+extern void stabilization_attitude_run(bool in_flight);
#endif /* STABILIZATION_ATTITUDE_H */
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_float.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_float.c
index a22cdadc90..a1f223ef56 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_float.c
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_float.c
@@ -128,7 +128,7 @@ void stabilization_attitude_init(void)
#endif
}
-void stabilization_attitude_read_rc(bool_t in_flight, bool_t in_carefree, bool_t coordinated_turn)
+void stabilization_attitude_read_rc(bool in_flight, bool in_carefree, bool coordinated_turn)
{
stabilization_attitude_read_rc_setpoint_eulers_f(&stab_att_sp_euler, in_flight, in_carefree, coordinated_turn);
}
@@ -173,7 +173,7 @@ void stabilization_attitude_set_earth_cmd_i(struct Int32Vect2 *cmd, int32_t head
#define MAX_SUM_ERR 200
-void stabilization_attitude_run(bool_t in_flight)
+void stabilization_attitude_run(bool in_flight)
{
#if USE_ATT_REF
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_int.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_int.c
index c1bb520681..064492a1c6 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_int.c
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_euler_int.c
@@ -153,7 +153,7 @@ void stabilization_attitude_init(void)
#endif
}
-void stabilization_attitude_read_rc(bool_t in_flight, bool_t in_carefree, bool_t coordinated_turn)
+void stabilization_attitude_read_rc(bool in_flight, bool in_carefree, bool coordinated_turn)
{
stabilization_attitude_read_rc_setpoint_eulers(&stab_att_sp_euler, in_flight, in_carefree, coordinated_turn);
}
@@ -194,7 +194,7 @@ void stabilization_attitude_set_earth_cmd_i(struct Int32Vect2 *cmd, int32_t head
#define MAX_SUM_ERR 4000000
-void stabilization_attitude_run(bool_t in_flight)
+void stabilization_attitude_run(bool in_flight)
{
/* update reference */
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_passthrough.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_passthrough.c
index d5ec9ffeb7..1fa401d10f 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_passthrough.c
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_passthrough.c
@@ -46,7 +46,7 @@ void stabilization_attitude_init(void)
INT_EULERS_ZERO(stab_att_sp_euler);
}
-void stabilization_attitude_read_rc(bool_t in_flight, bool_t in_carefree, bool_t coordinated_turn)
+void stabilization_attitude_read_rc(bool in_flight, bool in_carefree, bool coordinated_turn)
{
//Read from RC
stabilization_attitude_read_rc_setpoint_eulers(&stab_att_sp_euler, in_flight, in_carefree, coordinated_turn);
@@ -57,7 +57,7 @@ void stabilization_attitude_enter(void)
}
-void stabilization_attitude_run(bool_t in_flight __attribute__((unused)))
+void stabilization_attitude_run(bool in_flight __attribute__((unused)))
{
/* For roll and pitch we pass trough the desired angles as stabilization command */
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c
index b21c32e2dc..fb0f207601 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_float.c
@@ -292,7 +292,7 @@ static void attitude_run_fb(float fb_commands[], struct FloatAttitudeGains *gain
#endif
}
-void stabilization_attitude_run(bool_t enable_integrator)
+void stabilization_attitude_run(bool enable_integrator)
{
/*
@@ -358,7 +358,7 @@ void stabilization_attitude_run(bool_t enable_integrator)
BoundAbs(stabilization_cmd[COMMAND_YAW], MAX_PPRZ);
}
-void stabilization_attitude_read_rc(bool_t in_flight, bool_t in_carefree, bool_t coordinated_turn)
+void stabilization_attitude_read_rc(bool in_flight, bool in_carefree, bool coordinated_turn)
{
stabilization_attitude_read_rc_setpoint_quat_f(&stab_att_sp_quat, in_flight, in_carefree, coordinated_turn);
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_indi.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_indi.c
index 82fb77d1ea..d171907d46 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_indi.c
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_indi.c
@@ -57,12 +57,12 @@ void stabilization_attitude_set_earth_cmd_i(struct Int32Vect2 *cmd, int32_t head
stabilization_indi_set_earth_cmd_i(cmd, heading);
}
-void stabilization_attitude_run(bool_t enable_integrator)
+void stabilization_attitude_run(bool enable_integrator)
{
stabilization_indi_run(enable_integrator, FALSE);
}
-void stabilization_attitude_read_rc(bool_t in_flight, bool_t in_carefree, bool_t coordinated_turn)
+void stabilization_attitude_read_rc(bool in_flight, bool in_carefree, bool coordinated_turn)
{
stabilization_indi_read_rc(in_flight, in_carefree, coordinated_turn);
}
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c
index ba3069cb71..ef97ae0081 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_quat_int.c
@@ -227,7 +227,7 @@ static void attitude_run_fb(int32_t fb_commands[], struct Int32AttitudeGains *ga
}
-void stabilization_attitude_run(bool_t enable_integrator)
+void stabilization_attitude_run(bool enable_integrator)
{
/*
@@ -291,7 +291,7 @@ void stabilization_attitude_run(bool_t enable_integrator)
BoundAbs(stabilization_cmd[COMMAND_YAW], MAX_PPRZ);
}
-void stabilization_attitude_read_rc(bool_t in_flight, bool_t in_carefree, bool_t coordinated_turn)
+void stabilization_attitude_read_rc(bool in_flight, bool in_carefree, bool coordinated_turn)
{
struct FloatQuat q_sp;
#if USE_EARTH_BOUND_RC_SETPOINT
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_rc_setpoint.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_rc_setpoint.c
index 5f275665fb..7e1f3c1ea0 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_rc_setpoint.c
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_rc_setpoint.c
@@ -161,8 +161,8 @@ float stabilization_attitude_get_heading_f(void)
* @param[in] in_flight true if in flight
* @param[out] sp attitude setpoint as euler angles
*/
-void stabilization_attitude_read_rc_setpoint_eulers(struct Int32Eulers *sp, bool_t in_flight, bool_t in_carefree,
- bool_t coordinated_turn)
+void stabilization_attitude_read_rc_setpoint_eulers(struct Int32Eulers *sp, bool in_flight, bool in_carefree,
+ bool coordinated_turn)
{
/* last time this function was called, used to calculate yaw setpoint update */
static float last_ts = 0.f;
@@ -241,8 +241,8 @@ void stabilization_attitude_read_rc_setpoint_eulers(struct Int32Eulers *sp, bool
}
-void stabilization_attitude_read_rc_setpoint_eulers_f(struct FloatEulers *sp, bool_t in_flight, bool_t in_carefree,
- bool_t coordinated_turn)
+void stabilization_attitude_read_rc_setpoint_eulers_f(struct FloatEulers *sp, bool in_flight, bool in_carefree,
+ bool coordinated_turn)
{
/* last time this function was called, used to calculate yaw setpoint update */
static float last_ts = 0.f;
@@ -364,8 +364,8 @@ void stabilization_attitude_read_rc_roll_pitch_earth_quat_f(struct FloatQuat *q)
* @param[in] in_flight true if in flight
* @param[out] q_sp attitude setpoint as quaternion
*/
-void stabilization_attitude_read_rc_setpoint_quat_f(struct FloatQuat *q_sp, bool_t in_flight, bool_t in_carefree,
- bool_t coordinated_turn)
+void stabilization_attitude_read_rc_setpoint_quat_f(struct FloatQuat *q_sp, bool in_flight, bool in_carefree,
+ bool coordinated_turn)
{
// FIXME: remove me, do in quaternion directly
@@ -417,8 +417,8 @@ void stabilization_attitude_read_rc_setpoint_quat_f(struct FloatQuat *q_sp, bool
}
//Function that reads the rc setpoint in an earth bound frame
-void stabilization_attitude_read_rc_setpoint_quat_earth_bound_f(struct FloatQuat *q_sp, bool_t in_flight,
- bool_t in_carefree, bool_t coordinated_turn)
+void stabilization_attitude_read_rc_setpoint_quat_earth_bound_f(struct FloatQuat *q_sp, bool in_flight,
+ bool in_carefree, bool coordinated_turn)
{
// FIXME: remove me, do in quaternion directly
// is currently still needed, since the yaw setpoint integration is done in eulers
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_rc_setpoint.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_rc_setpoint.h
index 80a5834df8..af7726b7ff 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_rc_setpoint.h
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude_rc_setpoint.h
@@ -33,15 +33,15 @@
extern void stabilization_attitude_reset_care_free_heading(void);
extern int32_t stabilization_attitude_get_heading_i(void);
extern float stabilization_attitude_get_heading_f(void);
-extern void stabilization_attitude_read_rc_setpoint_eulers(struct Int32Eulers *sp, bool_t in_flight, bool_t in_carefree,
- bool_t coordinated_turn);
-extern void stabilization_attitude_read_rc_setpoint_eulers_f(struct FloatEulers *sp, bool_t in_flight,
- bool_t in_carefree, bool_t coordinated_turn);
+extern void stabilization_attitude_read_rc_setpoint_eulers(struct Int32Eulers *sp, bool in_flight, bool in_carefree,
+ bool coordinated_turn);
+extern void stabilization_attitude_read_rc_setpoint_eulers_f(struct FloatEulers *sp, bool in_flight,
+ bool in_carefree, bool coordinated_turn);
extern void stabilization_attitude_read_rc_roll_pitch_quat_f(struct FloatQuat *q);
extern void stabilization_attitude_read_rc_roll_pitch_earth_quat_f(struct FloatQuat *q);
-extern void stabilization_attitude_read_rc_setpoint_quat_f(struct FloatQuat *q_sp, bool_t in_flight, bool_t in_carefree,
- bool_t coordinated_turn);
-extern void stabilization_attitude_read_rc_setpoint_quat_earth_bound_f(struct FloatQuat *q_sp, bool_t in_flight,
- bool_t in_carefree, bool_t coordinated_turn);
+extern void stabilization_attitude_read_rc_setpoint_quat_f(struct FloatQuat *q_sp, bool in_flight, bool in_carefree,
+ bool coordinated_turn);
+extern void stabilization_attitude_read_rc_setpoint_quat_earth_bound_f(struct FloatQuat *q_sp, bool in_flight,
+ bool in_carefree, bool coordinated_turn);
#endif /* STABILIZATION_ATTITUDE_RC_SETPOINT_H */
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi.c
index 9f7c356da5..dc283914c4 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi.c
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi.c
@@ -21,12 +21,13 @@
*/
/** @file stabilization_attitude_quat_indi.c
- * MAVLab Delft University of Technology
+ * @brief MAVLab Delft University of Technology
* This control algorithm is Incremental Nonlinear Dynamic Inversion (INDI)
*
- * This is a simplified implementation of the (soon to be) publication in the
+ * This is a simplified implementation of the publication in the
* journal of Control Guidance and Dynamics: Adaptive Incremental Nonlinear
* Dynamic Inversion for Attitude Control of Micro Aerial Vehicles
+ * http://arc.aiaa.org/doi/pdf/10.2514/1.G001490
*/
#include "firmwares/rotorcraft/stabilization/stabilization_indi.h"
@@ -43,6 +44,8 @@
#error You have to define the first order time constant of the actuator dynamics!
#endif
+// these parameters are used in the filtering of the angular acceleration
+// define them in the airframe file if different values are required
#ifndef STABILIZATION_INDI_FILT_OMEGA
#define STABILIZATION_INDI_FILT_OMEGA 50.0
#endif
@@ -51,6 +54,7 @@
#define STABILIZATION_INDI_FILT_ZETA 0.55
#endif
+// the yaw sometimes requires more filtering
#ifndef STABILIZATION_INDI_FILT_OMEGA_R
#define STABILIZATION_INDI_FILT_OMEGA_R STABILIZATION_INDI_FILT_OMEGA
#endif
@@ -71,7 +75,7 @@ struct Int32Eulers stab_att_sp_euler;
struct Int32Quat stab_att_sp_quat;
static int32_t stabilization_att_indi_cmd[COMMANDS_NB];
-static inline void stabilization_indi_calc_cmd(int32_t indi_commands[], struct Int32Quat *att_err, bool_t rate_control);
+static inline void stabilization_indi_calc_cmd(int32_t indi_commands[], struct Int32Quat *att_err, bool rate_control);
static void stabilization_indi_second_order_filter_init(struct IndiFilter *filter, float omega, float zeta, float omega_r);
static void stabilization_indi_second_order_filter(struct IndiFilter *filter, struct FloatRates *input);
static inline void lms_estimation(void);
@@ -196,7 +200,7 @@ void stabilization_indi_set_earth_cmd_i(struct Int32Vect2 *cmd, int32_t heading)
quat_from_earth_cmd_i(&stab_att_sp_quat, cmd, heading);
}
-static inline void stabilization_indi_calc_cmd(int32_t indi_commands[], struct Int32Quat *att_err, bool_t rate_control)
+static inline void stabilization_indi_calc_cmd(int32_t indi_commands[], struct Int32Quat *att_err, bool rate_control)
{
/* Propagate the second order filter on the gyroscopes */
struct FloatRates *body_rates = stateGetBodyRates_f();
@@ -231,8 +235,8 @@ static inline void stabilization_indi_calc_cmd(int32_t indi_commands[], struct I
indi.angular_accel_ref.r = indi.reference_acceleration.rate_r * ((float)radio_control.values[RADIO_YAW] / MAX_PPRZ * indi.max_rate - body_rates->r);
}
- //Incremented in angular acceleration requires increment in control input
- //G1 is the actuator effectiveness. In the yaw axis, we need something additional: G2.
+ //Increment in angular acceleration requires increment in control input
+ //G1 is the control effectiveness. In the yaw axis, we need something additional: G2.
//It takes care of the angular acceleration caused by the change in rotation rate of the propellers
//(they have significant inertia, see the paper mentioned in the header for more explanation)
indi.du.p = 1.0 / indi.g1.p * (indi.angular_accel_ref.p - indi.rate.dx.p);
@@ -259,6 +263,8 @@ static inline void stabilization_indi_calc_cmd(int32_t indi_commands[], struct I
stabilization_indi_second_order_filter(&indi.u, &indi.u_act_dyn);
//Don't increment if thrust is off
+ //TODO: this should be something more elegant, but without this the inputs will increment to the maximum before
+ //even getting in the air.
if (stabilization_cmd[COMMAND_THRUST] < 300) {
FLOAT_RATES_ZERO(indi.du);
FLOAT_RATES_ZERO(indi.u_act_dyn);
@@ -267,6 +273,7 @@ static inline void stabilization_indi_calc_cmd(int32_t indi_commands[], struct I
FLOAT_RATES_ZERO(indi.u.dx);
FLOAT_RATES_ZERO(indi.u.ddx);
} else {
+ // only run the estimation if the commands are not zero.
lms_estimation();
}
@@ -276,7 +283,7 @@ static inline void stabilization_indi_calc_cmd(int32_t indi_commands[], struct I
indi_commands[COMMAND_YAW] = indi.u_in.r;
}
-void stabilization_indi_run(bool_t enable_integrator __attribute__((unused)), bool_t rate_control)
+void stabilization_indi_run(bool enable_integrator __attribute__((unused)), bool rate_control)
{
/* attitude error */
struct Int32Quat att_err;
@@ -301,7 +308,7 @@ void stabilization_indi_run(bool_t enable_integrator __attribute__((unused)), bo
}
// This function reads rc commands
-void stabilization_indi_read_rc(bool_t in_flight, bool_t in_carefree, bool_t coordinated_turn)
+void stabilization_indi_read_rc(bool in_flight, bool in_carefree, bool coordinated_turn)
{
struct FloatQuat q_sp;
#if USE_EARTH_BOUND_RC_SETPOINT
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi.h
index 4b0d1bad87..c703f50de8 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi.h
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi.h
@@ -81,7 +81,7 @@ struct IndiVariables {
struct ReferenceSystem reference_acceleration;
- bool_t adaptive; ///< Enable adataptive estimation
+ bool adaptive; ///< Enable adataptive estimation
float max_rate; ///< Maximum rate in rate control
struct IndiEstimation est; ///< Estimation parameters for adaptive INDI
};
@@ -93,8 +93,8 @@ extern void stabilization_indi_enter(void);
extern void stabilization_indi_set_failsafe_setpoint(void);
extern void stabilization_indi_set_rpy_setpoint_i(struct Int32Eulers *rpy);
extern void stabilization_indi_set_earth_cmd_i(struct Int32Vect2 *cmd, int32_t heading);
-extern void stabilization_indi_run(bool_t enable_integrator, bool_t rate_control);
-extern void stabilization_indi_read_rc(bool_t in_flight, bool_t in_carefree, bool_t coordinated_turn);
+extern void stabilization_indi_run(bool enable_integrator, bool rate_control);
+extern void stabilization_indi_read_rc(bool in_flight, bool in_carefree, bool coordinated_turn);
#endif /* STABILIZATION_INDI_H */
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.c
index a3aca85b22..b300c0584f 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.c
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.c
@@ -52,7 +52,7 @@ void stabilization_none_enter(void)
INT_RATES_ZERO(stabilization_none_rc_cmd);
}
-void stabilization_none_run(bool_t in_flight __attribute__((unused)))
+void stabilization_none_run(bool in_flight __attribute__((unused)))
{
/* just directly pass rc commands through */
stabilization_cmd[COMMAND_ROLL] = stabilization_none_rc_cmd.p;
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.h
index 07ddd22aca..0b41b971e1 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.h
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.h
@@ -33,7 +33,7 @@
extern void stabilization_none_init(void);
extern void stabilization_none_read_rc(void);
-extern void stabilization_none_run(bool_t in_flight);
+extern void stabilization_none_run(bool in_flight);
extern void stabilization_none_enter(void);
extern struct Int32Rates stabilization_none_rc_cmd;
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate.c
index 9316a00bfe..dfac8bbe7e 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate.c
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate.c
@@ -184,7 +184,7 @@ void stabilization_rate_enter(void)
INT_RATES_ZERO(stabilization_rate_sum_err);
}
-void stabilization_rate_run(bool_t in_flight)
+void stabilization_rate_run(bool in_flight)
{
/* compute feed-back command */
struct Int32Rates _error;
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate.h
index 5263e4dd31..608b0b0bfa 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate.h
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate.h
@@ -33,7 +33,7 @@
extern void stabilization_rate_init(void);
extern void stabilization_rate_read_rc(void);
extern void stabilization_rate_read_rc_switched_sticks(void);
-extern void stabilization_rate_run(bool_t in_flight);
+extern void stabilization_rate_run(bool in_flight);
extern void stabilization_rate_enter(void);
extern struct Int32Rates stabilization_rate_sp;
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate_indi.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate_indi.c
index 7b25db30b8..195e24139b 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate_indi.c
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate_indi.c
@@ -48,7 +48,7 @@ void stabilization_rate_enter(void)
stabilization_indi_enter();
}
-void stabilization_rate_run(bool_t in_flight)
+void stabilization_rate_run(bool in_flight)
{
stabilization_indi_run(in_flight, TRUE);
}
diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate_indi.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate_indi.h
index 2fa0e919bf..64fad42cdf 100644
--- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate_indi.h
+++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_rate_indi.h
@@ -31,7 +31,7 @@
extern void stabilization_rate_init(void);
extern void stabilization_rate_read_rc(void);
extern void stabilization_rate_read_rc_switched_sticks(void);
-extern void stabilization_rate_run(bool_t in_flight);
+extern void stabilization_rate_run(bool in_flight);
extern void stabilization_rate_enter(void);
#endif /* STABILIZATION_RATE_INDI */
diff --git a/sw/airborne/firmwares/tutorial/main_demo5.c b/sw/airborne/firmwares/tutorial/main_demo5.c
index ea56b03cab..34fc19d8f8 100644
--- a/sw/airborne/firmwares/tutorial/main_demo5.c
+++ b/sw/airborne/firmwares/tutorial/main_demo5.c
@@ -46,19 +46,19 @@ 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);
}
}
uint16_t foo;
-bool_t dl_msg_available;
+bool dl_msg_available;
#define MSG_SIZE 128
uint8_t dl_buffer[MSG_SIZE] __attribute__((aligned));
diff --git a/sw/airborne/firmwares/wind_tunnel/main.c b/sw/airborne/firmwares/wind_tunnel/main.c
index ee1d7606ea..7f121c345c 100644
--- a/sw/airborne/firmwares/wind_tunnel/main.c
+++ b/sw/airborne/firmwares/wind_tunnel/main.c
@@ -23,7 +23,7 @@ static inline void main_event_task(void);
uint16_t motor_power;
uint8_t dl_buffer[MSG_SIZE] __attribute__((aligned));
-bool_t dl_msg_available;
+bool dl_msg_available;
uint16_t datalink_time;
int main(void)
@@ -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/main_mb.c b/sw/airborne/firmwares/wind_tunnel/main_mb.c
index 48cd7172a2..ff7122cf1a 100644
--- a/sw/airborne/firmwares/wind_tunnel/main_mb.c
+++ b/sw/airborne/firmwares/wind_tunnel/main_mb.c
@@ -22,7 +22,7 @@ static inline void main_event_task(void);
//uint16_t motor_power;
uint8_t dl_buffer[MSG_SIZE] __attribute__((aligned));
-bool_t dl_msg_available;
+bool dl_msg_available;
uint16_t datalink_time;
int main(void)
diff --git a/sw/airborne/firmwares/wind_tunnel/wt_baro.c b/sw/airborne/firmwares/wind_tunnel/wt_baro.c
index 92d5d2ed91..bf74ccf75b 100644
--- a/sw/airborne/firmwares/wind_tunnel/wt_baro.c
+++ b/sw/airborne/firmwares/wind_tunnel/wt_baro.c
@@ -29,9 +29,9 @@
#include "spi.h"
uint32_t wt_baro_pressure;
-bool_t wt_baro_available;
+bool wt_baro_available;
-static bool_t status_read_data;
+static bool status_read_data;
#define CMD_INIT_1 0x24 // set chanel AIN1/AIN2 and next operation on filter high
#define CMD_INIT_2 0xCF // set unipolar mode, 24 bits, no boost, filter high
@@ -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/firmwares/wind_tunnel/wt_baro.h b/sw/airborne/firmwares/wind_tunnel/wt_baro.h
index eae620f47c..804b189e96 100644
--- a/sw/airborne/firmwares/wind_tunnel/wt_baro.h
+++ b/sw/airborne/firmwares/wind_tunnel/wt_baro.h
@@ -30,7 +30,7 @@
extern uint8_t buf_input[3];
extern uint8_t buf_output[3];
-extern bool_t wt_baro_available;
+extern bool wt_baro_available;
extern uint32_t wt_baro_pressure;
extern void wt_baro_init(void);
diff --git a/sw/airborne/inter_mcu.c b/sw/airborne/inter_mcu.c
index 09b463da87..235fd01948 100644
--- a/sw/airborne/inter_mcu.c
+++ b/sw/airborne/inter_mcu.c
@@ -37,11 +37,11 @@ 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_t inter_mcu_received_fbw = FALSE;
-volatile bool_t 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 */
-bool_t ap_ok;
+bool ap_ok;
uint8_t time_since_last_ap;
#endif
diff --git a/sw/airborne/inter_mcu.h b/sw/airborne/inter_mcu.h
index 25a7e32ebf..cda7252e06 100644
--- a/sw/airborne/inter_mcu.h
+++ b/sw/airborne/inter_mcu.h
@@ -78,14 +78,14 @@ struct ap_state {
extern struct fbw_state *fbw_state;
extern struct ap_state *ap_state;
-extern volatile bool_t inter_mcu_received_fbw;
-extern volatile bool_t inter_mcu_received_ap;
+extern volatile bool inter_mcu_received_fbw;
+extern volatile bool inter_mcu_received_ap;
#ifdef FBW
extern uint8_t time_since_last_ap;
-extern bool_t ap_ok;
+extern bool ap_ok;
#define AP_STALLED_TIME 30 // 500ms with a 60Hz timer
@@ -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_can.h b/sw/airborne/link_mcu_can.h
index 6cab3833d7..82aa28b581 100644
--- a/sw/airborne/link_mcu_can.h
+++ b/sw/airborne/link_mcu_can.h
@@ -40,7 +40,7 @@ struct link_mcu_msg {
extern struct link_mcu_msg link_mcu_from_ap_msg;
extern struct link_mcu_msg link_mcu_from_fbw_msg;
-extern bool_t link_mcu_received;
+extern bool link_mcu_received;
extern void link_mcu_send(void);
extern void link_mcu_init(void);
diff --git a/sw/airborne/link_mcu_spi.c b/sw/airborne/link_mcu_spi.c
index 88a48a90b6..b573d4eff0 100644
--- a/sw/airborne/link_mcu_spi.c
+++ b/sw/airborne/link_mcu_spi.c
@@ -31,7 +31,7 @@ struct link_mcu_msg link_mcu_from_fbw_msg;
struct spi_transaction link_mcu_trans;
-bool_t link_mcu_received;
+bool link_mcu_received;
static uint16_t crc = 0;
@@ -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_spi.h b/sw/airborne/link_mcu_spi.h
index 9967bc5f71..5eeff0b527 100644
--- a/sw/airborne/link_mcu_spi.h
+++ b/sw/airborne/link_mcu_spi.h
@@ -48,7 +48,7 @@ extern struct link_mcu_msg link_mcu_from_fbw_msg;
extern struct spi_transaction link_mcu_trans;
-extern bool_t link_mcu_received;
+extern bool link_mcu_received;
extern void link_mcu_init(void);
extern void link_mcu_event_task(void);
diff --git a/sw/airborne/link_mcu_usart.c b/sw/airborne/link_mcu_usart.c
index a9189e7cbe..067e2e5d46 100644
--- a/sw/airborne/link_mcu_usart.c
+++ b/sw/airborne/link_mcu_usart.c
@@ -140,7 +140,7 @@
#define INTERMCU_MAX_PAYLOAD 255
struct InterMcuData {
- bool_t msg_available;
+ bool msg_available;
uint8_t msg_buf[INTERMCU_MAX_PAYLOAD] __attribute__((aligned));
uint8_t msg_id;
uint8_t msg_class;
@@ -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/link_mcu_usart.h b/sw/airborne/link_mcu_usart.h
index 375717d2f1..558e17d578 100644
--- a/sw/airborne/link_mcu_usart.h
+++ b/sw/airborne/link_mcu_usart.h
@@ -40,7 +40,7 @@ struct link_mcu_msg {
extern struct link_mcu_msg link_mcu_from_ap_msg;
extern struct link_mcu_msg link_mcu_from_fbw_msg;
-extern bool_t link_mcu_received;
+extern bool link_mcu_received;
extern void link_mcu_send(void);
extern void link_mcu_init(void);
diff --git a/sw/airborne/math/pprz_orientation_conversion.h b/sw/airborne/math/pprz_orientation_conversion.h
index f2ce4b5b9d..5c5d3fadbe 100644
--- a/sw/airborne/math/pprz_orientation_conversion.h
+++ b/sw/airborne/math/pprz_orientation_conversion.h
@@ -132,7 +132,7 @@ extern void orientationCalcEulers_f(struct OrientationReps *orientation);
/*********************** validity test functions ******************/
/// Test if orientations are valid.
-static inline bool_t orienationCheckValid(struct OrientationReps *orientation)
+static inline bool orienationCheckValid(struct OrientationReps *orientation)
{
return (orientation->status);
}
diff --git a/sw/airborne/mcu_periph/i2c.c b/sw/airborne/mcu_periph/i2c.c
index 9698d367a1..88be61853d 100644
--- a/sw/airborne/mcu_periph/i2c.c
+++ b/sw/airborne/mcu_periph/i2c.c
@@ -255,7 +255,7 @@ void i2c_init(struct i2c_periph *p)
}
-bool_t i2c_transmit(struct i2c_periph *p, struct i2c_transaction *t,
+bool i2c_transmit(struct i2c_periph *p, struct i2c_transaction *t,
uint8_t s_addr, uint8_t len)
{
t->type = I2CTransTx;
@@ -265,7 +265,7 @@ bool_t i2c_transmit(struct i2c_periph *p, struct i2c_transaction *t,
return i2c_submit(p, t);
}
-bool_t i2c_receive(struct i2c_periph *p, struct i2c_transaction *t,
+bool i2c_receive(struct i2c_periph *p, struct i2c_transaction *t,
uint8_t s_addr, uint16_t len)
{
t->type = I2CTransRx;
@@ -275,7 +275,7 @@ bool_t i2c_receive(struct i2c_periph *p, struct i2c_transaction *t,
return i2c_submit(p, t);
}
-bool_t i2c_transceive(struct i2c_periph *p, struct i2c_transaction *t,
+bool i2c_transceive(struct i2c_periph *p, struct i2c_transaction *t,
uint8_t s_addr, uint8_t len_w, uint16_t len_r)
{
t->type = I2CTransTxRx;
diff --git a/sw/airborne/mcu_periph/i2c.h b/sw/airborne/mcu_periph/i2c.h
index 0bae71c549..35f09c5677 100644
--- a/sw/airborne/mcu_periph/i2c.h
+++ b/sw/airborne/mcu_periph/i2c.h
@@ -222,7 +222,7 @@ extern void i2c_init(struct i2c_periph *p);
* @param p i2c peripheral to be used
* @return TRUE if idle
*/
-extern bool_t i2c_idle(struct i2c_periph *p);
+extern bool i2c_idle(struct i2c_periph *p);
/** Submit a I2C transaction.
* Must be implemented by the underlying architecture
@@ -230,7 +230,7 @@ extern bool_t i2c_idle(struct i2c_periph *p);
* @param t i2c transaction
* @return TRUE if insertion to the transaction queue succeded
*/
-extern bool_t i2c_submit(struct i2c_periph *p, struct i2c_transaction *t);
+extern bool i2c_submit(struct i2c_periph *p, struct i2c_transaction *t);
/** Set I2C bitrate.
* @param p i2c peripheral to be used
@@ -255,7 +255,7 @@ extern void i2c_event(void);
* @param len number of bytes to transmit
* @return TRUE if insertion to the transaction queue succeded
*/
-extern bool_t i2c_transmit(struct i2c_periph *p, struct i2c_transaction *t,
+extern bool i2c_transmit(struct i2c_periph *p, struct i2c_transaction *t,
uint8_t s_addr, uint8_t len);
/** Submit a read only transaction.
@@ -267,7 +267,7 @@ extern bool_t i2c_transmit(struct i2c_periph *p, struct i2c_transaction *t,
* @param len number of bytes to receive
* @return TRUE if insertion to the transaction queue succeded
*/
-extern bool_t i2c_receive(struct i2c_periph *p, struct i2c_transaction *t,
+extern bool i2c_receive(struct i2c_periph *p, struct i2c_transaction *t,
uint8_t s_addr, uint16_t len);
/** Submit a write/read transaction.
@@ -280,7 +280,7 @@ extern bool_t i2c_receive(struct i2c_periph *p, struct i2c_transaction *t,
* @param len_r number of bytes to receive
* @return TRUE if insertion to the transaction queue succeded
*/
-extern bool_t i2c_transceive(struct i2c_periph *p, struct i2c_transaction *t,
+extern bool i2c_transceive(struct i2c_periph *p, struct i2c_transaction *t,
uint8_t s_addr, uint8_t len_w, uint16_t len_r);
/** @}*/
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/spi.h b/sw/airborne/mcu_periph/spi.h
index a49345cade..a82b164d37 100644
--- a/sw/airborne/mcu_periph/spi.h
+++ b/sw/airborne/mcu_periph/spi.h
@@ -256,7 +256,7 @@ extern void spi_init_slaves(void);
* @param t spi transaction
* @return TRUE if insertion to the transaction queue succeeded
*/
-extern bool_t spi_submit(struct spi_periph *p, struct spi_transaction *t);
+extern bool spi_submit(struct spi_periph *p, struct spi_transaction *t);
/** Select a slave.
* @param slave slave id
@@ -276,7 +276,7 @@ extern void spi_slave_unselect(uint8_t slave);
* @param slave slave id
* @return true if correctly locked
*/
-extern bool_t spi_lock(struct spi_periph *p, uint8_t slave);
+extern bool spi_lock(struct spi_periph *p, uint8_t slave);
/** Resume the SPI fifo.
* Only the slave that locks the fifo can unlock it.
@@ -284,7 +284,7 @@ extern bool_t spi_lock(struct spi_periph *p, uint8_t slave);
* @param slave slave id
* @return true if correctly unlocked
*/
-extern bool_t spi_resume(struct spi_periph *p, uint8_t slave);
+extern bool spi_resume(struct spi_periph *p, uint8_t slave);
#endif /* SPI_MASTER */
@@ -349,7 +349,7 @@ extern void spi_slave_init(struct spi_periph *p);
* @param t spi transaction
* @return return true if registered with success
*/
-extern bool_t spi_slave_register(struct spi_periph *p, struct spi_transaction *t);
+extern bool spi_slave_register(struct spi_periph *p, struct spi_transaction *t);
/** Initialized and wait for the next transaction.
* If a transaction is registered for this peripheral, the spi will be
@@ -357,7 +357,7 @@ extern bool_t spi_slave_register(struct spi_periph *p, struct spi_transaction *t
* @param p spi peripheral to be used
* @return return true if a transaction was register for this peripheral
*/
-extern bool_t spi_slave_wait(struct spi_periph *p);
+extern bool spi_slave_wait(struct spi_periph *p);
#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 afee1b835f..94ac166110 100644
--- a/sw/airborne/mcu_periph/sys_time.h
+++ b/sw/airborne/mcu_periph/sys_time.h
@@ -58,9 +58,9 @@ typedef uint8_t tid_t; ///< sys_time timer id type
typedef void (*sys_time_cb)(uint8_t id);
struct sys_time_timer {
- bool_t in_use;
+ bool in_use;
sys_time_cb cb;
- volatile bool_t elapsed;
+ volatile bool elapsed;
uint32_t end_time; ///< in SYS_TIME_TICKS
uint32_t duration; ///< in SYS_TIME_TICKS
};
@@ -108,13 +108,13 @@ extern void sys_time_update_timer(tid_t id, float duration);
* @param id Timer id
* @return TRUE if timer has elapsed
*/
-static inline bool_t sys_time_check_and_ack_timer(tid_t id)
+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 bbb98f4246..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;
@@ -254,7 +254,7 @@ void uart_periph_init(struct uart_periph *p)
#endif
}
-bool_t uart_check_free_space(struct uart_periph *p, uint8_t len)
+bool uart_check_free_space(struct uart_periph *p, uint8_t len)
{
int16_t space = p->tx_extract_idx - p->tx_insert_idx;
if (space <= 0) {
diff --git a/sw/airborne/mcu_periph/uart.h b/sw/airborne/mcu_periph/uart.h
index 3a847a3a56..177bfd42b6 100644
--- a/sw/airborne/mcu_periph/uart.h
+++ b/sw/airborne/mcu_periph/uart.h
@@ -94,9 +94,9 @@ struct uart_periph {
extern void uart_periph_init(struct uart_periph *p);
extern void uart_periph_set_baudrate(struct uart_periph *p, uint32_t baud);
extern void uart_periph_set_bits_stop_parity(struct uart_periph *p, uint8_t bits, uint8_t stop, uint8_t parity);
-extern void uart_periph_set_mode(struct uart_periph *p, bool_t tx_enabled, bool_t rx_enabled, bool_t hw_flow_control);
+extern void uart_periph_set_mode(struct uart_periph *p, bool tx_enabled, bool rx_enabled, bool hw_flow_control);
extern void uart_put_byte(struct uart_periph *p, uint8_t data);
-extern bool_t uart_check_free_space(struct uart_periph *p, uint8_t len);
+extern bool uart_check_free_space(struct uart_periph *p, uint8_t len);
extern uint8_t uart_getch(struct uart_periph *p);
/**
diff --git a/sw/airborne/mcu_periph/udp.c b/sw/airborne/mcu_periph/udp.c
index bac4e0d009..b064d9a1cb 100644
--- a/sw/airborne/mcu_periph/udp.c
+++ b/sw/airborne/mcu_periph/udp.c
@@ -55,7 +55,7 @@ PRINT_CONFIG_VAR(UDP2_BROADCAST)
/**
* Initialize the UDP peripheral
*/
-void udp_periph_init(struct udp_periph *p, char *host, int port_out, int port_in, bool_t broadcast)
+void udp_periph_init(struct udp_periph *p, char *host, int port_out, int port_in, bool broadcast)
{
p->rx_insert_idx = 0;
p->rx_extract_idx = 0;
@@ -77,7 +77,7 @@ void udp_periph_init(struct udp_periph *p, char *host, int port_out, int port_in
* @param len how many bytes of free space to check for
* @return TRUE if enough space for len bytes
*/
-bool_t udp_check_free_space(struct udp_periph *p, uint8_t len)
+bool udp_check_free_space(struct udp_periph *p, uint8_t len)
{
return (UDP_TX_BUFFER_SIZE - p->tx_insert_idx) >= len;
}
diff --git a/sw/airborne/mcu_periph/udp.h b/sw/airborne/mcu_periph/udp.h
index 1d33f03325..636adf91b6 100644
--- a/sw/airborne/mcu_periph/udp.h
+++ b/sw/airborne/mcu_periph/udp.h
@@ -49,12 +49,12 @@ struct udp_periph {
struct link_device device;
};
-extern void udp_periph_init(struct udp_periph *p, char *host, int port_out, int port_in, bool_t broadcast);
-extern bool_t udp_check_free_space(struct udp_periph *p, uint8_t len);
+extern void udp_periph_init(struct udp_periph *p, char *host, int port_out, int port_in, bool broadcast);
+extern bool udp_check_free_space(struct udp_periph *p, uint8_t len);
extern void udp_put_byte(struct udp_periph *p, uint8_t data);
extern uint16_t udp_char_available(struct udp_periph *p);
extern uint8_t udp_getch(struct udp_periph *p);
-extern void udp_arch_periph_init(struct udp_periph *p, char *host, int port_out, int port_in, bool_t broadcast);
+extern void udp_arch_periph_init(struct udp_periph *p, char *host, int port_out, int port_in, bool broadcast);
extern void udp_send_message(struct udp_periph *p);
extern void udp_send_raw(struct udp_periph *p, uint8_t *buffer, uint16_t size);
extern void udp_receive(struct udp_periph *p);
diff --git a/sw/airborne/mcu_periph/usb_serial.h b/sw/airborne/mcu_periph/usb_serial.h
index 85126dc0f1..17582a967b 100644
--- a/sw/airborne/mcu_periph/usb_serial.h
+++ b/sw/airborne/mcu_periph/usb_serial.h
@@ -42,7 +42,7 @@ extern struct usb_serial_periph usb_serial;
void VCOM_init(void);
int VCOM_putchar(int c);
int VCOM_getchar(void);
-bool_t VCOM_check_free_space(uint8_t len);
+bool VCOM_check_free_space(uint8_t len);
int VCOM_check_available(void);
void VCOM_set_linecoding(uint8_t mode);
void VCOM_allow_linecoding(uint8_t mode);
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/air_data/air_data.h b/sw/airborne/modules/air_data/air_data.h
index 95dcd523c3..e8578068f1 100644
--- a/sw/airborne/modules/air_data/air_data.h
+++ b/sw/airborne/modules/air_data/air_data.h
@@ -44,11 +44,11 @@ struct AirData {
float tas_factor; ///< factor to convert equivalent airspeed (EAS) to true airspeed (TAS)
float qnh; ///< Barometric pressure adjusted to sea level in hPa, -1 if unknown
float amsl_baro; ///< altitude above sea level in m from pressure and QNH
- bool_t amsl_baro_valid; ///< TRUE if #amsl_baro is currently valid
- bool_t calc_airspeed; ///< if TRUE, calculate airspeed from differential pressure
- bool_t calc_qnh_once; ///< flag to calculate QNH with next pressure measurement
- bool_t calc_amsl_baro; ///< if TRUE, calculate #amsl_baro
- bool_t calc_tas_factor; ///< if TRUE, calculate #tas_factor when getting a temp measurement
+ bool amsl_baro_valid; ///< TRUE if #amsl_baro is currently valid
+ bool calc_airspeed; ///< if TRUE, calculate airspeed from differential pressure
+ bool calc_qnh_once; ///< flag to calculate QNH with next pressure measurement
+ bool calc_amsl_baro; ///< if TRUE, calculate #amsl_baro
+ bool calc_tas_factor; ///< if TRUE, calculate #tas_factor when getting a temp measurement
float aoa; ///< angle of attack (rad)
float sideslip; ///< sideslip angle (rad)
diff --git a/sw/airborne/modules/airborne_ant_track/airborne_ant_track.c b/sw/airborne/modules/airborne_ant_track/airborne_ant_track.c
index 92114ea377..df897793f8 100644
--- a/sw/airborne/modules/airborne_ant_track/airborne_ant_track.c
+++ b/sw/airborne/modules/airborne_ant_track/airborne_ant_track.c
@@ -41,7 +41,7 @@ typedef struct {
} MATRIX;
float airborne_ant_pan;
-static bool_t ant_pan_positive = 0;
+static bool ant_pan_positive = 0;
void ant_point(void);
static void vSubtractVectors(VECTOR *svA, VECTOR svB, VECTOR svC);
diff --git a/sw/airborne/modules/benchmark/flight_benchmark.c b/sw/airborne/modules/benchmark/flight_benchmark.c
index 05b931d805..256e6caa19 100644
--- a/sw/airborne/modules/benchmark/flight_benchmark.c
+++ b/sw/airborne/modules/benchmark/flight_benchmark.c
@@ -26,8 +26,8 @@ float SquareSumErr_position;
float ToleranceAispeed;
float ToleranceAltitude;
float TolerancePosition;
-bool_t benchm_reset;
-bool_t benchm_go;
+bool benchm_reset;
+bool benchm_go;
//uint8_t numOfCount;
diff --git a/sw/airborne/modules/benchmark/flight_benchmark.h b/sw/airborne/modules/benchmark/flight_benchmark.h
index d2cc190ae5..0aa9c83258 100644
--- a/sw/airborne/modules/benchmark/flight_benchmark.h
+++ b/sw/airborne/modules/benchmark/flight_benchmark.h
@@ -10,7 +10,7 @@ void flight_benchmark_reset(void);
extern float ToleranceAispeed;
extern float ToleranceAltitude;
extern float TolerancePosition;
-extern bool_t benchm_reset;
-extern bool_t benchm_go;
+extern bool benchm_reset;
+extern bool benchm_go;
#endif /* FLIGHTBENCHMARK_H */
diff --git a/sw/airborne/modules/cam_control/cam.c b/sw/airborne/modules/cam_control/cam.c
index e4cb371a51..768d47fe47 100644
--- a/sw/airborne/modules/cam_control/cam.c
+++ b/sw/airborne/modules/cam_control/cam.c
@@ -89,7 +89,7 @@ uint8_t cam_target_ac;
#define CAM_MODE0 CAM_MODE_OFF
#endif
uint8_t cam_mode;
-bool_t cam_lock;
+bool cam_lock;
int16_t cam_pan_command;
int16_t cam_tilt_command;
diff --git a/sw/airborne/modules/cam_control/cam.h b/sw/airborne/modules/cam_control/cam.h
index 3ebd0396be..71db7b9378 100644
--- a/sw/airborne/modules/cam_control/cam.h
+++ b/sw/airborne/modules/cam_control/cam.h
@@ -90,7 +90,7 @@ extern float test_cam_estimator_hspeed_dir;
#if defined(COMMAND_CAM_PWR_SW) || defined(VIDEO_TX_SWITCH)
-extern bool_t video_tx_state;
+extern bool video_tx_state;
#define VIDEO_TX_ON() { video_tx_state = 1; 0; }
#define VIDEO_TX_OFF() { video_tx_state = 0; 0; }
diff --git a/sw/airborne/modules/cam_control/point.c b/sw/airborne/modules/cam_control/point.c
index 37d6d5662c..395c383c39 100644
--- a/sw/airborne/modules/cam_control/point.c
+++ b/sw/airborne/modules/cam_control/point.c
@@ -95,7 +95,7 @@ typedef struct {
float cam_theta;
float cam_phi;
-bool_t heading_positive = 0;
+bool heading_positive = 0;
float memory_x, memory_y, memory_z;
#if defined(SHOW_CAM_COORDINATES)
float cam_point_x;
@@ -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 2ecd2c3c7d..9ec8555d07 100644
--- a/sw/airborne/modules/cartography/cartography.c
+++ b/sw/airborne/modules/cartography/cartography.c
@@ -96,7 +96,7 @@ uint16_t camera_snapshot_image_number = 0;
////////////////////////////////////////////////////////////////////////////////////////////////
-bool_t survey_losange_uturn;//this flag indicates if the aircraft is turning between 2 rails (1) or if it is flying straight forward in the rail direction (0)
+bool survey_losange_uturn;//this flag indicates if the aircraft is turning between 2 rails (1) or if it is flying straight forward in the rail direction (0)
int railnumber; //indicate the number of the rail being acquired
int numberofrailtodo;
@@ -130,7 +130,7 @@ float normBM, normAM, distancefromrail;
float course_next_rail;
float angle_between;
-bool_t ProjectionInsideLimitOfRail;
+bool ProjectionInsideLimitOfRail;
@@ -165,41 +165,41 @@ void stop_carto(void)
///////////////////////////////////////////////////////////////////////////////////////////////
-bool_t nav_survey_Inc_railnumberSinceBoot(void)
+bool nav_survey_Inc_railnumberSinceBoot(void)
{
railnumberSinceBoot++;
- return FALSE;
+ return false;
}
///////////////////////////////////////////////////////////////////////////////////////////////
-bool_t nav_survey_Snapshoot(void)
+bool nav_survey_Snapshoot(void)
{
camera_snapshot_image_number = railnumberSinceBoot;
PRTDEBSTR(SNAPSHOT)
cartography_periodic_downlink_carto_status = MODULES_START;
- return FALSE;
+ return false;
}
///////////////////////////////////////////////////////////////////////////////////////////////
-bool_t nav_survey_Snapshoot_Continu(void)
+bool nav_survey_Snapshoot_Continu(void)
{
camera_snapshot_image_number = railnumberSinceBoot;
PRTDEBSTR(SNAPSHOT)
cartography_periodic_downlink_carto_status = MODULES_START;
- return TRUE;
+ return true;
}
///////////////////////////////////////////////////////////////////////////////////////////////
-bool_t nav_survey_StopSnapshoot(void)
+bool nav_survey_StopSnapshoot(void)
{
camera_snapshot_image_number = 0;
PRTDEBSTR(STOP SNAPSHOT)
cartography_periodic_downlink_carto_status = MODULES_START;
- return FALSE;
+ return false;
}
///////////////////////////////////////////////////////////////////////////////////////////////
-bool_t nav_survey_computefourth_corner(uint8_t wp1, uint8_t wp2, uint8_t wp3, uint8_t wp4)
+bool nav_survey_computefourth_corner(uint8_t wp1, uint8_t wp2, uint8_t wp3, uint8_t wp4)
{
waypoints[wp4].x = waypoints[wp2].x + waypoints[wp3].x - waypoints[wp1].x;
waypoints[wp4].y = waypoints[wp2].y + waypoints[wp3].y - waypoints[wp1].y;
@@ -207,15 +207,15 @@ bool_t nav_survey_computefourth_corner(uint8_t wp1, uint8_t wp2, uint8_t wp3, u
PRTDEBSTR(nav_survey_computefourth_corner)
PRTDEB(f, waypoints[wp4].x)
PRTDEB(f, waypoints[wp4].y)
- return FALSE;
+ return false;
}
////////////////////////////////////////////////////////////////////////////////////////////////
-bool_t nav_survey_ComputeProjectionOnLine(struct point pointAf, struct point pointBf, float pos_xf, float pos_yf,
+bool nav_survey_ComputeProjectionOnLine(struct point pointAf, struct point pointBf, float pos_xf, float pos_yf,
float *normAMf, float *normBMf, float *distancefromrailf);
-bool_t nav_survey_ComputeProjectionOnLine(struct point pointAf, struct point pointBf, float pos_xf, float pos_yf,
+bool nav_survey_ComputeProjectionOnLine(struct point pointAf, struct point pointBf, float pos_xf, float pos_yf,
float *normAMf, float *normBMf, float *distancefromrailf)
//return if the projection of the estimator on the AB line is located inside the AB interval
{
@@ -310,10 +310,10 @@ bool_t nav_survey_ComputeProjectionOnLine(struct point pointAf, struct point po
///////////////////////////////////////////////////////////////////////////
//if distrailinit = 0, the aircraft travel from wp1 -> wp2 then do the inverse travel passing through the wp3,
//This mode could be use to register bands of images aquired in a first nav_survey_losange_carto, done perpendicularly
-bool_t nav_survey_losange_carto_init(uint8_t wp1, uint8_t wp2, uint8_t wp3, float distrailinit, float distplusinit)
+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_t nav_survey_losange_carto_init(uint8_t wp1, uint8_t wp2, uint8_t wp3, flo
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_t nav_survey_losange_carto_init(uint8_t wp1, uint8_t wp2, uint8_t wp3, flo
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,13 +405,13 @@ bool_t nav_survey_losange_carto_init(uint8_t wp1, uint8_t wp2, uint8_t wp3, flo
}
- 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();
}
////////////////////////////////////////////////////////////////////////////////////////////////
-bool_t nav_survey_losange_carto(void)
+bool nav_survey_losange_carto(void)
{
//test pour modifier en vol la valeur distrail
@@ -438,15 +438,15 @@ bool_t 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_t 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_t 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_t 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_t 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_t 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_t 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_t 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/cartography/cartography.h b/sw/airborne/modules/cartography/cartography.h
index 578b1d04d0..b4c3233bf8 100644
--- a/sw/airborne/modules/cartography/cartography.h
+++ b/sw/airborne/modules/cartography/cartography.h
@@ -17,7 +17,7 @@ void stop_carto(void);
#if USE_ONBOARD_CAMERA
-extern bool_t CAMERA_SNAPSHOT_REQUIERED;
+extern bool CAMERA_SNAPSHOT_REQUIERED;
extern uint16_t camera_snapshot_image_number;
#endif
@@ -28,15 +28,15 @@ extern float distrailinteractif; //pour exporter la variable et pouvoir la chang
///////////////////////////////////////////////////////////////////////////////////////////////
-extern bool_t nav_survey_Inc_railnumberSinceBoot(void);
-extern bool_t nav_survey_Snapshoot(void);
-bool_t nav_survey_Snapshoot_Continu(void);
-extern bool_t nav_survey_StopSnapshoot(void);
-extern bool_t nav_survey_computefourth_corner(uint8_t wp1, uint8_t wp2, uint8_t wp3, uint8_t wp4);
+extern bool nav_survey_Inc_railnumberSinceBoot(void);
+extern bool nav_survey_Snapshoot(void);
+bool nav_survey_Snapshoot_Continu(void);
+extern bool nav_survey_StopSnapshoot(void);
+extern bool nav_survey_computefourth_corner(uint8_t wp1, uint8_t wp2, uint8_t wp3, uint8_t wp4);
-extern bool_t nav_survey_losange_carto_init(uint8_t wp1, uint8_t wp2, uint8_t wp3, float distrail, float distplus);
+extern bool nav_survey_losange_carto_init(uint8_t wp1, uint8_t wp2, uint8_t wp3, float distrail, float distplus);
-extern bool_t nav_survey_losange_carto(
+extern bool nav_survey_losange_carto(
void); // !!!! important il faut mettre void en parametres d'entrée, sinon le compilo dit: attention : function declaration isn»t a prototype
//(uint8_t wp1, uint8_t wp2, uint8_t wp3);
diff --git a/sw/airborne/modules/com/generic_com.c b/sw/airborne/modules/com/generic_com.c
index bc14d467ef..7a8850f509 100644
--- a/sw/airborne/modules/com/generic_com.c
+++ b/sw/airborne/modules/com/generic_com.c
@@ -47,11 +47,11 @@
struct i2c_transaction com_trans;
-bool_t active_com;
+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 714e55180b..1675afa0da 100644
--- a/sw/airborne/modules/com/usb_serial_stm32_example1.c
+++ b/sw/airborne/modules/com/usb_serial_stm32_example1.c
@@ -35,7 +35,7 @@ void cmd_execute(void);
char cmd_buf[64];
uint8_t cmd_idx;
-bool_t cmd_avail;
+bool cmd_avail;
uint8_t prompt = '$';
/**
@@ -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 8fd6515617..cd4636af8a 100644
--- a/sw/airborne/modules/computer_vision/bebop_front_camera.c
+++ b/sw/airborne/modules/computer_vision/bebop_front_camera.c
@@ -70,9 +70,9 @@ struct bebopfrontcamera_t bebop_front_camera = {
.shot_number = 0
};
-void bebop_front_camera_take_shot(bool_t take)
+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/bebop_front_camera.h b/sw/airborne/modules/computer_vision/bebop_front_camera.h
index 2643f28be3..afaf5255af 100644
--- a/sw/airborne/modules/computer_vision/bebop_front_camera.h
+++ b/sw/airborne/modules/computer_vision/bebop_front_camera.h
@@ -38,12 +38,12 @@
struct bebopfrontcamera_t {
struct v4l2_device *dev; ///< The V4L2 device that is used for the video stream
uint8_t fps; ///< The amount of frames per second
- volatile bool_t take_shot; ///< Wether to take an image
+ volatile bool take_shot; ///< Wether to take an image
uint16_t shot_number; ///< The last shot number
- volatile bool_t is_streaming; ///< When the device is streaming
+ volatile bool is_streaming; ///< When the device is streaming
uint8_t downsize_factor; ///< Downsize factor during the stream
uint8_t quality_factor; ///< Quality factor during the stream
- bool_t use_rtp; ///< Stream over RTP
+ bool use_rtp; ///< Stream over RTP
};
extern struct bebopfrontcamera_t bebop_front_camera;
@@ -52,7 +52,7 @@ extern void bebop_front_camera_init(void);
extern void bebop_front_camera_periodic(void); ///< A dummy for now
extern void bebop_front_camera_start(void);
extern void bebop_front_camera_stop(void);
-extern void bebop_front_camera_take_shot(bool_t take);
+extern void bebop_front_camera_take_shot(bool take);
#endif /* BEBOP_FRONT_CAMERA_H */
diff --git a/sw/airborne/modules/computer_vision/cv_blob_locator.c b/sw/airborne/modules/computer_vision/cv_blob_locator.c
index 03e65456d8..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_t blob_enabled = FALSE;
-volatile bool_t marker_enabled = FALSE;
-volatile bool_t 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/cv_georeference.c b/sw/airborne/modules/computer_vision/cv_georeference.c
index 6d43c3437c..b589e10797 100644
--- a/sw/airborne/modules/computer_vision/cv_georeference.c
+++ b/sw/airborne/modules/computer_vision/cv_georeference.c
@@ -116,7 +116,7 @@ void georeference_project(struct camera_frame_t *tar, int wp)
}
}
-void georeference_filter(bool_t kalman, int wp, int length)
+void georeference_filter(bool kalman, int wp, int length)
{
struct Int32Vect3 err;
diff --git a/sw/airborne/modules/computer_vision/cv_georeference.h b/sw/airborne/modules/computer_vision/cv_georeference.h
index c016e33986..9978065e41 100644
--- a/sw/airborne/modules/computer_vision/cv_georeference.h
+++ b/sw/airborne/modules/computer_vision/cv_georeference.h
@@ -43,7 +43,7 @@ struct camera_frame_t {
};
void georeference_project(struct camera_frame_t *tar, int wp);
-void georeference_filter(bool_t kalman, int wp, int length);
+void georeference_filter(bool kalman, int wp, int length);
#endif
diff --git a/sw/airborne/modules/computer_vision/lib/encoding/jpeg.c b/sw/airborne/modules/computer_vision/lib/encoding/jpeg.c
index a957574fb9..bfa375eeca 100644
--- a/sw/airborne/modules/computer_vision/lib/encoding/jpeg.c
+++ b/sw/airborne/modules/computer_vision/lib/encoding/jpeg.c
@@ -422,7 +422,7 @@ void MakeTables(int q)
* @param[in] quality_factor Quality factor of the encoding (0-99)
* @param[in] add_dri_header Add the DRI header (needed for full JPEG)
*/
-void jpeg_encode_image(struct image_t *in, struct image_t *out, uint32_t quality_factor, bool_t add_dri_header)
+void jpeg_encode_image(struct image_t *in, struct image_t *out, uint32_t quality_factor, bool add_dri_header)
{
uint16_t i, j;
uint8_t *output_ptr = out->buf;
diff --git a/sw/airborne/modules/computer_vision/lib/encoding/jpeg.h b/sw/airborne/modules/computer_vision/lib/encoding/jpeg.h
index 1895cb3eb1..263feecb4d 100644
--- a/sw/airborne/modules/computer_vision/lib/encoding/jpeg.h
+++ b/sw/airborne/modules/computer_vision/lib/encoding/jpeg.h
@@ -32,7 +32,7 @@
#define RGB 4
/* JPEG encode an image */
-void jpeg_encode_image(struct image_t *in, struct image_t *out, uint32_t quality_factor, bool_t add_dri_header);
+void jpeg_encode_image(struct image_t *in, struct image_t *out, uint32_t quality_factor, bool add_dri_header);
/* Create an SVS header */
int jpeg_create_svs_header(unsigned char *buf, int32_t size, int w);
diff --git a/sw/airborne/modules/computer_vision/lib/v4l/v4l2.c b/sw/airborne/modules/computer_vision/lib/v4l/v4l2.c
index 857da3174e..ccdc4a40d4 100644
--- a/sw/airborne/modules/computer_vision/lib/v4l/v4l2.c
+++ b/sw/airborne/modules/computer_vision/lib/v4l/v4l2.c
@@ -127,7 +127,7 @@ static void *v4l2_capture_thread(void *data)
* @param[in] width,height The width and height of the images
* @return Whether the subdevice was successfully initialized
*/
-bool_t v4l2_init_subdev(char *subdev_name, uint8_t pad, uint8_t which, uint16_t code, uint16_t width, uint16_t height)
+bool v4l2_init_subdev(char *subdev_name, uint8_t pad, uint8_t which, uint16_t code, uint16_t width, uint16_t height)
{
struct v4l2_subdev_format sfmt;
CLEAR(sfmt);
@@ -136,14 +136,14 @@ bool_t v4l2_init_subdev(char *subdev_name, uint8_t pad, uint8_t which, uint16_t
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_t v4l2_init_subdev(char *subdev_name, uint8_t pad, uint8_t which, uint16_t
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;
}
/**
@@ -329,7 +329,7 @@ void v4l2_image_get(struct v4l2_device *dev, struct image_t *img)
* @param[out] *img The image that we got from the video device
* @return Whether we got an image or not
*/
-bool_t v4l2_image_get_nonblock(struct v4l2_device *dev, struct image_t *img)
+bool v4l2_image_get_nonblock(struct v4l2_device *dev, struct image_t *img)
{
uint16_t img_idx = V4L2_IMG_NONE;
@@ -343,7 +343,7 @@ bool_t 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_t 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;
}
}
@@ -384,7 +384,7 @@ void v4l2_image_free(struct v4l2_device *dev, struct image_t *img)
* but keep in mind that if it is already started it will
* return FALSE.
*/
-bool_t v4l2_start_capture(struct v4l2_device *dev)
+bool v4l2_start_capture(struct v4l2_device *dev)
{
uint8_t i;
enum v4l2_buf_type type;
@@ -392,7 +392,7 @@ bool_t 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_t 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_t 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_t v4l2_start_capture(struct v4l2_device *dev)
// Reset the thread
dev->thread = (pthread_t) NULL;
- return FALSE;
+ return false;
}
- return TRUE;
+ return true;
}
/**
@@ -443,33 +443,33 @@ bool_t v4l2_start_capture(struct v4l2_device *dev)
* @return TRUE if it successfully stopped capturing. Note that it also returns FALSE
* when the capturing is already stopped.
*/
-bool_t v4l2_stop_capture(struct v4l2_device *dev)
+bool v4l2_stop_capture(struct v4l2_device *dev)
{
enum v4l2_buf_type type;
// 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/v4l/v4l2.h b/sw/airborne/modules/computer_vision/lib/v4l/v4l2.h
index 3d211a9448..29c2174f5d 100644
--- a/sw/airborne/modules/computer_vision/lib/v4l/v4l2.h
+++ b/sw/airborne/modules/computer_vision/lib/v4l/v4l2.h
@@ -58,14 +58,14 @@ struct v4l2_device {
};
/* External functions */
-bool_t v4l2_init_subdev(char *subdev_name, uint8_t pad, uint8_t which, uint16_t code, uint16_t width, uint16_t height);
+bool v4l2_init_subdev(char *subdev_name, uint8_t pad, uint8_t which, uint16_t code, uint16_t width, uint16_t height);
struct v4l2_device *v4l2_init(char *device_name, uint16_t width, uint16_t height, uint8_t buffers_cnt,
uint32_t _pixelformat);
void v4l2_image_get(struct v4l2_device *dev, struct image_t *img);
-bool_t v4l2_image_get_nonblock(struct v4l2_device *dev, struct image_t *img);
+bool v4l2_image_get_nonblock(struct v4l2_device *dev, struct image_t *img);
void v4l2_image_free(struct v4l2_device *dev, struct image_t *img);
-bool_t v4l2_start_capture(struct v4l2_device *dev);
-bool_t v4l2_stop_capture(struct v4l2_device *dev);
+bool v4l2_start_capture(struct v4l2_device *dev);
+bool v4l2_stop_capture(struct v4l2_device *dev);
void v4l2_close(struct v4l2_device *dev);
#endif /* _CV_LIB_V4L2_H */
diff --git a/sw/airborne/modules/computer_vision/lib/vision/bayer.h b/sw/airborne/modules/computer_vision/lib/vision/bayer.h
index c9fd9c97cb..e09eda84f2 100644
--- a/sw/airborne/modules/computer_vision/lib/vision/bayer.h
+++ b/sw/airborne/modules/computer_vision/lib/vision/bayer.h
@@ -77,18 +77,18 @@ void BayerToYUV(struct image_t *in, struct image_t *out,
uint16_t R2 = ii[i + j * in->w + 1] / 2;
uint16_t B2 = ii[i + (j + 1) * in->w] / 2;
- uint32_t u, y1, v, y2;
+ uint32_t u, my1, v, my2;
- y1 = (0.256788 * R1 + 0.504129 * G1 + 0.097906 * B1) / 128 + 16;
- y2 = (0.256788 * R2 + 0.504129 * G2 + 0.097906 * B2) / 128 + 16;
+ my1 = (0.256788 * R1 + 0.504129 * G1 + 0.097906 * B1) / 128 + 16;
+ my2 = (0.256788 * R2 + 0.504129 * G2 + 0.097906 * B2) / 128 + 16;
u = (-0.148223 * (R1 + R2) - 0.290993 * (G1 + G2) + 0.439216 * (B1 + B2)) / 256 + 128;
v = (0.439216 * (R1 + R2) - 0.367788 * (G1 + G2) - 0.071427 * (B1 + B2)) / 256 + 128;
oi[(x + y * out->w) * 2] = clip(u);
- oi[(x + y * out->w) * 2 + 1] = clip(y1);
+ oi[(x + y * out->w) * 2 + 1] = clip(my1);
oi[(x + y * out->w) * 2 + 2] = clip(v);
- oi[(x + y * out->w) * 2 + 3] = clip(y2);
+ oi[(x + y * out->w) * 2 + 3] = clip(my2);
} else {
oi[(x + y * out->w) * 2] = 0;
oi[(x + y * out->w) * 2 + 1] = 0;
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 2444140b66..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_t 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 712ccafc26..32641aab7b 100644
--- a/sw/airborne/modules/computer_vision/lib/vision/lucas_kanade.c
+++ b/sw/airborne/modules/computer_vision/lib/vision/lucas_kanade.c
@@ -1,10 +1,3 @@
-/*
- * lucas_kanade.c
- *
- * Created on: Jan 11, 2016
- * Author: hrvoje
- */
-
/*
* Copyright (C) 2014 G. de Croon
* 2015 Freek van Tienen
@@ -44,6 +37,8 @@
/**
+ * @file lucas_kanade.c
+ *
* Compute the optical flow of several points using the pyramidal Lucas-Kanade algorithm by Yves Bouguet
* The initial fixed-point implementation is done by G. de Croon and is adapted by
* Freek van Tienen for the implementation in Paparazzi.
@@ -59,27 +54,26 @@
* @param[in] max_points The maximum amount of points to track, we skip x points and then take a point.
* @param[in] pyramid_level Level of pyramid used in computation (0 == no pyramids used)
* @return The vectors from the original *points in subpixels
+ *
+ * Pyramidal implementation of Lucas-Kanade feature tracker.
+ *
+ * Uses input images to build pyramid of padded images.
+ * For every pyramid level:
+ * For all points:
+ * - (1) determine the subpixel neighborhood in the old image
+ * - (2) get the x- and y- gradients
+ * - (3) determine the 'G'-matrix [sum(Axx) sum(Axy); sum(Axy) sum(Ayy)], where sum is over the window
+ * - (4) iterate over taking steps in the image to minimize the error:
+ * + [a] get the subpixel neighborhood in the new image
+ * + [b] determine the image difference between the two neighborhoods
+ * + [c] calculate the 'b'-vector
+ * + [d] calculate the additional flow step and possibly terminate the iteration
+ * - (5) use calculated flow as initial flow estimation for next level of pyramid
*/
struct flow_t *opticFlowLK(struct image_t *new_img, struct image_t *old_img, struct point_t *points,
uint16_t *points_cnt, uint16_t half_window_size,
uint16_t subpixel_factor, uint8_t max_iterations, uint8_t step_threshold, uint8_t max_points, uint8_t pyramid_level)
{
-
-
- // Pyramidal implementation of Lucas-Kanade feature tracker.
- // Uses input images to build pyramid of padded images.
- // For every pyramid level:
- // For all points:
- // (1) determine the subpixel neighborhood in the old image
- // (2) get the x- and y- gradients
- // (3) determine the 'G'-matrix [sum(Axx) sum(Axy); sum(Axy) sum(Ayy)], where sum is over the window
- // (4) iterate over taking steps in the image to minimize the error:
- // [a] get the subpixel neighborhood in the new image
- // [b] determine the image difference between the two neighborhoods
- // [c] calculate the 'b'-vector
- // [d] calculate the additional flow step and possibly terminate the iteration
- // (5) use calculated flow as initial flow estimation for next level of pyramid
-
// Allocate some memory for returning the vectors
struct flow_t *vectors = malloc(sizeof(struct flow_t) * max_points);
@@ -162,7 +156,7 @@ struct flow_t *opticFlowLK(struct image_t *new_img, struct image_t *old_img, str
}
// (4) iterate over taking steps in the image to minimize the error:
- bool_t tracked = TRUE;
+ bool tracked = true;
for (uint8_t it = max_iterations; it--;) {
struct point_t new_point = { vectors[new_p].pos.x + vectors[new_p].flow_x,
@@ -175,7 +169,7 @@ struct flow_t *opticFlowLK(struct image_t *new_img, struct image_t *old_img, str
|| (new_point.x > ((pyramid_new[LVL].w - 1 - 2 * border_size)*subpixel_factor))
|| (((int32_t)vectors[new_p].pos.y + vectors[new_p].flow_y) < 0)
|| (new_point.y > ((pyramid_new[LVL].h - 1 - 2 * border_size)*subpixel_factor))) {
- tracked = FALSE;
+ tracked = false;
break;
}
@@ -186,7 +180,7 @@ struct flow_t *opticFlowLK(struct image_t *new_img, struct image_t *old_img, str
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 12a2b140c7..e324640a15 100644
--- a/sw/airborne/modules/computer_vision/opticflow/opticflow_calculator.c
+++ b/sw/airborne/modules/computer_vision/opticflow/opticflow_calculator.c
@@ -156,7 +156,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;
@@ -203,7 +203,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/opticflow_calculator.h b/sw/airborne/modules/computer_vision/opticflow/opticflow_calculator.h
index 7bff1f2bac..a55302ef24 100644
--- a/sw/airborne/modules/computer_vision/opticflow/opticflow_calculator.h
+++ b/sw/airborne/modules/computer_vision/opticflow/opticflow_calculator.h
@@ -36,7 +36,7 @@
#include "lib/v4l/v4l2.h"
struct opticflow_t {
- bool_t got_first_img; ///< If we got a image to work with
+ bool got_first_img; ///< If we got a image to work with
float prev_phi; ///< Phi from the previous image frame
float prev_theta; ///< Theta from the previous image frame
struct image_t img_gray; ///< Current gray image frame
@@ -54,7 +54,7 @@ struct opticflow_t {
uint8_t pyramid_level; ///< Number of pyramid levels used in Lucas Kanade algorithm (0 == no pyramids used)
uint8_t max_track_corners; ///< Maximum amount of corners Lucas Kanade should track
- bool_t fast9_adaptive; ///< Whether the FAST9 threshold should be adaptive
+ bool fast9_adaptive; ///< Whether the FAST9 threshold should be adaptive
uint8_t fast9_threshold; ///< FAST9 corner detection threshold
uint16_t fast9_min_distance; ///< Minimum distance in pixels between corners
diff --git a/sw/airborne/modules/computer_vision/opticflow_module.c b/sw/airborne/modules/computer_vision/opticflow_module.c
index 25c7d37742..4cada86567 100644
--- a/sw/airborne/modules/computer_vision/opticflow_module.c
+++ b/sw/airborne/modules/computer_vision/opticflow_module.c
@@ -75,7 +75,7 @@ static struct opticflow_state_t opticflow_state; ///< State of the drone to co
static struct v4l2_device *opticflow_dev; ///< The opticflow camera V4L2 device
static abi_event opticflow_agl_ev; ///< The altitude ABI event
static pthread_t opticflow_calc_thread; ///< The optical flow calculation thread
-static bool_t opticflow_got_result; ///< When we have an optical flow calculation
+static bool opticflow_got_result; ///< When we have an optical flow calculation
static pthread_mutex_t opticflow_mutex; ///< Mutex lock fo thread safety
struct UdpSocket video_sock;
@@ -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);
}
@@ -210,13 +210,12 @@ void opticflow_module_start(void)
*/
void opticflow_module_stop(void)
{
- // Stop the capturing
- v4l2_stop_capture(opticflow_dev);
-
// Cancel the opticalflow calculation thread
if (pthread_cancel(opticflow_calc_thread) != 0) {
printf("Thread cancel did not work\n");
}
+ // Stop the capturing
+ v4l2_stop_capture(opticflow_dev);
}
/**
@@ -263,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/qrcode/qr_code.h b/sw/airborne/modules/computer_vision/qrcode/qr_code.h
index 907422d34f..b0bb60a71e 100644
--- a/sw/airborne/modules/computer_vision/qrcode/qr_code.h
+++ b/sw/airborne/modules/computer_vision/qrcode/qr_code.h
@@ -34,7 +34,7 @@
#include "../lib/vision/image.h"
extern void qrcode_init(void);
-extern bool_t qrscan(struct image_t *img);
+extern bool qrscan(struct image_t *img);
#endif
diff --git a/sw/airborne/modules/computer_vision/video_thread.c b/sw/airborne/modules/computer_vision/video_thread.c
index 209d1b01c9..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)) {
@@ -305,7 +305,7 @@ void video_thread_stop(void)
* Take a shot and save it
* This will only work when the streaming is enabled
*/
-void video_thread_take_shot(bool_t take)
+void video_thread_take_shot(bool take)
{
video_thread.take_shot = take;
}
diff --git a/sw/airborne/modules/computer_vision/video_thread.h b/sw/airborne/modules/computer_vision/video_thread.h
index 818f2f257d..2f9a3e4f43 100644
--- a/sw/airborne/modules/computer_vision/video_thread.h
+++ b/sw/airborne/modules/computer_vision/video_thread.h
@@ -34,11 +34,11 @@
// Main video_thread structure
struct video_thread_t {
- volatile bool_t is_running; ///< When the device is running
+ volatile bool is_running; ///< When the device is running
struct v4l2_device *dev; ///< The V4L2 device that is used for the video stream
uint8_t fps; ///< The amount of frames per second
- volatile bool_t take_shot; ///< Wether to take an image
+ volatile bool take_shot; ///< Wether to take an image
uint16_t shot_number; ///< The last shot number
};
extern struct video_thread_t video_thread;
@@ -48,7 +48,7 @@ extern void video_thread_init(void);
extern void video_thread_periodic(void); ///< A dummy for now
extern void video_thread_start(void);
extern void video_thread_stop(void);
-extern void video_thread_take_shot(bool_t take);
+extern void video_thread_take_shot(bool take);
#endif /* VIDEO_THREAD_H */
diff --git a/sw/airborne/modules/computer_vision/video_thread_nps.c b/sw/airborne/modules/computer_vision/video_thread_nps.c
index 042bf5c3f8..4940c2c819 100644
--- a/sw/airborne/modules/computer_vision/video_thread_nps.c
+++ b/sw/airborne/modules/computer_vision/video_thread_nps.c
@@ -74,4 +74,4 @@ void video_thread_periodic(void)
void video_thread_start(void) {}
void video_thread_stop(void) {}
-void video_thread_take_shot(bool_t take __attribute__((unused))) {}
+void video_thread_take_shot(bool take __attribute__((unused))) {}
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/computer_vision/viewvideo.h b/sw/airborne/modules/computer_vision/viewvideo.h
index 64d1dba6db..cb44ee5785 100644
--- a/sw/airborne/modules/computer_vision/viewvideo.h
+++ b/sw/airborne/modules/computer_vision/viewvideo.h
@@ -36,10 +36,10 @@
// Main viewvideo structure
struct viewvideo_t {
- volatile bool_t is_streaming; ///< When the device is streaming
+ volatile bool is_streaming; ///< When the device is streaming
uint8_t downsize_factor; ///< Downsize factor during the stream
uint8_t quality_factor; ///< Quality factor during the stream
- bool_t use_rtp; ///< Stream over RTP
+ bool use_rtp; ///< Stream over RTP
};
extern struct viewvideo_t viewvideo;
diff --git a/sw/airborne/modules/computer_vision/viewvideo_nps.c b/sw/airborne/modules/computer_vision/viewvideo_nps.c
index ad6acaa3da..cd1120521d 100644
--- a/sw/airborne/modules/computer_vision/viewvideo_nps.c
+++ b/sw/airborne/modules/computer_vision/viewvideo_nps.c
@@ -39,4 +39,4 @@ void viewvideo_init(void) {}
void viewvideo_periodic(void) {}
void viewvideo_start(void) {}
void viewvideo_stop(void) {}
-void viewvideo_take_shot(bool_t take __attribute__((unused))) {}
+void viewvideo_take_shot(bool take __attribute__((unused))) {}
diff --git a/sw/airborne/modules/core/trigger_ext.c b/sw/airborne/modules/core/trigger_ext.c
index afdc003616..3b60e712c4 100644
--- a/sw/airborne/modules/core/trigger_ext.c
+++ b/sw/airborne/modules/core/trigger_ext.c
@@ -32,5 +32,5 @@
uint32_t trigger_t0;
uint32_t trigger_delta_t0;
-volatile bool_t trigger_ext_valid;
+volatile bool trigger_ext_valid;
diff --git a/sw/airborne/modules/core/trigger_ext.h b/sw/airborne/modules/core/trigger_ext.h
index d1fdf07ad7..790cfd9ec5 100644
--- a/sw/airborne/modules/core/trigger_ext.h
+++ b/sw/airborne/modules/core/trigger_ext.h
@@ -40,7 +40,7 @@
extern uint32_t trigger_t0;
extern uint32_t trigger_delta_t0;
-extern volatile bool_t trigger_ext_valid;
+extern volatile bool trigger_ext_valid;
void trigger_ext_init(void);
diff --git a/sw/airborne/modules/ctrl/ctrl_module_demo.c b/sw/airborne/modules/ctrl/ctrl_module_demo.c
index a86bc71713..b24607938b 100644
--- a/sw/airborne/modules/ctrl/ctrl_module_demo.c
+++ b/sw/airborne/modules/ctrl/ctrl_module_demo.c
@@ -43,7 +43,7 @@ float ctrl_module_demo_y_ff_gain = 0.4f; // Yaw
float ctrl_module_demo_y_d_gain = 0.05f;
void ctrl_module_init(void);
-void ctrl_module_run(bool_t in_flight);
+void ctrl_module_run(bool in_flight);
void ctrl_module_init(void)
{
@@ -54,7 +54,7 @@ void ctrl_module_init(void)
}
// simple rate control without reference model nor attitude
-void ctrl_module_run(bool_t in_flight)
+void ctrl_module_run(bool in_flight)
{
if (!in_flight) {
// Reset integrators
@@ -96,7 +96,7 @@ void guidance_h_module_read_rc(void)
ctrl_module_demo.rc_z = radio_control.values[RADIO_YAW];
}
-void guidance_h_module_run(bool_t in_flight)
+void guidance_h_module_run(bool in_flight)
{
// Call full inner-/outerloop / horizontal-/vertical controller:
ctrl_module_run(in_flight);
@@ -113,7 +113,7 @@ void guidance_v_module_enter(void)
// your code that should be executed when entering this vertical mode goes here
}
-void guidance_v_module_run(UNUSED bool_t in_flight)
+void guidance_v_module_run(UNUSED bool in_flight)
{
// your vertical controller goes here
}
diff --git a/sw/airborne/modules/ctrl/ctrl_module_demo.h b/sw/airborne/modules/ctrl/ctrl_module_demo.h
index 67d20c03dd..4d84ae6891 100644
--- a/sw/airborne/modules/ctrl/ctrl_module_demo.h
+++ b/sw/airborne/modules/ctrl/ctrl_module_demo.h
@@ -47,11 +47,11 @@ extern float ctrl_module_demo_y_d_gain;
extern void guidance_h_module_init(void);
extern void guidance_h_module_enter(void);
extern void guidance_h_module_read_rc(void);
-extern void guidance_h_module_run(bool_t in_flight);
+extern void guidance_h_module_run(bool in_flight);
// Implement own Vertical loops
extern void guidance_v_module_init(void);
extern void guidance_v_module_enter(void);
-extern void guidance_v_module_run(bool_t in_flight);
+extern void guidance_v_module_run(bool in_flight);
#endif /* CTRL_MODULE_DEMO_H_ */
diff --git a/sw/airborne/modules/ctrl/vertical_ctrl_module_demo.c b/sw/airborne/modules/ctrl/vertical_ctrl_module_demo.c
index 3b33cd489b..14ce2bddf7 100644
--- a/sw/airborne/modules/ctrl/vertical_ctrl_module_demo.c
+++ b/sw/airborne/modules/ctrl/vertical_ctrl_module_demo.c
@@ -54,7 +54,7 @@ struct VerticalCtrlDemo v_ctrl;
void vertical_ctrl_module_init(void);
-void vertical_ctrl_module_run(bool_t in_flight);
+void vertical_ctrl_module_run(bool in_flight);
void vertical_ctrl_module_init(void)
{
@@ -69,7 +69,7 @@ void vertical_ctrl_module_init(void)
}
-void vertical_ctrl_module_run(bool_t in_flight)
+void vertical_ctrl_module_run(bool in_flight)
{
if (!in_flight) {
// Reset integrators
@@ -104,7 +104,7 @@ void guidance_v_module_enter(void)
v_ctrl.sum_err = 0.0f;
}
-void guidance_v_module_run(bool_t in_flight)
+void guidance_v_module_run(bool in_flight)
{
vertical_ctrl_module_run(in_flight);
}
diff --git a/sw/airborne/modules/ctrl/vertical_ctrl_module_demo.h b/sw/airborne/modules/ctrl/vertical_ctrl_module_demo.h
index 00ce243323..d5f834c3c7 100644
--- a/sw/airborne/modules/ctrl/vertical_ctrl_module_demo.h
+++ b/sw/airborne/modules/ctrl/vertical_ctrl_module_demo.h
@@ -49,6 +49,6 @@ extern struct VerticalCtrlDemo v_ctrl;
// Implement own Vertical loops
extern void guidance_v_module_init(void);
extern void guidance_v_module_enter(void);
-extern void guidance_v_module_run(bool_t in_flight);
+extern void guidance_v_module_run(bool in_flight);
#endif /* VERTICAL_CTRL_MODULE_DEMO_H_ */
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 a66bdaff7a..0ef5f3bb62 100644
--- a/sw/airborne/modules/display/max7456.c
+++ b/sw/airborne/modules/display/max7456.c
@@ -54,7 +54,7 @@
static char ascii_to_osd_c(char c);
static void osd_put_s(char *string, uint8_t attributes, uint8_t char_nb, uint8_t row, uint8_t column);
-static bool_t _osd_sprintf(char *buffer, char *string, float value);
+static bool _osd_sprintf(char *buffer, char *string, float value);
struct spi_transaction max7456_trans;
@@ -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_t 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):
@@ -362,7 +362,7 @@ static void osd_put_s(char *string, uint8_t attributes, uint8_t char_nb, uint8_t
}
// A VERY VERY STRIPED DOWN sprintf function suitable only for the paparazzi OSD.
-static bool_t _osd_sprintf(char *buffer, char *string, float value)
+static bool _osd_sprintf(char *buffer, char *string, float value)
{
uint8_t param_start = 0;
diff --git a/sw/airborne/modules/enose/anemotaxis.c b/sw/airborne/modules/enose/anemotaxis.c
index ba9589009f..d62b518194 100644
--- a/sw/airborne/modules/enose/anemotaxis.c
+++ b/sw/airborne/modules/enose/anemotaxis.c
@@ -18,16 +18,16 @@ static void last_plume_was_here(void)
last_plume.y = stateGetPositionEnu_f()->y;
}
-bool_t nav_anemotaxis_downwind(uint8_t c, float radius)
+bool nav_anemotaxis_downwind(uint8_t c, float radius)
{
struct FloatVect2 *wind = stateGetHorizontalWindspeed_f();
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_t nav_anemotaxis_init(uint8_t c)
+bool nav_anemotaxis_init(uint8_t c)
{
status = UTURN;
sign = 1;
@@ -36,10 +36,10 @@ bool_t 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_t nav_anemotaxis(uint8_t c, uint8_t c1, uint8_t c2, uint8_t plume)
+bool nav_anemotaxis(uint8_t c, uint8_t c1, uint8_t c2, uint8_t plume)
{
if (chemo_sensor) {
last_plume_was_here();
@@ -104,5 +104,5 @@ bool_t 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/anemotaxis.h b/sw/airborne/modules/enose/anemotaxis.h
index 16e571b252..19b55962ad 100644
--- a/sw/airborne/modules/enose/anemotaxis.h
+++ b/sw/airborne/modules/enose/anemotaxis.h
@@ -3,8 +3,8 @@
#include "std.h"
-extern bool_t nav_anemotaxis_downwind(uint8_t c, float radius);
-extern bool_t nav_anemotaxis_init(uint8_t c);
-extern bool_t nav_anemotaxis(uint8_t c, uint8_t c1, uint8_t c2, uint8_t plume);
+extern bool nav_anemotaxis_downwind(uint8_t c, float radius);
+extern bool nav_anemotaxis_init(uint8_t c);
+extern bool nav_anemotaxis(uint8_t c, uint8_t c1, uint8_t c2, uint8_t plume);
#endif /** ANEMOTAXIS_H */
diff --git a/sw/airborne/modules/enose/chemotaxis.c b/sw/airborne/modules/enose/chemotaxis.c
index 7733a4b94b..88f83c09dd 100644
--- a/sw/airborne/modules/enose/chemotaxis.c
+++ b/sw/airborne/modules/enose/chemotaxis.c
@@ -15,17 +15,17 @@ static uint8_t last_plume_value;
static float radius;
static int8_t sign;
-bool_t nav_chemotaxis_init(uint8_t c, uint8_t plume)
+bool nav_chemotaxis_init(uint8_t c, uint8_t plume)
{
radius = MAX_RADIUS;
last_plume_value = 0;
sign = 1;
waypoints[plume].x = waypoints[c].x;
waypoints[plume].y = waypoints[c].y;
- return FALSE;
+ return false;
}
-bool_t nav_chemotaxis(uint8_t c, uint8_t plume)
+bool nav_chemotaxis(uint8_t c, uint8_t plume)
{
if (chemo_sensor > last_plume_value) {
@@ -53,5 +53,5 @@ bool_t nav_chemotaxis(uint8_t c, uint8_t plume)
}
NavCircleWaypoint(c, radius);
- return TRUE;
+ return true;
}
diff --git a/sw/airborne/modules/enose/chemotaxis.h b/sw/airborne/modules/enose/chemotaxis.h
index ad0c26e587..629017098f 100644
--- a/sw/airborne/modules/enose/chemotaxis.h
+++ b/sw/airborne/modules/enose/chemotaxis.h
@@ -3,7 +3,7 @@
#include "std.h"
-extern bool_t nav_chemotaxis_init(uint8_t c, uint8_t plume);
-extern bool_t nav_chemotaxis(uint8_t c, uint8_t plume);
+extern bool nav_chemotaxis_init(uint8_t c, uint8_t plume);
+extern bool nav_chemotaxis(uint8_t c, uint8_t plume);
#endif /** CHEMOTAXIS_H */
diff --git a/sw/airborne/modules/enose/enose.c b/sw/airborne/modules/enose/enose.c
index 47bb5d1bc8..bb7fa9d614 100644
--- a/sw/airborne/modules/enose/enose.c
+++ b/sw/airborne/modules/enose/enose.c
@@ -18,7 +18,7 @@ uint16_t enose_PID_val;
#define ENOSE_HEAT_INIT 237
static uint8_t enose_conf_requested;
-static volatile bool_t enose_i2c_done;
+static volatile bool enose_i2c_done;
static struct adc_buf buf_PID;
@@ -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/geo_mag/geo_mag.h b/sw/airborne/modules/geo_mag/geo_mag.h
index bc3ca49145..cedee8dbe8 100644
--- a/sw/airborne/modules/geo_mag/geo_mag.h
+++ b/sw/airborne/modules/geo_mag/geo_mag.h
@@ -34,8 +34,8 @@
struct GeoMag {
struct DoubleVect3 vect;
- bool_t calc_once;
- bool_t ready;
+ bool calc_once;
+ bool ready;
};
extern void geo_mag_init(void);
diff --git a/sw/airborne/modules/gps/gps_i2c.c b/sw/airborne/modules/gps/gps_i2c.c
deleted file mode 100644
index 07241cce31..0000000000
--- a/sw/airborne/modules/gps/gps_i2c.c
+++ /dev/null
@@ -1,150 +0,0 @@
-/*
- * Copyright (C) 2009 ENAC, Pascal Brisset, Michel Gorraz,Gautier Hattenberger
- *
- * This file is part of paparazzi.
- *
- * paparazzi is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation; either version 2, or (at your option)
- * any later version.
- *
- * paparazzi is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with paparazzi; see the file COPYING. If not, write to
- * the Free Software Foundation, 59 Temple Place - Suite 330,
- * Boston, MA 02111-1307, USA.
- *
- */
-
-#include "modules/gps/gps_i2c.h"
-#include "mcu_periph/i2c.h"
-#include "subsystems/gps.h"
-
-struct i2c_transaction i2c_gps_trans;
-
-
-uint8_t gps_i2c_rx_buf[GPS_I2C_BUF_SIZE];
-uint8_t gps_i2c_rx_insert_idx, gps_i2c_rx_extract_idx;
-uint8_t gps_i2c_tx_buf[GPS_I2C_BUF_SIZE];
-uint8_t gps_i2c_tx_insert_idx, gps_i2c_tx_extract_idx;
-bool_t gps_i2c_done, gps_i2c_data_ready_to_transmit;
-
-/* u-blox5 protocole, page 4 */
-#define GPS_I2C_ADDR_NB_AVAIL_BYTES 0xFD
-#define GPS_I2C_ADDR_DATA 0xFF
-
-#define GPS_I2C_STATUS_IDLE 0
-#define GPS_I2C_STATUS_ASKING_DATA 1
-#define GPS_I2C_STATUS_ASKING_NB_AVAIL_BYTES 2
-#define GPS_I2C_STATUS_READING_NB_AVAIL_BYTES 3
-#define GPS_I2C_STATUS_READING_DATA 4
-
-#define gps_i2c_AddCharToRxBuf(_x) { \
- gps_i2c_rx_buf[gps_i2c_rx_insert_idx] = _x; \
- gps_i2c_rx_insert_idx++; /* size=256, No check for buf overflow */ \
- }
-
-static uint8_t gps_i2c_status;
-//static uint16_t gps_i2c_nb_avail_bytes; /* size buffer =~ 12k */
-//static uint8_t data_buf_len;
-
-void gps_i2c_init(void)
-{
- gps_i2c_status = GPS_I2C_STATUS_IDLE;
- gps_i2c_done = TRUE;
- gps_i2c_data_ready_to_transmit = FALSE;
- gps_i2c_rx_insert_idx = 0;
- gps_i2c_rx_extract_idx = 0;
- gps_i2c_tx_insert_idx = 0;
-#ifdef GPS_CONFIGURE
- /* The call in main_ap.c is made before the modules init (too early) */
- gps_configure_uart();
-#endif
-}
-
-void gps_i2c_periodic(void)
-{
- /*
- if (gps_i2c_done && gps_i2c_status == GPS_I2C_STATUS_IDLE) {
- i2c0_buf[0] = GPS_I2C_ADDR_NB_AVAIL_BYTES;
- i2c0_transmit_no_stop(GPS_I2C_SLAVE_ADDR, 1, &gps_i2c_done);
- gps_i2c_done = FALSE;
- gps_i2c_status = GPS_I2C_STATUS_ASKING_NB_AVAIL_BYTES;
- }
- */
-
-}
-
-void gps_i2c_event(void)
-{
- /*
- * switch (gps_i2c_status) {
- case GPS_I2C_STATUS_IDLE:
- if (gps_i2c_data_ready_to_transmit) {
- // Copy data from our buffer to the i2c buffer
- uint8_t data_size = Min(gps_i2c_tx_insert_idx-gps_i2c_tx_extract_idx, I2C0_BUF_LEN);
- uint8_t i;
- for(i = 0; i < data_size; i++, gps_i2c_tx_extract_idx++)
- i2c0_buf[i] = gps_i2c_tx_buf[gps_i2c_tx_extract_idx];
-
- // Start i2c transmit
- i2c0_transmit(GPS_I2C_SLAVE_ADDR, data_size, &gps_i2c_done);
- gps_i2c_done = FALSE;
-
- // Reset flag if finished
- if (gps_i2c_tx_extract_idx >= gps_i2c_tx_insert_idx) {
- gps_i2c_data_ready_to_transmit = FALSE;
- gps_i2c_tx_insert_idx = 0;
- }
- }
- break;
-
- case GPS_I2C_STATUS_ASKING_NB_AVAIL_BYTES:
- i2c0_receive(GPS_I2C_SLAVE_ADDR, 2, &gps_i2c_done);
- gps_i2c_done = FALSE;
- gps_i2c_status = GPS_I2C_STATUS_READING_NB_AVAIL_BYTES;
- break;
-
- case GPS_I2C_STATUS_READING_NB_AVAIL_BYTES:
- gps_i2c_nb_avail_bytes = (i2c0_buf[0]<<8) | i2c0_buf[1];
-
- if (gps_i2c_nb_avail_bytes)
- goto continue_reading;
- else
- gps_i2c_status = GPS_I2C_STATUS_IDLE;
- break;
-
- continue_reading:
-
- case GPS_I2C_STATUS_ASKING_DATA:
- data_buf_len = Min(gps_i2c_nb_avail_bytes, I2C0_BUF_LEN);
- gps_i2c_nb_avail_bytes -= data_buf_len;
-
- i2c0_receive(GPS_I2C_SLAVE_ADDR, data_buf_len, &gps_i2c_done);
- gps_i2c_done = FALSE;
- gps_i2c_status = GPS_I2C_STATUS_READING_DATA;
- break;
-
- case GPS_I2C_STATUS_READING_DATA: {
- uint8_t i;
- for(i = 0; i < data_buf_len; i++) {
- gps_i2c_AddCharToRxBuf(i2c0_buf[i]);
- }
-
- if (gps_i2c_nb_avail_bytes)
- goto continue_reading;
- else
- gps_i2c_status = GPS_I2C_STATUS_IDLE;
- break;
- }
-
- default:
- return;
- }
- */
-
-}
diff --git a/sw/airborne/modules/gps/gps_i2c.h b/sw/airborne/modules/gps/gps_i2c.h
deleted file mode 100644
index f89fe03d9f..0000000000
--- a/sw/airborne/modules/gps/gps_i2c.h
+++ /dev/null
@@ -1,57 +0,0 @@
-/*
- * Copyright (C) 2009 ENAC, Pascal Brisset, Michel Gorraz,Gautier Hattenberger
- *
- * This file is part of paparazzi.
- *
- * paparazzi is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation; either version 2, or (at your option)
- * any later version.
- *
- * paparazzi is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with paparazzi; see the file COPYING. If not, write to
- * the Free Software Foundation, 59 Temple Place - Suite 330,
- * Boston, MA 02111-1307, USA.
- *
- */
-
-#ifndef GPS_I2C
-#define GPS_I2C
-
-#include "std.h"
-
-/// Default address for u-blox (and others?)
-#define GPS_I2C_SLAVE_ADDR (0x42 << 1)
-
-#define GPS_I2C_BUF_SIZE 256
-extern uint8_t gps_i2c_rx_buf[GPS_I2C_BUF_SIZE];
-extern uint8_t gps_i2c_rx_insert_idx, gps_i2c_rx_extract_idx;
-extern uint8_t gps_i2c_tx_buf[GPS_I2C_BUF_SIZE];
-extern uint8_t gps_i2c_tx_insert_idx, gps_i2c_tx_extract_idx;
-
-extern bool_t gps_i2c_done, gps_i2c_data_ready_to_transmit;
-
-void gps_i2c_init(void);
-void gps_i2c_event(void);
-void gps_i2c_periodic(void);
-
-#define gps_i2cEvent() { if (gps_i2c_done) gps_i2c_event(); }
-#define gps_i2cChAvailable() (gps_i2c_rx_insert_idx != gps_i2c_rx_extract_idx)
-#define gps_i2cGetch() (gps_i2c_rx_buf[gps_i2c_rx_extract_idx++])
-#define gps_i2cTransmit(_char) { \
- if (! gps_i2c_data_ready_to_transmit) /* Else transmitting, overrun*/ \
- gps_i2c_tx_buf[gps_i2c_tx_insert_idx++] = _char; \
- }
-#define gps_i2cSendMessage() { \
- gps_i2c_data_ready_to_transmit = TRUE; \
- gps_i2c_tx_extract_idx = 0; \
- }
-// #define gps_i2cTxRunning (gps_i2c_data_ready_to_transmit)
-// #define gps_i2cInitParam(_baud, _uart_prm1, _uart_prm2) {}
-
-#endif // GPS_I2C
diff --git a/sw/airborne/modules/gps/gps_ubx_i2c.c b/sw/airborne/modules/gps/gps_ubx_i2c.c
new file mode 100644
index 0000000000..8ec8c6fd6d
--- /dev/null
+++ b/sw/airborne/modules/gps/gps_ubx_i2c.c
@@ -0,0 +1,223 @@
+/*
+ * Copyright (C) 2009 ENAC, Pascal Brisset, Michel Gorraz,Gautier Hattenberger,
+ * 2016 Michael Sierra
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+/**
+ * @file modules/gps/gps_ubx_i2c.c
+ * pprz link device for Ublox over I2C
+ *
+ * This module adds i2c functionality for the ublox using existing
+ * driver
+ */
+
+#include "mcu_periph/i2c.h"
+#include "modules/gps/gps_ubx_i2c.h"
+#include "subsystems/datalink/downlink.h"
+#include
+
+// ublox i2c address
+#define GPS_I2C_SLAVE_ADDR (0x42 << 1)
+
+#ifndef GPS_UBX_I2C_DEV
+#define GPS_UBX_I2C_DEV i2c2
+#endif
+PRINT_CONFIG_VAR(GPS_UBX_I2C_DEV)
+
+#define GPS_I2C_ADDR_NB_AVAIL_BYTES 0xFD ///< number of bytes available register
+#define GPS_I2C_ADDR_DATA 0xFF ///< data stream register
+
+// Global variables
+struct GpsUbxI2C gps_i2c;
+
+// Local variables
+bool gps_ubx_i2c_ucenter_done; ///< ucenter finished configuring flag
+uint16_t gps_ubx_i2c_bytes_to_read; ///< ublox bytes to read
+
+/** null function
+ * @param p unused
+ */
+void null_function(struct GpsUbxI2C *p);
+/** Put byte into transmit buffer.
+ * @param p unused
+ * @param data byte to put in buffer
+ */
+void gps_i2c_put_byte(struct GpsUbxI2C *p, uint8_t data);
+
+/** send buffer when ready
+ * @param p unused
+ */
+void gps_i2c_msg_ready(struct GpsUbxI2C *p);
+/** check if a new character is available
+ * @param p unused
+ */
+uint8_t gps_i2c_char_available(struct GpsUbxI2C *p);
+/** get a new char
+ * @param p unused
+ */
+uint8_t gps_i2c_getch(struct GpsUbxI2C *p);
+
+void gps_ubx_i2c_init(void)
+{
+ gps_ubx_i2c_ucenter_done = FALSE;
+ gps_i2c.read_state = gps_i2c_read_standby;
+ gps_i2c.write_state = gps_i2c_write_standby;
+
+ gps_i2c.trans.status = I2CTransDone;
+ gps_i2c.rx_buf_avail = 0;
+ gps_i2c.rx_buf_idx = 0;
+ gps_i2c.tx_buf_idx = 0;
+ gps_i2c.tx_rdy = TRUE;
+
+ gps_i2c.device.periph = (void *)&gps_i2c;
+ gps_i2c.device.check_free_space = (check_free_space_t)null_function; ///< check if transmit buffer is not full
+ gps_i2c.device.put_byte = (put_byte_t)gps_i2c_put_byte; ///< put one byte
+ gps_i2c.device.send_message = (send_message_t)gps_i2c_msg_ready; ///< send completed buffer
+ gps_i2c.device.char_available = (char_available_t)gps_i2c_char_available; ///< check if a new character is available
+ gps_i2c.device.get_byte = (get_byte_t)gps_i2c_getch; ///< get a new char
+ gps_i2c.device.set_baudrate = (set_baudrate_t)null_function; ///< set device baudrate
+}
+
+void null_function(struct GpsUbxI2C *p __attribute__((unused))) {}
+
+void gps_i2c_put_byte(struct GpsUbxI2C *p __attribute__((unused)), uint8_t data)
+{
+ gps_i2c.tx_buf[gps_i2c.tx_buf_idx++] = data;
+}
+
+void gps_i2c_msg_ready(struct GpsUbxI2C *p __attribute__((unused)))
+{
+ gps_i2c.write_state = gps_i2c_write_cfg;
+ gps_i2c.tx_rdy = FALSE;
+}
+
+uint8_t gps_i2c_char_available(struct GpsUbxI2C *p __attribute__((unused)))
+{
+ return (((int)gps_i2c.rx_buf_avail - (int)gps_i2c.rx_buf_idx) > 0);
+}
+
+bool gps_i2c_tx_is_ready(void)
+{
+ return gps_i2c.tx_rdy;
+}
+
+void gps_i2c_begin(void)
+{
+ gps_ubx_i2c_ucenter_done = TRUE;
+}
+
+uint8_t gps_i2c_getch(struct GpsUbxI2C *p __attribute__((unused)))
+{
+ return gps_i2c.rx_buf[gps_i2c.rx_buf_idx++];
+}
+
+void gps_ubx_i2c_periodic(void)
+{
+ if (gps_i2c.trans.status == I2CTransDone)
+ {
+ switch(gps_i2c.write_state)
+ {
+ case gps_i2c_write_standby:
+ if (!gps_i2c_char_available(&gps_i2c))
+ {
+ if (gps_ubx_i2c_bytes_to_read > GPS_I2C_BUF_SIZE || gps_ubx_i2c_ucenter_done)
+ {
+ gps_i2c.write_state = gps_i2c_write_request_size;
+ } else {
+ gps_i2c.tx_rdy = TRUE;
+ }
+ }
+ break;
+
+ case gps_i2c_write_request_size:
+ gps_i2c.trans.buf[0] = GPS_I2C_ADDR_NB_AVAIL_BYTES;
+ i2c_transceive(&GPS_UBX_I2C_DEV, &gps_i2c.trans, GPS_I2C_SLAVE_ADDR, 1, 2);
+ gps_i2c.write_state = gps_i2c_write_standby;
+ gps_i2c.read_state = gps_i2c_read_sizeof;
+ break;
+
+ case gps_i2c_write_cfg:
+ memcpy(&gps_i2c.trans.buf, gps_i2c.tx_buf, gps_i2c.tx_buf_idx);
+ i2c_transmit(&GPS_UBX_I2C_DEV, &gps_i2c.trans, GPS_I2C_SLAVE_ADDR, gps_i2c.tx_buf_idx);
+ gps_i2c.tx_buf_idx = 0;
+ gps_i2c.read_state = gps_i2c_read_standby;
+ gps_i2c.write_state = gps_i2c_write_request_size;
+ break;
+
+ default:
+ break;
+ }
+ }
+}
+
+void gps_ubx_i2c_read_event(void)
+{
+ switch(gps_i2c.read_state)
+ {
+ case gps_i2c_read_standby:
+ break;
+ break;
+
+ // how many bytes are available
+ case gps_i2c_read_sizeof:
+ gps_ubx_i2c_bytes_to_read = ((uint16_t)(gps_i2c.trans.buf[0]) << 7) | (uint16_t)(gps_i2c.trans.buf[1]);
+ gps_i2c.trans.status = I2CTransDone;
+ if (gps_ubx_i2c_bytes_to_read == 0xFFFF || gps_ubx_i2c_bytes_to_read == 0x0000)
+ {
+ gps_i2c.write_state = gps_i2c_write_request_size;
+ return;
+ } else if (gps_ubx_i2c_bytes_to_read > GPS_I2C_BUF_SIZE)
+ {
+ gps_i2c.trans.buf[0] = GPS_I2C_ADDR_DATA;
+ i2c_transceive(&GPS_UBX_I2C_DEV, &gps_i2c.trans, GPS_I2C_SLAVE_ADDR, 1, GPS_I2C_BUF_SIZE);
+ gps_i2c.read_state = gps_i2c_read_data;
+ } else
+ {
+ gps_i2c.trans.buf[0] = GPS_I2C_ADDR_DATA;
+ i2c_transceive(&GPS_UBX_I2C_DEV, &gps_i2c.trans, GPS_I2C_SLAVE_ADDR, 1, gps_ubx_i2c_bytes_to_read);
+ gps_i2c.read_state = gps_i2c_read_data;
+ return;
+ }
+ break;
+ case gps_i2c_read_data:
+ if (gps_ubx_i2c_bytes_to_read > GPS_I2C_BUF_SIZE)
+ {
+ memcpy(&gps_i2c.rx_buf, &gps_i2c.trans.buf, GPS_I2C_BUF_SIZE);
+ gps_i2c.rx_buf_idx = 0;
+ gps_i2c.rx_buf_avail = GPS_I2C_BUF_SIZE;
+ } else
+ {
+ memcpy(&gps_i2c.rx_buf, &gps_i2c.trans.buf, gps_ubx_i2c_bytes_to_read);
+ gps_i2c.rx_buf_idx = 0;
+ gps_i2c.rx_buf_avail = gps_ubx_i2c_bytes_to_read;
+ }
+
+ gps_i2c.write_state = gps_i2c_write_standby;
+ gps_i2c.read_state = gps_i2c_read_standby;
+ break;
+
+ default:
+ break;
+ }
+
+ // Transaction has been read
+ gps_i2c.trans.status = I2CTransDone;
+}
diff --git a/sw/airborne/modules/gps/gps_ubx_i2c.h b/sw/airborne/modules/gps/gps_ubx_i2c.h
new file mode 100644
index 0000000000..c5c0884fb2
--- /dev/null
+++ b/sw/airborne/modules/gps/gps_ubx_i2c.h
@@ -0,0 +1,111 @@
+/*
+ * Copyright (C) 2009 ENAC, Pascal Brisset, Michel Gorraz,Gautier Hattenberger,
+ * 2016 Michael Sierra
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+/**
+ * @file modules/gps/gps_ubx_i2c.h
+ * pprz link device for Ublox over I2C
+ *
+ * This module adds i2c functionality for the ublox using existing
+ * driver
+ */
+
+#ifndef GPS_UBX_I2C_H
+#define GPS_UBX_I2C_H
+
+#include "std.h"
+#include "mcu_periph/i2c.h"
+#include "pprzlink/pprzlink_device.h"
+
+#define GPS_I2C_BUF_SIZE 255
+
+/** read states
+ */
+typedef enum GpsI2CReadState
+{
+ gps_i2c_read_standby, ///< dont read anything
+ gps_i2c_read_sizeof, ///< read size of ubx buffer
+ gps_i2c_read_data ///< read data from ubx buffer
+} GpsI2CReadState;
+
+/** write states
+ */
+typedef enum GpsI2CWriteState
+{
+ gps_i2c_write_standby, ///< wait for gps_ubx to read buffer or ucenter to transmit
+ gps_i2c_write_request_size, ///< request size of ubx buffer
+ gps_i2c_write_cfg ///< send a config msg and get reply
+} GpsI2CWriteState;
+
+/** ubx_i2c state
+ */
+struct GpsUbxI2C
+{
+ GpsI2CReadState read_state;
+ GpsI2CWriteState write_state;
+
+ uint8_t rx_buf[GPS_I2C_BUF_SIZE]; ///< receive buffer
+ uint8_t tx_buf[GPS_I2C_BUF_SIZE]; ///< transmit buffer
+
+ uint16_t rx_buf_avail; ///< how many bytes are waiting to be read
+ uint16_t rx_buf_idx; ///< rx buf index
+ uint16_t tx_buf_idx; ///< tx buf index
+
+ bool tx_rdy; ///< are we ready to transmit
+
+ struct i2c_transaction trans; ///< i2c transaction
+
+ int baudrate; ///< baudrate, unused
+
+ struct link_device device; ///< ppz link device
+};
+
+extern struct GpsUbxI2C gps_i2c;
+/** init function
+ */
+extern void gps_ubx_i2c_init(void);
+/** handle message sending
+ */
+extern void gps_ubx_i2c_periodic(void);
+/** handle message reception
+ */
+extern void gps_ubx_i2c_read_event(void);
+/** is driver ready to send a message
+ */
+extern bool gps_i2c_tx_is_ready(void);
+/** config is done, begin reading messages
+ */
+extern void gps_i2c_begin(void);
+
+/** i2c event
+ */
+static inline void GpsUbxi2cEvent(void)
+{
+ if (gps_i2c.trans.status == I2CTransSuccess) {
+ gps_ubx_i2c_read_event();
+ } else if (gps_i2c.trans.status == I2CTransFailed) {
+ // if transaction failed, mark as done so can be retried
+ gps_i2c.trans.status = I2CTransDone;
+ }
+}
+
+#endif // GPS_UBX_I2C_H
\ No newline at end of file
diff --git a/sw/airborne/modules/gps/gps_ubx_ucenter.c b/sw/airborne/modules/gps/gps_ubx_ucenter.c
index 0b4b623666..e43a46f906 100644
--- a/sw/airborne/modules/gps/gps_ubx_ucenter.c
+++ b/sw/airborne/modules/gps/gps_ubx_ucenter.c
@@ -43,13 +43,15 @@
//////////////////////////////////////////////////////////////////////////////////////
//
// UCENTER: init, periodic and event
-
-static bool_t gps_ubx_ucenter_autobaud(uint8_t nr);
-static bool_t gps_ubx_ucenter_configure(uint8_t nr);
+#ifndef GPS_I2C
+static bool gps_ubx_ucenter_autobaud(uint8_t nr);
+#endif
+static bool gps_ubx_ucenter_configure(uint8_t nr);
#define GPS_UBX_UCENTER_STATUS_STOPPED 0
#define GPS_UBX_UCENTER_STATUS_AUTOBAUD 1
#define GPS_UBX_UCENTER_STATUS_CONFIG 2
+#define GPS_UBX_UCENTER_STATUS_WAITING 3
#define GPS_UBX_UCENTER_REPLY_NONE 0
#define GPS_UBX_UCENTER_REPLY_ACK 1
@@ -101,8 +103,13 @@ void gps_ubx_ucenter_periodic(void)
// Save processing time inflight
case GPS_UBX_UCENTER_STATUS_STOPPED:
return;
+ break;
// Automatically Determine Current Baudrate
case GPS_UBX_UCENTER_STATUS_AUTOBAUD:
+#ifdef GPS_I2C
+ gps_ubx_ucenter.cnt = 0;
+ gps_ubx_ucenter.status = GPS_UBX_UCENTER_STATUS_CONFIG;
+#else
if (gps_ubx_ucenter_autobaud(gps_ubx_ucenter.cnt) == FALSE) {
gps_ubx_ucenter.status = GPS_UBX_UCENTER_STATUS_CONFIG;
gps_ubx_ucenter.cnt = 0;
@@ -116,16 +123,29 @@ void gps_ubx_ucenter_periodic(void)
} else {
gps_ubx_ucenter.cnt++;
}
+#endif /* GPS_I2C */
break;
// Send Configuration
case GPS_UBX_UCENTER_STATUS_CONFIG:
if (gps_ubx_ucenter_configure(gps_ubx_ucenter.cnt) == FALSE) {
gps_ubx_ucenter.status = GPS_UBX_UCENTER_STATUS_STOPPED;
+#ifdef GPS_I2C
+ gps_i2c_begin();
+#endif
gps_ubx_ucenter.cnt = 0;
} else {
gps_ubx_ucenter.cnt++;
+#ifdef GPS_I2C
+ gps_ubx_ucenter.status = GPS_UBX_UCENTER_STATUS_WAITING;
}
break;
+ case GPS_UBX_UCENTER_STATUS_WAITING:
+ if (gps_i2c_tx_is_ready())
+ {
+ gps_ubx_ucenter.status = GPS_UBX_UCENTER_STATUS_CONFIG;
+#endif /*GPS_I2C*/
+ }
+ break;
default:
// stop this module now...
// todo
@@ -147,10 +167,10 @@ void gps_ubx_ucenter_event(void)
// Read Configuration Reply's
switch (gps_ubx.msg_class) {
case UBX_ACK_ID:
- if (gps_ubx.msg_id == UBX_ACK_ACK_ID) {
+ if (gps_ubx.msg_id & UBX_ACK_ACK_ID) {
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_ACK;
DEBUG_PRINT("ACK\n");
- } else {
+ } else if (gps_ubx.msg_id & UBX_ACK_NAK_ID) {
gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NACK;
DEBUG_PRINT("NACK\n");
}
@@ -226,7 +246,8 @@ static inline void gps_ubx_ucenter_enable_msg(uint8_t class, uint8_t id, uint8_t
* @param nr Autobaud step number to perform
* @return FALSE when completed
*/
-static bool_t gps_ubx_ucenter_autobaud(uint8_t nr)
+#ifndef GPS_I2C
+static bool gps_ubx_ucenter_autobaud(uint8_t nr)
{
switch (nr) {
case 0:
@@ -242,7 +263,7 @@ static bool_t 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?
@@ -251,7 +272,7 @@ static bool_t 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?
@@ -260,7 +281,7 @@ static bool_t 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?
@@ -269,7 +290,7 @@ static bool_t 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
@@ -278,7 +299,7 @@ static bool_t 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
@@ -287,20 +308,20 @@ static bool_t 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 */
/////////////////////////////////////
// UBlox internal Navigation Solution
@@ -393,7 +414,7 @@ static inline void gps_ubx_ucenter_config_port(void)
// I2C Interface
case GPS_PORT_DDC:
#ifdef GPS_I2C
- UbxSend_CFG_PRT(gps_ubx_ucenter.dev, gps_ubx_ucenter.port_id, 0x0, 0x0, GPS_I2C_SLAVE_ADDR, 0x0, UBX_PROTO_MASK | NMEA_PROTO_MASK, UBX_PROTO_MASK| NMEA_PROTO_MASK, 0x0, 0x0);
+ UbxSend_CFG_PRT(gps_ubx_ucenter.dev, gps_ubx_ucenter.port_id, 0x0, 0x0, (0x42<<1), 0x0, UBX_PROTO_MASK, UBX_PROTO_MASK, 0x0, 0x0);
#else
DEBUG_PRINT("WARNING: Please include the gps_i2c module.\n");
#endif
@@ -442,7 +463,7 @@ static inline void gps_ubx_ucenter_config_sbas(void)
// Text Telemetry for Debugging
#undef GOT_PAYLOAD
-static bool_t gps_ubx_ucenter_configure(uint8_t nr)
+static bool gps_ubx_ucenter_configure(uint8_t nr)
{
DEBUG_PRINT("gps_ubx_ucenter_configure nr: %u\n", nr);
@@ -457,6 +478,7 @@ static bool_t gps_ubx_ucenter_configure(uint8_t nr)
gps_ubx_ucenter_config_port();
break;
case 1:
+#ifndef GPS_I2C
#if PRINT_DEBUG_GPS_UBX_UCENTER
if (gps_ubx_ucenter.reply != GPS_UBX_UCENTER_REPLY_ACK) {
DEBUG_PRINT("ublox did not acknowledge port configuration.\n");
@@ -467,6 +489,7 @@ static bool_t gps_ubx_ucenter_configure(uint8_t nr)
// Now the GPS baudrate should have changed
uart_periph_set_baudrate(&(UBX_GPS_LINK), gps_ubx_ucenter.baud_target);
gps_ubx_ucenter.baud_run = UART_SPEED(gps_ubx_ucenter.baud_target);
+#endif /*GPS_I2C*/
UbxSend_MON_GET_VER(gps_ubx_ucenter.dev);
break;
case 2:
@@ -551,11 +574,11 @@ static bool_t 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/guidance_opticflow/guidance_opticflow_hover.c b/sw/airborne/modules/guidance_opticflow/guidance_opticflow_hover.c
index 62e3dbef04..e6daa87ba8 100644
--- a/sw/airborne/modules/guidance_opticflow/guidance_opticflow_hover.c
+++ b/sw/airborne/modules/guidance_opticflow/guidance_opticflow_hover.c
@@ -136,7 +136,7 @@ void guidance_h_module_read_rc(void)
* Main guidance loop
* @param[in] in_flight Whether we are in flight or not
*/
-void guidance_h_module_run(bool_t in_flight)
+void guidance_h_module_run(bool in_flight)
{
/* Update the setpoint */
stabilization_attitude_set_rpy_setpoint_i(&opticflow_stab.cmd);
diff --git a/sw/airborne/modules/guidance_opticflow/guidance_opticflow_hover.h b/sw/airborne/modules/guidance_opticflow/guidance_opticflow_hover.h
index 93fbe665a2..08a1e954e1 100644
--- a/sw/airborne/modules/guidance_opticflow/guidance_opticflow_hover.h
+++ b/sw/airborne/modules/guidance_opticflow/guidance_opticflow_hover.h
@@ -52,6 +52,6 @@ extern struct opticflow_stab_t opticflow_stab;
extern void guidance_h_module_init(void);
extern void guidance_h_module_enter(void);
extern void guidance_h_module_read_rc(void);
-extern void guidance_h_module_run(bool_t in_flight);
+extern void guidance_h_module_run(bool in_flight);
#endif /* GUIDANCE_OPTICFLOW_HOVER_H_ */
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 47081b186e..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_t 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/helicopter/throttle_curve.c b/sw/airborne/modules/helicopter/throttle_curve.c
index b709d99e5f..6304a281a1 100644
--- a/sw/airborne/modules/helicopter/throttle_curve.c
+++ b/sw/airborne/modules/helicopter/throttle_curve.c
@@ -49,7 +49,7 @@ void throttle_curve_init(void)
* Run the throttle curve and generate the output throttle and pitch
* This depends on the FMODE(flight mode) and TRHUST command
*/
-void throttle_curve_run(bool_t motors_on, pprz_t in_cmd[])
+void throttle_curve_run(bool motors_on, pprz_t in_cmd[])
{
// Calculate the mode value from the switch
int8_t mode = ((float)(in_cmd[COMMAND_FMODE] + MAX_PPRZ) / THROTTLE_CURVE_SWITCH_VAL);
diff --git a/sw/airborne/modules/helicopter/throttle_curve.h b/sw/airborne/modules/helicopter/throttle_curve.h
index 8fb4fef2f2..9c7324f29b 100644
--- a/sw/airborne/modules/helicopter/throttle_curve.h
+++ b/sw/airborne/modules/helicopter/throttle_curve.h
@@ -51,6 +51,6 @@ extern struct throttle_curve_t throttle_curve;
/* External functions */
extern void throttle_curve_init(void);
-void throttle_curve_run(bool_t motors_on, pprz_t in_cmd[]);
+void throttle_curve_run(bool motors_on, pprz_t in_cmd[]);
#endif
diff --git a/sw/airborne/modules/hott/hott.c b/sw/airborne/modules/hott/hott.c
index b5b1467552..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_t 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_t HOTT_REQ_UPDATE_GPS = FALSE;
+bool HOTT_REQ_UPDATE_GPS = false;
#endif
#if HOTT_SIM_EAM_SENSOR
-bool_t HOTT_REQ_UPDATE_EAM = FALSE;
+bool HOTT_REQ_UPDATE_EAM = false;
#endif
#if HOTT_SIM_VARIO_SENSOR
-bool_t HOTT_REQ_UPDATE_VARIO = FALSE;
+bool HOTT_REQ_UPDATE_VARIO = false;
#endif
#if HOTT_SIM_GAM_SENSOR
-bool_t 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.h b/sw/airborne/modules/ins/ahrs_chimu.h
index 6f47e2c638..0bc40c4e57 100644
--- a/sw/airborne/modules/ins/ahrs_chimu.h
+++ b/sw/airborne/modules/ins/ahrs_chimu.h
@@ -30,8 +30,8 @@
#include "subsystems/ahrs.h"
struct AhrsChimu {
- bool_t is_enabled;
- bool_t is_aligned;
+ bool is_enabled;
+ bool is_aligned;
};
extern struct AhrsChimu ahrs_chimu;
diff --git a/sw/airborne/modules/ins/ahrs_chimu_spi.c b/sw/airborne/modules/ins/ahrs_chimu_spi.c
index a52c2bdadf..f5edc7fd15 100644
--- a/sw/airborne/modules/ins/ahrs_chimu_spi.c
+++ b/sw/airborne/modules/ins/ahrs_chimu_spi.c
@@ -55,7 +55,7 @@ static void gps_cb(uint8_t sender_id __attribute__((unused)),
ahrs_chimu_update_gps(gps_s->fix, gps_s->speed_3d);
}
-static bool_t ahrs_chimu_enable_output(bool_t enable)
+static bool ahrs_chimu_enable_output(bool enable)
{
ahrs_chimu.is_enabled = enable;
return ahrs_chimu.is_enabled;
@@ -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 27aed008f6..c1b16891bd 100644
--- a/sw/airborne/modules/ins/ahrs_chimu_uart.c
+++ b/sw/airborne/modules/ins/ahrs_chimu_uart.c
@@ -32,7 +32,7 @@ INS_FORMAT ins_pitch_neutral;
struct AhrsChimu ahrs_chimu;
-static bool_t ahrs_chimu_enable_output(bool_t enable)
+static bool ahrs_chimu_enable_output(bool enable)
{
ahrs_chimu.is_enabled = enable;
return ahrs_chimu.is_enabled;
@@ -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/imu_xsens.c b/sw/airborne/modules/ins/imu_xsens.c
new file mode 100644
index 0000000000..37c186dd8f
--- /dev/null
+++ b/sw/airborne/modules/ins/imu_xsens.c
@@ -0,0 +1,96 @@
+/*
+ * Copyright (C) 2003 Pascal Brisset, Antoine Drouin
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+/** @file imu_xsens.c
+ * XSENS to just provide IMU measurements.
+ * For use with an external AHRS algorithm.
+ */
+
+#include "imu_xsens.h"
+#include "xsens.h"
+#include "xsens_common.h"
+
+#include "generated/airframe.h"
+
+#include "mcu_periph/sys_time.h"
+#include "subsystems/abi.h"
+
+static void handle_ins_msg(void);
+
+void imu_xsens_init(void)
+{
+ xsens_init();
+}
+
+void imu_xsens_event(void)
+{
+ xsens_event();
+ if (xsens.msg_received) {
+ parse_xsens_msg();
+ handle_ins_msg();
+ xsens.msg_received = FALSE;
+ }
+}
+
+static void handle_ins_msg(void)
+{
+ uint32_t now_ts = get_sys_time_usec();
+#ifdef XSENS_BACKWARDS
+ if (xsens.gyro_available) {
+ RATES_ASSIGN(imu.gyro_unscaled, -RATE_BFP_OF_REAL(xsens.gyro.p), -RATE_BFP_OF_REAL(xsens.gyro.q), RATE_BFP_OF_REAL(xsens.gyro.r));
+ xsens.gyro_available = FALSE;
+ imu_scale_gyro(&imu);
+ AbiSendMsgIMU_GYRO_INT32(IMU_XSENS_ID, now_ts, &imu.gyro);
+ }
+ if (xsens.accel_available) {
+ VECT3_ASSIGN(imu.accel_unscaled, -ACCEL_BFP_OF_REAL(xsens.accel.ax), -ACCEL_BFP_OF_REAL(xsens.accel.ay), ACCEL_BFP_OF_REAL(xsens.accel.az));
+ xsens.accel_available = FALSE;
+ imu_scale_accel(&imu);
+ AbiSendMsgIMU_ACCEL_INT32(IMU_XSENS_ID, now_ts, &imu.accel);
+ }
+ if (xsens.mag_available) {
+ VECT3_ASSIGN(imu.mag_unscaled, -MAG_BFP_OF_REAL(xsens.mag.mx), -MAG_BFP_OF_REAL(xsens.mag.my), MAG_BFP_OF_REAL(xsens.mag.mz));
+ xsens.mag_available = FALSE;
+ imu_scale_mag(&imu);
+ AbiSendMsgIMU_MAG_INT32(IMU_XSENS_ID, now_ts, &imu.mag);
+ }
+#else
+ if (xsens.gyro_available) {
+ RATES_BFP_OF_REAL(imu.gyro_unscaled, xsens.gyro);
+ xsens.gyro_available = FALSE;
+ imu_scale_gyro(&imu);
+ AbiSendMsgIMU_GYRO_INT32(IMU_XSENS_ID, now_ts, &imu.gyro);
+ }
+ if (xsens.accel_available) {
+ ACCELS_BFP_OF_REAL(imu.accel_unscaled, xsens.accel);
+ xsens.accel_available = FALSE;
+ imu_scale_accel(&imu);
+ AbiSendMsgIMU_ACCEL_INT32(IMU_XSENS_ID, now_ts, &imu.accel);
+ }
+ if (xsens.mag_available) {
+ MAGS_BFP_OF_REAL(imu.mag_unscaled, xsens.mag);
+ xsens.mag_available = FALSE;
+ imu_scale_mag(&imu);
+ AbiSendMsgIMU_MAG_INT32(IMU_XSENS_ID, now_ts, &imu.mag);
+ }
+#endif /* XSENS_BACKWARDS */
+}
diff --git a/sw/airborne/modules/ins/imu_xsens.h b/sw/airborne/modules/ins/imu_xsens.h
new file mode 100644
index 0000000000..d347515a52
--- /dev/null
+++ b/sw/airborne/modules/ins/imu_xsens.h
@@ -0,0 +1,45 @@
+/*
+ * Copyright (C) 2010 ENAC
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+/**
+ * @file modules/ins/imu_xsens.h
+ *
+ * XSENS to just provide IMU measurements.
+ * For use with an external AHRS algorithm.
+ */
+
+#ifndef IMU_XSENS_H
+#define IMU_XSENS_H
+
+#include "std.h"
+
+#include "subsystems/imu.h"
+#include "xsens.h"
+
+extern void imu_xsens_init(void);
+extern void imu_xsens_event(void);
+
+#define ImuEvent imu_xsens_event
+#define imu_impl_init imu_xsens_init
+#define imu_periodic xsens_periodic
+
+#endif
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 f9e319fa1f..9a73b40479 100644
--- a/sw/airborne/modules/ins/ins_arduimu_basic.c
+++ b/sw/airborne/modules/ins/ins_arduimu_basic.c
@@ -68,15 +68,15 @@ float ins_pitch_neutral;
// Ask the arduimu to recalibrate the gyros and accels neutrals
// After calibration, values are store in the arduimu eeprom
-bool_t arduimu_calibrate_neutrals;
+bool arduimu_calibrate_neutrals;
// High Accel Flag
#define HIGH_ACCEL_LOW_SPEED 15.0
#define HIGH_ACCEL_LOW_SPEED_RESUME 4.0 // Hysteresis
#define HIGH_ACCEL_HIGH_THRUST (0.8*MAX_PPRZ)
#define HIGH_ACCEL_HIGH_THRUST_RESUME (0.1*MAX_PPRZ) // Hysteresis
-bool_t high_accel_done;
-bool_t high_accel_flag;
+bool high_accel_done;
+bool high_accel_flag;
void ArduIMU_init(void)
{
@@ -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_arduimu_basic.h b/sw/airborne/modules/ins/ins_arduimu_basic.h
index ddb207539c..5a6b887a8a 100644
--- a/sw/airborne/modules/ins/ins_arduimu_basic.h
+++ b/sw/airborne/modules/ins/ins_arduimu_basic.h
@@ -35,7 +35,7 @@ extern struct FloatVect3 arduimu_accel;
extern float ins_roll_neutral;
extern float ins_pitch_neutral;
-extern bool_t arduimu_calibrate_neutrals;
+extern bool arduimu_calibrate_neutrals;
void ArduIMU_init(void);
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 15bf8cbce6..3a6fd7e349 100644
--- a/sw/airborne/modules/ins/ins_vn100.c
+++ b/sw/airborne/modules/ins/ins_vn100.c
@@ -106,7 +106,7 @@ void vn100_init(void)
}
-static inline bool_t ins_configure(void)
+static inline bool ins_configure(void)
{
// nothing to receive during conf
vn100_trans.input_length = 0;
@@ -128,13 +128,13 @@ static inline bool_t 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 f24b6d5f0c..b8f709d3bf 100644
--- a/sw/airborne/modules/ins/ins_xsens.c
+++ b/sw/airborne/modules/ins/ins_xsens.c
@@ -21,244 +21,28 @@
*/
/** @file ins_xsens.c
- * Parser for the Xsens protocol.
+ * Xsens as a full INS solution
*/
-#include "ins_module.h"
#include "ins_xsens.h"
+#include "xsens_common.h"
#include "subsystems/ins.h"
-#include
-
#include "generated/airframe.h"
#include "mcu_periph/sys_time.h"
-#include "pprzlink/messages.h"
+#include "subsystems/abi.h"
+#include "state.h"
#if USE_GPS_XSENS
#if !USE_GPS
#error "USE_GPS needs to be 1 to use the Xsens GPS!"
#endif
#include "subsystems/gps.h"
-#include "subsystems/abi.h"
-#include "math/pprz_geodetic_wgs84.h"
#include "math/pprz_geodetic_float.h"
#include "subsystems/navigation/common_nav.h" /* needed for nav_utm_zone0 */
-bool_t gps_xsens_msg_available;
#endif
-// positions
-INS_FORMAT ins_x;
-INS_FORMAT ins_y;
-INS_FORMAT ins_z;
-
-// velocities
-INS_FORMAT ins_vx;
-INS_FORMAT ins_vy;
-INS_FORMAT ins_vz;
-
-// body angles
-INS_FORMAT ins_phi;
-INS_FORMAT ins_theta;
-INS_FORMAT ins_psi;
-
-// angle rates
-INS_FORMAT ins_p;
-INS_FORMAT ins_q;
-INS_FORMAT ins_r;
-
-// accelerations
-INS_FORMAT ins_ax;
-INS_FORMAT ins_ay;
-INS_FORMAT ins_az;
-
-// magnetic
-INS_FORMAT ins_mx;
-INS_FORMAT ins_my;
-INS_FORMAT ins_mz;
-
-#if USE_INS_MODULE
-float ins_pitch_neutral;
-float ins_roll_neutral;
-#endif
-
-
-//////////////////////////////////////////////////////////////////////////////////////////
-//
-// XSens Specific
-//
-
-volatile uint8_t ins_msg_received;
-
-#define XsensInitCheksum() { send_ck = 0; }
-#define XsensUpdateChecksum(c) { send_ck += c; }
-
-#define XsensSend1(c) { uint8_t i8=c; InsUartSend1(i8); XsensUpdateChecksum(i8); }
-#define XsensSend1ByAddr(x) { XsensSend1(*x); }
-#define XsensSend2ByAddr(x) { XsensSend1(*(x+1)); XsensSend1(*x); }
-#define XsensSend4ByAddr(x) { XsensSend1(*(x+3)); XsensSend1(*(x+2)); XsensSend1(*(x+1)); XsensSend1(*x); }
-
-#define XsensHeader(msg_id, len) { \
- InsUartSend1(XSENS_START); \
- XsensInitCheksum(); \
- XsensSend1(XSENS_BID); \
- XsensSend1(msg_id); \
- XsensSend1(len); \
- }
-#define XsensTrailer() { uint8_t i8=0x100-send_ck; InsUartSend1(i8); }
-
-/** Includes macros generated from xsens_MTi-G.xml */
-#include "xsens_protocol.h"
-
-
-#define XSENS_MAX_PAYLOAD 254
-uint8_t xsens_msg_buf[XSENS_MAX_PAYLOAD];
-
-/* output mode : calibrated, orientation, position, velocity, status
- * -----------
- *
- * bit 0 temp
- * bit 1 calibrated
- * bit 2 orentation
- * bit 3 aux
- *
- * bit 4 position
- * bit 5 velocity
- * bit 6-7 Reserved
- *
- * bit 8-10 Reserved
- * bit 11 status
- *
- * bit 12 GPS PVT+baro
- * bit 13 Reserved
- * bit 14 Raw
- * bit 15 Reserved
- */
-
-#ifndef XSENS_OUTPUT_MODE
-#define XSENS_OUTPUT_MODE 0x1836
-#endif
-/* output settings : timestamp, euler, acc, rate, mag, float, no aux, lla, m/s, NED
- * -----------
- *
- * bit 01 0=none, 1=sample counter, 2=utc, 3=sample+utc
- * bit 23 0=quaternion, 1=euler, 2=DCM
- *
- * bit 4 1=disable acc output
- * bit 5 1=disable gyro output
- * bit 6 1=disable magneto output
- * bit 7 Reserved
- *
- * bit 89 0=float, 1=fixedpoint12.20, 2=fixedpoint16.32
- * bit 10 1=disable aux analog 1
- * bit 11 1=disable aux analog 2
- *
- * bit 12-15 0-only: 14-16 WGS84
- *
- * bit 16-19 0-only: 16-18 m/s XYZ
- *
- * bit 20-23 Reserved
- *
- * bit 24-27 Reseverd
- *
- * bit 28-30 Reseverd
- * bit 31 0=X-North-Z-Up, 1=North-East-Down
- */
-#ifndef XSENS_OUTPUT_SETTINGS
-#define XSENS_OUTPUT_SETTINGS 0x80000C05
-#endif
-
-#define UNINIT 0
-#define GOT_START 1
-#define GOT_BID 2
-#define GOT_MID 3
-#define GOT_LEN 4
-#define GOT_DATA 5
-#define GOT_CHECKSUM 6
-
-// FIXME Debugging Only
-#include "mcu_periph/uart.h"
-#include "pprzlink/messages.h"
-#include "subsystems/datalink/downlink.h"
-
-
-uint8_t xsens_errorcode;
-uint8_t xsens_msg_status;
-uint16_t xsens_time_stamp;
-uint16_t xsens_output_mode;
-uint32_t xsens_output_settings;
-
-
-float xsens_declination = 0;
-float xsens_gps_arm_x = 0;
-float xsens_gps_arm_y = 0;
-float xsens_gps_arm_z = 0;
-
-#if USE_GPS_XSENS
-struct LlaCoor_f lla_f;
-struct UtmCoor_f utm_f;
-#endif
-
-struct XsensTime xsens_time;
-
-static uint8_t xsens_id;
-static uint8_t xsens_status;
-static uint8_t xsens_len;
-static uint8_t xsens_msg_idx;
-static uint8_t ck;
-uint8_t send_ck;
-
-volatile int xsens_configured = 0;
-
-void xsens_init(void);
-
-void xsens_init(void)
-{
-
- xsens_status = UNINIT;
- xsens_configured = 20;
-
-#if USE_INS_MODULE
- ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT;
- ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT;
-#endif
-
- xsens_msg_status = 0;
- xsens_time_stamp = 0;
- xsens_output_mode = XSENS_OUTPUT_MODE;
- xsens_output_settings = XSENS_OUTPUT_SETTINGS;
-}
-
-#if USE_IMU
-struct ImuXsens imu_xsens;
-
-void imu_impl_init(void)
-{
- xsens_init();
- imu_xsens.gyro_available = FALSE;
- imu_xsens.accel_available = FALSE;
- imu_xsens.mag_available = FALSE;
-}
-
-void imu_periodic(void)
-{
- xsens_periodic();
-}
-#endif /* USE_IMU */
-
-#if USE_INS_MODULE
-void ins_xsens_update_gps(struct GpsState *gps_s);
-
-void ins_xsens_init(void)
-{
- struct UtmCoor_f utm0 = { nav_utm_north0, nav_utm_east0, 0., nav_utm_zone0 };
- stateSetLocalUtmOrigin_f(&utm0);
- stateSetPositionUtm_f(&utm0);
-
- xsens_init();
-}
-
-#include "subsystems/abi.h"
/** ABI binding for gps data.
* Used for GPS ABI messages.
*/
@@ -267,12 +51,15 @@ void ins_xsens_init(void)
#endif
PRINT_CONFIG_VAR(INS_XSENS_GPS_ID)
static abi_event gps_ev;
+
+float ins_pitch_neutral;
+float ins_roll_neutral;
+
+static void handle_ins_msg(void);
+static void update_state_interface(void);
static void gps_cb(uint8_t sender_id __attribute__((unused)),
uint32_t stamp __attribute__((unused)),
- struct GpsState *gps_s)
-{
- ins_xsens_update_gps(gps_s);
-}
+ struct GpsState *gps_s);
void ins_xsens_register(void)
{
@@ -280,7 +67,31 @@ void ins_xsens_register(void)
AbiBindMsgGPS(INS_XSENS_GPS_ID, &gps_ev, gps_cb);
}
-void ins_xsens_update_gps(struct GpsState *gps_s)
+void ins_xsens_init(void)
+{
+ xsens_init();
+
+ ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT;
+ ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT;
+
+ struct UtmCoor_f utm0 = { nav_utm_north0, nav_utm_east0, 0., nav_utm_zone0 };
+ stateSetLocalUtmOrigin_f(&utm0);
+ stateSetPositionUtm_f(&utm0);
+}
+
+void ins_xsens_event(void)
+{
+ xsens_event();
+ if (xsens.msg_received) {
+ parse_xsens_msg();
+ handle_ins_msg();
+ xsens.msg_received = false;
+ }
+}
+
+static void gps_cb(uint8_t sender_id __attribute__((unused)),
+ uint32_t stamp __attribute__((unused)),
+ struct GpsState *gps_s)
{
struct UtmCoor_f utm = utm_float_from_gps(gps_s, nav_utm_zone0);
utm.alt = gps_s->hmsl / 1000.;
@@ -296,485 +107,85 @@ void ins_xsens_update_gps(struct GpsState *gps_s)
// set velocity
stateSetSpeedNed_f(&ned_vel);
}
-#endif
#if USE_GPS_XSENS
void gps_xsens_init(void)
{
- gps.nb_channels = 0;
+ xsens.gps.nb_channels = 0;
}
static void gps_xsens_publish(void)
{
// publish gps data
uint32_t now_ts = get_sys_time_usec();
- gps.last_msg_ticks = sys_time.nb_sec_rem;
- gps.last_msg_time = sys_time.nb_sec;
- if (gps.fix == GPS_FIX_3D) {
- gps.last_3dfix_ticks = sys_time.nb_sec_rem;
- gps.last_3dfix_time = sys_time.nb_sec;
+ xsens.gps.last_msg_ticks = sys_time.nb_sec_rem;
+ xsens.gps.last_msg_time = sys_time.nb_sec;
+ if (xsens.gps.fix == GPS_FIX_3D) {
+ xsens.gps.last_3dfix_ticks = sys_time.nb_sec_rem;
+ xsens.gps.last_3dfix_time = sys_time.nb_sec;
}
- AbiSendMsgGPS(GPS_XSENS_ID, now_ts, &gps);
+ AbiSendMsgGPS(GPS_XSENS_ID, now_ts, &xsens.gps);
}
#endif
-void xsens_periodic(void)
-{
- if (xsens_configured > 0) {
- switch (xsens_configured) {
- case 20:
- /* send mode and settings to MT */
- XSENS_GoToConfig();
- XSENS_SetOutputMode(xsens_output_mode);
- XSENS_SetOutputSettings(xsens_output_settings);
- break;
- case 18:
- // Give pulses on SyncOut
- XSENS_SetSyncOutSettings(0, 0x0002);
- break;
- case 17:
- // 1 pulse every 100 samples
- XSENS_SetSyncOutSettings(1, 100);
- break;
- case 2:
- XSENS_ReqLeverArmGps();
- break;
- case 6:
- XSENS_ReqMagneticDeclination();
- break;
-
- case 13:
-#ifdef AHRS_H_X
-#pragma message "Sending XSens Magnetic Declination."
- xsens_declination = atan2(AHRS_H_Y, AHRS_H_X);
- XSENS_SetMagneticDeclination(xsens_declination);
-#endif
- break;
- case 12:
-#ifdef GPS_IMU_LEVER_ARM_X
-#pragma message "Sending XSens GPS Arm."
- XSENS_SetLeverArmGps(GPS_IMU_LEVER_ARM_X, GPS_IMU_LEVER_ARM_Y, GPS_IMU_LEVER_ARM_Z);
-#endif
- break;
- case 10: {
- uint8_t baud = 1;
- XSENS_SetBaudrate(baud);
- }
- break;
-
- case 1:
- XSENS_GoToMeasurment();
- break;
-
- default:
- break;
- }
- xsens_configured--;
- return;
- }
-
- RunOnceEvery(100, XSENS_ReqGPSStatus());
-}
-
-#if USE_INS_MODULE
-#include "state.h"
-
-static inline void update_state_interface(void)
+static void update_state_interface(void)
{
// Send to Estimator (Control)
#ifdef XSENS_BACKWARDS
struct FloatEulers att = {
- -ins_phi + ins_roll_neutral,
- -ins_theta + ins_pitch_neutral,
- ins_psi + RadOfDeg(180)
+ -xsens.euler.phi + ins_roll_neutral,
+ -xsens.euler.theta + ins_pitch_neutral,
+ xsens.euler.psi + RadOfDeg(180)
};
- struct FloatRates rates = {
- -ins_p,
- -ins_q,
- ins_r
+ struct FloatEulerstRates rates = {
+ -xsens.gyro.p,
+ -xsens.gyro.q,
+ xsens.gyro.r
};
#else
struct FloatEulers att = {
- ins_phi + ins_roll_neutral,
- ins_theta + ins_pitch_neutral,
- ins_psi
- };
- struct FloatRates rates = {
- ins_p,
- ins_q,
- ins_r
+ xsens.euler.phi + ins_roll_neutral,
+ xsens.euler.theta + ins_pitch_neutral,
+ xsens.euler.psi
};
+ struct FloatRates rates = xsens.gyro;
#endif
stateSetNedToBodyEulers_f(&att);
stateSetBodyRates_f(&rates);
}
-#endif /* USE_INS_MODULE */
-void handle_ins_msg(void)
+
+static void handle_ins_msg(void)
{
-#if USE_INS_MODULE
update_state_interface();
-#endif
-#if USE_IMU
- uint32_t now_ts = get_sys_time_usec();
-#ifdef XSENS_BACKWARDS
- if (imu_xsens.gyro_available) {
- RATES_ASSIGN(imu.gyro_unscaled, -RATE_BFP_OF_REAL(ins_p), -RATE_BFP_OF_REAL(ins_q), RATE_BFP_OF_REAL(ins_r));
- imu_xsens.gyro_available = FALSE;
- imu_scale_gyro(&imu);
- AbiSendMsgIMU_GYRO_INT32(IMU_XSENS_ID, now_ts, &imu.gyro);
+ if (xsens.new_attitude) {
+ new_ins_attitude = true;
+ xsens.new_attitude = false;
}
- if (imu_xsens.accel_available) {
- VECT3_ASSIGN(imu.accel_unscaled, -ACCEL_BFP_OF_REAL(ins_ax), -ACCEL_BFP_OF_REAL(ins_ay), ACCEL_BFP_OF_REAL(ins_az));
- imu_xsens.accel_available = FALSE;
- imu_scale_accel(&imu);
- AbiSendMsgIMU_ACCEL_INT32(IMU_XSENS_ID, now_ts, &imu.accel);
- }
- if (imu_xsens.mag_available) {
- VECT3_ASSIGN(imu.mag_unscaled, -MAG_BFP_OF_REAL(ins_mx), -MAG_BFP_OF_REAL(ins_my), MAG_BFP_OF_REAL(ins_mz));
- imu_xsens.mag_available = FALSE;
- imu_scale_mag(&imu);
- AbiSendMsgIMU_MAG_INT32(IMU_XSENS_ID, now_ts, &imu.mag);
- }
-#else
- if (imu_xsens.gyro_available) {
- RATES_ASSIGN(imu.gyro_unscaled, RATE_BFP_OF_REAL(ins_p), RATE_BFP_OF_REAL(ins_q), RATE_BFP_OF_REAL(ins_r));
- imu_xsens.gyro_available = FALSE;
- imu_scale_gyro(&imu);
- AbiSendMsgIMU_GYRO_INT32(IMU_XSENS_ID, now_ts, &imu.gyro);
- }
- if (imu_xsens.accel_available) {
- VECT3_ASSIGN(imu.accel_unscaled, ACCEL_BFP_OF_REAL(ins_ax), ACCEL_BFP_OF_REAL(ins_ay), ACCEL_BFP_OF_REAL(ins_az));
- imu_xsens.accel_available = FALSE;
- imu_scale_accel(&imu);
- AbiSendMsgIMU_ACCEL_INT32(IMU_XSENS_ID, now_ts, &imu.accel);
- }
- if (imu_xsens.mag_available) {
- VECT3_ASSIGN(imu.mag_unscaled, MAG_BFP_OF_REAL(ins_mx), MAG_BFP_OF_REAL(ins_my), MAG_BFP_OF_REAL(ins_mz));
- imu_xsens.mag_available = FALSE;
- imu_scale_mag(&imu);
- AbiSendMsgIMU_MAG_INT32(IMU_XSENS_ID, now_ts, &imu.mag);
- }
-#endif /* XSENS_BACKWARDS */
-#endif /* USE_IMU */
#if USE_GPS_XSENS
+ if (xsens.gps_available) {
+ // Horizontal speed
+ float fspeed = FLOAT_VECT2_NORM(xsens.vel);
+ if (xsens.gps.fix != GPS_FIX_3D) {
+ fspeed = 0;
+ }
+ xsens.gps.gspeed = fspeed * 100.;
+ xsens.gps.speed_3d = float_vect3_norm(&xsens.vel) * 100;
- // Horizontal speed
- float fspeed = sqrt(ins_vx * ins_vx + ins_vy * ins_vy);
- if (gps.fix != GPS_FIX_3D) {
- fspeed = 0;
+ float fcourse = atan2f(xsens.vel.y, xsens.vel.x);
+ xsens.gps.course = fcourse * 1e7;
+ SetBit(xsens.gps.valid_fields, GPS_VALID_COURSE_BIT);
+
+ gps_xsens_publish();
+ xsens.gps_available = false;
}
- gps.gspeed = fspeed * 100.;
- gps.speed_3d = (uint16_t)(sqrt(ins_vx * ins_vx + ins_vy * ins_vy + ins_vz * ins_vz) * 100);
-
- float fcourse = atan2f((float)ins_vy, (float)ins_vx);
- gps.course = fcourse * 1e7;
- SetBit(gps.valid_fields, GPS_VALID_COURSE_BIT);
#endif // USE_GPS_XSENS
}
-void parse_ins_msg(void)
-{
- uint8_t offset = 0;
- if (xsens_id == XSENS_ReqOutputModeAck_ID) {
- xsens_output_mode = XSENS_ReqOutputModeAck_mode(xsens_msg_buf);
- } else if (xsens_id == XSENS_ReqOutputSettings_ID) {
- xsens_output_settings = XSENS_ReqOutputSettingsAck_settings(xsens_msg_buf);
- } else if (xsens_id == XSENS_ReqMagneticDeclinationAck_ID) {
- xsens_declination = DegOfRad(XSENS_ReqMagneticDeclinationAck_declination(xsens_msg_buf));
-
- DOWNLINK_SEND_IMU_MAG_SETTINGS(DefaultChannel, DefaultDevice, &xsens_declination, &xsens_declination, &xsens_gps_arm_x,
- &xsens_gps_arm_y, &xsens_gps_arm_z);
- } else if (xsens_id == XSENS_ReqLeverArmGpsAck_ID) {
- xsens_gps_arm_x = XSENS_ReqLeverArmGpsAck_x(xsens_msg_buf);
- xsens_gps_arm_y = XSENS_ReqLeverArmGpsAck_y(xsens_msg_buf);
- xsens_gps_arm_z = XSENS_ReqLeverArmGpsAck_z(xsens_msg_buf);
-
- DOWNLINK_SEND_IMU_MAG_SETTINGS(DefaultChannel, DefaultDevice, &xsens_declination, &xsens_declination, &xsens_gps_arm_x,
- &xsens_gps_arm_y, &xsens_gps_arm_z);
- } else if (xsens_id == XSENS_Error_ID) {
- xsens_errorcode = XSENS_Error_errorcode(xsens_msg_buf);
- }
-#if USE_GPS_XSENS
- else if (xsens_id == XSENS_GPSStatus_ID) {
- gps.nb_channels = XSENS_GPSStatus_nch(xsens_msg_buf);
- gps.num_sv = 0;
-
- uint8_t i;
- // Do not write outside buffer
- for (i = 0; i < Min(gps.nb_channels, GPS_NB_CHANNELS); i++) {
- uint8_t ch = XSENS_GPSStatus_chn(xsens_msg_buf, i);
- if (ch > gps.nb_channels) { continue; }
- gps.svinfos[ch].svid = XSENS_GPSStatus_svid(xsens_msg_buf, i);
- gps.svinfos[ch].flags = XSENS_GPSStatus_bitmask(xsens_msg_buf, i);
- gps.svinfos[ch].qi = XSENS_GPSStatus_qi(xsens_msg_buf, i);
- gps.svinfos[ch].cno = XSENS_GPSStatus_cnr(xsens_msg_buf, i);
- if (gps.svinfos[ch].flags > 0) {
- gps.num_sv++;
- }
- }
- }
-#endif
- else if (xsens_id == XSENS_MTData_ID) {
- /* test RAW modes else calibrated modes */
- //if ((XSENS_MASK_RAWInertial(xsens_output_mode)) || (XSENS_MASK_RAWGPS(xsens_output_mode)))Â {
- if (XSENS_MASK_RAWInertial(xsens_output_mode)) {
- ins_p = XSENS_DATA_RAWInertial_gyrX(xsens_msg_buf, offset);
- ins_q = XSENS_DATA_RAWInertial_gyrY(xsens_msg_buf, offset);
- ins_r = XSENS_DATA_RAWInertial_gyrZ(xsens_msg_buf, offset);
-#if USE_IMU
- imu_xsens.gyro_available = TRUE;
-#endif
- offset += XSENS_DATA_RAWInertial_LENGTH;
- }
- if (XSENS_MASK_RAWGPS(xsens_output_mode)) {
-#if USE_GPS_XSENS_RAW_DATA && USE_GPS_XSENS
-
- gps.week = 0; // FIXME
- gps.tow = XSENS_DATA_RAWGPS_itow(xsens_msg_buf, offset) * 10;
- gps.lla_pos.lat = XSENS_DATA_RAWGPS_lat(xsens_msg_buf, offset);
- gps.lla_pos.lon = XSENS_DATA_RAWGPS_lon(xsens_msg_buf, offset);
- gps.lla_pos.alt = XSENS_DATA_RAWGPS_alt(xsens_msg_buf, offset);
- SetBit(gps.valid_fields, GPS_VALID_POS_LLA_BIT);
-
- /* Set the real UTM zone */
- gps.utm_pos.zone = (gps.lla_pos.lon / 1e7 + 180) / 6 + 1;
- LLA_FLOAT_OF_BFP(lla_f, gps.lla_pos);
- utm_f.zone = nav_utm_zone0;
- /* convert to utm */
- utm_of_lla_f(&utm_f, &lla_f);
- /* copy results of utm conversion */
- gps.utm_pos.east = utm_f.east * 100;
- gps.utm_pos.north = utm_f.north * 100;
- gps.utm_pos.alt = gps.lla_pos.alt;
- SetBit(gps.valid_fields, GPS_VALID_POS_UTM_BIT);
-
- ins_x = utm_f.east;
- ins_y = utm_f.north;
- // Altitude: Xsens LLH gives ellipsoid height
- ins_z = -(INS_FORMAT)XSENS_DATA_RAWGPS_alt(xsens_msg_buf, offset) / 1000.;
-
- // Compute geoid (MSL) height
- float hmsl = wgs84_ellipsoid_to_geoid(lla_f.lat, lla_f.lon);
- gps.hmsl = XSENS_DATA_RAWGPS_alt(xsens_msg_buf, offset) - (hmsl * 1000.0f);
- SetBit(gps.valid_fields, GPS_VALID_HMSL_BIT);
-
- ins_vx = ((INS_FORMAT)XSENS_DATA_RAWGPS_vel_n(xsens_msg_buf, offset)) / 100.;
- ins_vy = ((INS_FORMAT)XSENS_DATA_RAWGPS_vel_e(xsens_msg_buf, offset)) / 100.;
- ins_vz = ((INS_FORMAT)XSENS_DATA_RAWGPS_vel_d(xsens_msg_buf, offset)) / 100.;
- gps.ned_vel.x = XSENS_DATA_RAWGPS_vel_n(xsens_msg_buf, offset);
- gps.ned_vel.y = XSENS_DATA_RAWGPS_vel_e(xsens_msg_buf, offset);
- gps.ned_vel.z = XSENS_DATA_RAWGPS_vel_d(xsens_msg_buf, offset);
- SetBit(gps.valid_fields, GPS_VALID_VEL_NED_BIT);
- gps.pacc = XSENS_DATA_RAWGPS_hacc(xsens_msg_buf, offset) / 100;
- gps.sacc = XSENS_DATA_RAWGPS_sacc(xsens_msg_buf, offset) / 100;
- gps.pdop = 5; // FIXME Not output by XSens
-
- gps_xsens_publish();
-#endif
- offset += XSENS_DATA_RAWGPS_LENGTH;
- }
- //} else {
- if (XSENS_MASK_Temp(xsens_output_mode)) {
- offset += XSENS_DATA_Temp_LENGTH;
- }
- if (XSENS_MASK_Calibrated(xsens_output_mode)) {
- uint8_t l = 0;
- if (!XSENS_MASK_AccOut(xsens_output_settings)) {
- ins_ax = XSENS_DATA_Calibrated_accX(xsens_msg_buf, offset);
- ins_ay = XSENS_DATA_Calibrated_accY(xsens_msg_buf, offset);
- ins_az = XSENS_DATA_Calibrated_accZ(xsens_msg_buf, offset);
-#if USE_IMU
- imu_xsens.accel_available = TRUE;
-#endif
- l++;
- }
- if (!XSENS_MASK_GyrOut(xsens_output_settings)) {
- ins_p = XSENS_DATA_Calibrated_gyrX(xsens_msg_buf, offset);
- ins_q = XSENS_DATA_Calibrated_gyrY(xsens_msg_buf, offset);
- ins_r = XSENS_DATA_Calibrated_gyrZ(xsens_msg_buf, offset);
-#if USE_IMU
- imu_xsens.gyro_available = TRUE;
-#endif
- l++;
- }
- if (!XSENS_MASK_MagOut(xsens_output_settings)) {
- ins_mx = XSENS_DATA_Calibrated_magX(xsens_msg_buf, offset);
- ins_my = XSENS_DATA_Calibrated_magY(xsens_msg_buf, offset);
- ins_mz = XSENS_DATA_Calibrated_magZ(xsens_msg_buf, offset);
-#if USE_IMU
- imu_xsens.mag_available = TRUE;
-#endif
- l++;
- }
- offset += l * XSENS_DATA_Calibrated_LENGTH / 3;
- }
- if (XSENS_MASK_Orientation(xsens_output_mode)) {
- if (XSENS_MASK_OrientationMode(xsens_output_settings) == 0x00) {
- float q0 = XSENS_DATA_Quaternion_q0(xsens_msg_buf, offset);
- float q1 = XSENS_DATA_Quaternion_q1(xsens_msg_buf, offset);
- float q2 = XSENS_DATA_Quaternion_q2(xsens_msg_buf, offset);
- float q3 = XSENS_DATA_Quaternion_q3(xsens_msg_buf, offset);
- float dcm00 = 1.0 - 2 * (q2 * q2 + q3 * q3);
- float dcm01 = 2 * (q1 * q2 + q0 * q3);
- float dcm02 = 2 * (q1 * q3 - q0 * q2);
- float dcm12 = 2 * (q2 * q3 + q0 * q1);
- float dcm22 = 1.0 - 2 * (q1 * q1 + q2 * q2);
- ins_phi = atan2(dcm12, dcm22);
- ins_theta = -asin(dcm02);
- ins_psi = atan2(dcm01, dcm00);
- offset += XSENS_DATA_Quaternion_LENGTH;
- }
- if (XSENS_MASK_OrientationMode(xsens_output_settings) == 0x01) {
- ins_phi = XSENS_DATA_Euler_roll(xsens_msg_buf, offset) * M_PI / 180;
- ins_theta = XSENS_DATA_Euler_pitch(xsens_msg_buf, offset) * M_PI / 180;
- ins_psi = XSENS_DATA_Euler_yaw(xsens_msg_buf, offset) * M_PI / 180;
- offset += XSENS_DATA_Euler_LENGTH;
- }
- if (XSENS_MASK_OrientationMode(xsens_output_settings) == 0x10) {
- offset += XSENS_DATA_Matrix_LENGTH;
- }
- new_ins_attitude = 1;
- }
- if (XSENS_MASK_Auxiliary(xsens_output_mode)) {
- uint8_t l = 0;
- if (!XSENS_MASK_Aux1Out(xsens_output_settings)) {
- l++;
- }
- if (!XSENS_MASK_Aux2Out(xsens_output_settings)) {
- l++;
- }
- offset += l * XSENS_DATA_Auxiliary_LENGTH / 2;
- }
- if (XSENS_MASK_Position(xsens_output_mode)) {
-#if (! USE_GPS_XSENS_RAW_DATA) && USE_GPS_XSENS
- lla_f.lat = RadOfDeg(XSENS_DATA_Position_lat(xsens_msg_buf, offset));
- lla_f.lon = RadOfDeg(XSENS_DATA_Position_lon(xsens_msg_buf, offset));
- gps.lla_pos.lat = (int32_t)(DegOfRad(lla_f.lat) * 1e7);
- gps.lla_pos.lon = (int32_t)(DegOfRad(lla_f.lon) * 1e7);
- SetBit(gps.valid_fields, GPS_VALID_POS_LLA_BIT);
- gps.utm_pos.zone = (DegOfRad(lla_f.lon) + 180) / 6 + 1;
- /* convert to utm */
- utm_of_lla_f(&utm_f, &lla_f);
- /* copy results of utm conversion */
- gps.utm_pos.east = utm_f.east * 100;
- gps.utm_pos.north = utm_f.north * 100;
- SetBit(gps.valid_fields, GPS_VALID_POS_UTM_BIT);
- ins_x = utm_f.east;
- ins_y = utm_f.north;
- ins_z = XSENS_DATA_Position_alt(xsens_msg_buf, offset); //TODO is this hms or above ellipsoid?
- gps.hmsl = ins_z * 1000;
- SetBit(gps.valid_fields, GPS_VALID_HMSL_BIT);
- // what about gps.lla_pos.alt and gps.utm_pos.alt ?
-
- gps_xsens_publish();
-#endif
- offset += XSENS_DATA_Position_LENGTH;
- }
- if (XSENS_MASK_Velocity(xsens_output_mode)) {
-#if (! USE_GPS_XSENS_RAW_DATA) && USE_GPS_XSENS
- ins_vx = XSENS_DATA_Velocity_vx(xsens_msg_buf, offset);
- ins_vy = XSENS_DATA_Velocity_vy(xsens_msg_buf, offset);
- ins_vz = XSENS_DATA_Velocity_vz(xsens_msg_buf, offset);
-#endif
- offset += XSENS_DATA_Velocity_LENGTH;
- }
- if (XSENS_MASK_Status(xsens_output_mode)) {
- xsens_msg_status = XSENS_DATA_Status_status(xsens_msg_buf, offset);
-#if USE_GPS_XSENS
- if (bit_is_set(xsens_msg_status, 2)) { gps.fix = GPS_FIX_3D; } // gps fix
- else if (bit_is_set(xsens_msg_status, 1)) { gps.fix = 0x01; } // efk valid
- else { gps.fix = GPS_FIX_NONE; }
-#ifdef GPS_LED
- if (gps.fix == GPS_FIX_3D) {
- LED_ON(GPS_LED);
- } else {
- LED_TOGGLE(GPS_LED);
- }
-#endif // GPS_LED
-#endif // USE_GPS_XSENS
- offset += XSENS_DATA_Status_LENGTH;
- }
- if (XSENS_MASK_TimeStamp(xsens_output_settings)) {
- xsens_time_stamp = XSENS_DATA_TimeStamp_ts(xsens_msg_buf, offset);
-#if USE_GPS_XSENS
- gps.tow = xsens_time_stamp;
-#endif
- offset += XSENS_DATA_TimeStamp_LENGTH;
- }
- if (XSENS_MASK_UTC(xsens_output_settings)) {
- xsens_time.hour = XSENS_DATA_UTC_hour(xsens_msg_buf, offset);
- xsens_time.min = XSENS_DATA_UTC_min(xsens_msg_buf, offset);
- xsens_time.sec = XSENS_DATA_UTC_sec(xsens_msg_buf, offset);
- xsens_time.nanosec = XSENS_DATA_UTC_nanosec(xsens_msg_buf, offset);
- xsens_time.year = XSENS_DATA_UTC_year(xsens_msg_buf, offset);
- xsens_time.month = XSENS_DATA_UTC_month(xsens_msg_buf, offset);
- xsens_time.day = XSENS_DATA_UTC_day(xsens_msg_buf, offset);
-
- offset += XSENS_DATA_UTC_LENGTH;
- }
- //}
- }
-
-}
-
-void parse_ins_buffer(uint8_t c)
-{
- ck += c;
- switch (xsens_status) {
- case UNINIT:
- if (c != XSENS_START) {
- goto error;
- }
- xsens_status++;
- ck = 0;
- break;
- case GOT_START:
- if (c != XSENS_BID) {
- goto error;
- }
- xsens_status++;
- break;
- case GOT_BID:
- xsens_id = c;
- xsens_status++;
- break;
- case GOT_MID:
- xsens_len = c;
- if (xsens_len > XSENS_MAX_PAYLOAD) {
- goto error;
- }
- xsens_msg_idx = 0;
- xsens_status++;
- break;
- case GOT_LEN:
- xsens_msg_buf[xsens_msg_idx] = c;
- xsens_msg_idx++;
- if (xsens_msg_idx >= xsens_len) {
- xsens_status++;
- }
- break;
- case GOT_DATA:
- if (ck != 0) {
- goto error;
- }
- ins_msg_received = TRUE;
- goto restart;
- break;
- default:
- break;
- }
- return;
-error:
-restart:
- xsens_status = UNINIT;
- return;
-}
-
#ifdef USE_GPS_XSENS
/*
* register callbacks & structs
diff --git a/sw/airborne/modules/ins/ins_xsens.h b/sw/airborne/modules/ins/ins_xsens.h
index 2b7bf22a9d..9e55c00136 100644
--- a/sw/airborne/modules/ins/ins_xsens.h
+++ b/sw/airborne/modules/ins/ins_xsens.h
@@ -21,7 +21,8 @@
*/
/**
- * \brief Library for the XSENS AHRS
+ * @file modules/ins/ins_xsens.h
+ * Xsens as a full INS solution
*/
#ifndef INS_XSENS_H
@@ -29,54 +30,22 @@
#include "std.h"
-#include "ins_module.h"
+// hack to not use this in sim/nps
+#ifndef SITL
+#include "xsens.h"
-struct XsensTime {
- int8_t hour;
- int8_t min;
- int8_t sec;
- int32_t nanosec;
- int16_t year;
- int8_t month;
- int8_t day;
-};
-
-extern struct XsensTime xsens_time;
-
-extern uint8_t xsens_msg_status;
-extern uint16_t xsens_time_stamp;
-
-extern void xsens_periodic(void);
-
-/* To use Xsens to just provide IMU measurements
- * for use with an external AHRS algorithm
- */
-#if USE_IMU
-#include "subsystems/imu.h"
-#include "subsystems/abi.h"
-
-struct ImuXsens {
- bool_t gyro_available;
- bool_t accel_available;
- bool_t mag_available;
-};
-extern struct ImuXsens imu_xsens;
-
-#define ImuEvent() {}
-#endif /* USE_IMU */
-
-
-/* use Xsens as a full INS solution */
-#if USE_INS_MODULE
-#define InsEvent() { \
- ins_event_check_and_handle(handle_ins_msg); \
- }
-#define DefaultInsImpl ins_xsens
-#define InsPeriodic xsens_periodic
-extern void ins_xsens_init(void);
-extern void ins_xsens_register(void);
+#ifdef AHRS_TRIGGERED_ATTITUDE_LOOP
+extern volatile uint8_t new_ins_attitude;
#endif
+extern float ins_pitch_neutral;
+extern float ins_roll_neutral;
+
+#define DefaultInsImpl ins_xsens
+
+extern void ins_xsens_init(void);
+extern void ins_xsens_register(void);
+extern void ins_xsens_event(void);
#if USE_GPS_XSENS
#ifndef PRIMARY_GPS
@@ -86,4 +55,11 @@ extern void gps_xsens_init(void);
extern void gps_xsens_register(void);
#endif
+#else // SITL
+
+static inline void xsens_periodic(void) {}
+static inline void ins_xsens_event(void) {}
+
+#endif
+
#endif
diff --git a/sw/airborne/modules/ins/ins_xsens700.c b/sw/airborne/modules/ins/ins_xsens700.c
index a9a180616b..1ead510db0 100644
--- a/sw/airborne/modules/ins/ins_xsens700.c
+++ b/sw/airborne/modules/ins/ins_xsens700.c
@@ -22,15 +22,13 @@
/**
* @file modules/ins/ins_xsens700.c
- * Parser for the Xsens protocol.
+ * Xsens700 as a full INS solution
*/
-#include "ins_module.h"
-#include "ins_xsens.h"
+#include "ins_xsens700.h"
+#include "xsens_common.h"
#include "subsystems/ins.h"
-#include
-
#include "generated/airframe.h"
#include "mcu_periph/sys_time.h"
@@ -48,148 +46,6 @@
#include "subsystems/navigation/common_nav.h" /* needed for nav_utm_zone0 */
#endif
-// positions
-INS_FORMAT ins_x;
-INS_FORMAT ins_y;
-INS_FORMAT ins_z;
-
-// velocities
-INS_FORMAT ins_vx;
-INS_FORMAT ins_vy;
-INS_FORMAT ins_vz;
-
-// body angles
-INS_FORMAT ins_phi;
-INS_FORMAT ins_theta;
-INS_FORMAT ins_psi;
-
-// angle rates
-INS_FORMAT ins_p;
-INS_FORMAT ins_q;
-INS_FORMAT ins_r;
-
-// accelerations
-INS_FORMAT ins_ax;
-INS_FORMAT ins_ay;
-INS_FORMAT ins_az;
-
-// magnetic
-INS_FORMAT ins_mx;
-INS_FORMAT ins_my;
-INS_FORMAT ins_mz;
-
-#if USE_INS_MODULE
-float ins_pitch_neutral;
-float ins_roll_neutral;
-#endif
-
-
-//////////////////////////////////////////////////////////////////////////////////////////
-//
-// XSens Specific
-//
-
-volatile uint8_t ins_msg_received;
-
-#define XsensInitCheksum() { send_ck = 0; }
-#define XsensUpdateChecksum(c) { send_ck += c; }
-
-#define XsensSend1(c) { uint8_t i8=c; InsUartSend1(i8); XsensUpdateChecksum(i8); }
-#define XsensSend1ByAddr(x) { XsensSend1(*x); }
-#define XsensSend2ByAddr(x) { XsensSend1(*(x+1)); XsensSend1(*x); }
-#define XsensSend4ByAddr(x) { XsensSend1(*(x+3)); XsensSend1(*(x+2)); XsensSend1(*(x+1)); XsensSend1(*x); }
-
-#define XsensHeader(msg_id, len) { \
- InsUartSend1(XSENS_START); \
- XsensInitCheksum(); \
- XsensSend1(XSENS_BID); \
- XsensSend1(msg_id); \
- XsensSend1(len); \
- }
-#define XsensTrailer() { uint8_t i8=0x100-send_ck; InsUartSend1(i8); }
-
-/** Includes macros generated from xsens_MTi-G.xml */
-#include "xsens_protocol.h"
-
-
-#define XSENS_MAX_PAYLOAD 254
-uint8_t xsens_msg_buf[XSENS_MAX_PAYLOAD];
-
-
-#define UNINIT 0
-#define GOT_START 1
-#define GOT_BID 2
-#define GOT_MID 3
-#define GOT_LEN 4
-#define GOT_DATA 5
-#define GOT_CHECKSUM 6
-
-// FIXME Debugging Only
-#include "mcu_periph/uart.h"
-#include "pprzlink/messages.h"
-#include "subsystems/datalink/downlink.h"
-
-
-uint8_t xsens_errorcode;
-uint32_t xsens_msg_statusword;
-uint16_t xsens_time_stamp;
-uint16_t xsens_output_mode;
-uint32_t xsens_output_settings;
-float xsens_declination = 0;
-float xsens_gps_arm_x = 0;
-float xsens_gps_arm_y = 0;
-float xsens_gps_arm_z = 0;
-
-
-int8_t xsens_hour;
-int8_t xsens_min;
-int8_t xsens_sec;
-int32_t xsens_nanosec;
-int16_t xsens_year;
-int8_t xsens_month;
-int8_t xsens_day;
-
-static uint8_t xsens_id;
-static uint8_t xsens_status;
-static uint8_t xsens_len;
-static uint8_t xsens_msg_idx;
-static uint8_t ck;
-uint8_t send_ck;
-
-struct LlaCoor_f lla_f;
-struct UtmCoor_f utm_f;
-
-volatile int xsens_configured = 0;
-
-void xsens_init(void);
-
-void xsens_init(void)
-{
-
- xsens_status = UNINIT;
- xsens_configured = 30;
-
- xsens_msg_statusword = 0;
- xsens_time_stamp = 0;
-
-}
-
-#if USE_INS_MODULE
-void ins_xsens_update_gps(struct GpsState *gps_s);
-
-void ins_xsens_init(void)
-{
- struct UtmCoor_f utm0 = { nav_utm_north0, nav_utm_east0, 0., nav_utm_zone0 };
- stateSetLocalUtmOrigin_f(&utm0);
- stateSetPositionUtm_f(&utm0);
-
- ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT;
- ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT;
-
- xsens_init();
-}
-
-#include "subsystems/abi.h"
/** ABI binding for gps data.
* Used for GPS ABI messages.
*/
@@ -198,20 +54,47 @@ void ins_xsens_init(void)
#endif
PRINT_CONFIG_VAR(INS_XSENS700_GPS_ID)
static abi_event gps_ev;
+
+float ins_pitch_neutral;
+float ins_roll_neutral;
+
+static void handle_ins_msg(void);
+static void update_state_interface(void);
static void gps_cb(uint8_t sender_id __attribute__((unused)),
uint32_t stamp __attribute__((unused)),
- struct GpsState *gps_s)
-{
- ins_xsens_update_gps(gps_s);
-}
+ struct GpsState *gps_s);
-void ins_xsens_register(void)
+void ins_xsens700_register(void)
{
- ins_register_impl(ins_xsens_init);
+ ins_register_impl(ins_xsens700_init);
AbiBindMsgGPS(INS_XSENS700_GPS_ID, &gps_ev, gps_cb);
}
-void ins_xsens_update_gps(struct GpsState *gps_s)
+void ins_xsens700_init(void)
+{
+ xsens700_init();
+
+ ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT;
+ ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT;
+
+ struct UtmCoor_f utm0 = { nav_utm_north0, nav_utm_east0, 0., nav_utm_zone0 };
+ stateSetLocalUtmOrigin_f(&utm0);
+ stateSetPositionUtm_f(&utm0);
+}
+
+void ins_xsens700_event(void)
+{
+ xsens_event();
+ if (xsens700.msg_received) {
+ parse_xsens700_msg();
+ handle_ins_msg();
+ xsens700.msg_received = false;
+ }
+}
+
+static void gps_cb(uint8_t sender_id __attribute__((unused)),
+ uint32_t stamp __attribute__((unused)),
+ struct GpsState *gps_s)
{
struct UtmCoor_f utm = utm_float_from_gps(gps_s, nav_utm_zone0);
utm.alt = gps_s->hmsl / 1000.;
@@ -227,409 +110,97 @@ void ins_xsens_update_gps(struct GpsState *gps_s)
// set velocity
stateSetSpeedNed_f(&ned_vel);
}
-#endif
+
#if USE_GPS_XSENS
-void gps_xsens_init(void)
+void gps_xsens700_init(void)
{
- gps.nb_channels = 0;
+ xsens700.gps.nb_channels = 0;
}
-static void gps_xsens_publish(void)
+static void gps_xsens700_publish(void)
{
// publish gps data
uint32_t now_ts = get_sys_time_usec();
- gps.last_msg_ticks = sys_time.nb_sec_rem;
- gps.last_msg_time = sys_time.nb_sec;
- if (gps.fix == GPS_FIX_3D) {
- gps.last_3dfix_ticks = sys_time.nb_sec_rem;
- gps.last_3dfix_time = sys_time.nb_sec;
+ xsens700.gps.last_msg_ticks = sys_time.nb_sec_rem;
+ xsens700.gps.last_msg_time = sys_time.nb_sec;
+ if (xsens700.gps.fix == GPS_FIX_3D) {
+ xsens700.gps.last_3dfix_ticks = sys_time.nb_sec_rem;
+ xsens700.gps.last_3dfix_time = sys_time.nb_sec;
}
- AbiSendMsgGPS(GPS_XSENS_ID, now_ts, &gps);
+ AbiSendMsgGPS(GPS_XSENS_ID, now_ts, &xsens700.gps);
}
#endif
-static void xsens_ask_message_rate(uint8_t c1, uint8_t c2, uint8_t freq)
-{
- uint8_t foo = 0;
- XsensSend1ByAddr(&c1);
- XsensSend1ByAddr(&c2);
- XsensSend1ByAddr(&foo);
- XsensSend1ByAddr(&freq);
-}
-void xsens_periodic(void)
-{
- if (xsens_configured > 0) {
- switch (xsens_configured) {
- case 25:
- /* send mode and settings to MT */
- XSENS_GoToConfig();
- //XSENS_SetOutputMode(xsens_output_mode);
- //XSENS_SetOutputSettings(xsens_output_settings);
- break;
- case 18:
- // Give pulses on SyncOut
- //XSENS_SetSyncOutSettings(0,0x0002);
- break;
- case 17:
-
- XsensHeader(XSENS_SetOutputConfiguration_ID, 44);
- xsens_ask_message_rate(0x10, 0x10, 4); // UTC
- xsens_ask_message_rate(0x20, 0x30, 100); // Attitude Euler
- xsens_ask_message_rate(0x40, 0x10, 100); // Delta-V
- xsens_ask_message_rate(0x80, 0x20, 100); // Rate of turn
- xsens_ask_message_rate(0xE0, 0x20, 50); // Status
- xsens_ask_message_rate(0x30, 0x10, 50); // Baro Pressure
- xsens_ask_message_rate(0x88, 0x40, 1); // NavSol
- xsens_ask_message_rate(0x88, 0xA0, 1); // SV Info
- xsens_ask_message_rate(0x50, 0x20, 50); // GPS Altitude Ellipsiod
- xsens_ask_message_rate(0x50, 0x40, 50); // GPS Position
- xsens_ask_message_rate(0xD0, 0x10, 50); // GPS Speed
- XsensTrailer();
- break;
- case 2:
- //XSENS_ReqLeverArmGps();
- break;
-
- case 6:
- //XSENS_ReqMagneticDeclination();
- break;
-
- case 13:
- //#ifdef AHRS_H_X
- //#pragma message "Sending XSens Magnetic Declination."
- //xsens_declination = atan2(AHRS_H_Y, AHRS_H_X);
- //XSENS_SetMagneticDeclination(xsens_declination);
- //#endif
- break;
- case 12:
-#ifdef GPS_IMU_LEVER_ARM_X
-#pragma message "Sending XSens GPS Arm."
- XSENS_SetLeverArmGps(GPS_IMU_LEVER_ARM_X, GPS_IMU_LEVER_ARM_Y, GPS_IMU_LEVER_ARM_Z);
-#endif
- break;
- case 10: {
- uint8_t baud = 1;
- XSENS_SetBaudrate(baud);
- }
- break;
-
- case 1:
- XSENS_GoToMeasurment();
- break;
- default:
- break;
- }
- xsens_configured--;
- return;
- }
-
- //RunOnceEvery(100,XSENS_ReqGPSStatus());
-}
-
-#if USE_INS_MODULE
-#include "state.h"
-
-static inline void update_state_interface(void)
+static void update_state_interface(void)
{
// Send to Estimator (Control)
-#if XSENS_BACKWARDS
+#ifdef XSENS_BACKWARDS
struct FloatEulers att = {
- ins_phi + ins_roll_neutral,
- -ins_theta + ins_pitch_neutral,
- -ins_psi + RadOfDeg(180)
+ xsens700.euler.phi + ins_roll_neutral,
+ -xsens700.euler.theta + ins_pitch_neutral,
+ -xsens700.euler.psi + RadOfDeg(180)
};
- struct FloatRates rates = {
- ins_p,
- -ins_q,
- -ins_r
+ struct FloatEulerstRates rates = {
+ xsens700.gyro.p,
+ -xsens700.gyro.q,
+ -xsens700.gyro.r
};
#else
struct FloatEulers att = {
- -ins_phi + ins_roll_neutral,
- ins_theta + ins_pitch_neutral,
- -ins_psi
+ -xsens700.euler.phi + ins_roll_neutral,
+ xsens700.euler.theta + ins_pitch_neutral,
+ -xsens700.euler.psi
};
- struct FloatRates rates = {
- -ins_p,
- ins_q,
- -ins_r
+ struct FloatRates rates = {
+ -xsens700.gyro.p,
+ xsens700.gyro.q,
+ -xsens700.gyro.r
};
#endif
stateSetNedToBodyEulers_f(&att);
stateSetBodyRates_f(&rates);
}
-#endif /* USE_INS_MODULE */
+
void handle_ins_msg(void)
{
-#if USE_INS_MODULE
update_state_interface();
-#endif
+
+ if (xsens700.new_attitude) {
+ new_ins_attitude = true;
+ xsens700.new_attitude = false;
+ }
#if USE_GPS_XSENS
- // Horizontal speed
- float fspeed = sqrt(ins_vx * ins_vx + ins_vy * ins_vy);
- if (gps.fix != GPS_FIX_3D) {
- fspeed = 0;
- }
- gps.gspeed = fspeed * 100.;
- gps.speed_3d = (uint16_t)(sqrt(ins_vx * ins_vx + ins_vy * ins_vy + ins_vz * ins_vz) * 100);
+ if (xsens700.gps_available) {
+ // Horizontal speed
+ float fspeed = FLOAT_VECT2_NORM(xsens700.vel);
+ if (xsens700.gps.fix != GPS_FIX_3D) {
+ fspeed = 0;
+ }
+ xsens700.gps.gspeed = fspeed * 100.;
+ xsens700.gps.speed_3d = float_vect3_norm(&xsens700.vel) * 100;
- float fcourse = atan2f((float)ins_vy, (float)ins_vx);
- gps.course = fcourse * 1e7;
+ float fcourse = atan2f(xsens700.vel.y, xsens700.vel.x);
+ xsens700.gps.course = fcourse * 1e7;
+ SetBit(xsens700.gps.valid_fields, GPS_VALID_COURSE_BIT);
+
+ gps_xsens700_publish();
+ xsens700.gps_available = false;
+ }
#endif // USE_GPS_XSENS
}
-void parse_ins_msg(void)
-{
- uint8_t offset = 0;
- if (xsens_id == XSENS_ReqLeverArmGpsAck_ID) {
- xsens_gps_arm_x = XSENS_ReqLeverArmGpsAck_x(xsens_msg_buf);
- xsens_gps_arm_y = XSENS_ReqLeverArmGpsAck_y(xsens_msg_buf);
- xsens_gps_arm_z = XSENS_ReqLeverArmGpsAck_z(xsens_msg_buf);
-
- DOWNLINK_SEND_IMU_MAG_SETTINGS(DefaultChannel, DefaultDevice, &xsens_declination, &xsens_declination, &xsens_gps_arm_x,
- &xsens_gps_arm_y, &xsens_gps_arm_z);
- } else if (xsens_id == XSENS_Error_ID) {
- xsens_errorcode = XSENS_Error_errorcode(xsens_msg_buf);
- } else if (xsens_id == XSENS_MTData2_ID) {
- for (offset = 0; offset < xsens_len;) {
- uint8_t code1 = xsens_msg_buf[offset];
- uint8_t code2 = xsens_msg_buf[offset + 1];
- int subpacklen = (int)xsens_msg_buf[offset + 2];
- offset += 3;
-
-
- if (code1 == 0x10) {
- if (code2 == 0x10) {
- // UTC
- } else if (code2 == 0x20) {
- // Packet Counter
- }
- if (code2 == 0x30) {
- // ITOW
- }
- } else if (code1 == 0x20) {
- if (code2 == 0x30) {
- // Attitude Euler
- ins_phi = XSENS_DATA_Euler_roll(xsens_msg_buf, offset) * M_PI / 180;
- ins_theta = XSENS_DATA_Euler_pitch(xsens_msg_buf, offset) * M_PI / 180;
- ins_psi = XSENS_DATA_Euler_yaw(xsens_msg_buf, offset) * M_PI / 180;
-
- new_ins_attitude = 1;
-
- }
- } else if (code1 == 0x40) {
- if (code2 == 0x10) {
- // Delta-V
- ins_ax = XSENS_DATA_Acceleration_x(xsens_msg_buf, offset) * 100.0f;
- ins_ay = XSENS_DATA_Acceleration_y(xsens_msg_buf, offset) * 100.0f;
- ins_az = XSENS_DATA_Acceleration_z(xsens_msg_buf, offset) * 100.0f;
- }
- } else if (code1 == 0x80) {
- if (code2 == 0x20) {
- // Rate Of Turn
- ins_p = XSENS_DATA_RateOfTurn_x(xsens_msg_buf, offset) * M_PI / 180;
- ins_q = XSENS_DATA_RateOfTurn_y(xsens_msg_buf, offset) * M_PI / 180;
- ins_r = XSENS_DATA_RateOfTurn_z(xsens_msg_buf, offset) * M_PI / 180;
- }
- } else if (code1 == 0x30) {
- if (code2 == 0x10) {
- // Baro Pressure
- }
- } else if (code1 == 0xE0) {
- if (code2 == 0x20) {
- // Status Word
- xsens_msg_statusword = XSENS_DATA_StatusWord_status(xsens_msg_buf, offset);
- //gps.tow = xsens_msg_statusword;
-#if USE_GPS_XSENS
- if (bit_is_set(xsens_msg_statusword, 2) && bit_is_set(xsens_msg_statusword, 1)) {
- if (bit_is_set(xsens_msg_statusword, 23) && bit_is_set(xsens_msg_statusword, 24)) {
- gps.fix = GPS_FIX_3D;
- } else {
- gps.fix = GPS_FIX_2D;
- }
- } else { gps.fix = GPS_FIX_NONE; }
-#endif
- }
- } else if (code1 == 0x88) {
- if (code2 == 0x40) {
- gps.week = XSENS_DATA_GpsSol_week(xsens_msg_buf, offset);
- gps.num_sv = XSENS_DATA_GpsSol_numSv(xsens_msg_buf, offset);
- gps.pacc = XSENS_DATA_GpsSol_pAcc(xsens_msg_buf, offset);
- gps.sacc = XSENS_DATA_GpsSol_sAcc(xsens_msg_buf, offset);
- gps.pdop = XSENS_DATA_GpsSol_pDop(xsens_msg_buf, offset);
- } else if (code2 == 0xA0) {
- // SVINFO
- gps.tow = XSENS_XDI_GpsSvInfo_iTOW(xsens_msg_buf + offset);
-
-#if USE_GPS_XSENS
- gps.nb_channels = XSENS_XDI_GpsSvInfo_nch(xsens_msg_buf + offset);
-
- gps.last_3dfix_ticks = sys_time.nb_sec_rem;
- gps.last_3dfix_time = sys_time.nb_sec;
-
- uint8_t i;
- // Do not write outside buffer
- for (i = 0; i < Min(gps.nb_channels, GPS_NB_CHANNELS); i++) {
- uint8_t ch = XSENS_XDI_GpsSvInfo_chn(xsens_msg_buf + offset, i);
- if (ch > gps.nb_channels) { continue; }
- gps.svinfos[ch].svid = XSENS_XDI_GpsSvInfo_svid(xsens_msg_buf + offset, i);
- gps.svinfos[ch].flags = XSENS_XDI_GpsSvInfo_bitmask(xsens_msg_buf + offset, i);
- gps.svinfos[ch].qi = XSENS_XDI_GpsSvInfo_qi(xsens_msg_buf + offset, i);
- gps.svinfos[ch].cno = XSENS_XDI_GpsSvInfo_cnr(xsens_msg_buf + offset, i);
- }
-#endif
- }
- } else if (code1 == 0x50) {
- if (code2 == 0x10) {
- //gps.hmsl = XSENS_DATA_Altitude_h(xsens_msg_buf,offset)* 1000.0f;
- } else if (code2 == 0x20) {
- // Altitude Elipsoid
- gps.utm_pos.alt = XSENS_DATA_Altitude_h(xsens_msg_buf, offset) * 1000.0f;
-
- // Compute geoid (MSL) height
- float geoid_h = wgs84_ellipsoid_to_geoid(lla_f.lat, lla_f.lon);
- gps.hmsl = gps.utm_pos.alt - (geoid_h * 1000.0f);
- SetBit(gps.valid_fields, GPS_VALID_HMSL_BIT);
-
- //gps.tow = geoid_h * 1000.0f; //gps.utm_pos.alt;
- } else if (code2 == 0x40) {
- // LatLong
-#ifdef GPS_LED
- LED_TOGGLE(GPS_LED);
-#endif
- gps.last_3dfix_ticks = sys_time.nb_sec_rem;
- gps.last_3dfix_time = sys_time.nb_sec;
- gps.week = 0; // FIXME
- lla_f.lat = RadOfDeg(XSENS_DATA_LatLon_lat(xsens_msg_buf, offset));
- lla_f.lon = RadOfDeg(XSENS_DATA_LatLon_lon(xsens_msg_buf, offset));
-
- // Set the real UTM zone
- gps.utm_pos.zone = (DegOfRad(lla_f.lon) + 180) / 6 + 1;
-
- utm_f.zone = nav_utm_zone0;
- // convert to utm
- utm_of_lla_f(&utm_f, &lla_f);
- // copy results of utm conversion
- gps.utm_pos.east = utm_f.east * 100;
- gps.utm_pos.north = utm_f.north * 100;
- SetBit(gps.valid_fields, GPS_VALID_POS_UTM_BIT);
-
- gps_xsens_publish();
- }
- } else if (code1 == 0xD0) {
- if (code2 == 0x10) {
- // Velocity
- ins_vx = ((INS_FORMAT)XSENS_DATA_VelocityXYZ_x(xsens_msg_buf, offset));
- ins_vy = ((INS_FORMAT)XSENS_DATA_VelocityXYZ_y(xsens_msg_buf, offset));
- ins_vz = ((INS_FORMAT)XSENS_DATA_VelocityXYZ_z(xsens_msg_buf, offset));
- gps.ned_vel.x = ins_vx;
- gps.ned_vel.y = ins_vy;
- gps.ned_vel.z = ins_vx;
- SetBit(gps.valid_fields, GPS_VALID_VEL_NED_BIT);
- }
- }
-
- if (subpacklen < 0) {
- subpacklen = 0;
- }
- offset += subpacklen;
- }
-
-
- /*
-
- gps.pacc = XSENS_DATA_RAWGPS_hacc(xsens_msg_buf,offset) / 100;
- gps.sacc = XSENS_DATA_RAWGPS_sacc(xsens_msg_buf,offset) / 100;
- gps.pdop = 5; // FIXME Not output by XSens
- */
-
- /*
- */
-
-
- /*
- ins_mx = XSENS_DATA_Calibrated_magX(xsens_msg_buf,offset);
- ins_my = XSENS_DATA_Calibrated_magY(xsens_msg_buf,offset);
- ins_mz = XSENS_DATA_Calibrated_magZ(xsens_msg_buf,offset);
- */
-
-
- /*
- xsens_time_stamp = XSENS_DATA_TimeStamp_ts(xsens_msg_buf,offset);
- #if USE_GPS_XSENS
- gps.tow = xsens_time_stamp;
- #endif
- */
-
- }
-
-}
-
-
-void parse_ins_buffer(uint8_t c)
-{
- ck += c;
- switch (xsens_status) {
- case UNINIT:
- if (c != XSENS_START) {
- goto error;
- }
- xsens_status++;
- ck = 0;
- break;
- case GOT_START:
- if (c != XSENS_BID) {
- goto error;
- }
- xsens_status++;
- break;
- case GOT_BID:
- xsens_id = c;
- xsens_status++;
- break;
- case GOT_MID:
- xsens_len = c;
- if (xsens_len > XSENS_MAX_PAYLOAD) {
- goto error;
- }
- xsens_msg_idx = 0;
- xsens_status++;
- break;
- case GOT_LEN:
- xsens_msg_buf[xsens_msg_idx] = c;
- xsens_msg_idx++;
- if (xsens_msg_idx >= xsens_len) {
- xsens_status++;
- }
- break;
- case GOT_DATA:
- if (ck != 0) {
- goto error;
- }
- ins_msg_received = TRUE;
- goto restart;
- break;
- default:
- break;
- }
- return;
-error:
-restart:
- xsens_status = UNINIT;
- return;
-}
#ifdef USE_GPS_XSENS
/*
* register callbacks & structs
*/
-void gps_xsens_register(void)
+void gps_xsens700_register(void)
{
- gps_register_impl(gps_xsens_init, NULL, GPS_XSENS_ID);
+ gps_register_impl(gps_xsens700_init, NULL, GPS_XSENS_ID);
}
#endif
diff --git a/sw/airborne/modules/ins/ins_xsens700.h b/sw/airborne/modules/ins/ins_xsens700.h
new file mode 100644
index 0000000000..75bd5fc380
--- /dev/null
+++ b/sw/airborne/modules/ins/ins_xsens700.h
@@ -0,0 +1,56 @@
+/*
+ * Copyright (C) 2010 ENAC
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+/**
+ * @file modules/ins/ins_xsens700.h
+ * Xsens700 as a full INS solution
+ */
+
+#ifndef INS_XSENS700_H
+#define INS_XSENS700_H
+
+#include "std.h"
+
+#include "xsens700.h"
+
+#ifdef AHRS_TRIGGERED_ATTITUDE_LOOP
+extern volatile uint8_t new_ins_attitude;
+#endif
+
+extern float ins_pitch_neutral;
+extern float ins_roll_neutral;
+
+#define DefaultInsImpl ins_xsens700
+
+extern void ins_xsens700_init(void);
+extern void ins_xsens700_register(void);
+extern void ins_xsens700_event(void);
+
+#if USE_GPS_XSENS
+#ifndef PRIMARY_GPS
+#define PRIMARY_GPS gps_xsens700
+#endif
+extern void gps_xsens700_init(void);
+extern void gps_xsens700_register(void);
+#endif
+
+#endif
diff --git a/sw/airborne/modules/ins/xsens.c b/sw/airborne/modules/ins/xsens.c
new file mode 100644
index 0000000000..f0ae21cf52
--- /dev/null
+++ b/sw/airborne/modules/ins/xsens.c
@@ -0,0 +1,373 @@
+/*
+ * Copyright (C) 2003 Pascal Brisset, Antoine Drouin
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ */
+
+/** @file modules/ins/xsens.c
+ * Parser for the Xsens protocol.
+ */
+
+#include "xsens.h"
+#include "xsens_common.h"
+
+#include "generated/airframe.h"
+
+#if USE_GPS_XSENS
+#include "math/pprz_geodetic_wgs84.h"
+#endif
+
+// FIXME Debugging Only
+#include "mcu_periph/uart.h"
+#include "pprzlink/messages.h"
+#include "subsystems/datalink/downlink.h"
+
+
+/* output mode : calibrated, orientation, position, velocity, status
+ * -----------
+ *
+ * bit 0 temp
+ * bit 1 calibrated
+ * bit 2 orentation
+ * bit 3 aux
+ *
+ * bit 4 position
+ * bit 5 velocity
+ * bit 6-7 Reserved
+ *
+ * bit 8-10 Reserved
+ * bit 11 status
+ *
+ * bit 12 GPS PVT+baro
+ * bit 13 Reserved
+ * bit 14 Raw
+ * bit 15 Reserved
+ */
+
+#ifndef XSENS_OUTPUT_MODE
+#define XSENS_OUTPUT_MODE 0x1836
+#endif
+/* output settings : timestamp, euler, acc, rate, mag, float, no aux, lla, m/s, NED
+ * -----------
+ *
+ * bit 01 0=none, 1=sample counter, 2=utc, 3=sample+utc
+ * bit 23 0=quaternion, 1=euler, 2=DCM
+ *
+ * bit 4 1=disable acc output
+ * bit 5 1=disable gyro output
+ * bit 6 1=disable magneto output
+ * bit 7 Reserved
+ *
+ * bit 89 0=float, 1=fixedpoint12.20, 2=fixedpoint16.32
+ * bit 10 1=disable aux analog 1
+ * bit 11 1=disable aux analog 2
+ *
+ * bit 12-15 0-only: 14-16 WGS84
+ *
+ * bit 16-19 0-only: 16-18 m/s XYZ
+ *
+ * bit 20-23 Reserved
+ *
+ * bit 24-27 Reseverd
+ *
+ * bit 28-30 Reseverd
+ * bit 31 0=X-North-Z-Up, 1=North-East-Down
+ */
+#ifndef XSENS_OUTPUT_SETTINGS
+#define XSENS_OUTPUT_SETTINGS 0x80000C05
+#endif
+
+uint8_t xsens_errorcode;
+uint8_t xsens_msg_status;
+uint16_t xsens_time_stamp;
+uint16_t xsens_output_mode;
+uint32_t xsens_output_settings;
+
+
+float xsens_declination = 0;
+float xsens_gps_arm_x = 0;
+float xsens_gps_arm_y = 0;
+float xsens_gps_arm_z = 0;
+
+volatile int xsens_configured = 0;
+
+struct Xsens xsens;
+
+void parse_xsens_buffer(uint8_t c);
+
+void xsens_init(void)
+{
+ xsens_status = UNINIT;
+ xsens_configured = 20;
+
+ xsens_msg_status = 0;
+ xsens_time_stamp = 0;
+ xsens_output_mode = XSENS_OUTPUT_MODE;
+ xsens_output_settings = XSENS_OUTPUT_SETTINGS;
+}
+
+void xsens_periodic(void)
+{
+ if (xsens_configured > 0) {
+ switch (xsens_configured) {
+ case 20:
+ /* send mode and settings to MT */
+ XSENS_GoToConfig();
+ XSENS_SetOutputMode(xsens_output_mode);
+ XSENS_SetOutputSettings(xsens_output_settings);
+ break;
+ case 18:
+ // Give pulses on SyncOut
+ XSENS_SetSyncOutSettings(0, 0x0002);
+ break;
+ case 17:
+ // 1 pulse every 100 samples
+ XSENS_SetSyncOutSettings(1, 100);
+ break;
+ case 2:
+ XSENS_ReqLeverArmGps();
+ break;
+
+ case 6:
+ XSENS_ReqMagneticDeclination();
+ break;
+
+ case 13:
+#ifdef AHRS_H_X
+#pragma message "Sending XSens Magnetic Declination."
+ xsens_declination = atan2(AHRS_H_Y, AHRS_H_X);
+ XSENS_SetMagneticDeclination(xsens_declination);
+#endif
+ break;
+ case 12:
+#ifdef GPS_IMU_LEVER_ARM_X
+#pragma message "Sending XSens GPS Arm."
+ XSENS_SetLeverArmGps(GPS_IMU_LEVER_ARM_X, GPS_IMU_LEVER_ARM_Y, GPS_IMU_LEVER_ARM_Z);
+#endif
+ break;
+ case 10: {
+ uint8_t baud = 1;
+ XSENS_SetBaudrate(baud);
+ }
+ break;
+
+ case 1:
+ XSENS_GoToMeasurment();
+ break;
+
+ default:
+ break;
+ }
+ xsens_configured--;
+ return;
+ }
+
+ RunOnceEvery(100, XSENS_ReqGPSStatus());
+}
+
+
+void parse_xsens_msg(void)
+{
+ uint8_t offset = 0;
+ if (xsens_id == XSENS_ReqOutputModeAck_ID) {
+ xsens_output_mode = XSENS_ReqOutputModeAck_mode(xsens_msg_buf);
+ } else if (xsens_id == XSENS_ReqOutputSettings_ID) {
+ xsens_output_settings = XSENS_ReqOutputSettingsAck_settings(xsens_msg_buf);
+ } else if (xsens_id == XSENS_ReqMagneticDeclinationAck_ID) {
+ xsens_declination = DegOfRad(XSENS_ReqMagneticDeclinationAck_declination(xsens_msg_buf));
+
+ DOWNLINK_SEND_IMU_MAG_SETTINGS(DefaultChannel, DefaultDevice, &xsens_declination, &xsens_declination, &xsens_gps_arm_x,
+ &xsens_gps_arm_y, &xsens_gps_arm_z);
+ } else if (xsens_id == XSENS_ReqLeverArmGpsAck_ID) {
+ xsens_gps_arm_x = XSENS_ReqLeverArmGpsAck_x(xsens_msg_buf);
+ xsens_gps_arm_y = XSENS_ReqLeverArmGpsAck_y(xsens_msg_buf);
+ xsens_gps_arm_z = XSENS_ReqLeverArmGpsAck_z(xsens_msg_buf);
+
+ DOWNLINK_SEND_IMU_MAG_SETTINGS(DefaultChannel, DefaultDevice, &xsens_declination, &xsens_declination, &xsens_gps_arm_x,
+ &xsens_gps_arm_y, &xsens_gps_arm_z);
+ } else if (xsens_id == XSENS_Error_ID) {
+ xsens_errorcode = XSENS_Error_errorcode(xsens_msg_buf);
+ }
+#if USE_GPS_XSENS
+ else if (xsens_id == XSENS_GPSStatus_ID) {
+ xsens.gps.nb_channels = XSENS_GPSStatus_nch(xsens_msg_buf);
+ xsens.gps.num_sv = 0;
+
+ uint8_t i;
+ // Do not write outside buffer
+ for (i = 0; i < Min(xsens.gps.nb_channels, GPS_NB_CHANNELS); i++) {
+ uint8_t ch = XSENS_GPSStatus_chn(xsens_msg_buf, i);
+ if (ch > xsens.gps.nb_channels) { continue; }
+ xsens.gps.svinfos[ch].svid = XSENS_GPSStatus_svid(xsens_msg_buf, i);
+ xsens.gps.svinfos[ch].flags = XSENS_GPSStatus_bitmask(xsens_msg_buf, i);
+ xsens.gps.svinfos[ch].qi = XSENS_GPSStatus_qi(xsens_msg_buf, i);
+ xsens.gps.svinfos[ch].cno = XSENS_GPSStatus_cnr(xsens_msg_buf, i);
+ if (xsens.gps.svinfos[ch].flags > 0) {
+ xsens.gps.num_sv++;
+ }
+ }
+ }
+#endif
+ else if (xsens_id == XSENS_MTData_ID) {
+ /* test RAW modes else calibrated modes */
+ //if ((XSENS_MASK_RAWInertial(xsens_output_mode)) || (XSENS_MASK_RAWGPS(xsens_output_mode)))Â {
+ if (XSENS_MASK_RAWInertial(xsens_output_mode)) {
+ /* should we write raw data to separate struct? */
+ xsens.gyro.p = XSENS_DATA_RAWInertial_gyrX(xsens_msg_buf, offset);
+ xsens.gyro.q = XSENS_DATA_RAWInertial_gyrY(xsens_msg_buf, offset);
+ xsens.gyro.r = XSENS_DATA_RAWInertial_gyrZ(xsens_msg_buf, offset);
+ xsens.gyro_available = TRUE;
+ offset += XSENS_DATA_RAWInertial_LENGTH;
+ }
+ if (XSENS_MASK_RAWGPS(xsens_output_mode)) {
+#if USE_GPS_XSENS_RAW_DATA && USE_GPS_XSENS
+ xsens.gps.week = 0; // FIXME
+ xsens.gps.tow = XSENS_DATA_RAWGPS_itow(xsens_msg_buf, offset) * 10;
+ xsens.gps.lla_pos.lat = XSENS_DATA_RAWGPS_lat(xsens_msg_buf, offset);
+ xsens.gps.lla_pos.lon = XSENS_DATA_RAWGPS_lon(xsens_msg_buf, offset);
+ xsens.gps.lla_pos.alt = XSENS_DATA_RAWGPS_alt(xsens_msg_buf, offset);
+ SetBit(xsens.gps.valid_fields, GPS_VALID_POS_LLA_BIT);
+
+ // Compute geoid (MSL) height
+ float hmsl = wgs84_ellipsoid_to_geoid_i(xsens.gps.lla_pos.lat, xsens.gps.lla_pos.lon);
+ xsens.gps.hmsl = XSENS_DATA_RAWGPS_alt(xsens_msg_buf, offset) - (hmsl * 1000.0f);
+ SetBit(gps.valid_fields, GPS_VALID_HMSL_BIT);
+
+ xsens.gps.ned_vel.x = XSENS_DATA_RAWGPS_vel_n(xsens_msg_buf, offset);
+ xsens.gps.ned_vel.y = XSENS_DATA_RAWGPS_vel_e(xsens_msg_buf, offset);
+ xsens.gps.ned_vel.z = XSENS_DATA_RAWGPS_vel_d(xsens_msg_buf, offset);
+ SetBit(gps.valid_fields, GPS_VALID_VEL_NED_BIT);
+ xsens.gps.pacc = XSENS_DATA_RAWGPS_hacc(xsens_msg_buf, offset) / 100;
+ xsens.gps.sacc = XSENS_DATA_RAWGPS_sacc(xsens_msg_buf, offset) / 100;
+ xsens.gps.pdop = 5; // FIXME Not output by XSens
+
+ xsens.gps_available = TRUE;
+#endif
+ offset += XSENS_DATA_RAWGPS_LENGTH;
+ }
+ //} else {
+ if (XSENS_MASK_Temp(xsens_output_mode)) {
+ offset += XSENS_DATA_Temp_LENGTH;
+ }
+ if (XSENS_MASK_Calibrated(xsens_output_mode)) {
+ uint8_t l = 0;
+ if (!XSENS_MASK_AccOut(xsens_output_settings)) {
+ xsens.accel.x = XSENS_DATA_Calibrated_accX(xsens_msg_buf, offset);
+ xsens.accel.y = XSENS_DATA_Calibrated_accY(xsens_msg_buf, offset);
+ xsens.accel.z = XSENS_DATA_Calibrated_accZ(xsens_msg_buf, offset);
+ xsens.accel_available = TRUE;
+ l++;
+ }
+ if (!XSENS_MASK_GyrOut(xsens_output_settings)) {
+ xsens.gyro.p = XSENS_DATA_Calibrated_gyrX(xsens_msg_buf, offset);
+ xsens.gyro.q = XSENS_DATA_Calibrated_gyrY(xsens_msg_buf, offset);
+ xsens.gyro.r = XSENS_DATA_Calibrated_gyrZ(xsens_msg_buf, offset);
+ xsens.gyro_available = TRUE;
+ l++;
+ }
+ if (!XSENS_MASK_MagOut(xsens_output_settings)) {
+ xsens.mag.x = XSENS_DATA_Calibrated_magX(xsens_msg_buf, offset);
+ xsens.mag.y = XSENS_DATA_Calibrated_magY(xsens_msg_buf, offset);
+ xsens.mag.z = XSENS_DATA_Calibrated_magZ(xsens_msg_buf, offset);
+ xsens.mag_available = TRUE;
+ l++;
+ }
+ offset += l * XSENS_DATA_Calibrated_LENGTH / 3;
+ }
+ if (XSENS_MASK_Orientation(xsens_output_mode)) {
+ if (XSENS_MASK_OrientationMode(xsens_output_settings) == 0x00) {
+ xsens.quat.qi = XSENS_DATA_Quaternion_q0(xsens_msg_buf, offset);
+ xsens.quat.qx = XSENS_DATA_Quaternion_q1(xsens_msg_buf, offset);
+ xsens.quat.qy = XSENS_DATA_Quaternion_q2(xsens_msg_buf, offset);
+ xsens.quat.qz = XSENS_DATA_Quaternion_q3(xsens_msg_buf, offset);
+ //float_eulers_of_quat(&xsens.euler, &xsens.quat);
+ offset += XSENS_DATA_Quaternion_LENGTH;
+ }
+ if (XSENS_MASK_OrientationMode(xsens_output_settings) == 0x01) {
+ xsens.euler.phi = XSENS_DATA_Euler_roll(xsens_msg_buf, offset) * M_PI / 180;
+ xsens.euler.theta = XSENS_DATA_Euler_pitch(xsens_msg_buf, offset) * M_PI / 180;
+ xsens.euler.psi = XSENS_DATA_Euler_yaw(xsens_msg_buf, offset) * M_PI / 180;
+ offset += XSENS_DATA_Euler_LENGTH;
+ }
+ if (XSENS_MASK_OrientationMode(xsens_output_settings) == 0x10) {
+ offset += XSENS_DATA_Matrix_LENGTH;
+ }
+ xsens.new_attitude = TRUE;
+ }
+ if (XSENS_MASK_Auxiliary(xsens_output_mode)) {
+ uint8_t l = 0;
+ if (!XSENS_MASK_Aux1Out(xsens_output_settings)) {
+ l++;
+ }
+ if (!XSENS_MASK_Aux2Out(xsens_output_settings)) {
+ l++;
+ }
+ offset += l * XSENS_DATA_Auxiliary_LENGTH / 2;
+ }
+ if (XSENS_MASK_Position(xsens_output_mode)) {
+ xsens.lla_f.lat = RadOfDeg(XSENS_DATA_Position_lat(xsens_msg_buf, offset));
+ xsens.lla_f.lon = RadOfDeg(XSENS_DATA_Position_lon(xsens_msg_buf, offset));
+ xsens.lla_f.alt = XSENS_DATA_Position_alt(xsens_msg_buf, offset);
+ offset += XSENS_DATA_Position_LENGTH;
+
+#if (! USE_GPS_XSENS_RAW_DATA) && USE_GPS_XSENS
+ LLA_BFP_OF_REAL(xsens.gps.lla_pos, xsens.lla_f);
+ SetBit(gps.valid_fields, GPS_VALID_POS_LLA_BIT);
+ xsens.gps_available = TRUE;
+#endif
+ }
+ if (XSENS_MASK_Velocity(xsens_output_mode)) {
+ xsens.vel.x = XSENS_DATA_Velocity_vx(xsens_msg_buf, offset);
+ xsens.vel.y = XSENS_DATA_Velocity_vy(xsens_msg_buf, offset);
+ xsens.vel.z = XSENS_DATA_Velocity_vz(xsens_msg_buf, offset);
+ offset += XSENS_DATA_Velocity_LENGTH;
+ }
+ if (XSENS_MASK_Status(xsens_output_mode)) {
+ xsens_msg_status = XSENS_DATA_Status_status(xsens_msg_buf, offset);
+#if USE_GPS_XSENS
+ if (bit_is_set(xsens_msg_status, 2)) { xsens.gps.fix = GPS_FIX_3D; } // gps fix
+ else if (bit_is_set(xsens_msg_status, 1)) { xsens.gps.fix = 0x01; } // efk valid
+ else { xsens.gps.fix = GPS_FIX_NONE; }
+#ifdef GPS_LED
+ if (xsens.gps.fix == GPS_FIX_3D) {
+ LED_ON(GPS_LED);
+ } else {
+ LED_TOGGLE(GPS_LED);
+ }
+#endif // GPS_LED
+#endif // USE_GPS_XSENS
+ offset += XSENS_DATA_Status_LENGTH;
+ }
+ if (XSENS_MASK_TimeStamp(xsens_output_settings)) {
+ xsens.time_stamp = XSENS_DATA_TimeStamp_ts(xsens_msg_buf, offset);
+ offset += XSENS_DATA_TimeStamp_LENGTH;
+ }
+ if (XSENS_MASK_UTC(xsens_output_settings)) {
+ xsens.time.hour = XSENS_DATA_UTC_hour(xsens_msg_buf, offset);
+ xsens.time.min = XSENS_DATA_UTC_min(xsens_msg_buf, offset);
+ xsens.time.sec = XSENS_DATA_UTC_sec(xsens_msg_buf, offset);
+ xsens.time.nanosec = XSENS_DATA_UTC_nanosec(xsens_msg_buf, offset);
+ xsens.time.year = XSENS_DATA_UTC_year(xsens_msg_buf, offset);
+ xsens.time.month = XSENS_DATA_UTC_month(xsens_msg_buf, offset);
+ xsens.time.day = XSENS_DATA_UTC_day(xsens_msg_buf, offset);
+
+ offset += XSENS_DATA_UTC_LENGTH;
+ }
+ }
+
+}
diff --git a/sw/airborne/modules/ins/xsens.h b/sw/airborne/modules/ins/xsens.h
new file mode 100644
index 0000000000..9e7fd48f79
--- /dev/null
+++ b/sw/airborne/modules/ins/xsens.h
@@ -0,0 +1,82 @@
+/*
+ * Copyright (C) 2010 ENAC
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+/** @file modules/ins/xsens.h
+ * Parser for the Xsens protocol.
+ */
+
+#ifndef XSENS_H
+#define XSENS_H
+
+#include "std.h"
+#include "math/pprz_algebra_float.h"
+#include "math/pprz_geodetic_float.h"
+#include "math/pprz_geodetic_int.h"
+
+#if USE_GPS_XSENS
+#include "subsystems/gps.h"
+#endif
+
+struct XsensTime {
+ int8_t hour;
+ int8_t min;
+ int8_t sec;
+ int32_t nanosec;
+ int16_t year;
+ int8_t month;
+ int8_t day;
+};
+
+struct Xsens {
+ struct XsensTime time;
+ uint16_t time_stamp;
+
+ struct FloatRates gyro;
+ struct FloatVect3 accel;
+ struct FloatVect3 mag;
+
+ struct LlaCoor_f lla_f;
+ struct FloatVect3 vel; ///< NED velocity in m/s
+
+ struct FloatQuat quat;
+ struct FloatEulers euler;
+
+ volatile bool msg_received;
+ volatile bool new_attitude;
+
+ bool gyro_available;
+ bool accel_available;
+ bool mag_available;
+
+#if USE_GPS_XSENS
+ struct GpsState gps;
+ bool gps_available;
+#endif
+};
+
+extern struct Xsens xsens;
+
+extern void xsens_init(void);
+extern void xsens_periodic(void);
+extern void parse_xsens_msg(void);
+
+#endif /* XSENS_H */
diff --git a/sw/airborne/modules/ins/xsens700.c b/sw/airborne/modules/ins/xsens700.c
new file mode 100644
index 0000000000..c9e76ac923
--- /dev/null
+++ b/sw/airborne/modules/ins/xsens700.c
@@ -0,0 +1,285 @@
+/*
+ * Copyright (C) 2013 Christophe De Wagter
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+/**
+ * @file modules/ins/xsens700.c
+ * Parser for the Xsens700 protocol.
+ */
+
+#include "xsens700.h"
+#include "xsens_common.h"
+
+#include "generated/airframe.h"
+
+#if USE_GPS_XSENS
+#include "math/pprz_geodetic_wgs84.h"
+#endif
+
+// FIXME Debugging Only
+#include "mcu_periph/uart.h"
+#include "pprzlink/messages.h"
+#include "subsystems/datalink/downlink.h"
+
+
+uint8_t xsens_errorcode;
+uint32_t xsens_msg_statusword;
+uint16_t xsens_time_stamp;
+uint16_t xsens_output_mode;
+uint32_t xsens_output_settings;
+
+float xsens_gps_arm_x = 0;
+float xsens_gps_arm_y = 0;
+float xsens_gps_arm_z = 0;
+
+struct Xsens xsens700;
+
+volatile int xsens_configured = 0;
+
+void xsens700_init(void)
+{
+ xsens_status = UNINIT;
+ xsens_configured = 30;
+
+ xsens_msg_statusword = 0;
+ xsens_time_stamp = 0;
+}
+
+static void xsens_ask_message_rate(uint8_t c1, uint8_t c2, uint8_t freq)
+{
+ uint8_t foo = 0;
+ XsensSend1ByAddr(&c1);
+ XsensSend1ByAddr(&c2);
+ XsensSend1ByAddr(&foo);
+ XsensSend1ByAddr(&freq);
+}
+
+void xsens700_periodic(void)
+{
+ if (xsens_configured > 0) {
+ switch (xsens_configured) {
+ case 25:
+ /* send mode and settings to MT */
+ XSENS_GoToConfig();
+ //XSENS_SetOutputMode(xsens_output_mode);
+ //XSENS_SetOutputSettings(xsens_output_settings);
+ break;
+ case 18:
+ // Give pulses on SyncOut
+ //XSENS_SetSyncOutSettings(0,0x0002);
+ break;
+ case 17:
+
+ XsensHeader(XSENS_SetOutputConfiguration_ID, 44);
+ xsens_ask_message_rate(0x10, 0x10, 4); // UTC
+ xsens_ask_message_rate(0x20, 0x30, 100); // Attitude Euler
+ xsens_ask_message_rate(0x40, 0x10, 100); // Delta-V
+ xsens_ask_message_rate(0x80, 0x20, 100); // Rate of turn
+ xsens_ask_message_rate(0xE0, 0x20, 50); // Status
+ xsens_ask_message_rate(0x30, 0x10, 50); // Baro Pressure
+ xsens_ask_message_rate(0x88, 0x40, 1); // NavSol
+ xsens_ask_message_rate(0x88, 0xA0, 1); // SV Info
+ xsens_ask_message_rate(0x50, 0x20, 50); // GPS Altitude Ellipsiod
+ xsens_ask_message_rate(0x50, 0x40, 50); // GPS Position
+ xsens_ask_message_rate(0xD0, 0x10, 50); // GPS Speed
+ XsensTrailer();
+ break;
+ case 2:
+ //XSENS_ReqLeverArmGps();
+ break;
+
+ case 6:
+ //XSENS_ReqMagneticDeclination();
+ break;
+
+ case 13:
+ //#ifdef AHRS_H_X
+ //#pragma message "Sending XSens Magnetic Declination."
+ //xsens_declination = atan2(AHRS_H_Y, AHRS_H_X);
+ //XSENS_SetMagneticDeclination(xsens_declination);
+ //#endif
+ break;
+ case 12:
+#ifdef GPS_IMU_LEVER_ARM_X
+#pragma message "Sending XSens GPS Arm."
+ XSENS_SetLeverArmGps(GPS_IMU_LEVER_ARM_X, GPS_IMU_LEVER_ARM_Y, GPS_IMU_LEVER_ARM_Z);
+#endif
+ break;
+ case 10: {
+ uint8_t baud = 1;
+ XSENS_SetBaudrate(baud);
+ }
+ break;
+
+ case 1:
+ XSENS_GoToMeasurment();
+ break;
+ default:
+ break;
+ }
+ xsens_configured--;
+ return;
+ }
+
+}
+
+
+void parse_xsens700_msg(void)
+{
+ uint8_t offset = 0;
+ if (xsens_id == XSENS_ReqLeverArmGpsAck_ID) {
+ xsens_gps_arm_x = XSENS_ReqLeverArmGpsAck_x(xsens_msg_buf);
+ xsens_gps_arm_y = XSENS_ReqLeverArmGpsAck_y(xsens_msg_buf);
+ xsens_gps_arm_z = XSENS_ReqLeverArmGpsAck_z(xsens_msg_buf);
+ } else if (xsens_id == XSENS_Error_ID) {
+ xsens_errorcode = XSENS_Error_errorcode(xsens_msg_buf);
+ } else if (xsens_id == XSENS_MTData2_ID) {
+ for (offset = 0; offset < xsens_len;) {
+ uint8_t code1 = xsens_msg_buf[offset];
+ uint8_t code2 = xsens_msg_buf[offset + 1];
+ int subpacklen = (int)xsens_msg_buf[offset + 2];
+ offset += 3;
+
+ if (code1 == 0x10) {
+ if (code2 == 0x10) {
+ // UTC
+ } else if (code2 == 0x20) {
+ // Packet Counter
+ }
+ if (code2 == 0x30) {
+ // ITOW
+ }
+ } else if (code1 == 0x20) {
+ if (code2 == 0x30) {
+ // Attitude Euler
+ xsens700.euler.phi = XSENS_DATA_Euler_roll(xsens_msg_buf, offset) * M_PI / 180;
+ xsens700.euler.theta = XSENS_DATA_Euler_pitch(xsens_msg_buf, offset) * M_PI / 180;
+ xsens700.euler.psi = XSENS_DATA_Euler_yaw(xsens_msg_buf, offset) * M_PI / 180;
+
+ xsens700.new_attitude = TRUE;
+ }
+ } else if (code1 == 0x40) {
+ if (code2 == 0x10) {
+ // Delta-V
+ xsens700.accel.x = XSENS_DATA_Acceleration_x(xsens_msg_buf, offset) * 100.0f;
+ xsens700.accel.y = XSENS_DATA_Acceleration_y(xsens_msg_buf, offset) * 100.0f;
+ xsens700.accel.z = XSENS_DATA_Acceleration_z(xsens_msg_buf, offset) * 100.0f;
+ }
+ } else if (code1 == 0x80) {
+ if (code2 == 0x20) {
+ // Rate Of Turn
+ xsens700.gyro.p = XSENS_DATA_RateOfTurn_x(xsens_msg_buf, offset) * M_PI / 180;
+ xsens700.gyro.q = XSENS_DATA_RateOfTurn_y(xsens_msg_buf, offset) * M_PI / 180;
+ xsens700.gyro.r = XSENS_DATA_RateOfTurn_z(xsens_msg_buf, offset) * M_PI / 180;
+ }
+ } else if (code1 == 0x30) {
+ if (code2 == 0x10) {
+ // Baro Pressure
+ }
+ } else if (code1 == 0xE0) {
+ if (code2 == 0x20) {
+ // Status Word
+ xsens_msg_statusword = XSENS_DATA_StatusWord_status(xsens_msg_buf, offset);
+ //xsens700.gps.tow = xsens_msg_statusword;
+#if USE_GPS_XSENS
+ if (bit_is_set(xsens_msg_statusword, 2) && bit_is_set(xsens_msg_statusword, 1)) {
+ if (bit_is_set(xsens_msg_statusword, 23) && bit_is_set(xsens_msg_statusword, 24)) {
+ xsens700.gps.fix = GPS_FIX_3D;
+ } else {
+ xsens700.gps.fix = GPS_FIX_2D;
+ }
+ } else { xsens700.gps.fix = GPS_FIX_NONE; }
+#endif
+ }
+ } else if (code1 == 0x88) {
+ if (code2 == 0x40) {
+ xsens700.gps.week = XSENS_DATA_GpsSol_week(xsens_msg_buf, offset);
+ xsens700.gps.num_sv = XSENS_DATA_GpsSol_numSv(xsens_msg_buf, offset);
+ xsens700.gps.pacc = XSENS_DATA_GpsSol_pAcc(xsens_msg_buf, offset);
+ xsens700.gps.sacc = XSENS_DATA_GpsSol_sAcc(xsens_msg_buf, offset);
+ xsens700.gps.pdop = XSENS_DATA_GpsSol_pDop(xsens_msg_buf, offset);
+ } else if (code2 == 0xA0) {
+ // SVINFO
+ xsens700.gps.tow = XSENS_XDI_GpsSvInfo_iTOW(xsens_msg_buf + offset);
+
+#if USE_GPS_XSENS
+ xsens700.gps.nb_channels = XSENS_XDI_GpsSvInfo_nch(xsens_msg_buf + offset);
+
+ xsens700.gps.last_3dfix_ticks = sys_time.nb_sec_rem;
+ xsens700.gps.last_3dfix_time = sys_time.nb_sec;
+
+ uint8_t i;
+ // Do not write outside buffer
+ for (i = 0; i < Min(xsens700.gps.nb_channels, GPS_NB_CHANNELS); i++) {
+ uint8_t ch = XSENS_XDI_GpsSvInfo_chn(xsens_msg_buf + offset, i);
+ if (ch > xsens700.gps.nb_channels) { continue; }
+ xsens700.gps.svinfos[ch].svid = XSENS_XDI_GpsSvInfo_svid(xsens_msg_buf + offset, i);
+ xsens700.gps.svinfos[ch].flags = XSENS_XDI_GpsSvInfo_bitmask(xsens_msg_buf + offset, i);
+ xsens700.gps.svinfos[ch].qi = XSENS_XDI_GpsSvInfo_qi(xsens_msg_buf + offset, i);
+ xsens700.gps.svinfos[ch].cno = XSENS_XDI_GpsSvInfo_cnr(xsens_msg_buf + offset, i);
+ }
+#endif
+ }
+ } else if (code1 == 0x50) {
+ if (code2 == 0x10) {
+ //xsens700.gps.hmsl = XSENS_DATA_Altitude_h(xsens_msg_buf,offset)* 1000.0f;
+ } else if (code2 == 0x20) {
+ // Altitude Elipsoid
+ xsens700.gps.lla_pos.alt = XSENS_DATA_Altitude_h(xsens_msg_buf, offset) * 1000.0f;
+
+ // Compute geoid (MSL) height
+ float geoid_h = wgs84_ellipsoid_to_geoid(xsens700.lla_f.lat, xsens700.lla_f.lon);
+ xsens700.gps.hmsl = xsens700.gps.lla_pos.alt - (geoid_h * 1000.0f);
+ SetBit(xsens700.gps.valid_fields, GPS_VALID_HMSL_BIT);
+
+ //xsens700.gps.tow = geoid_h * 1000.0f; //xsens700.gps.utm_pos.alt;
+ } else if (code2 == 0x40) {
+ // LatLong
+#ifdef GPS_LED
+ LED_TOGGLE(GPS_LED);
+#endif
+ xsens700.gps.last_3dfix_ticks = sys_time.nb_sec_rem;
+ xsens700.gps.last_3dfix_time = sys_time.nb_sec;
+ xsens700.gps.week = 0; // FIXME
+
+ xsens700.lla_f.lat = RadOfDeg(XSENS_DATA_LatLon_lat(xsens_msg_buf, offset));
+ xsens700.lla_f.lon = RadOfDeg(XSENS_DATA_LatLon_lon(xsens_msg_buf, offset));
+ }
+ } else if (code1 == 0xD0) {
+ if (code2 == 0x10) {
+ // Velocity
+ xsens700.vel.x = XSENS_DATA_VelocityXYZ_x(xsens_msg_buf, offset);
+ xsens700.vel.y = XSENS_DATA_VelocityXYZ_y(xsens_msg_buf, offset);
+ xsens700.vel.z = XSENS_DATA_VelocityXYZ_z(xsens_msg_buf, offset);
+ xsens700.gps.ned_vel.x = xsens700.vel.x;
+ xsens700.gps.ned_vel.y = xsens700.vel.y;
+ xsens700.gps.ned_vel.z = xsens700.vel.x;
+ SetBit(xsens700.gps.valid_fields, GPS_VALID_VEL_NED_BIT);
+ }
+ }
+
+ if (subpacklen < 0) {
+ subpacklen = 0;
+ }
+ offset += subpacklen;
+ }
+ }
+}
diff --git a/sw/airborne/modules/ins/xsens700.h b/sw/airborne/modules/ins/xsens700.h
new file mode 100644
index 0000000000..ef221d76fc
--- /dev/null
+++ b/sw/airborne/modules/ins/xsens700.h
@@ -0,0 +1,82 @@
+/*
+ * Copyright (C) 2010 ENAC
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+/** @file modules/ins/xsens_700.h
+ * Parser for the Xsens protocol.
+ */
+
+#ifndef XSENS700_H
+#define XSENS700_H
+
+#include "std.h"
+#include "math/pprz_algebra_float.h"
+#include "math/pprz_geodetic_float.h"
+#include "math/pprz_geodetic_int.h"
+
+#if USE_GPS_XSENS
+#include "subsystems/gps.h"
+#endif
+
+struct XsensTime {
+ int8_t hour;
+ int8_t min;
+ int8_t sec;
+ int32_t nanosec;
+ int16_t year;
+ int8_t month;
+ int8_t day;
+};
+
+struct Xsens {
+ struct XsensTime time;
+ uint16_t time_stamp;
+
+ struct FloatRates gyro;
+ struct FloatVect3 accel;
+ struct FloatVect3 mag;
+
+ struct LlaCoor_f lla_f;
+ struct FloatVect3 vel; ///< NED velocity in m/s
+
+ struct FloatQuat quat;
+ struct FloatEulers euler;
+
+ volatile bool msg_received;
+ volatile bool new_attitude;
+
+ bool gyro_available;
+ bool accel_available;
+ bool mag_available;
+
+#if USE_GPS_XSENS
+ struct GpsState gps;
+ bool gps_available;
+#endif
+};
+
+extern struct Xsens xsens700;
+
+extern void xsens700_init(void);
+extern void xsens700_periodic(void);
+extern void parse_xsens700_msg(void);
+
+#endif /* XSENS700_H */
diff --git a/sw/airborne/modules/ins/xsens_common.c b/sw/airborne/modules/ins/xsens_common.c
new file mode 100644
index 0000000000..4c2c9ba95a
--- /dev/null
+++ b/sw/airborne/modules/ins/xsens_common.c
@@ -0,0 +1,105 @@
+/*
+ * Copyright (C) 2003 Pascal Brisset, Antoine Drouin
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ */
+
+/** @file modules/ins/xsens_common.c
+ * Parser for the Xsens protocol.
+ */
+
+#include "xsens_common.h"
+
+#include "pprzlink/pprzlink_device.h"
+#include "mcu_periph/uart.h"
+
+volatile uint8_t xsens_msg_received;
+
+uint8_t xsens_id;
+uint8_t xsens_status;
+uint8_t xsens_len;
+uint8_t xsens_msg_idx;
+uint8_t ck;
+uint8_t send_ck;
+
+uint8_t xsens_msg_buf[XSENS_MAX_PAYLOAD];
+
+void parse_xsens_buffer(uint8_t c);
+
+void xsens_event(void)
+{
+ struct link_device *dev = &((XSENS_LINK).device);
+ if (dev->char_available(dev->periph)) {
+ while (dev->char_available(dev->periph) && !xsens_msg_received) {
+ parse_xsens_buffer(dev->get_byte(dev->periph));
+ }
+ }
+}
+
+void parse_xsens_buffer(uint8_t c)
+{
+ ck += c;
+ switch (xsens_status) {
+ case UNINIT:
+ if (c != XSENS_START) {
+ goto error;
+ }
+ xsens_status++;
+ ck = 0;
+ break;
+ case GOT_START:
+ if (c != XSENS_BID) {
+ goto error;
+ }
+ xsens_status++;
+ break;
+ case GOT_BID:
+ xsens_id = c;
+ xsens_status++;
+ break;
+ case GOT_MID:
+ xsens_len = c;
+ if (xsens_len > XSENS_MAX_PAYLOAD) {
+ goto error;
+ }
+ xsens_msg_idx = 0;
+ xsens_status++;
+ break;
+ case GOT_LEN:
+ xsens_msg_buf[xsens_msg_idx] = c;
+ xsens_msg_idx++;
+ if (xsens_msg_idx >= xsens_len) {
+ xsens_status++;
+ }
+ break;
+ case GOT_DATA:
+ if (ck != 0) {
+ goto error;
+ }
+ xsens_msg_received = TRUE;
+ goto restart;
+ break;
+ default:
+ break;
+ }
+ return;
+error:
+restart:
+ xsens_status = UNINIT;
+ return;
+}
diff --git a/sw/airborne/modules/ins/xsens_common.h b/sw/airborne/modules/ins/xsens_common.h
new file mode 100644
index 0000000000..8abd2dc9ed
--- /dev/null
+++ b/sw/airborne/modules/ins/xsens_common.h
@@ -0,0 +1,75 @@
+/*
+ * Copyright (C) 2003 Pascal Brisset, Antoine Drouin
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING. If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ */
+
+/** @file modules/ins/xsens_common.h
+ * Parser for the Xsens protocol.
+ */
+
+#ifndef XSENS_COMMON_H
+#define XSENS_COMMON_H
+
+#include "std.h"
+
+/** Includes macros generated from xsens_MTi-G.xml */
+#include "xsens_protocol.h"
+
+extern uint8_t xsens_id;
+extern uint8_t xsens_status;
+extern uint8_t xsens_len;
+extern uint8_t xsens_msg_idx;
+extern uint8_t ck;
+extern uint8_t send_ck;
+
+#define XsensLinkDevice (&((XSENS_LINK).device))
+
+#define XsensInitCheksum() { send_ck = 0; }
+#define XsensUpdateChecksum(c) { send_ck += c; }
+
+#define XsensUartSend1(c) XsensLinkDevice->put_byte(XsensLinkDevice->periph, c)
+#define XsensSend1(c) { uint8_t i8=c; XsensUartSend1(i8); XsensUpdateChecksum(i8); }
+#define XsensSend1ByAddr(x) { XsensSend1(*x); }
+#define XsensSend2ByAddr(x) { XsensSend1(*(x+1)); XsensSend1(*x); }
+#define XsensSend4ByAddr(x) { XsensSend1(*(x+3)); XsensSend1(*(x+2)); XsensSend1(*(x+1)); XsensSend1(*x); }
+
+#define XsensHeader(msg_id, len) { \
+ XsensUartSend1(XSENS_START); \
+ XsensInitCheksum(); \
+ XsensSend1(XSENS_BID); \
+ XsensSend1(msg_id); \
+ XsensSend1(len); \
+ }
+#define XsensTrailer() { uint8_t i8=0x100-send_ck; XsensUartSend1(i8); }
+
+
+#define XSENS_MAX_PAYLOAD 254
+extern uint8_t xsens_msg_buf[XSENS_MAX_PAYLOAD];
+
+#define UNINIT 0
+#define GOT_START 1
+#define GOT_BID 2
+#define GOT_MID 3
+#define GOT_LEN 4
+#define GOT_DATA 5
+#define GOT_CHECKSUM 6
+
+extern void xsens_event(void);
+
+#endif /* XSENS_COMMON_H */
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 d245082cf1..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_t 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 fd8993d0d8..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_t 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 7e02d7eaaa..22092fb2bc 100644
--- a/sw/airborne/modules/loggers/sdlogger_spi_direct.c
+++ b/sw/airborne/modules/loggers/sdlogger_spi_direct.c
@@ -344,15 +344,15 @@ void sdlogger_spi_direct_command(void)
sdlogger_spi.command = 0;
}
-bool_t sdlogger_spi_direct_check_free_space(struct sdlogger_spi_periph *p, uint8_t len)
+bool sdlogger_spi_direct_check_free_space(struct sdlogger_spi_periph *p, uint8_t len)
{
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/loggers/sdlogger_spi_direct.h b/sw/airborne/modules/loggers/sdlogger_spi_direct.h
index 2d55fa744e..251b8c84a6 100644
--- a/sw/airborne/modules/loggers/sdlogger_spi_direct.h
+++ b/sw/airborne/modules/loggers/sdlogger_spi_direct.h
@@ -72,7 +72,7 @@ extern void sdlogger_spi_direct_index_received(void);
extern void sdlogger_spi_direct_multiwrite_written(void);
extern void sdlogger_spi_direct_command(void);
-extern bool_t sdlogger_spi_direct_check_free_space(struct sdlogger_spi_periph *p, uint8_t len);
+extern bool sdlogger_spi_direct_check_free_space(struct sdlogger_spi_periph *p, uint8_t len);
extern void sdlogger_spi_direct_put_byte(struct sdlogger_spi_periph *p, uint8_t data);
extern void sdlogger_spi_direct_send_message(void *p);
extern int sdlogger_spi_direct_char_available(void *p);
diff --git a/sw/airborne/modules/meteo/humid_sht.c b/sw/airborne/modules/meteo/humid_sht.c
index 884cb3a5dc..17c49496ff 100644
--- a/sw/airborne/modules/meteo/humid_sht.c
+++ b/sw/airborne/modules/meteo/humid_sht.c
@@ -40,7 +40,7 @@
#include "sdLog.h"
#include "subsystems/chibios-libopencm3/chibios_sdlog.h"
#include "subsystems/gps.h"
-bool_t log_sht_started;
+bool log_sht_started;
#endif
//#include "led.h"
@@ -86,7 +86,7 @@ bool_t log_sht_started;
uint16_t humidsht, tempsht;
float fhumidsht, ftempsht;
-bool_t humid_sht_available;
+bool humid_sht_available;
uint8_t humid_sht_status;
uint8_t s_write_byte(uint8_t value);
@@ -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/humid_sht.h b/sw/airborne/modules/meteo/humid_sht.h
index 68436a6646..c3cd97344a 100644
--- a/sw/airborne/modules/meteo/humid_sht.h
+++ b/sw/airborne/modules/meteo/humid_sht.h
@@ -34,7 +34,7 @@
extern uint16_t humidsht, tempsht;
extern float fhumidsht, ftempsht;
-extern bool_t humid_sht_available;
+extern bool humid_sht_available;
extern uint8_t humid_sht_status;
void humid_sht_init(void);
diff --git a/sw/airborne/modules/meteo/meteo_france_DAQ.c b/sw/airborne/modules/meteo/meteo_france_DAQ.c
index 59db68ba77..872b991e1d 100644
--- a/sw/airborne/modules/meteo/meteo_france_DAQ.c
+++ b/sw/airborne/modules/meteo/meteo_france_DAQ.c
@@ -44,7 +44,7 @@
#include "modules/datalink/extra_pprz_dl.h"
struct MF_DAQ mf_daq;
-bool_t log_started;
+bool log_started;
#ifndef MF_DAQ_POWER_INIT
#define MF_DAQ_POWER_INIT TRUE
@@ -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 ff0a836950..0aa864a4c1 100644
--- a/sw/airborne/modules/meteo/meteo_stick.c
+++ b/sw/airborne/modules/meteo/meteo_stick.c
@@ -175,7 +175,7 @@ static inline float get_humidity(uint32_t raw)
#if LOG_MS
#include "sdLog.h"
#include "subsystems/chibios-libopencm3/chibios_sdlog.h"
-bool_t log_ptu_started;
+bool log_ptu_started;
#endif
/* Includes and function to send over telemetry
@@ -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/meteo_stick.h b/sw/airborne/modules/meteo/meteo_stick.h
index 6360c37965..33b94fd91d 100644
--- a/sw/airborne/modules/meteo/meteo_stick.h
+++ b/sw/airborne/modules/meteo/meteo_stick.h
@@ -69,7 +69,7 @@ struct MeteoStick {
struct Eeprom25AA256 eeprom; ///< eeprom with calibration data
Calibration_params calib; ///< calibration
#endif
- bool_t reset_dp_offset; ///< reset differential pressure offset
+ bool reset_dp_offset; ///< reset differential pressure offset
};
extern struct MeteoStick meteo_stick;
diff --git a/sw/airborne/modules/meteo/mf_ptu.c b/sw/airborne/modules/meteo/mf_ptu.c
index 45ebadb974..333f53092f 100644
--- a/sw/airborne/modules/meteo/mf_ptu.c
+++ b/sw/airborne/modules/meteo/mf_ptu.c
@@ -64,7 +64,7 @@ uint32_t humid_period;
#if LOG_PTU
#include "sdLog.h"
#include "subsystems/chibios-libopencm3/chibios_sdlog.h"
-bool_t log_ptu_started;
+bool log_ptu_started;
#endif
#if SEND_PTU
@@ -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 6883409669..bfa9d6e0ec 100644
--- a/sw/airborne/modules/meteo/temp_temod.c
+++ b/sw/airborne/modules/meteo/temp_temod.c
@@ -38,7 +38,7 @@
#include "sdLog.h"
#include "subsystems/chibios-libopencm3/chibios_sdlog.h"
#include "subsystems/gps.h"
-bool_t log_temod_started;
+bool log_temod_started;
#endif
float ftmd_temperature;
@@ -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 fb949fc25b..e7ce945802 100644
--- a/sw/airborne/modules/mission/mission_common.c
+++ b/sw/airborne/modules/mission/mission_common.c
@@ -44,23 +44,23 @@ void mission_init(void)
// Insert element
-bool_t mission_insert(enum MissionInsertMode insert, struct _mission_element *element)
+bool mission_insert(enum MissionInsertMode insert, struct _mission_element *element)
{
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_t mission_insert(enum MissionInsertMode insert, struct _mission_element *el
break;
default:
// unknown insertion mode
- return FALSE;
+ return false;
}
- return TRUE;
+ return true;
}
// Weak implementation of mission_element_convert (leave element unchanged)
-bool_t __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_common.h b/sw/airborne/modules/mission/mission_common.h
index a9c41e3585..10c7aa4591 100644
--- a/sw/airborne/modules/mission/mission_common.h
+++ b/sw/airborne/modules/mission/mission_common.h
@@ -127,13 +127,13 @@ extern void mission_init(void);
* @param element mission element structure
* @return return TRUE if insertion is succesful, FALSE otherwise
*/
-extern bool_t mission_insert(enum MissionInsertMode insert, struct _mission_element *element);
+extern bool mission_insert(enum MissionInsertMode insert, struct _mission_element *element);
/** Convert mission element's points format if needed
* @param el pointer to the mission element
* @return return TRUE if conversion is succesful, FALSE otherwise
*/
-extern bool_t mission_element_convert(struct _mission_element *el);
+extern bool mission_element_convert(struct _mission_element *el);
/** Get current mission element
* @return return a pointer to the next mission element or NULL if no more elements
@@ -146,7 +146,7 @@ extern struct _mission_element *mission_get(void);
* @param lla pointer to the input LLA coordinates (int)
* @return TRUE if conversion is succesful, FALSE otherwise
*/
-extern bool_t mission_point_of_lla(struct EnuCoor_f *point, struct LlaCoor_i *lla);
+extern bool mission_point_of_lla(struct EnuCoor_f *point, struct LlaCoor_i *lla);
/** Run mission
*
diff --git a/sw/airborne/modules/mission/mission_fw_nav.c b/sw/airborne/modules/mission/mission_fw_nav.c
index 473aef46e2..1b980b9e55 100644
--- a/sw/airborne/modules/mission/mission_fw_nav.c
+++ b/sw/airborne/modules/mission/mission_fw_nav.c
@@ -35,7 +35,7 @@
#include "generated/flight_plan.h"
/// Utility function: converts lla (int) to local point (float)
-bool_t mission_point_of_lla(struct EnuCoor_f *point, struct LlaCoor_i *lla)
+bool mission_point_of_lla(struct EnuCoor_f *point, struct LlaCoor_i *lla)
{
/// TODO: don't convert to float, either use double or do completely in fixed point
struct LlaCoor_f lla_f;
@@ -60,7 +60,7 @@ bool_t 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
@@ -71,50 +71,50 @@ struct EnuCoor_f last_wp_f = { 0., 0., 0. };
/** Navigation function to a single waypoint
*/
-static inline bool_t mission_nav_wp(struct _mission_wp *wp)
+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
*/
-static inline bool_t mission_nav_circle(struct _mission_circle *circle)
+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
*/
-static inline bool_t mission_nav_segment(struct _mission_segment *segment)
+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
*/
-static inline bool_t mission_nav_path(struct _mission_path *path)
+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_t 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_t 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_t 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 4b6db2f238..ff918d5701 100644
--- a/sw/airborne/modules/mission/mission_rotorcraft_nav.c
+++ b/sw/airborne/modules/mission/mission_rotorcraft_nav.c
@@ -38,11 +38,11 @@
#define BUFFER_ZONE_DIST 10
/// Utility function: converts lla (int) to local point (float)
-bool_t mission_point_of_lla(struct EnuCoor_f *point, struct LlaCoor_i *lla)
+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,11 +72,11 @@ bool_t 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
-bool_t mission_element_convert(struct _mission_element *el)
+bool mission_element_convert(struct _mission_element *el)
{
struct _mission_element tmp_element = *el;
uint8_t i = 0;
@@ -99,11 +99,11 @@ bool_t mission_element_convert(struct _mission_element *el)
break;
default:
// invalid element type
- return FALSE;
+ return false;
break;
}
- return TRUE;
+ return true;
}
// navigation time step
@@ -114,7 +114,7 @@ struct EnuCoor_i last_mission_wp = { 0., 0., 0. };
/** Navigation function to a single waypoint
*/
-static inline bool_t mission_nav_wp(struct _mission_element *el)
+static inline bool mission_nav_wp(struct _mission_element *el)
{
struct EnuCoor_i *target_wp = &(el->element.mission_wp.wp.wp_i);
@@ -123,8 +123,8 @@ static inline bool_t 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,12 +133,12 @@ static inline bool_t 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
*/
-static inline bool_t mission_nav_circle(struct _mission_element *el)
+static inline bool mission_nav_circle(struct _mission_element *el)
{
struct EnuCoor_i *center_wp = &(el->element.mission_circle.center.center_i);
int32_t radius = el->element.mission_circle.radius;
@@ -150,15 +150,15 @@ static inline bool_t 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
*/
-static inline bool_t mission_nav_segment(struct _mission_element *el)
+static inline bool mission_nav_segment(struct _mission_element *el)
{
struct EnuCoor_i *from_wp = &(el->element.mission_segment.from.from_i);
struct EnuCoor_i *to_wp = &(el->element.mission_segment.to.to_i);
@@ -168,8 +168,8 @@ static inline bool_t 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,16 +178,16 @@ static inline bool_t mission_nav_segment(struct _mission_element *el)
NavVerticalAutoThrottleMode(RadOfDeg(0.0));
NavVerticalAltitudeMode(POS_FLOAT_OF_BFP(to_wp->z), 0.);
- return TRUE;
+ return true;
}
/** Navigation function along a path
*/
-static inline bool_t mission_nav_path(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_t 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_t 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 f93a46c282..eced90b37e 100644
--- a/sw/airborne/modules/nav/nav_bungee_takeoff.c
+++ b/sw/airborne/modules/nav/nav_bungee_takeoff.c
@@ -142,7 +142,7 @@ static void compute_points_from_bungee(void)
VECT2_SUM(throttle_point, bungee_point, throttle_point);
}
-bool_t nav_bungee_takeoff_setup(uint8_t bungee_wp)
+bool nav_bungee_takeoff_setup(uint8_t bungee_wp)
{
// Store bungee point (from WP id, altitude should be ground alt)
// FIXME use current alt instead ?
@@ -155,10 +155,10 @@ bool_t nav_bungee_takeoff_setup(uint8_t bungee_wp)
CTakeoffStatus = Launch;
kill_throttle = 1;
- return FALSE;
+ return false;
}
-bool_t nav_bungee_takeoff_run(void)
+bool nav_bungee_takeoff_run(void)
{
float cross = 0.;
@@ -208,15 +208,15 @@ bool_t 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_bungee_takeoff.h b/sw/airborne/modules/nav/nav_bungee_takeoff.h
index d7c9c50b6e..70beeebaca 100644
--- a/sw/airborne/modules/nav/nav_bungee_takeoff.h
+++ b/sw/airborne/modules/nav/nav_bungee_takeoff.h
@@ -69,7 +69,7 @@
* @param[in] bungee_wp Waypoint ID correcponding to the bungee location
* @return always false, since called only once by the flight plan
*/
-extern bool_t nav_bungee_takeoff_setup(uint8_t bungee_wp);
+extern bool nav_bungee_takeoff_setup(uint8_t bungee_wp);
/** Bungee takeoff run function
*
@@ -77,7 +77,7 @@ extern bool_t nav_bungee_takeoff_setup(uint8_t bungee_wp);
*
* @return true until the takeoff procedure ends
*/
-extern bool_t nav_bungee_takeoff_run(void);
+extern bool nav_bungee_takeoff_run(void);
#endif
diff --git a/sw/airborne/modules/nav/nav_catapult.c b/sw/airborne/modules/nav/nav_catapult.c
index bf01285cd8..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_t nav_catapult_armed = FALSE;
+static bool nav_catapult_armed = false;
static uint16_t nav_catapult_launch = 0;
#ifndef NAV_CATAPULT_ACCELERATION_THRESHOLD
@@ -94,7 +94,7 @@ static float nav_catapult_y = 0;
void nav_catapult_highrate_module(void)
{
- bool_t reset_lauch;
+ bool reset_lauch;
// Only run when
if (nav_catapult_armed) {
if (nav_catapult_launch < nav_catapult_heading_delay * NAV_CATAPULT_HIGHRATE_MODULE_FREQ) {
@@ -131,18 +131,18 @@ void nav_catapult_highrate_module(void)
//###############################################################################################
// Code that runs in 4Hz Nav
-bool_t nav_catapult_setup(void)
+bool nav_catapult_setup(void)
{
- nav_catapult_armed = TRUE;
+ nav_catapult_armed = true;
nav_catapult_launch = 0;
- return FALSE;
+ return false;
}
-bool_t nav_catapult_run(uint8_t _to, uint8_t _climb)
+bool nav_catapult_run(uint8_t _to, uint8_t _climb)
{
float alt = WaypointAlt(_climb);
@@ -191,15 +191,15 @@ bool_t nav_catapult_run(uint8_t _to, uint8_t _climb)
}
- return TRUE;
+ return true;
}
-bool_t nav_select_touch_down(uint8_t _td)
+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_catapult.h b/sw/airborne/modules/nav/nav_catapult.h
index 08ef05f0d8..4074c867cb 100644
--- a/sw/airborne/modules/nav/nav_catapult.h
+++ b/sw/airborne/modules/nav/nav_catapult.h
@@ -42,12 +42,12 @@ extern float nav_catapult_initial_throttle;
void nav_catapult_highrate_module(void);
// Flightplan Code
-extern bool_t nav_catapult_setup(void);
+extern bool nav_catapult_setup(void);
-extern bool_t nav_catapult_arm(void);
-extern bool_t nav_catapult_run(uint8_t _to, uint8_t _climb);
-extern bool_t nav_catapult_disarm(void);
+extern bool nav_catapult_arm(void);
+extern bool nav_catapult_run(uint8_t _to, uint8_t _climb);
+extern bool nav_catapult_disarm(void);
-extern bool_t nav_select_touch_down(uint8_t _td);
+extern bool nav_select_touch_down(uint8_t _td);
#endif
diff --git a/sw/airborne/modules/nav/nav_cube.c b/sw/airborne/modules/nav/nav_cube.c
index cd1cb1e05c..916f5734eb 100644
--- a/sw/airborne/modules/nav/nav_cube.c
+++ b/sw/airborne/modules/nav/nav_cube.c
@@ -36,7 +36,7 @@
struct NavCube nav_cube;
-bool_t nav_cube_setup(uint8_t center, uint8_t tb, uint8_t te)
+bool nav_cube_setup(uint8_t center, uint8_t tb, uint8_t te)
{
int32_t j, start_bx, start_by, start_bz, start_ex, start_ey, start_ez;
@@ -138,19 +138,19 @@ bool_t 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_t nav_cube_run(int8_t j, int8_t i,
+bool nav_cube_run(int8_t j, int8_t i,
uint8_t dest_b, uint8_t dest_e,
uint8_t src_b, uint8_t src_e)
{
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_t 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_cube.h b/sw/airborne/modules/nav/nav_cube.h
index 590cfb7fed..54767604d8 100644
--- a/sw/airborne/modules/nav/nav_cube.h
+++ b/sw/airborne/modules/nav/nav_cube.h
@@ -122,8 +122,8 @@ struct NavCube {
extern struct NavCube nav_cube;
-extern bool_t nav_cube_setup(uint8_t turb, uint8_t tb, uint8_t te);
-bool_t nav_cube_run(int8_t j, int8_t i,
+extern bool nav_cube_setup(uint8_t turb, uint8_t tb, uint8_t te);
+bool nav_cube_run(int8_t j, int8_t i,
uint8_t dest_b, uint8_t dest_e,
uint8_t src_b, uint8_t src_e);
diff --git a/sw/airborne/modules/nav/nav_drop.c b/sw/airborne/modules/nav/nav_drop.c
index aa0573ef1c..5e6c6048f8 100644
--- a/sw/airborne/modules/nav/nav_drop.c
+++ b/sw/airborne/modules/nav/nav_drop.c
@@ -191,7 +191,7 @@ unit_t nav_drop_shoot(void)
}
/* Compute start and end waypoints to be aligned on w1-w2 */
-bool_t compute_alignment(uint8_t w1, uint8_t w2, uint8_t wp_before, uint8_t wp_after, float d_before, float d_after)
+bool compute_alignment(uint8_t w1, uint8_t w2, uint8_t wp_before, uint8_t wp_after, float d_before, float d_after)
{
float x_0 = waypoints[w2].x - waypoints[w1].x;
float y_0 = waypoints[w2].y - waypoints[w1].y;
@@ -206,7 +206,7 @@ bool_t compute_alignment(uint8_t w1, uint8_t w2, uint8_t wp_before, uint8_t wp_a
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_drop.h b/sw/airborne/modules/nav/nav_drop.h
index 0f873501a1..78e62a3be7 100644
--- a/sw/airborne/modules/nav/nav_drop.h
+++ b/sw/airborne/modules/nav/nav_drop.h
@@ -37,7 +37,7 @@ extern unit_t nav_drop_compute_approach(uint8_t wp_target, uint8_t wp_start, uin
extern unit_t nav_drop_update_release(uint8_t wp_target);
extern unit_t nav_drop_shoot(void);
extern float nav_drop_trigger_delay, nav_drop_start_qdr;
-extern bool_t compute_alignment(uint8_t w1, uint8_t w2, uint8_t start, uint8_t end, float d_before, float d_after);
+extern bool compute_alignment(uint8_t w1, uint8_t w2, uint8_t start, uint8_t end, float d_before, float d_after);
#define NavDropComputeApproach(_target, _start, _radius) nav_drop_compute_approach(_target, _start, _radius)
#define NavDropUpdateRelease(_wp) nav_drop_update_release(_wp)
diff --git a/sw/airborne/modules/nav/nav_flower.c b/sw/airborne/modules/nav/nav_flower.c
index 4653d3dffd..4ac8ff54ea 100644
--- a/sw/airborne/modules/nav/nav_flower.c
+++ b/sw/airborne/modules/nav/nav_flower.c
@@ -57,7 +57,7 @@ static float Flowerradius;
static uint8_t Center;
static uint8_t Edge;
-bool_t nav_flower_setup(uint8_t CenterWP, uint8_t EdgeWP)
+bool nav_flower_setup(uint8_t CenterWP, uint8_t EdgeWP)
{
Center = CenterWP;
Edge = EdgeWP;
@@ -85,20 +85,20 @@ bool_t nav_flower_setup(uint8_t CenterWP, uint8_t EdgeWP)
CircleX = 0;
CircleY = 0;
- return FALSE;
+ return false;
}
-bool_t nav_flower_run(void)
+bool nav_flower_run(void)
{
TransCurrentX = stateGetPositionEnu_f()->x - WaypointX(Center);
TransCurrentY = stateGetPositionEnu_f()->y - WaypointY(Center);
DistanceFromCenter = sqrtf(TransCurrentX * TransCurrentX + TransCurrentY * TransCurrentY);
- bool_t InCircle = TRUE;
+ bool InCircle = true;
float CircleTheta;
if (DistanceFromCenter > Flowerradius) {
- InCircle = FALSE;
+ InCircle = false;
}
NavVerticalAutoThrottleMode(0); /* No pitch */
@@ -150,5 +150,5 @@ bool_t nav_flower_run(void)
default:
break;
}
- return TRUE;
+ return true;
}
diff --git a/sw/airborne/modules/nav/nav_flower.h b/sw/airborne/modules/nav/nav_flower.h
index 527f0a551e..520e70e359 100644
--- a/sw/airborne/modules/nav/nav_flower.h
+++ b/sw/airborne/modules/nav/nav_flower.h
@@ -29,7 +29,7 @@
#include "std.h"
-extern bool_t nav_flower_run(void);
-extern bool_t nav_flower_setup(uint8_t CenterWP, uint8_t EdgeWP);
+extern bool nav_flower_run(void);
+extern bool nav_flower_setup(uint8_t CenterWP, uint8_t EdgeWP);
#endif
diff --git a/sw/airborne/modules/nav/nav_gls.c b/sw/airborne/modules/nav/nav_gls.c
index 6bd541c411..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_t init = TRUE;
+bool init = true;
#ifndef APP_TARGET_SPEED
#define APP_TARGET_SPEED NOMINAL_AIRSPEED
@@ -79,7 +79,7 @@ float sd_intercept;
float sd_tod_x;
float sd_tod_y;
-static inline bool_t gls_compute_TOD(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td)
+static inline bool gls_compute_TOD(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td)
{
if ((WaypointX(_af) == WaypointX(_td)) && (WaypointY(_af) == WaypointY(_td))) {
@@ -128,14 +128,14 @@ static inline bool_t gls_compute_TOD(uint8_t _af, uint8_t _sd, uint8_t _tod, uin
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_t gls_start(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td)
+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,11 +152,11 @@ bool_t 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() */
-bool_t gls_run(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td)
+bool gls_run(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td)
{
@@ -165,7 +165,7 @@ bool_t 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_t 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_gls.h b/sw/airborne/modules/nav/nav_gls.h
index 126cab0034..8d5db00be1 100644
--- a/sw/airborne/modules/nav/nav_gls.h
+++ b/sw/airborne/modules/nav/nav_gls.h
@@ -30,7 +30,7 @@
#include "std.h"
#include "paparazzi.h"
-extern bool_t gls_start(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td);
-extern bool_t gls_run(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td);
+extern bool gls_start(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td);
+extern bool gls_run(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td);
#endif // NAV_GLS_H
diff --git a/sw/airborne/modules/nav/nav_line.c b/sw/airborne/modules/nav/nav_line.c
index 3569638aff..6a19a861ef 100644
--- a/sw/airborne/modules/nav/nav_line.c
+++ b/sw/airborne/modules/nav/nav_line.c
@@ -33,13 +33,13 @@
enum line_status { LR12, LQC21, LTC2, LQC22, LR21, LQC12, LTC1, LQC11 };
static enum line_status line_status;
-bool_t nav_line_setup(void)
+bool nav_line_setup(void)
{
line_status = LR12;
- return FALSE;
+ return false;
}
-bool_t nav_line_run(uint8_t l1, uint8_t l2, float radius)
+bool nav_line_run(uint8_t l1, uint8_t l2, float radius)
{
radius = fabs(radius);
float alt = waypoints[l1].a;
@@ -146,7 +146,7 @@ bool_t 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.h b/sw/airborne/modules/nav/nav_line.h
index a255fa58b6..a157516359 100644
--- a/sw/airborne/modules/nav/nav_line.h
+++ b/sw/airborne/modules/nav/nav_line.h
@@ -30,7 +30,7 @@
#include "std.h"
-extern bool_t nav_line_setup(void);
-extern bool_t nav_line_run(uint8_t wp1, uint8_t wp2, float radius);
+extern bool nav_line_setup(void);
+extern bool nav_line_run(uint8_t wp1, uint8_t wp2, float radius);
#endif /* NAV_LINE_H */
diff --git a/sw/airborne/modules/nav/nav_line_border.c b/sw/airborne/modules/nav/nav_line_border.c
index 52c846e802..57e3d93bd3 100644
--- a/sw/airborne/modules/nav/nav_line_border.c
+++ b/sw/airborne/modules/nav/nav_line_border.c
@@ -37,13 +37,13 @@
enum line_border_status { LR12, LQC21, LTC2, LQC22, LR21, LQC12, LTC1, LQC11 };
static enum line_border_status line_border_status;
-bool_t nav_line_border_setup(void)
+bool nav_line_border_setup(void)
{
line_border_status = LR12;
- return FALSE;
+ return false;
}
-bool_t nav_line_border_run(uint8_t l1, uint8_t l2, float radius)
+bool nav_line_border_run(uint8_t l1, uint8_t l2, float radius)
{
radius = fabs(radius);
float alt = waypoints[l1].a;
@@ -133,7 +133,7 @@ bool_t 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_border.h b/sw/airborne/modules/nav/nav_line_border.h
index fce937c0e4..804c34c128 100644
--- a/sw/airborne/modules/nav/nav_line_border.h
+++ b/sw/airborne/modules/nav/nav_line_border.h
@@ -29,7 +29,7 @@
#include "std.h"
-extern bool_t nav_line_border_setup(void);
-extern bool_t nav_line_border_run(uint8_t wp1, uint8_t wp2, float radius);
+extern bool nav_line_border_setup(void);
+extern bool nav_line_border_run(uint8_t wp1, uint8_t wp2, float radius);
#endif /* NAV_LINE_BORDER_H */
diff --git a/sw/airborne/modules/nav/nav_line_osam.c b/sw/airborne/modules/nav/nav_line_osam.c
index 2dbc6be484..410dc42972 100644
--- a/sw/airborne/modules/nav/nav_line_osam.c
+++ b/sw/airborne/modules/nav/nav_line_osam.c
@@ -68,7 +68,7 @@ static void TranslateAndRotateFromWorld(struct Point2D *p, float Zrot, float tra
}
-bool_t nav_line_osam_run(uint8_t From_WP, uint8_t To_WP, float radius, float Space_Before, float Space_After)
+bool nav_line_osam_run(uint8_t From_WP, uint8_t To_WP, float radius, float Space_Before, float Space_After)
{
struct Point2D V;
struct Point2D P;
@@ -161,19 +161,19 @@ bool_t nav_line_osam_run(uint8_t From_WP, uint8_t To_WP, float radius, float Spa
case FLFinished:
CFLStatus = FLInitialize;
nav_init_stage();
- return FALSE;
+ return false;
break;
default:
break;
}
- return TRUE;
+ return true;
}
static uint8_t FLBlockCount = 0;
-bool_t nav_line_osam_block_run(uint8_t First_WP, uint8_t Last_WP, float radius, float Space_Before, float Space_After)
+bool nav_line_osam_block_run(uint8_t First_WP, uint8_t Last_WP, float radius, float Space_Before, float Space_After)
{
if (First_WP < Last_WP) {
nav_line_osam_run(First_WP + FLBlockCount, First_WP + FLBlockCount + 1, radius, Space_Before, Space_After);
@@ -182,7 +182,7 @@ bool_t nav_line_osam_block_run(uint8_t First_WP, uint8_t Last_WP, float radius,
FLBlockCount++;
if (First_WP + FLBlockCount >= Last_WP) {
FLBlockCount = 0;
- return FALSE;
+ return false;
}
}
} else {
@@ -192,10 +192,10 @@ bool_t nav_line_osam_block_run(uint8_t First_WP, uint8_t Last_WP, float radius,
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_line_osam.h b/sw/airborne/modules/nav/nav_line_osam.h
index 70dda5297f..d6ae48cbf1 100644
--- a/sw/airborne/modules/nav/nav_line_osam.h
+++ b/sw/airborne/modules/nav/nav_line_osam.h
@@ -29,8 +29,8 @@
#include "std.h"
-extern bool_t nav_line_osam_run(uint8_t From_WP, uint8_t To_WP, float radius, float Space_Before, float Space_After);
-extern bool_t nav_line_osam_block_run(uint8_t First_WP, uint8_t Last_WP, float radius, float Space_Before,
+extern bool nav_line_osam_run(uint8_t From_WP, uint8_t To_WP, float radius, float Space_Before, float Space_After);
+extern bool nav_line_osam_block_run(uint8_t First_WP, uint8_t Last_WP, float radius, float Space_Before,
float Space_After);
#endif
diff --git a/sw/airborne/modules/nav/nav_smooth.c b/sw/airborne/modules/nav/nav_smooth.c
index 3439012580..33fd8a371c 100644
--- a/sw/airborne/modules/nav/nav_smooth.c
+++ b/sw/airborne/modules/nav/nav_smooth.c
@@ -46,7 +46,7 @@ static float u_a_ca_x, u_a_ca_y;
static uint8_t ground_speed_timer;
/* D is the current position */
-bool_t snav_init(uint8_t a, float desired_course_rad, float radius)
+bool snav_init(uint8_t a, float desired_course_rad, float radius)
{
wp_a = a;
radius = fabs(radius);
@@ -114,11 +114,11 @@ bool_t 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;
}
-bool_t snav_circle1(void)
+bool snav_circle1(void)
{
/* circle around CD until QDR_TD */
NavVerticalAutoThrottleMode(0); /* No pitch */
@@ -127,7 +127,7 @@ bool_t snav_circle1(void)
return (! NavQdrCloseTo(DegOfRad(qdr_td)));
}
-bool_t snav_route(void)
+bool snav_route(void)
{
/* Straight route from TD to TA */
NavVerticalAutoThrottleMode(0); /* No pitch */
@@ -137,7 +137,7 @@ bool_t snav_route(void)
return (! nav_approaching_xy(wp_ta.x, wp_ta.y, wp_td.x, wp_td.y, CARROT));
}
-bool_t snav_circle2(void)
+bool snav_circle2(void)
{
/* circle around CA until QDR_A */
NavVerticalAutoThrottleMode(0); /* No pitch */
@@ -176,7 +176,7 @@ static void compute_ground_speed(float airspeed,
}
/* Adjusting a circle around CA, tangent in A, to end at snav_desired_tow */
-bool_t snav_on_time(float nominal_radius)
+bool snav_on_time(float nominal_radius)
{
nominal_radius = fabs(nominal_radius);
diff --git a/sw/airborne/modules/nav/nav_smooth.h b/sw/airborne/modules/nav/nav_smooth.h
index cfece53816..ad70a3d798 100644
--- a/sw/airborne/modules/nav/nav_smooth.h
+++ b/sw/airborne/modules/nav/nav_smooth.h
@@ -34,10 +34,10 @@
extern float snav_desired_tow; /* time of week, s */
-bool_t snav_init(uint8_t wp_a, float desired_course_rad, float radius);
-bool_t snav_circle1(void);
-bool_t snav_route(void);
-bool_t snav_circle2(void);
-bool_t snav_on_time(float radius);
+bool snav_init(uint8_t wp_a, float desired_course_rad, float radius);
+bool snav_circle1(void);
+bool snav_route(void);
+bool snav_circle2(void);
+bool snav_on_time(float radius);
#endif // SNAV_H
diff --git a/sw/airborne/modules/nav/nav_spiral.c b/sw/airborne/modules/nav/nav_spiral.c
index f42394c846..9999812744 100644
--- a/sw/airborne/modules/nav/nav_spiral.c
+++ b/sw/airborne/modules/nav/nav_spiral.c
@@ -47,7 +47,7 @@
struct NavSpiral nav_spiral;
-bool_t nav_spiral_setup(uint8_t center_wp, uint8_t edge_wp, float radius_start, float radius_inc, float segments)
+bool nav_spiral_setup(uint8_t center_wp, uint8_t edge_wp, float radius_start, float radius_inc, float segments)
{
VECT2_COPY(nav_spiral.center, waypoints[center_wp]); // center of the helix
nav_spiral.center.z = waypoints[center_wp].a;
@@ -81,10 +81,10 @@ bool_t nav_spiral_setup(uint8_t center_wp, uint8_t edge_wp, float radius_start,
if (nav_spiral.dist_from_center > nav_spiral.radius) {
nav_spiral.status = SpiralOutside;
}
- return FALSE;
+ return false;
}
-bool_t nav_spiral_run(void)
+bool nav_spiral_run(void)
{
struct EnuCoor_f pos_enu = *stateGetPositionEnu_f();
@@ -166,5 +166,5 @@ bool_t 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_spiral.h b/sw/airborne/modules/nav/nav_spiral.h
index 51ddf0ec11..ee6c3dd2c1 100644
--- a/sw/airborne/modules/nav/nav_spiral.h
+++ b/sw/airborne/modules/nav/nav_spiral.h
@@ -51,8 +51,8 @@ struct NavSpiral {
extern struct NavSpiral nav_spiral;
-extern bool_t nav_spiral_run(void);
-extern bool_t nav_spiral_setup(uint8_t center_wp, uint8_t edge_wp, float radius_start,
+extern bool nav_spiral_run(void);
+extern bool nav_spiral_setup(uint8_t center_wp, uint8_t edge_wp, float radius_start,
float radius_inc, float segments);
#endif // NAV_SPIRAL_H
diff --git a/sw/airborne/modules/nav/nav_survey_disc.c b/sw/airborne/modules/nav/nav_survey_disc.c
index 9ec01faa27..ea7bcb2131 100644
--- a/sw/airborne/modules/nav/nav_survey_disc.c
+++ b/sw/airborne/modules/nav/nav_survey_disc.c
@@ -46,17 +46,17 @@ struct DiscSurvey {
static struct DiscSurvey disc_survey;
-bool_t nav_survey_disc_setup(float grid)
+bool nav_survey_disc_setup(float grid)
{
nav_survey_shift = grid;
disc_survey.status = DOWNWIND;
disc_survey.sign = 1;
disc_survey.c1.x = stateGetPositionEnu_f()->x;
disc_survey.c1.y = stateGetPositionEnu_f()->y;
- return FALSE;
+ return false;
}
-bool_t nav_survey_disc_run(uint8_t center_wp, float radius)
+bool nav_survey_disc_run(uint8_t center_wp, float radius)
{
struct FloatVect2 *wind = stateGetHorizontalWindspeed_f();
float wind_dir = atan2(wind->x, wind->y) + M_PI;
@@ -120,5 +120,5 @@ bool_t 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_disc.h b/sw/airborne/modules/nav/nav_survey_disc.h
index 385268ce81..6040383050 100644
--- a/sw/airborne/modules/nav/nav_survey_disc.h
+++ b/sw/airborne/modules/nav/nav_survey_disc.h
@@ -29,7 +29,7 @@
#include "std.h"
-extern bool_t nav_survey_disc_setup(float grid);
-extern bool_t nav_survey_disc_run(uint8_t c, float radius);
+extern bool nav_survey_disc_setup(float grid);
+extern bool nav_survey_disc_run(uint8_t c, float radius);
#endif /* NAV_SURVEY_DISC_H */
diff --git a/sw/airborne/modules/nav/nav_survey_poly_osam.c b/sw/airborne/modules/nav/nav_survey_poly_osam.c
index 4edd3acfcd..d8aa839ed1 100644
--- a/sw/airborne/modules/nav/nav_survey_poly_osam.c
+++ b/sw/airborne/modules/nav/nav_survey_poly_osam.c
@@ -69,9 +69,9 @@
uint8_t Poly_Size = POLY_OSAM_DEFAULT_SIZE;
float Poly_Sweep = POLY_OSAM_DEFAULT_SWEEP;
-bool_t use_full_circle = POLY_OSAM_USE_FULL_CIRCLE;
+bool use_full_circle = POLY_OSAM_USE_FULL_CIRCLE;
-bool_t nav_survey_poly_osam_setup_towards(uint8_t FirstWP, uint8_t Size, float Sweep, int SecondWP)
+bool nav_survey_poly_osam_setup_towards(uint8_t FirstWP, uint8_t Size, float Sweep, int SecondWP)
{
float dx = waypoints[SecondWP].x - waypoints[FirstWP].x;
float dy = waypoints[SecondWP].y - waypoints[FirstWP].y;
@@ -127,7 +127,7 @@ uint16_t PolySurveySweepNum;
uint16_t PolySurveySweepBackNum;
float EntryRadius;
-bool_t nav_survey_poly_osam_setup(uint8_t EntryWP, uint8_t Size, float sw, float Orientation)
+bool nav_survey_poly_osam_setup(uint8_t EntryWP, uint8_t Size, float sw, float Orientation)
{
SmallestCorner.x = 0;
SmallestCorner.y = 0;
@@ -168,7 +168,7 @@ bool_t nav_survey_poly_osam_setup(uint8_t EntryWP, uint8_t Size, float sw, float
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,10 +329,10 @@ bool_t nav_survey_poly_osam_setup(uint8_t EntryWP, uint8_t Size, float sw, float
LINE_STOP_FUNCTION;
}
- return FALSE;
+ return false;
}
-bool_t nav_survey_poly_osam_run(void)
+bool nav_survey_poly_osam_run(void)
{
struct Point2D C;
struct Point2D ToP;
@@ -340,8 +340,8 @@ bool_t nav_survey_poly_osam_run(void)
float ys;
static struct Point2D LastPoint;
int i;
- bool_t LastHalfSweep;
- static bool_t HalfSweep = FALSE;
+ bool LastHalfSweep;
+ static bool HalfSweep = false;
float XIntercept1 = 0;
float XIntercept2 = 0;
float DInt1 = 0;
@@ -412,10 +412,10 @@ bool_t 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_t 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_t 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_osam.h b/sw/airborne/modules/nav/nav_survey_poly_osam.h
index cb3f8455f9..8f00714d2c 100644
--- a/sw/airborne/modules/nav/nav_survey_poly_osam.h
+++ b/sw/airborne/modules/nav/nav_survey_poly_osam.h
@@ -41,7 +41,7 @@ extern uint16_t PolySurveySweepBackNum;
* @param Sweep distance between scan lines
* @param Orientation angle of scan lines in degrees (CCW, east)
*/
-extern bool_t nav_survey_poly_osam_setup(uint8_t FirstWP, uint8_t Size, float Sweep, float Orientation);
+extern bool nav_survey_poly_osam_setup(uint8_t FirstWP, uint8_t Size, float Sweep, float Orientation);
/**
* Setup "dynamic" polygon survey with sweep orientation towards a waypoint.
@@ -54,9 +54,9 @@ extern bool_t nav_survey_poly_osam_setup(uint8_t FirstWP, uint8_t Size, float Sw
* @param Sweep distance between scan lines, if zero uses Poly_Sweep
* @param SecondWP second waypoint towards which the sweep orientation is computed
*/
-extern bool_t nav_survey_poly_osam_setup_towards(uint8_t FirstWP, uint8_t Size, float Sweep, int SecondWP);
+extern bool nav_survey_poly_osam_setup_towards(uint8_t FirstWP, uint8_t Size, float Sweep, int SecondWP);
/** Run polygon survey */
-extern bool_t nav_survey_poly_osam_run(void);
+extern bool nav_survey_poly_osam_run(void);
#endif
diff --git a/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.c b/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.c
index 301e2b75c1..d4ce302c77 100644
--- a/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.c
+++ b/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.c
@@ -66,7 +66,7 @@ uint8_t Poly_Size = POLYSURVEY_DEFAULT_SIZE;
float Poly_Distance = POLYSURVEY_DEFAULT_DISTANCE;
-bool_t nav_survey_poly_setup_towards(uint8_t FirstWP, uint8_t Size, float Sweep, int SecondWP)
+bool nav_survey_poly_setup_towards(uint8_t FirstWP, uint8_t Size, float Sweep, int SecondWP)
{
float dx = waypoints[SecondWP].enu_f.x - waypoints[FirstWP].enu_f.x;
float dy = waypoints[SecondWP].enu_f.y - waypoints[FirstWP].enu_f.y;
@@ -128,7 +128,7 @@ uint16_t PolySurveySweepBackNum;
float EntryRadius;
//=========================================================================================================================
-bool_t nav_survey_poly_setup(uint8_t EntryWP, uint8_t Size, float sw, float Orientation)
+bool nav_survey_poly_setup(uint8_t EntryWP, uint8_t Size, float sw, float Orientation)
{
SmallestCorner.x = 0;
SmallestCorner.y = 0;
@@ -162,7 +162,7 @@ bool_t nav_survey_poly_setup(uint8_t EntryWP, uint8_t Size, float sw, float Orie
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,11 +309,11 @@ bool_t nav_survey_poly_setup(uint8_t EntryWP, uint8_t Size, float sw, float Orie
}
- return FALSE;
+ return false;
}
//=========================================================================================================================
-bool_t nav_survey_poly_run(void)
+bool nav_survey_poly_run(void)
{
struct EnuCoor_f C;
@@ -322,8 +322,8 @@ bool_t nav_survey_poly_run(void)
float ys = 0;
static struct EnuCoor_f LastPoint;
int i;
- bool_t LastHalfSweep;
- static bool_t HalfSweep = FALSE;
+ bool LastHalfSweep;
+ static bool HalfSweep = false;
float XIntercept1 = 0;
float XIntercept2 = 0;
float DInt1 = 0;
@@ -392,10 +392,10 @@ bool_t 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_t 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_t 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_poly_rotorcraft.h b/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.h
index 1981ecf871..d5a865604c 100644
--- a/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.h
+++ b/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.h
@@ -41,7 +41,7 @@ extern uint16_t PolySurveySweepBackNum;
* @param Sweep distance between scan lines
* @param Orientation angle of scan lines in degrees (CCW, east)
*/
-extern bool_t nav_survey_poly_setup(uint8_t FirstWP, uint8_t Size, float Sweep, float Orientation);
+extern bool nav_survey_poly_setup(uint8_t FirstWP, uint8_t Size, float Sweep, float Orientation);
/**
* Setup "dynamic" polygon survey with sweep orientation towards a waypoint.
@@ -54,9 +54,9 @@ extern bool_t nav_survey_poly_setup(uint8_t FirstWP, uint8_t Size, float Sweep,
* @param Sweep distance between scan lines, if zero uses Poly_Distance
* @param SecondWP second waypoint towards which the sweep orientation is computed
*/
-extern bool_t nav_survey_poly_setup_towards(uint8_t FirstWP, uint8_t Size, float Sweep, int SecondWP);
+extern bool nav_survey_poly_setup_towards(uint8_t FirstWP, uint8_t Size, float Sweep, int SecondWP);
/** Run polygon survey */
-extern bool_t nav_survey_poly_run(void);
+extern bool nav_survey_poly_run(void);
#endif
diff --git a/sw/airborne/modules/nav/nav_survey_polygon.c b/sw/airborne/modules/nav/nav_survey_polygon.c
index 609f1d07c6..ed0cc9bc39 100644
--- a/sw/airborne/modules/nav/nav_survey_polygon.c
+++ b/sw/airborne/modules/nav/nav_survey_polygon.c
@@ -52,21 +52,21 @@ static void nav_points(struct FloatVect2 start, struct FloatVect2 end)
* @param x, y first line is defined by point x and y (goes through this points)
* @param a1, a2, b1, b2 second line by coordinates a1/a2, b1/b2
*/
-static bool_t intercept_two_lines(struct FloatVect2 *p, struct FloatVect2 x, struct FloatVect2 y, float a1, float a2,
+static bool intercept_two_lines(struct FloatVect2 *p, struct FloatVect2 x, struct FloatVect2 y, float a1, float a2,
float b1, float b2)
{
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;
}
/**
@@ -75,7 +75,7 @@ static bool_t intercept_two_lines(struct FloatVect2 *p, struct FloatVect2 x, str
* @param x, y intersection points
* @param a, b define the line to intersection
*/
-static bool_t get_two_intersects(struct FloatVect2 *x, struct FloatVect2 *y, struct FloatVect2 a, struct FloatVect2 b)
+static bool get_two_intersects(struct FloatVect2 *x, struct FloatVect2 *y, struct FloatVect2 a, struct FloatVect2 b)
{
int i, count = 0;
struct FloatVect2 tmp;
@@ -103,7 +103,7 @@ static bool_t get_two_intersects(struct FloatVect2 *x, struct FloatVect2 *y, str
}
if (count != 2) {
- return FALSE;
+ return false;
}
//change points
@@ -119,7 +119,7 @@ static bool_t get_two_intersects(struct FloatVect2 *x, struct FloatVect2 *y, str
*y = tmp;
}
- return TRUE;
+ return true;
}
/**
@@ -132,7 +132,7 @@ static bool_t get_two_intersects(struct FloatVect2 *x, struct FloatVect2 *y, str
* @param min_rad minimal radius when navigating
* @param altitude the altitude that must be reached before the flyover starts
**/
-bool_t nav_survey_polygon_setup(uint8_t first_wp, uint8_t size, float angle, float sweep_width, float shot_dist,
+bool nav_survey_polygon_setup(uint8_t first_wp, uint8_t size, float angle, float sweep_width, float shot_dist,
float min_rad, float altitude)
{
int i;
@@ -212,7 +212,7 @@ bool_t nav_survey_polygon_setup(uint8_t first_wp, uint8_t size, float angle, flo
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_t nav_survey_polygon_setup(uint8_t first_wp, uint8_t size, float angle, flo
survey.stage = ENTRY;
- return FALSE;
+ return false;
}
/**
@@ -232,7 +232,7 @@ bool_t nav_survey_polygon_setup(uint8_t first_wp, uint8_t size, float angle, flo
* Position and stage and navigates accordingly.
* @returns True until the survey is finished
*/
-bool_t nav_survey_polygon_run(void)
+bool nav_survey_polygon_run(void)
{
NavVerticalAutoThrottleMode(0.0);
NavVerticalAltitudeMode(survey.psa_altitude, 0.0);
@@ -269,7 +269,7 @@ bool_t 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_t nav_survey_polygon_run(void)
}
}
- return TRUE;
+ return true;
}
diff --git a/sw/airborne/modules/nav/nav_survey_polygon.h b/sw/airborne/modules/nav/nav_survey_polygon.h
index 3e67c54d52..f15237c033 100644
--- a/sw/airborne/modules/nav/nav_survey_polygon.h
+++ b/sw/airborne/modules/nav/nav_survey_polygon.h
@@ -82,8 +82,8 @@ struct SurveyPolyAdv {
struct FloatVect2 ret_end;
};
-extern bool_t nav_survey_polygon_setup(uint8_t first_wp, uint8_t size, float angle, float sweep_width, float shot_dist,
+extern bool nav_survey_polygon_setup(uint8_t first_wp, uint8_t size, float angle, float sweep_width, float shot_dist,
float min_rad, float altitude);
-extern bool_t nav_survey_polygon_run(void);
+extern bool nav_survey_polygon_run(void);
#endif
diff --git a/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.c b/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.c
index ef47a6823a..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_t nav_survey_rectangle_active = FALSE;
+static bool nav_survey_rectangle_active = false;
uint16_t rectangle_survey_sweep_num;
-bool_t nav_in_segment = FALSE;
-bool_t nav_in_circle = FALSE;
-bool_t interleave = USE_INTERLEAVE;
+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_t survey_uturn __attribute__((unused)) = FALSE;
+static bool survey_uturn __attribute__((unused)) = false;
static survey_orientation_t survey_orientation = NS;
float nav_survey_shift;
@@ -96,7 +96,7 @@ void nav_survey_rectangle_rotorcraft_init(void)
#endif
}
-bool_t nav_survey_rectangle_rotorcraft_setup(uint8_t wp1, uint8_t wp2, float grid, survey_orientation_t so)
+bool nav_survey_rectangle_rotorcraft_setup(uint8_t wp1, uint8_t wp2, float grid, survey_orientation_t so)
{
rectangle_survey_sweep_num = 0;
nav_survey_west = Min(WaypointX(wp1), WaypointX(wp2));
@@ -137,8 +137,8 @@ bool_t nav_survey_rectangle_rotorcraft_setup(uint8_t wp1, uint8_t wp2, float gri
}
}
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_t nav_survey_rectangle_rotorcraft_setup(uint8_t wp1, uint8_t wp2, float gri
} else {
nav_set_heading_deg(90);
}
- return FALSE;
+ return false;
}
-bool_t nav_survey_rectangle_rotorcraft_run(uint8_t wp1, uint8_t wp2)
+bool nav_survey_rectangle_rotorcraft_run(uint8_t wp1, uint8_t wp2)
{
- static bool_t 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_t 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_t 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_t 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_t 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_t 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_t 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_t 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_rectangle_rotorcraft.h b/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.h
index 162c8c2da3..22c60047bc 100644
--- a/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.h
+++ b/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.h
@@ -37,12 +37,12 @@ typedef enum {NS, WE} survey_orientation_t;
extern float sweep;
extern uint16_t rectangle_survey_sweep_num;
-extern bool_t interleave;
+extern bool interleave;
extern void nav_survey_rectangle_rotorcraft_init(void);
-extern bool_t nav_survey_rectangle_rotorcraft_setup(uint8_t wp1, uint8_t wp2, float grid1, survey_orientation_t so);
-extern bool_t nav_survey_rectangle_rotorcraft_run(uint8_t wp1, uint8_t wp2);
+extern bool nav_survey_rectangle_rotorcraft_setup(uint8_t wp1, uint8_t wp2, float grid1, survey_orientation_t so);
+extern bool nav_survey_rectangle_rotorcraft_run(uint8_t wp1, uint8_t wp2);
#define NavSurveyRectangleInit(_wp1, _wp2, _grid, _orientation) nav_survey_rectangle_rotorcraft_setup(_wp1, _wp2, _grid, _orientation)
#define NavSurveyRectangle(_wp1, _wp2) nav_survey_rectangle_rotorcraft_run(_wp1, _wp2)
diff --git a/sw/airborne/modules/nav/nav_survey_zamboni.c b/sw/airborne/modules/nav/nav_survey_zamboni.c
index c35d6013fb..2cc5515443 100644
--- a/sw/airborne/modules/nav/nav_survey_zamboni.c
+++ b/sw/airborne/modules/nav/nav_survey_zamboni.c
@@ -54,7 +54,7 @@ struct ZamboniSurvey zs;
* @param sweep_lines number of sweep_lines to fly
* @param altitude the altitude that must be reached before the flyover starts
*/
-bool_t nav_survey_zamboni_setup(uint8_t center_wp, uint8_t dir_wp, float sweep_length, float sweep_spacing,
+bool nav_survey_zamboni_setup(uint8_t center_wp, uint8_t dir_wp, float sweep_length, float sweep_spacing,
int sweep_lines, float altitude)
{
zs.current_laps = 0;
@@ -118,7 +118,7 @@ bool_t nav_survey_zamboni_setup(uint8_t center_wp, uint8_t dir_wp, float sweep_l
zs.stage = Z_ENTRY;
- return FALSE;
+ return false;
}
/**
@@ -128,7 +128,7 @@ bool_t nav_survey_zamboni_setup(uint8_t center_wp, uint8_t dir_wp, float sweep_l
*
* @returns TRUE until the survey is finished
*/
-bool_t nav_survey_zamboni_run(void)
+bool nav_survey_zamboni_run(void)
{
// retain altitude
NavVerticalAutoThrottleMode(0.0);
@@ -211,8 +211,8 @@ bool_t 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_survey_zamboni.h b/sw/airborne/modules/nav/nav_survey_zamboni.h
index 4b5153253f..c7dea17347 100644
--- a/sw/airborne/modules/nav/nav_survey_zamboni.h
+++ b/sw/airborne/modules/nav/nav_survey_zamboni.h
@@ -70,8 +70,8 @@ struct ZamboniSurvey {
};
-extern bool_t nav_survey_zamboni_setup(uint8_t center_wp, uint8_t dir_wp, float sweep_length, float sweep_spacing,
+extern bool nav_survey_zamboni_setup(uint8_t center_wp, uint8_t dir_wp, float sweep_length, float sweep_spacing,
int sweep_lines, float altitude);
-extern bool_t nav_survey_zamboni_run(void);
+extern bool nav_survey_zamboni_run(void);
#endif //ZAMBONI_SURVEY_H
diff --git a/sw/airborne/modules/nav/nav_vertical_raster.c b/sw/airborne/modules/nav/nav_vertical_raster.c
index be29c3afd5..ad9b5e1f9b 100644
--- a/sw/airborne/modules/nav/nav_vertical_raster.c
+++ b/sw/airborne/modules/nav/nav_vertical_raster.c
@@ -40,13 +40,13 @@
enum line_status { LR12, LQC21, LTC2, LQC22, LR21, LQC12, LTC1, LQC11 };
static enum line_status line_status;
-bool_t nav_vertical_raster_setup(void)
+bool nav_vertical_raster_setup(void)
{
line_status = LR12;
- return FALSE;
+ return false;
}
-bool_t nav_vertical_raster_run(uint8_t l1, uint8_t l2, float radius, float AltSweep)
+bool nav_vertical_raster_run(uint8_t l1, uint8_t l2, float radius, float AltSweep)
{
radius = fabs(radius);
float alt = waypoints[l1].a;
@@ -156,5 +156,5 @@ bool_t nav_vertical_raster_run(uint8_t l1, uint8_t l2, float radius, float AltSw
default:
break;
}
- return TRUE; /* This pattern never ends */
+ return true; /* This pattern never ends */
}
diff --git a/sw/airborne/modules/nav/nav_vertical_raster.h b/sw/airborne/modules/nav/nav_vertical_raster.h
index 150c514030..dcb8e602ee 100644
--- a/sw/airborne/modules/nav/nav_vertical_raster.h
+++ b/sw/airborne/modules/nav/nav_vertical_raster.h
@@ -29,7 +29,7 @@
#include "std.h"
-extern bool_t nav_vertical_raster_setup(void);
-extern bool_t nav_vertical_raster_run(uint8_t wp1, uint8_t wp2, float radius, float AltSweep);
+extern bool nav_vertical_raster_setup(void);
+extern bool nav_vertical_raster_run(uint8_t wp1, uint8_t wp2, float radius, float AltSweep);
#endif
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/obstacle_avoidance/guidance_OA.c b/sw/airborne/modules/obstacle_avoidance/guidance_OA.c
index 10460e700a..cab84a9cd1 100644
--- a/sw/airborne/modules/obstacle_avoidance/guidance_OA.c
+++ b/sw/airborne/modules/obstacle_avoidance/guidance_OA.c
@@ -172,7 +172,7 @@ void guidance_h_module_read_rc(void)
* Main guidance loop
* @param[in] in_flight Whether we are in flight or not
*/
-void guidance_h_module_run(bool_t in_flight)
+void guidance_h_module_run(bool in_flight)
{
OA_update();
/* Update the setpoint */
diff --git a/sw/airborne/modules/obstacle_avoidance/guidance_OA.h b/sw/airborne/modules/obstacle_avoidance/guidance_OA.h
index f266772e63..98f85116f5 100644
--- a/sw/airborne/modules/obstacle_avoidance/guidance_OA.h
+++ b/sw/airborne/modules/obstacle_avoidance/guidance_OA.h
@@ -65,7 +65,7 @@ extern float speed_pot;
extern void guidance_h_module_init(void);
extern void guidance_h_module_enter(void);
extern void guidance_h_module_read_rc(void);
-extern void guidance_h_module_run(bool_t in_flight);
+extern void guidance_h_module_run(bool in_flight);
// Update the stabiliztion commands based on a vision result
extern void OA_update(void);
diff --git a/sw/airborne/modules/optical_flow/px4flow.c b/sw/airborne/modules/optical_flow/px4flow.c
index 56c863328c..72f673e214 100644
--- a/sw/airborne/modules/optical_flow/px4flow.c
+++ b/sw/airborne/modules/optical_flow/px4flow.c
@@ -31,7 +31,7 @@
#include "subsystems/abi.h"
struct mavlink_optical_flow optical_flow;
-bool_t optical_flow_available;
+bool optical_flow_available;
// message ID in Mavlink (v1.0)
#define MAVLINK_OPTICAL_FLOW_MSG_ID 100
@@ -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/optical_flow/px4flow.h b/sw/airborne/modules/optical_flow/px4flow.h
index 57c0fcff23..4bd1738eb1 100644
--- a/sw/airborne/modules/optical_flow/px4flow.h
+++ b/sw/airborne/modules/optical_flow/px4flow.h
@@ -48,7 +48,7 @@ struct mavlink_optical_flow {
};
extern struct mavlink_optical_flow optical_flow;
-extern bool_t optical_flow_available;
+extern bool optical_flow_available;
extern void px4flow_init(void);
extern void px4flow_downlink(void);
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/px4_flash/px4_flash.c b/sw/airborne/modules/px4_flash/px4_flash.c
index b16383b41f..7aa81f17e2 100644
--- a/sw/airborne/modules/px4_flash/px4_flash.c
+++ b/sw/airborne/modules/px4_flash/px4_flash.c
@@ -62,13 +62,13 @@ tid_t px4iobl_tid; ///< id for time out of the px4 bootloader reset
#define PROTO_GET_CRC 0x29 ///< compute & return a CRC
#define PROTO_BOOT 0x30 ///< boot the application
-bool_t setToBootloaderMode;
-bool_t px4ioRebootTimeout;
+bool setToBootloaderMode;
+bool px4ioRebootTimeout;
void px4flash_init(void)
{
- setToBootloaderMode = FALSE;
- px4ioRebootTimeout = FALSE;
+ setToBootloaderMode = false;
+ px4ioRebootTimeout = false;
px4iobl_tid = sys_time_register_timer(15.0, NULL); //20 (fbw pprz bl timeout)-5 (px4 fmu bl timeout)
}
@@ -129,7 +129,7 @@ void px4flash_event(void)
//first check if the bootloader has not timeout:
if (sys_time_check_and_ack_timer(px4iobl_tid) || px4ioRebootTimeout) {
- px4ioRebootTimeout = TRUE;
+ px4ioRebootTimeout = true;
sys_time_cancel_timer(px4iobl_tid);
FLASH_PORT->put_byte(FLASH_PORT->periph, 'T');
FLASH_PORT->put_byte(FLASH_PORT->periph, 'I');
diff --git a/sw/airborne/modules/sensors/airspeed_amsys.c b/sw/airborne/modules/sensors/airspeed_amsys.c
index 3782153982..ea120435f1 100644
--- a/sw/airborne/modules/sensors/airspeed_amsys.c
+++ b/sw/airborne/modules/sensors/airspeed_amsys.c
@@ -70,7 +70,7 @@ PRINT_CONFIG_MSG("USE_AIRSPEED_AMSYS automatically set to TRUE")
// Global variables
uint16_t airspeed_amsys_raw;
uint16_t tempAS_amsys_raw;
-bool_t airspeed_amsys_valid;
+bool airspeed_amsys_valid;
float airspeed_amsys_offset;
float airspeed_amsys_tmp;
float airspeed_amsys_p; //Pascal
@@ -80,10 +80,10 @@ float airspeed_filter;
struct i2c_transaction airspeed_amsys_i2c_trans;
// Local variables
-volatile bool_t airspeed_amsys_i2c_done;
+volatile bool airspeed_amsys_i2c_done;
float airspeed_temperature = 0.0;
float airspeed_old = 0.0;
-bool_t airspeed_amsys_offset_init;
+bool airspeed_amsys_offset_init;
double airspeed_amsys_offset_tmp;
uint16_t airspeed_amsys_cnt;
@@ -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 eceb9d25aa..a231d162d0 100644
--- a/sw/airborne/modules/sensors/airspeed_ets.c
+++ b/sw/airborne/modules/sensors/airspeed_ets.c
@@ -88,7 +88,7 @@ PRINT_CONFIG_VAR(AIRSPEED_ETS_START_DELAY)
#include "sdLog.h"
#include "subsystems/chibios-libopencm3/chibios_sdlog.h"
#include "subsystems/gps.h"
-bool_t log_airspeed_ets_started;
+bool log_airspeed_ets_started;
#endif
#endif
@@ -96,7 +96,7 @@ bool_t log_airspeed_ets_started;
// Global variables
uint16_t airspeed_ets_raw;
uint16_t airspeed_ets_offset;
-bool_t airspeed_ets_valid;
+bool airspeed_ets_valid;
float airspeed_ets;
int airspeed_ets_buffer_idx;
float airspeed_ets_buffer[AIRSPEED_ETS_NBSAMPLES_AVRG];
@@ -104,12 +104,12 @@ float airspeed_ets_buffer[AIRSPEED_ETS_NBSAMPLES_AVRG];
struct i2c_transaction airspeed_ets_i2c_trans;
// Local variables
-volatile bool_t airspeed_ets_i2c_done;
-bool_t airspeed_ets_offset_init;
+volatile bool airspeed_ets_i2c_done;
+bool airspeed_ets_offset_init;
uint32_t airspeed_ets_offset_tmp;
uint16_t airspeed_ets_cnt;
uint32_t airspeed_ets_delay_time;
-bool_t airspeed_ets_delay_done;
+bool airspeed_ets_delay_done;
void airspeed_ets_init(void)
{
@@ -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/airspeed_ets.h b/sw/airborne/modules/sensors/airspeed_ets.h
index de9565d5c3..4fe58fafbc 100644
--- a/sw/airborne/modules/sensors/airspeed_ets.h
+++ b/sw/airborne/modules/sensors/airspeed_ets.h
@@ -46,7 +46,7 @@
extern uint16_t airspeed_ets_raw;
extern uint16_t airspeed_ets_offset;
-extern bool_t airspeed_ets_valid;
+extern bool airspeed_ets_valid;
extern float airspeed_ets;
extern struct i2c_transaction airspeed_ets_i2c_trans;
diff --git a/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.h b/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.h
index 6b95c3c863..e6e1d84aa2 100644
--- a/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.h
+++ b/sw/airborne/modules/sensors/airspeed_ms45xx_i2c.h
@@ -35,7 +35,7 @@ struct AirspeedMs45xx {
float airspeed_scale; ///< quadratic scale factor to convert differential pressure to airspeed
float pressure_scale; ///< scaling factor from raw measurement to Pascal
float pressure_offset; ///< offset in Pascal
- bool_t sync_send; ///< flag to enable sending every new measurement via telemetry
+ bool sync_send; ///< flag to enable sending every new measurement via telemetry
};
extern struct AirspeedMs45xx ms45xx;
diff --git a/sw/airborne/modules/sensors/alt_srf08.c b/sw/airborne/modules/sensors/alt_srf08.c
index b950db614c..329ab3fab9 100644
--- a/sw/airborne/modules/sensors/alt_srf08.c
+++ b/sw/airborne/modules/sensors/alt_srf08.c
@@ -40,7 +40,7 @@
#endif
/* Global Variables */
-bool_t srf08_received, srf08_got;
+bool srf08_received, srf08_got;
struct i2c_transaction srf_trans;
uint16_t srf08_range;
@@ -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/alt_srf08.h b/sw/airborne/modules/sensors/alt_srf08.h
index 06a5f82051..871f5ebdc1 100644
--- a/sw/airborne/modules/sensors/alt_srf08.h
+++ b/sw/airborne/modules/sensors/alt_srf08.h
@@ -107,7 +107,7 @@ extern void srf08_initiate_ranging(void);
extern void srf08_receive(void);
extern uint16_t srf08_range;
-extern bool_t srf08_received, srf08_got;
+extern bool srf08_received, srf08_got;
/** Read values on the bus */
extern void srf08_read(void);
/** Copy the I2C buffer */
diff --git a/sw/airborne/modules/sensors/aoa_pwm.c b/sw/airborne/modules/sensors/aoa_pwm.c
index ae11c4c6c5..fdbaf12c48 100644
--- a/sw/airborne/modules/sensors/aoa_pwm.c
+++ b/sw/airborne/modules/sensors/aoa_pwm.c
@@ -36,7 +36,7 @@
#if LOG_AOA
#include "sdLog.h"
#include "subsystems/chibios-libopencm3/chibios_sdlog.h"
-bool_t log_started;
+bool log_started;
#endif
#ifndef AOA_PWM_CHANNEL
@@ -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 c6e1d4ef66..cbd51cef00 100644
--- a/sw/airborne/modules/sensors/baro_MS5534A.c
+++ b/sw/airborne/modules/sensors/baro_MS5534A.c
@@ -38,11 +38,11 @@
#include "state.h"
-bool_t baro_MS5534A_do_reset;
+bool baro_MS5534A_do_reset;
uint32_t baro_MS5534A_pressure;
uint16_t baro_MS5534A_temp;
-bool_t baro_MS5534A_available;
-bool_t alt_baro_enabled;
+bool baro_MS5534A_available;
+bool alt_baro_enabled;
uint32_t baro_MS5534A_ground_pressure;
float baro_MS5534A_r;
float baro_MS5534A_sigma2;
@@ -58,7 +58,7 @@ float baro_MS5534A_z;
#define STATUS_RESET 6
static uint8_t status;
-static bool_t status_read_data;
+static bool status_read_data;
static uint16_t words[4];
#define InitStatus() (status <= STATUS_INIT4)
@@ -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_MS5534A.h b/sw/airborne/modules/sensors/baro_MS5534A.h
index c141b12760..bd3705aad3 100644
--- a/sw/airborne/modules/sensors/baro_MS5534A.h
+++ b/sw/airborne/modules/sensors/baro_MS5534A.h
@@ -33,11 +33,11 @@
#if USE_BARO_MS5534A
-extern bool_t baro_MS5534A_do_reset;
-extern bool_t baro_MS5534A_available;
+extern bool baro_MS5534A_do_reset;
+extern bool baro_MS5534A_available;
extern uint32_t baro_MS5534A_pressure;
extern uint16_t baro_MS5534A_temp;
-extern bool_t alt_baro_enabled;
+extern bool alt_baro_enabled;
extern uint32_t baro_MS5534A_ground_pressure;
extern float baro_MS5534A_r;
extern float baro_MS5534A_sigma2;
diff --git a/sw/airborne/modules/sensors/baro_amsys.c b/sw/airborne/modules/sensors/baro_amsys.c
index 28e6123990..2d29747805 100644
--- a/sw/airborne/modules/sensors/baro_amsys.c
+++ b/sw/airborne/modules/sensors/baro_amsys.c
@@ -72,9 +72,9 @@ uint16_t pBaroRaw;
uint16_t tBaroRaw;
uint16_t baro_amsys_adc;
float baro_amsys_offset;
-bool_t baro_amsys_valid;
+bool baro_amsys_valid;
float baro_amsys_altitude;
-bool_t baro_amsys_enabled;
+bool baro_amsys_enabled;
float baro_amsys_r;
float baro_amsys_sigma2;
float baro_amsys_temp;
@@ -90,7 +90,7 @@ float baro_old;
struct i2c_transaction baro_amsys_i2c_trans;
// Local variables
-bool_t baro_amsys_offset_init;
+bool baro_amsys_offset_init;
double baro_amsys_offset_tmp;
uint16_t baro_amsys_cnt;
@@ -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_amsys.h b/sw/airborne/modules/sensors/baro_amsys.h
index f6a3817d34..3afd01b3be 100644
--- a/sw/airborne/modules/sensors/baro_amsys.h
+++ b/sw/airborne/modules/sensors/baro_amsys.h
@@ -33,8 +33,8 @@
extern uint16_t baro_amsys_adc;
// extern float baro_amsys_offset;
-extern bool_t baro_amsys_valid;
-extern bool_t baro_amsys_enabled;
+extern bool baro_amsys_valid;
+extern bool baro_amsys_enabled;
extern float baro_amsys_altitude;
extern float baro_amsys_r;
extern float baro_amsys_sigma2;
diff --git a/sw/airborne/modules/sensors/baro_bmp.c b/sw/airborne/modules/sensors/baro_bmp.c
index eaa2d147cd..34625761da 100644
--- a/sw/airborne/modules/sensors/baro_bmp.c
+++ b/sw/airborne/modules/sensors/baro_bmp.c
@@ -51,7 +51,7 @@
struct Bmp085 baro_bmp;
-bool_t baro_bmp_enabled;
+bool baro_bmp_enabled;
float baro_bmp_r;
float baro_bmp_sigma2;
int32_t baro_bmp_alt;
@@ -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_bmp.h b/sw/airborne/modules/sensors/baro_bmp.h
index aa56e10266..cd79f03893 100644
--- a/sw/airborne/modules/sensors/baro_bmp.h
+++ b/sw/airborne/modules/sensors/baro_bmp.h
@@ -38,7 +38,7 @@ extern struct Bmp085 baro_bmp;
/// new measurement every 3rd baro_bmp_periodic
#define BARO_BMP_DT (BARO_BMP_PERIODIC_PERIOD / 3)
-extern bool_t baro_bmp_enabled;
+extern bool baro_bmp_enabled;
extern float baro_bmp_r;
extern float baro_bmp_sigma2;
extern int32_t baro_bmp_alt;
diff --git a/sw/airborne/modules/sensors/baro_ets.c b/sw/airborne/modules/sensors/baro_ets.c
index a5d667c2e1..b4d42943d5 100644
--- a/sw/airborne/modules/sensors/baro_ets.c
+++ b/sw/airborne/modules/sensors/baro_ets.c
@@ -102,20 +102,20 @@ PRINT_CONFIG_VAR(BARO_ETS_START_DELAY)
// Global variables
uint16_t baro_ets_adc;
uint16_t baro_ets_offset;
-bool_t baro_ets_valid;
+bool baro_ets_valid;
float baro_ets_altitude;
-bool_t baro_ets_enabled;
+bool baro_ets_enabled;
float baro_ets_r;
float baro_ets_sigma2;
struct i2c_transaction baro_ets_i2c_trans;
// Local variables
-bool_t baro_ets_offset_init;
+bool baro_ets_offset_init;
uint32_t baro_ets_offset_tmp;
uint16_t baro_ets_cnt;
uint32_t baro_ets_delay_time;
-bool_t baro_ets_delay_done;
+bool baro_ets_delay_done;
void baro_ets_init(void)
{
@@ -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_ets.h b/sw/airborne/modules/sensors/baro_ets.h
index 3af6a94fb3..7da4e011b2 100644
--- a/sw/airborne/modules/sensors/baro_ets.h
+++ b/sw/airborne/modules/sensors/baro_ets.h
@@ -50,8 +50,8 @@
extern uint16_t baro_ets_adc;
extern uint16_t baro_ets_offset;
-extern bool_t baro_ets_valid;
-extern bool_t baro_ets_enabled;
+extern bool baro_ets_valid;
+extern bool baro_ets_enabled;
extern float baro_ets_altitude;
extern float baro_ets_r;
extern float baro_ets_sigma2;
diff --git a/sw/airborne/modules/sensors/baro_hca.c b/sw/airborne/modules/sensors/baro_hca.c
index 4c36172083..98286e7f71 100644
--- a/sw/airborne/modules/sensors/baro_hca.c
+++ b/sw/airborne/modules/sensors/baro_hca.c
@@ -53,7 +53,7 @@
// Global variables
uint16_t pBaroRaw;
-bool_t baro_hca_valid;
+bool baro_hca_valid;
float baro_hca_p;
@@ -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 2aeca5c956..5a23371cc9 100644
--- a/sw/airborne/modules/sensors/baro_ms5611_i2c.c
+++ b/sw/airborne/modules/sensors/baro_ms5611_i2c.c
@@ -50,8 +50,8 @@ struct Ms5611_I2c baro_ms5611;
float fbaroms, ftempms;
float baro_ms5611_alt;
-bool_t baro_ms5611_alt_valid;
-bool_t baro_ms5611_enabled;
+bool baro_ms5611_alt_valid;
+bool baro_ms5611_enabled;
float baro_ms5611_r;
float baro_ms5611_sigma2;
@@ -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_i2c.h b/sw/airborne/modules/sensors/baro_ms5611_i2c.h
index ac57cf2d8d..71615bdc46 100644
--- a/sw/airborne/modules/sensors/baro_ms5611_i2c.h
+++ b/sw/airborne/modules/sensors/baro_ms5611_i2c.h
@@ -12,8 +12,8 @@ extern float baro_ms5611_r;
extern float baro_ms5611_sigma2;
extern float baro_ms5611_alt;
-extern bool_t baro_ms5611_alt_valid;
-extern bool_t baro_ms5611_enabled;
+extern bool baro_ms5611_alt_valid;
+extern bool baro_ms5611_enabled;
extern struct Ms5611_I2c baro_ms5611;
diff --git a/sw/airborne/modules/sensors/baro_ms5611_spi.c b/sw/airborne/modules/sensors/baro_ms5611_spi.c
index 768c8aa4d9..1f7ed49c28 100644
--- a/sw/airborne/modules/sensors/baro_ms5611_spi.c
+++ b/sw/airborne/modules/sensors/baro_ms5611_spi.c
@@ -49,8 +49,8 @@ struct Ms5611_Spi baro_ms5611;
float fbaroms, ftempms;
float baro_ms5611_alt;
-bool_t baro_ms5611_alt_valid;
-bool_t baro_ms5611_enabled;
+bool baro_ms5611_alt_valid;
+bool baro_ms5611_enabled;
float baro_ms5611_r;
float baro_ms5611_sigma2;
@@ -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_ms5611_spi.h b/sw/airborne/modules/sensors/baro_ms5611_spi.h
index 43eb997e02..784b211140 100644
--- a/sw/airborne/modules/sensors/baro_ms5611_spi.h
+++ b/sw/airborne/modules/sensors/baro_ms5611_spi.h
@@ -40,8 +40,8 @@ extern float baro_ms5611_r;
extern float baro_ms5611_sigma2;
extern float baro_ms5611_alt;
-extern bool_t baro_ms5611_alt_valid;
-extern bool_t baro_ms5611_enabled;
+extern bool baro_ms5611_alt_valid;
+extern bool baro_ms5611_enabled;
extern struct Ms5611_Spi baro_ms5611;
diff --git a/sw/airborne/modules/sensors/baro_scp.c b/sw/airborne/modules/sensors/baro_scp.c
index 05a819dc52..b30653fb18 100644
--- a/sw/airborne/modules/sensors/baro_scp.c
+++ b/sw/airborne/modules/sensors/baro_scp.c
@@ -24,7 +24,7 @@
uint8_t baro_scp_status;
uint32_t baro_scp_pressure;
uint16_t baro_scp_temperature;
-bool_t baro_scp_available;
+bool baro_scp_available;
static void baro_scp_start_high_res_measurement(void);
static void baro_scp_read(void);
@@ -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/baro_scp.h b/sw/airborne/modules/sensors/baro_scp.h
index c69534ec0f..96bd0388e0 100644
--- a/sw/airborne/modules/sensors/baro_scp.h
+++ b/sw/airborne/modules/sensors/baro_scp.h
@@ -14,7 +14,7 @@
extern uint8_t baro_scp_status;
extern uint32_t baro_scp_pressure;
extern uint16_t baro_scp_temperature;
-extern bool_t baro_scp_available;
+extern bool baro_scp_available;
void baro_scp_init(void);
void baro_scp_periodic(void);
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_hmc5843.c b/sw/airborne/modules/sensors/mag_hmc5843.c
index a47f5830b6..64d30e1bb8 100644
--- a/sw/airborne/modules/sensors/mag_hmc5843.c
+++ b/sw/airborne/modules/sensors/mag_hmc5843.c
@@ -27,7 +27,7 @@
int32_t mag_x, mag_y, mag_z;
-bool_t mag_valid;
+bool mag_valid;
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/pressure_board_navarro.h b/sw/airborne/modules/sensors/pressure_board_navarro.h
index f8f1eb6593..efa352dbfd 100644
--- a/sw/airborne/modules/sensors/pressure_board_navarro.h
+++ b/sw/airborne/modules/sensors/pressure_board_navarro.h
@@ -46,7 +46,7 @@ struct PBNState {
float altitude;
float airspeed;
float airspeed_filter;
- bool_t data_valid;
+ bool data_valid;
};
extern struct PBNState pbn;
diff --git a/sw/airborne/modules/sensors/temp_adc.h b/sw/airborne/modules/sensors/temp_adc.h
index 4de27274fb..64da048e49 100644
--- a/sw/airborne/modules/sensors/temp_adc.h
+++ b/sw/airborne/modules/sensors/temp_adc.h
@@ -29,7 +29,7 @@
#include "std.h"
/// flag to enable sending every new measurement via telemetry
-bool_t temp_adc_sync_send;
+bool temp_adc_sync_send;
float calc_ntc(int16_t raw_temp);
float calc_lm35(int16_t raw_temp);
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 b3025728fc..aa13e080b2 100644
--- a/sw/airborne/modules/servo_switch/servo_switch.c
+++ b/sw/airborne/modules/servo_switch/servo_switch.c
@@ -23,7 +23,7 @@
#include "generated/airframe.h"
#include "subsystems/actuators.h"
-bool_t servo_switch_on;
+bool servo_switch_on;
// One level of macro stack to allow redefinition of the default servo
#define _ServoSwitch(_n, _v) ActuatorSet(_n, _v)
@@ -31,7 +31,7 @@ bool_t 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 2c2a187131..9704e9af7d 100644
--- a/sw/airborne/modules/servo_switch/servo_switch.h
+++ b/sw/airborne/modules/servo_switch/servo_switch.h
@@ -26,7 +26,7 @@
#include "paparazzi.h"
#include "generated/airframe.h"
-extern bool_t servo_switch_on;
+extern bool servo_switch_on;
extern int16_t servo_switch_value;
#ifndef SERVO_SWITCH_ON_VALUE
@@ -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 c958d71d09..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_t 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 35104332cf..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_t 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/stereocam/nav_line_avoid/avoid_navigation.h b/sw/airborne/modules/stereocam/nav_line_avoid/avoid_navigation.h
index 094f2bbb7e..c1734b5d73 100644
--- a/sw/airborne/modules/stereocam/nav_line_avoid/avoid_navigation.h
+++ b/sw/airborne/modules/stereocam/nav_line_avoid/avoid_navigation.h
@@ -47,7 +47,7 @@ struct AvoidNavigationStruct {
/** global VIDEO state */
extern struct AvoidNavigationStruct avoid_navigation_data;
-extern bool_t obstacle_detected;
+extern bool obstacle_detected;
void init_avoid_navigation(void);
void run_avoid_navigation_onvision(void);
diff --git a/sw/airborne/modules/vehicle_interface/vi.c b/sw/airborne/modules/vehicle_interface/vi.c
index 3665570a85..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;
@@ -64,7 +64,7 @@ void vi_periodic(void)
vi_impl_periodic();
}
-void vi_set_enabled(bool_t enabled)
+void vi_set_enabled(bool enabled)
{
vi_impl_set_enabled(enabled);
diff --git a/sw/airborne/modules/vehicle_interface/vi.h b/sw/airborne/modules/vehicle_interface/vi.h
index 576ce96d9a..c2f6403350 100644
--- a/sw/airborne/modules/vehicle_interface/vi.h
+++ b/sw/airborne/modules/vehicle_interface/vi.h
@@ -75,8 +75,8 @@ struct Vi_command {
};
struct VehicleInterface {
- bool_t enabled;
- bool_t timeouted;
+ bool enabled;
+ bool timeouted;
uint8_t last_msg;
struct Vi_info info;
struct Vi_command input;
@@ -86,7 +86,7 @@ struct VehicleInterface {
extern struct VehicleInterface vi;
extern void vi_init(void);
-extern void vi_set_enabled(bool_t enabled);
+extern void vi_set_enabled(bool enabled);
extern void vi_periodic(void);
extern void vi_update_info(void);
@@ -98,7 +98,7 @@ extern void vi_notify_baro_abs_available(void);
/* must be implemented by specific module */
extern void vi_impl_init(void);
extern void vi_impl_periodic(void);
-extern void vi_impl_set_enabled(bool_t enabled);
+extern void vi_impl_set_enabled(bool enabled);
#define vi_SetEnabled(_val) { \
diff --git a/sw/airborne/modules/vehicle_interface/vi_datalink.c b/sw/airborne/modules/vehicle_interface/vi_datalink.c
index 183740f517..ba58162344 100644
--- a/sw/airborne/modules/vehicle_interface/vi_datalink.c
+++ b/sw/airborne/modules/vehicle_interface/vi_datalink.c
@@ -29,7 +29,7 @@ void vi_impl_periodic(void)
{
}
-void vi_impl_set_enabled(bool_t enabled __attribute__((unused)))
+void vi_impl_set_enabled(bool enabled __attribute__((unused)))
{
}
diff --git a/sw/airborne/modules/vehicle_interface/vi_test_signal.c b/sw/airborne/modules/vehicle_interface/vi_test_signal.c
index ee2615a0c0..6af01bc944 100644
--- a/sw/airborne/modules/vehicle_interface/vi_test_signal.c
+++ b/sw/airborne/modules/vehicle_interface/vi_test_signal.c
@@ -84,7 +84,7 @@ void booz_fms_impl_periodic(void)
}
}
-void booz_fms_impl_set_enabled(bool_t enabled)
+void booz_fms_impl_set_enabled(bool enabled)
{
if (enabled) {
fms_test_signal.counter = 0;
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 42107279cb..291b2839fd 100644
--- a/sw/airborne/peripherals/ads1114.h
+++ b/sw/airborne/peripherals/ads1114.h
@@ -116,8 +116,8 @@
struct ads1114_periph {
struct i2c_transaction trans;
uint8_t i2c_addr;
- bool_t config_done;
- bool_t data_available;
+ bool config_done;
+ bool data_available;
};
#if USE_ADS1114_1
@@ -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/ads1220.h b/sw/airborne/peripherals/ads1220.h
index 40e5279273..6e687f899e 100644
--- a/sw/airborne/peripherals/ads1220.h
+++ b/sw/airborne/peripherals/ads1220.h
@@ -130,7 +130,7 @@ struct Ads1220Config {
enum Ads1220ConfStatus status; ///< config status
enum Ads1220Mux mux; ///< input multiplexer
enum Ads1220Gain gain; ///< gain
- bool_t pga_bypass; ///< bypass PGA (PGA enabled = 0)
+ bool pga_bypass; ///< bypass PGA (PGA enabled = 0)
enum Ads1220SampleRate rate; ///< data output rate
enum Ads1220ConvMode conv; ///< conversion mode
enum Ads1220VRef vref; ///< voltage ref
@@ -158,7 +158,7 @@ struct Ads1220 {
struct Ads1220Config config; ///< configuration
// Data
uint32_t data; ///< raw ADC value
- volatile bool_t data_available; ///< data ready flag
+ volatile bool data_available; ///< data ready flag
};
// Functions
diff --git a/sw/airborne/peripherals/adxl345.h b/sw/airborne/peripherals/adxl345.h
index cfedad8bd8..5c0688957d 100644
--- a/sw/airborne/peripherals/adxl345.h
+++ b/sw/airborne/peripherals/adxl345.h
@@ -43,24 +43,24 @@ enum Adxl345ConfStatus {
};
struct Adxl345Config {
- bool_t drdy_int_enable; ///< Enable Data Ready Interrupt
- bool_t int_invert; ///< Invert Interrupt FALSE: active high, TRUE: active low
- bool_t full_res; ///< Full Resolution: FALSE: 10bit, TRUE: full with 4mg/LSB
- bool_t justify_msb; ///< justify: FALSE: right with sign-extension, TRUE: MSB (left)
- bool_t self_test; ///< Enable self-test-force causing shift in output data.
- bool_t spi_3_wire; ///< Set 3-wire SPI mode, if FALSE: 4-wire SPI mode
+ bool drdy_int_enable; ///< Enable Data Ready Interrupt
+ bool int_invert; ///< Invert Interrupt FALSE: active high, TRUE: active low
+ bool full_res; ///< Full Resolution: FALSE: 10bit, TRUE: full with 4mg/LSB
+ bool justify_msb; ///< justify: FALSE: right with sign-extension, TRUE: MSB (left)
+ bool self_test; ///< Enable self-test-force causing shift in output data.
+ bool spi_3_wire; ///< Set 3-wire SPI mode, if FALSE: 4-wire SPI mode
enum Adxl345Ranges range; ///< g Range
enum Adxl345Rates rate; ///< Data Output Rate
};
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_i2c.h b/sw/airborne/peripherals/adxl345_i2c.h
index 2bbd51f709..bd14e77d50 100644
--- a/sw/airborne/peripherals/adxl345_i2c.h
+++ b/sw/airborne/peripherals/adxl345_i2c.h
@@ -40,8 +40,8 @@ struct Adxl345_I2c {
struct i2c_periph *i2c_p;
struct i2c_transaction i2c_trans;
enum Adxl345ConfStatus init_status; ///< init status
- bool_t initialized; ///< config done flag
- volatile bool_t data_available; ///< data ready flag
+ bool initialized; ///< config done flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int16Vect3 vect; ///< data vector in accel coordinate system
int16_t value[3]; ///< data values accessible by channel index
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/adxl345_spi.h b/sw/airborne/peripherals/adxl345_spi.h
index fc4139a754..bb391ea3e7 100644
--- a/sw/airborne/peripherals/adxl345_spi.h
+++ b/sw/airborne/peripherals/adxl345_spi.h
@@ -42,8 +42,8 @@ struct Adxl345_Spi {
volatile uint8_t tx_buf[7];
volatile uint8_t rx_buf[7];
enum Adxl345ConfStatus init_status; ///< init status
- bool_t initialized; ///< config done flag
- volatile bool_t data_available; ///< data ready flag
+ bool initialized; ///< config done flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int16Vect3 vect; ///< data vector in accel coordinate system
int16_t value[3]; ///< data values accessible by channel index
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/ak8963.h b/sw/airborne/peripherals/ak8963.h
index 92db595306..3ab7a7eee4 100644
--- a/sw/airborne/peripherals/ak8963.h
+++ b/sw/airborne/peripherals/ak8963.h
@@ -53,12 +53,12 @@ enum Ak8963Status {
struct Ak8963 {
struct i2c_periph *i2c_p; ///< peripheral used for communcation
struct i2c_transaction i2c_trans; ///< i2c transaction used for communication with the ak8936
- bool_t initialized; ///< config done flag
+ bool initialized; ///< config done flag
enum Ak8963Status status; ///< main status
enum Ak8963ConfStatus init_status; ///< init status
- volatile bool_t data_available; ///< data ready flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int16Vect3 vect; ///< data vector in mag coordinate system
int16_t value[3]; ///< data values accessible by channel index
diff --git a/sw/airborne/peripherals/ak8975.c b/sw/airborne/peripherals/ak8975.c
index 4a2f972c8d..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:
@@ -159,9 +159,9 @@ void ak8975_event(struct Ak8975 *ak)
// 1 byte
// Read status and error bytes
- const bool_t dr = ak->i2c_trans.buf[0] & 0x01; // data ready
- const bool_t de = ak->i2c_trans.buf[7] & 0x04; // data error
- const bool_t mo = ak->i2c_trans.buf[7] & 0x08; // mag overflow
+ const bool dr = ak->i2c_trans.buf[0] & 0x01; // data ready
+ const bool de = ak->i2c_trans.buf[7] & 0x04; // data error
+ const bool mo = ak->i2c_trans.buf[7] & 0x08; // mag overflow
if (de || !dr) {
// read error or data not ready, keep reading
break;
@@ -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/ak8975.h b/sw/airborne/peripherals/ak8975.h
index bf06c8fcc5..02e03a17b3 100644
--- a/sw/airborne/peripherals/ak8975.h
+++ b/sw/airborne/peripherals/ak8975.h
@@ -59,13 +59,13 @@ enum Ak8975Status {
struct Ak8975 {
struct i2c_periph *i2c_p; ///< peripheral used for communcation
struct i2c_transaction i2c_trans; ///< i2c transaction used for communication with the ak8936
- bool_t initialized; ///< config done flag
+ bool initialized; ///< config done flag
enum Ak8975Status status; ///< main status
enum Ak8975ConfStatus init_status; ///< init status
uint32_t last_meas_time; ///< last measurement time in ms
- volatile bool_t data_available; ///< data ready flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int16Vect3 vect; ///< data vector in mag coordinate system
int16_t value[3]; ///< data values accessible by channel index
diff --git a/sw/airborne/peripherals/bmp085.c b/sw/airborne/peripherals/bmp085.c
index 0d3d55f1dc..74a2aa082c 100644
--- a/sw/airborne/peripherals/bmp085.c
+++ b/sw/airborne/peripherals/bmp085.c
@@ -64,16 +64,16 @@ static int32_t bmp085_compensated_pressure(struct Bmp085Calib *calib, int32_t ra
* Dummy function to always return TRUE on EndOfConversion check.
* Ensure proper timing trough frequency of bmp085_periodic instead!
*/
-static bool_t bmp085_eoc_true(void)
+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/bmp085.h b/sw/airborne/peripherals/bmp085.h
index eab6924d03..3722d743f5 100644
--- a/sw/airborne/peripherals/bmp085.h
+++ b/sw/airborne/peripherals/bmp085.h
@@ -57,15 +57,15 @@ struct Bmp085Calib {
int32_t b5;
};
-typedef bool_t (*Bmp085EOC)(void);
+typedef bool (*Bmp085EOC)(void);
struct Bmp085 {
struct i2c_periph *i2c_p;
struct i2c_transaction i2c_trans;
Bmp085EOC eoc; ///< function to check End Of Conversion
enum Bmp085Status status; ///< state machine status
- bool_t initialized; ///< config done flag
- volatile bool_t data_available; ///< data ready flag
+ bool initialized; ///< config done flag
+ volatile bool data_available; ///< data ready flag
struct Bmp085Calib calib;
int32_t ut; ///< uncompensated temperature
int32_t up; ///< uncompensated pressure
diff --git a/sw/airborne/peripherals/cyrf6936.c b/sw/airborne/peripherals/cyrf6936.c
index ef7593bf27..33e73f3e60 100644
--- a/sw/airborne/peripherals/cyrf6936.c
+++ b/sw/airborne/peripherals/cyrf6936.c
@@ -35,11 +35,11 @@
#include "subsystems/datalink/downlink.h"
/* Static functions used in the different statuses */
-static bool_t cyrf6936_write_register(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data);
-static bool_t cyrf6936_write_block(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data[],
+static bool cyrf6936_write_register(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data);
+static bool cyrf6936_write_block(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data[],
const uint8_t length);
-static bool_t cyrf6936_read_register(struct Cyrf6936 *cyrf, const uint8_t addr);
-static bool_t cyrf6936_read_block(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t length);
+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);
/**
* Initializing the cyrf chip
@@ -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;
}
@@ -267,7 +267,7 @@ void cyrf6936_event(struct Cyrf6936 *cyrf)
/**
* Write a byte to a register
*/
-static bool_t cyrf6936_write_register(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data)
+static bool cyrf6936_write_register(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data)
{
return cyrf6936_write_block(cyrf, addr, &data, 1);
}
@@ -275,13 +275,13 @@ static bool_t cyrf6936_write_register(struct Cyrf6936 *cyrf, const uint8_t addr,
/**
* Write multiple bytes to a register
*/
-static bool_t cyrf6936_write_block(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data[],
+static bool cyrf6936_write_block(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data[],
const uint8_t length)
{
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 */
@@ -301,7 +301,7 @@ static bool_t cyrf6936_write_block(struct Cyrf6936 *cyrf, const uint8_t addr, co
/**
* Read a byte from a register
*/
-static bool_t cyrf6936_read_register(struct Cyrf6936 *cyrf, const uint8_t addr)
+static bool cyrf6936_read_register(struct Cyrf6936 *cyrf, const uint8_t addr)
{
return cyrf6936_read_block(cyrf, addr, 1);
}
@@ -309,10 +309,10 @@ static bool_t cyrf6936_read_register(struct Cyrf6936 *cyrf, const uint8_t addr)
/**
* Read multiple bytes from a register
*/
-static bool_t cyrf6936_read_block(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t length)
+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 */
@@ -327,7 +327,7 @@ static bool_t cyrf6936_read_block(struct Cyrf6936 *cyrf, const uint8_t addr, con
/**
* Write to one register
*/
-bool_t cyrf6936_write(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data)
+bool cyrf6936_write(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data)
{
const uint8_t data_multi[][2] = {
{addr, data}
@@ -338,12 +338,12 @@ bool_t cyrf6936_write(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t d
/**
* Write to multiple registers one byte
*/
-bool_t cyrf6936_multi_write(struct Cyrf6936 *cyrf, const uint8_t data[][2], const uint8_t length)
+bool cyrf6936_multi_write(struct Cyrf6936 *cyrf, const uint8_t data[][2], const uint8_t length)
{
uint8_t i;
/* Check if the cyrf6936 isn't busy */
if (cyrf->status != CYRF6936_IDLE) {
- return FALSE;
+ return false;
}
// Set the status
@@ -364,19 +364,19 @@ bool_t cyrf6936_multi_write(struct Cyrf6936 *cyrf, const uint8_t data[][2], cons
cyrf6936_write_register(cyrf, data[0][0], data[0][1]);
}
- return TRUE;
+ return true;
}
/**
* Set the channel, SOP code, DATA code and the CRC seed
*/
-bool_t cyrf6936_write_chan_sop_data_crc(struct Cyrf6936 *cyrf, const uint8_t chan, const uint8_t sop_code[],
+bool cyrf6936_write_chan_sop_data_crc(struct Cyrf6936 *cyrf, const uint8_t chan, const uint8_t sop_code[],
const uint8_t data_code[], const uint16_t crc_seed)
{
uint8_t i;
/* Check if the cyrf6936 isn't busy */
if (cyrf->status != CYRF6936_IDLE) {
- return FALSE;
+ return false;
}
// Set the status
@@ -403,17 +403,17 @@ bool_t cyrf6936_write_chan_sop_data_crc(struct Cyrf6936 *cyrf, const uint8_t cha
cyrf->buffer_idx = 0;
cyrf6936_write_register(cyrf, CYRF_CRC_SEED_LSB, cyrf->buffer[0]);
- return TRUE;
+ return true;
}
/**
* Read the RX IRQ status register, the rx status register and the rx packet
*/
-bool_t cyrf6936_read_rx_irq_status_packet(struct Cyrf6936 *cyrf)
+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,19 +423,19 @@ bool_t 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;
}
/**
* Send a packet with a certain length
*/
-bool_t cyrf6936_send(struct Cyrf6936 *cyrf, const uint8_t data[], const uint8_t length)
+bool cyrf6936_send(struct Cyrf6936 *cyrf, const uint8_t data[], const uint8_t length)
{
int i;
/* Check if the cyrf6936 isn't busy */
if (cyrf->status != CYRF6936_IDLE) {
- return FALSE;
+ return false;
}
// Set the status
@@ -451,5 +451,5 @@ bool_t cyrf6936_send(struct Cyrf6936 *cyrf, const uint8_t data[], const uint8_t
cyrf->buffer_idx = 0;
cyrf6936_write_register(cyrf, CYRF_TX_LENGTH, cyrf->buffer[0]);
- return TRUE;
+ return true;
}
diff --git a/sw/airborne/peripherals/cyrf6936.h b/sw/airborne/peripherals/cyrf6936.h
index 111de18e0c..680263155a 100644
--- a/sw/airborne/peripherals/cyrf6936.h
+++ b/sw/airborne/peripherals/cyrf6936.h
@@ -56,7 +56,7 @@ struct Cyrf6936 {
uint8_t buffer_length; /**< The length of the buffer used for MULTIWRITE */
uint8_t buffer_idx; /**< The index of the buffer used for MULTIWRITE and used as sub-status for other statuses */
- bool_t has_irq; /**< When the CYRF6936 is done reading the irq */
+ bool has_irq; /**< When the CYRF6936 is done reading the irq */
uint8_t mfg_id[6]; /**< The manufacturer id of the CYRF6936 chip */
uint8_t tx_irq_status; /**< The last send interrupt status */
uint8_t rx_irq_status; /**< The last receive interrupt status */
@@ -69,11 +69,11 @@ extern void cyrf6936_init(struct Cyrf6936 *cyrf, struct spi_periph *spi_p, const
const uint32_t rst_port, const uint16_t rst_pin);
void cyrf6936_event(struct Cyrf6936 *cyrf);
-bool_t cyrf6936_write(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data);
-bool_t cyrf6936_multi_write(struct Cyrf6936 *cyrf, const uint8_t data[][2], const uint8_t length);
-bool_t cyrf6936_write_chan_sop_data_crc(struct Cyrf6936 *cyrf, const uint8_t chan, const uint8_t sop_code[],
+bool cyrf6936_write(struct Cyrf6936 *cyrf, const uint8_t addr, const uint8_t data);
+bool cyrf6936_multi_write(struct Cyrf6936 *cyrf, const uint8_t data[][2], const uint8_t length);
+bool cyrf6936_write_chan_sop_data_crc(struct Cyrf6936 *cyrf, const uint8_t chan, const uint8_t sop_code[],
const uint8_t data_code[], const uint16_t crc_seed);
-bool_t cyrf6936_read_rx_irq_status_packet(struct Cyrf6936 *cyrf);
-bool_t cyrf6936_send(struct Cyrf6936 *cyrf, const uint8_t data[], const uint8_t length);
+bool cyrf6936_read_rx_irq_status_packet(struct Cyrf6936 *cyrf);
+bool cyrf6936_send(struct Cyrf6936 *cyrf, const uint8_t data[], const uint8_t length);
#endif /* CYRF6936_H */
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/eeprom25AA256.h b/sw/airborne/peripherals/eeprom25AA256.h
index 7f5e9760cf..48c4336344 100644
--- a/sw/airborne/peripherals/eeprom25AA256.h
+++ b/sw/airborne/peripherals/eeprom25AA256.h
@@ -59,7 +59,7 @@ struct Eeprom25AA256 {
struct spi_transaction spi_trans; ///< spi transaction
volatile uint8_t tx_buf[E25_OUT_BUFFER_LEN]; ///< transmit buffer
volatile uint8_t rx_buf[E25_IN_BUFFER_LEN]; ///< receive buffer
- bool_t data_available; ///< data read flag
+ bool data_available; ///< data read flag
};
/** Init function
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/hmc58xx.h b/sw/airborne/peripherals/hmc58xx.h
index 30769864f4..c91cd9f004 100644
--- a/sw/airborne/peripherals/hmc58xx.h
+++ b/sw/airborne/peripherals/hmc58xx.h
@@ -60,9 +60,9 @@ enum Hmc58xxType {
struct Hmc58xx {
struct i2c_periph *i2c_p;
struct i2c_transaction i2c_trans;
- bool_t initialized; ///< config done flag
+ bool initialized; ///< config done flag
enum Hmc58xxConfStatus init_status; ///< init status
- volatile bool_t data_available; ///< data ready flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int16Vect3 vect; ///< data vector in mag coordinate system
int16_t value[3]; ///< data values accessible by channel index
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/itg3200.h b/sw/airborne/peripherals/itg3200.h
index 4648f58124..5971b1ab3e 100644
--- a/sw/airborne/peripherals/itg3200.h
+++ b/sw/airborne/peripherals/itg3200.h
@@ -70,9 +70,9 @@ enum Itg3200ConfStatus {
struct Itg3200 {
struct i2c_periph *i2c_p;
struct i2c_transaction i2c_trans;
- bool_t initialized; ///< config done flag
+ bool initialized; ///< config done flag
enum Itg3200ConfStatus init_status; ///< init status
- volatile bool_t data_available; ///< data ready flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int32Rates rates; ///< data as angular rates in gyro coordinate system
int32_t value[3]; ///< data values accessible by channel index
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/l3g4200.h b/sw/airborne/peripherals/l3g4200.h
index cb94932bbf..11bc530d72 100644
--- a/sw/airborne/peripherals/l3g4200.h
+++ b/sw/airborne/peripherals/l3g4200.h
@@ -67,9 +67,9 @@ enum L3g4200ConfStatus {
struct L3g4200 {
struct i2c_periph *i2c_p;
struct i2c_transaction i2c_trans;
- bool_t initialized; ///< config done flag
+ bool initialized; ///< config done flag
enum L3g4200ConfStatus init_status; ///< init status
- volatile bool_t data_available; ///< data ready flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int32Rates rates; ///< data as angular rates in gyro coordinate system
int32_t value[3]; ///< data values accessible by channel index
diff --git a/sw/airborne/peripherals/l3gd20.h b/sw/airborne/peripherals/l3gd20.h
index 23676eb9bc..93e5afe475 100644
--- a/sw/airborne/peripherals/l3gd20.h
+++ b/sw/airborne/peripherals/l3gd20.h
@@ -41,7 +41,7 @@ enum L3gd20ConfStatus {
};
struct L3gd20Config {
- bool_t spi_3_wire; ///< Set 3-wire SPI mode, if FALSE: 4-wire SPI mode
+ bool spi_3_wire; ///< Set 3-wire SPI mode, if FALSE: 4-wire SPI mode
enum L3gd20FullScale full_scale; ///< gyro full scale
enum L3gd20DRBW drbw; ///< Data rate and bandwidth
@@ -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/l3gd20_spi.h b/sw/airborne/peripherals/l3gd20_spi.h
index 42d50c4bb5..0bff591ee5 100644
--- a/sw/airborne/peripherals/l3gd20_spi.h
+++ b/sw/airborne/peripherals/l3gd20_spi.h
@@ -41,8 +41,8 @@ struct L3gd20_Spi {
volatile uint8_t tx_buf[2];
volatile uint8_t rx_buf[8];
enum L3gd20ConfStatus init_status; ///< init status
- bool_t initialized; ///< config done flag
- volatile bool_t data_available; ///< data ready flag
+ bool initialized; ///< config done flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int16Rates rates; ///< data vector in accel coordinate system
int16_t value[3]; ///< data values accessible by channel index
diff --git a/sw/airborne/peripherals/lis302dl.h b/sw/airborne/peripherals/lis302dl.h
index a71fabc96a..275fe2229c 100644
--- a/sw/airborne/peripherals/lis302dl.h
+++ b/sw/airborne/peripherals/lis302dl.h
@@ -42,22 +42,22 @@ enum Lis302dlConfStatus {
};
struct Lis302dlConfig {
- bool_t int_invert; ///< Invert Interrupt FALSE: active high, TRUE: active low
- bool_t spi_3_wire; ///< Set 3-wire SPI mode, if FALSE: 4-wire SPI mode
+ bool int_invert; ///< Invert Interrupt FALSE: active high, TRUE: active low
+ bool spi_3_wire; ///< Set 3-wire SPI mode, if FALSE: 4-wire SPI mode
/** Filtered Data Selection.
* FALSE: internal filter bypassed;
* TRUE: data from internal filter sent to output register */
- bool_t filt_data;
+ bool filt_data;
enum Lis302dlRanges range; ///< g Range
enum Lis302dlRates rate; ///< Data Output Rate
};
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/lis302dl_spi.h b/sw/airborne/peripherals/lis302dl_spi.h
index 3fb9851fb9..99794e4f36 100644
--- a/sw/airborne/peripherals/lis302dl_spi.h
+++ b/sw/airborne/peripherals/lis302dl_spi.h
@@ -42,8 +42,8 @@ struct Lis302dl_Spi {
volatile uint8_t tx_buf[2];
volatile uint8_t rx_buf[8];
enum Lis302dlConfStatus init_status; ///< init status
- bool_t initialized; ///< config done flag
- volatile bool_t data_available; ///< data ready flag
+ bool initialized; ///< config done flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int8Vect3 vect; ///< data vector in accel coordinate system
int8_t value[3]; ///< data values accessible by channel index
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/lsm303dlhc.h b/sw/airborne/peripherals/lsm303dlhc.h
index bfea938f9e..2f4da82ddd 100644
--- a/sw/airborne/peripherals/lsm303dlhc.h
+++ b/sw/airborne/peripherals/lsm303dlhc.h
@@ -70,12 +70,12 @@ enum Lsm303dlhcMagConfStatus {
struct Lsm303dlhc {
struct i2c_periph *i2c_p;
struct i2c_transaction i2c_trans;
- bool_t initialized; ///< config done flag
+ bool initialized; ///< config done flag
union {
enum Lsm303dlhcAccConfStatus acc; ///< init status
enum Lsm303dlhcMagConfStatus mag; ///< init status
} init_status;
- volatile bool_t data_available; ///< data ready flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int16Vect3 vect; ///< data vector in acc coordinate system
int16_t value[3]; ///< data values accessible by channel index
diff --git a/sw/airborne/peripherals/mcp355x.c b/sw/airborne/peripherals/mcp355x.c
index a8ddc27edd..f296168140 100644
--- a/sw/airborne/peripherals/mcp355x.c
+++ b/sw/airborne/peripherals/mcp355x.c
@@ -27,7 +27,7 @@
#include "peripherals/mcp355x.h"
#include "mcu_periph/spi.h"
-bool_t mcp355x_data_available;
+bool mcp355x_data_available;
int32_t mcp355x_data;
uint8_t mcp355x_val[4];
@@ -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/mcp355x.h b/sw/airborne/peripherals/mcp355x.h
index cbc94e021f..6134e3a7b6 100644
--- a/sw/airborne/peripherals/mcp355x.h
+++ b/sw/airborne/peripherals/mcp355x.h
@@ -28,7 +28,7 @@
#include "std.h"
-extern bool_t mcp355x_data_available;
+extern bool mcp355x_data_available;
extern int32_t mcp355x_data;
extern void mcp355x_init(void);
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/mpl3115.h b/sw/airborne/peripherals/mpl3115.h
index 096f91c4ce..a7804e2f4b 100644
--- a/sw/airborne/peripherals/mpl3115.h
+++ b/sw/airborne/peripherals/mpl3115.h
@@ -72,10 +72,10 @@ struct Mpl3115 {
struct i2c_transaction trans; ///< I2C transaction for reading and configuring
struct i2c_transaction req_trans; ///< I2C transaction for conversion request
enum Mpl3115Status init_status;
- bool_t initialized; ///< config done flag
- volatile bool_t data_available; ///< data ready flag
- bool_t raw_mode; ///< set to TRUE to enable raw output
- bool_t alt_mode; ///< set to TRUE to enable altitude output (otherwise pressure)
+ bool initialized; ///< config done flag
+ volatile bool data_available; ///< data ready flag
+ bool raw_mode; ///< set to TRUE to enable raw output
+ bool alt_mode; ///< set to TRUE to enable altitude output (otherwise pressure)
int16_t temperature; ///< temperature in 1/16 degrees Celcius
uint32_t pressure; ///< pressure in 1/4 Pascal
float altitude; ///< altitude in meters
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.h b/sw/airborne/peripherals/mpu60x0.h
index 693068ad3c..4293cb6b26 100644
--- a/sw/airborne/peripherals/mpu60x0.h
+++ b/sw/airborne/peripherals/mpu60x0.h
@@ -69,7 +69,7 @@ enum Mpu60x0ConfStatus {
typedef void (*Mpu60x0ConfigSet)(void *mpu, uint8_t _reg, uint8_t _val);
/// function prototype for configuration of a single I2C slave
-typedef bool_t (*Mpu60x0I2cSlaveConfigure)(Mpu60x0ConfigSet mpu_set, void *mpu);
+typedef bool (*Mpu60x0I2cSlaveConfigure)(Mpu60x0ConfigSet mpu_set, void *mpu);
struct Mpu60x0I2cSlave {
Mpu60x0I2cSlaveConfigure configure;
@@ -80,16 +80,16 @@ struct Mpu60x0Config {
enum Mpu60x0DLPF dlpf_cfg; ///< Digital Low Pass Filter
enum Mpu60x0GyroRanges gyro_range; ///< deg/s Range
enum Mpu60x0AccelRanges accel_range; ///< g Range
- bool_t drdy_int_enable; ///< Enable Data Ready Interrupt
+ bool drdy_int_enable; ///< Enable Data Ready Interrupt
uint8_t clk_sel; ///< Clock select
uint8_t nb_bytes; ///< number of bytes to read starting with MPU60X0_REG_INT_STATUS
enum Mpu60x0ConfStatus init_status; ///< init status
- bool_t initialized; ///< config done flag
+ bool initialized; ///< config done flag
/** Bypass MPU I2C.
* Only effective if using the I2C implementation.
*/
- bool_t i2c_bypass;
+ bool i2c_bypass;
uint8_t nb_slaves; ///< number of used I2C slaves
uint8_t nb_slave_init; ///< number of already configured/initialized slaves
@@ -110,6 +110,6 @@ extern void mpu60x0_send_config(Mpu60x0ConfigSet mpu_set, void *mpu, struct Mpu6
* @param mpu Mpu60x0Spi or Mpu60x0I2c peripheral
* @return TRUE when all slaves are configured
*/
-extern bool_t mpu60x0_configure_i2c_slaves(Mpu60x0ConfigSet mpu_set, void *mpu);
+extern bool mpu60x0_configure_i2c_slaves(Mpu60x0ConfigSet mpu_set, void *mpu);
#endif // MPU60X0_H
diff --git a/sw/airborne/peripherals/mpu60x0_i2c.c b/sw/airborne/peripherals/mpu60x0_i2c.c
index 1a403896cc..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;
}
@@ -131,7 +131,7 @@ void mpu60x0_i2c_event(struct Mpu60x0_I2c *mpu)
}
/** configure the registered I2C slaves */
-bool_t mpu60x0_configure_i2c_slaves(Mpu60x0ConfigSet mpu_set, void *mpu)
+bool mpu60x0_configure_i2c_slaves(Mpu60x0ConfigSet mpu_set, void *mpu)
{
struct Mpu60x0_I2c *mpu_i2c = (struct Mpu60x0_I2c *)(mpu);
@@ -194,9 +194,9 @@ bool_t 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_i2c.h b/sw/airborne/peripherals/mpu60x0_i2c.h
index 07e3de4255..f372ce1101 100644
--- a/sw/airborne/peripherals/mpu60x0_i2c.h
+++ b/sw/airborne/peripherals/mpu60x0_i2c.h
@@ -54,7 +54,7 @@ enum Mpu60x0I2cSlaveInitStatus {
struct Mpu60x0_I2c {
struct i2c_periph *i2c_p;
struct i2c_transaction i2c_trans;
- volatile bool_t data_available; ///< data ready flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int16Vect3 vect; ///< accel data vector in accel coordinate system
int16_t value[3]; ///< accel data values accessible by channel index
diff --git a/sw/airborne/peripherals/mpu60x0_spi.c b/sw/airborne/peripherals/mpu60x0_spi.c
index b85885f069..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;
}
@@ -149,7 +149,7 @@ void mpu60x0_spi_event(struct Mpu60x0_Spi *mpu)
}
/** configure the registered I2C slaves */
-bool_t mpu60x0_configure_i2c_slaves(Mpu60x0ConfigSet mpu_set, void *mpu)
+bool mpu60x0_configure_i2c_slaves(Mpu60x0ConfigSet mpu_set, void *mpu)
{
struct Mpu60x0_Spi *mpu_spi = (struct Mpu60x0_Spi *)(mpu);
@@ -188,9 +188,9 @@ bool_t 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/mpu60x0_spi.h b/sw/airborne/peripherals/mpu60x0_spi.h
index fa7e5ab039..2baae15f01 100644
--- a/sw/airborne/peripherals/mpu60x0_spi.h
+++ b/sw/airborne/peripherals/mpu60x0_spi.h
@@ -53,7 +53,7 @@ struct Mpu60x0_Spi {
struct spi_transaction spi_trans;
volatile uint8_t tx_buf[2];
volatile uint8_t rx_buf[MPU60X0_BUFFER_LEN];
- volatile bool_t data_available; ///< data ready flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int16Vect3 vect; ///< accel data vector in accel coordinate system
int16_t value[3]; ///< accel data values accessible by channel index
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.h b/sw/airborne/peripherals/mpu9250.h
index fd8daa8057..2ad631df5c 100644
--- a/sw/airborne/peripherals/mpu9250.h
+++ b/sw/airborne/peripherals/mpu9250.h
@@ -71,7 +71,7 @@ enum Mpu9250ConfStatus {
typedef void (*Mpu9250ConfigSet)(void *mpu, uint8_t _reg, uint8_t _val);
/// function prototype for configuration of a single I2C slave
-typedef bool_t (*Mpu9250I2cSlaveConfigure)(Mpu9250ConfigSet mpu_set, void *mpu);
+typedef bool (*Mpu9250I2cSlaveConfigure)(Mpu9250ConfigSet mpu_set, void *mpu);
struct Mpu9250I2cSlave {
Mpu9250I2cSlaveConfigure configure;
@@ -83,16 +83,16 @@ struct Mpu9250Config {
enum Mpu9250DLPFGyro dlpf_gyro_cfg; ///< Digital Low Pass Filter for gyroscope
enum Mpu9250GyroRanges gyro_range; ///< deg/s Range
enum Mpu9250AccelRanges accel_range; ///< g Range
- bool_t drdy_int_enable; ///< Enable Data Ready Interrupt
+ bool drdy_int_enable; ///< Enable Data Ready Interrupt
uint8_t clk_sel; ///< Clock select
uint8_t nb_bytes; ///< number of bytes to read starting with MPU9250_REG_INT_STATUS
enum Mpu9250ConfStatus init_status; ///< init status
- bool_t initialized; ///< config done flag
+ bool initialized; ///< config done flag
/** Bypass MPU I2C.
* Only effective if using the I2C implementation.
*/
- bool_t i2c_bypass;
+ bool i2c_bypass;
uint8_t nb_slaves; ///< number of used I2C slaves
uint8_t nb_slave_init; ///< number of already configured/initialized slaves
@@ -113,6 +113,6 @@ extern void mpu9250_send_config(Mpu9250ConfigSet mpu_set, void *mpu, struct Mpu9
* @param mpu Mpu9250Spi or Mpu9250I2c peripheral
* @return TRUE when all slaves are configured
*/
-extern bool_t mpu9250_configure_i2c_slaves(Mpu9250ConfigSet mpu_set, void *mpu);
+extern bool mpu9250_configure_i2c_slaves(Mpu9250ConfigSet mpu_set, void *mpu);
#endif // MPU9250_H
diff --git a/sw/airborne/peripherals/mpu9250_i2c.c b/sw/airborne/peripherals/mpu9250_i2c.c
index 9cd52538a3..e547c8b6c1 100644
--- a/sw/airborne/peripherals/mpu9250_i2c.c
+++ b/sw/airborne/peripherals/mpu9250_i2c.c
@@ -27,7 +27,7 @@
#include "peripherals/mpu9250_i2c.h"
-bool_t imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set __attribute__((unused)),
+bool imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set __attribute__((unused)),
void *mpu __attribute__((unused)));
void mpu9250_i2c_init(struct Mpu9250_I2c *mpu, struct i2c_periph *i2c_p, uint8_t addr)
@@ -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;
}
@@ -151,20 +151,20 @@ void mpu9250_i2c_event(struct Mpu9250_I2c *mpu)
/** callback function to configure ak8963 mag
* @return TRUE if mag configuration finished
*/
-bool_t imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set __attribute__((unused)), void *mpu)
+bool imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set __attribute__((unused)), void *mpu)
{
struct Mpu9250_I2c *mpu_i2c = (struct Mpu9250_I2c *)(mpu);
ak8963_configure(&mpu_i2c->akm);
if (mpu_i2c->akm.initialized) {
- return TRUE;
+ return true;
} else {
- return FALSE;
+ return false;
}
}
/** configure the registered I2C slaves */
-bool_t mpu9250_configure_i2c_slaves(Mpu9250ConfigSet mpu_set, void *mpu)
+bool mpu9250_configure_i2c_slaves(Mpu9250ConfigSet mpu_set, void *mpu)
{
struct Mpu9250_I2c *mpu_i2c = (struct Mpu9250_I2c *)(mpu);
@@ -227,9 +227,9 @@ bool_t 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_i2c.h b/sw/airborne/peripherals/mpu9250_i2c.h
index dd22192fc3..0d6a9bc2c5 100644
--- a/sw/airborne/peripherals/mpu9250_i2c.h
+++ b/sw/airborne/peripherals/mpu9250_i2c.h
@@ -55,7 +55,7 @@ enum Mpu9250I2cSlaveInitStatus {
struct Mpu9250_I2c {
struct i2c_periph *i2c_p;
struct i2c_transaction i2c_trans;
- volatile bool_t data_available; ///< data ready flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int16Vect3 vect; ///< accel data vector in accel coordinate system
int16_t value[3]; ///< accel data values accessible by channel index
diff --git a/sw/airborne/peripherals/mpu9250_spi.c b/sw/airborne/peripherals/mpu9250_spi.c
index ac6ed5667f..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;
}
@@ -146,7 +146,7 @@ void mpu9250_spi_event(struct Mpu9250_Spi *mpu)
}
/** configure the registered I2C slaves */
-bool_t mpu9250_configure_i2c_slaves(Mpu9250ConfigSet mpu_set, void *mpu)
+bool mpu9250_configure_i2c_slaves(Mpu9250ConfigSet mpu_set, void *mpu)
{
struct Mpu9250_Spi *mpu_spi = (struct Mpu9250_Spi *)(mpu);
@@ -185,9 +185,9 @@ bool_t 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/mpu9250_spi.h b/sw/airborne/peripherals/mpu9250_spi.h
index 2b8866c742..30cb5c2a48 100644
--- a/sw/airborne/peripherals/mpu9250_spi.h
+++ b/sw/airborne/peripherals/mpu9250_spi.h
@@ -53,7 +53,7 @@ struct Mpu9250_Spi {
struct spi_transaction spi_trans;
volatile uint8_t tx_buf[2];
volatile uint8_t rx_buf[MPU9250_BUFFER_LEN];
- volatile bool_t data_available; ///< data ready flag
+ volatile bool data_available; ///< data ready flag
union {
struct Int16Vect3 vect; ///< accel data vector in accel coordinate system
int16_t value[3]; ///< accel data values accessible by channel index
diff --git a/sw/airborne/peripherals/ms5611.c b/sw/airborne/peripherals/ms5611.c
index 99ed156f10..79f4c0784d 100644
--- a/sw/airborne/peripherals/ms5611.c
+++ b/sw/airborne/peripherals/ms5611.c
@@ -33,7 +33,7 @@
* Check if CRC of PROM data is OK.
* @return TRUE if OK, FALSE otherwise
*/
-bool_t ms5611_prom_crc_ok(uint16_t *prom)
+bool ms5611_prom_crc_ok(uint16_t *prom)
{
int32_t i, j;
uint32_t res = 0;
@@ -54,9 +54,9 @@ bool_t ms5611_prom_crc_ok(uint16_t *prom)
}
prom[7] |= crc;
if (crc == ((res >> 12) & 0xF)) {
- return TRUE;
+ return true;
} else {
- return FALSE;
+ return false;
}
}
@@ -64,7 +64,7 @@ bool_t ms5611_prom_crc_ok(uint16_t *prom)
* Calculate temperature and compensated pressure for MS5611.
* @return TRUE if measurement was valid, FALSE otherwise
*/
-bool_t ms5611_calc(struct Ms5611Data *ms)
+bool ms5611_calc(struct Ms5611Data *ms)
{
int64_t dt, tempms, off, sens, t2, off2, sens2;
@@ -97,9 +97,9 @@ bool_t 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;
}
/**
@@ -107,7 +107,7 @@ bool_t ms5611_calc(struct Ms5611Data *ms)
* MS5607 basically has half the resolution of the MS5611.
* @return TRUE if measurement was valid, FALSE otherwise
*/
-bool_t ms5607_calc(struct Ms5611Data *ms)
+bool ms5607_calc(struct Ms5611Data *ms)
{
int64_t dt, tempms, off, sens, t2, off2, sens2;
@@ -140,7 +140,7 @@ bool_t 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.h b/sw/airborne/peripherals/ms5611.h
index dd51cff1e8..14ace57d28 100644
--- a/sw/airborne/peripherals/ms5611.h
+++ b/sw/airborne/peripherals/ms5611.h
@@ -56,8 +56,8 @@ struct Ms5611Data {
uint32_t d2;
};
-extern bool_t ms5611_prom_crc_ok(uint16_t *prom);
-extern bool_t ms5611_calc(struct Ms5611Data *ms);
-extern bool_t ms5607_calc(struct Ms5611Data *ms);
+extern bool ms5611_prom_crc_ok(uint16_t *prom);
+extern bool ms5611_calc(struct Ms5611Data *ms);
+extern bool ms5607_calc(struct Ms5611Data *ms);
#endif /* MS5611_H */
diff --git a/sw/airborne/peripherals/ms5611_i2c.c b/sw/airborne/peripherals/ms5611_i2c.c
index ccc2c9017e..b4c068e812 100644
--- a/sw/airborne/peripherals/ms5611_i2c.c
+++ b/sw/airborne/peripherals/ms5611_i2c.c
@@ -31,7 +31,7 @@
void ms5611_i2c_init(struct Ms5611_I2c *ms, struct i2c_periph *i2c_p, uint8_t addr,
- bool_t is_ms5607)
+ bool is_ms5607)
{
/* set i2c_peripheral */
ms->i2c_p = i2c_p;
@@ -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_i2c.h b/sw/airborne/peripherals/ms5611_i2c.h
index 8954e66a8c..11f5523380 100644
--- a/sw/airborne/peripherals/ms5611_i2c.h
+++ b/sw/airborne/peripherals/ms5611_i2c.h
@@ -37,16 +37,16 @@ struct Ms5611_I2c {
struct i2c_periph *i2c_p;
struct i2c_transaction i2c_trans;
enum Ms5611Status status;
- bool_t is_ms5607; ///< TRUE if MS5607, FALSE if MS5611
- bool_t initialized; ///< config done flag
- volatile bool_t data_available; ///< data ready flag
+ bool is_ms5607; ///< TRUE if MS5607, FALSE if MS5611
+ bool initialized; ///< config done flag
+ volatile bool data_available; ///< data ready flag
struct Ms5611Data data;
int32_t prom_cnt; ///< number of bytes read from PROM
};
// Functions
extern void ms5611_i2c_init(struct Ms5611_I2c *ms, struct i2c_periph *i2c_p, uint8_t addr,
- bool_t is_ms5607);
+ bool is_ms5607);
extern void ms5611_i2c_start_configure(struct Ms5611_I2c *ms);
extern void ms5611_i2c_start_conversion(struct Ms5611_I2c *ms);
extern void ms5611_i2c_periodic_check(struct Ms5611_I2c *ms);
diff --git a/sw/airborne/peripherals/ms5611_spi.c b/sw/airborne/peripherals/ms5611_spi.c
index a3b8d0e988..eeebcc1ab1 100644
--- a/sw/airborne/peripherals/ms5611_spi.c
+++ b/sw/airborne/peripherals/ms5611_spi.c
@@ -31,7 +31,7 @@
void ms5611_spi_init(struct Ms5611_Spi *ms, struct spi_periph *spi_p, uint8_t slave_idx,
- bool_t is_ms5607)
+ bool is_ms5607)
{
/* set spi_peripheral */
ms->spi_p = spi_p;
@@ -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/ms5611_spi.h b/sw/airborne/peripherals/ms5611_spi.h
index 5e8b809d29..d007edb9a0 100644
--- a/sw/airborne/peripherals/ms5611_spi.h
+++ b/sw/airborne/peripherals/ms5611_spi.h
@@ -39,16 +39,16 @@ struct Ms5611_Spi {
volatile uint8_t tx_buf[1];
volatile uint8_t rx_buf[4];
enum Ms5611Status status;
- bool_t is_ms5607; ///< TRUE if MS5607, FALSE if MS5611
- bool_t initialized; ///< config done flag
- volatile bool_t data_available; ///< data ready flag
+ bool is_ms5607; ///< TRUE if MS5607, FALSE if MS5611
+ bool initialized; ///< config done flag
+ volatile bool data_available; ///< data ready flag
struct Ms5611Data data;
int32_t prom_cnt; ///< number of bytes read from PROM
};
// Functions
extern void ms5611_spi_init(struct Ms5611_Spi *ms, struct spi_periph *spi_p, uint8_t addr,
- bool_t is_ms5607);
+ bool is_ms5607);
extern void ms5611_spi_start_configure(struct Ms5611_Spi *ms);
extern void ms5611_spi_start_conversion(struct Ms5611_Spi *ms);
extern void ms5611_spi_periodic_check(struct Ms5611_Spi *ms);
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/peripherals/vn200_serial.h b/sw/airborne/peripherals/vn200_serial.h
index dd57948477..8228e42047 100644
--- a/sw/airborne/peripherals/vn200_serial.h
+++ b/sw/airborne/peripherals/vn200_serial.h
@@ -53,7 +53,7 @@ enum VNMsgStatus {
};
struct VNPacket {
- bool_t msg_available;
+ bool msg_available;
uint32_t chksm_error;
uint32_t hdr_error;
uint8_t msg_buf[VN_BUFFER_SIZE];
diff --git a/sw/airborne/rc_settings.c b/sw/airborne/rc_settings.c
index 1e880f9ae7..fa5a60e243 100644
--- a/sw/airborne/rc_settings.c
+++ b/sw/airborne/rc_settings.c
@@ -46,7 +46,7 @@ float slider_1_val, slider_2_val;
#include "generated/settings.h"
-void rc_settings(bool_t mode_changed __attribute__((unused)))
+void rc_settings(bool mode_changed __attribute__((unused)))
{
RCSettings(mode_changed);
}
diff --git a/sw/airborne/rc_settings.h b/sw/airborne/rc_settings.h
index ee03721831..9ce3360e61 100644
--- a/sw/airborne/rc_settings.h
+++ b/sw/airborne/rc_settings.h
@@ -53,7 +53,7 @@ extern uint8_t rc_settings_mode;
extern float slider_1_val, slider_2_val;
-void rc_settings(bool_t mode_changed);
+void rc_settings(bool mode_changed);
#define RcSettingsOff() (rc_settings_mode==RC_SETTINGS_MODE_NONE)
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 80fd8da0c5..17b13bc2aa 100644
--- a/sw/airborne/state.h
+++ b/sw/airborne/state.h
@@ -164,7 +164,7 @@ struct State {
/**
* true if local int coordinate frame is initialsed
*/
- bool_t ned_initialized_i;
+ bool ned_initialized_i;
/**
* Position in North East Down coordinates.
@@ -216,7 +216,7 @@ struct State {
struct LtpDef_f ned_origin_f;
/// True if local float coordinate frame is initialsed
- bool_t ned_initialized_f;
+ bool ned_initialized_f;
/**
* Definition of the origin of Utm coordinate system.
@@ -228,7 +228,7 @@ struct State {
struct UtmCoor_f utm_origin_f;
/// True if utm origin (float) coordinate frame is initialsed
- bool_t utm_initialized_f;
+ bool utm_initialized_f;
/**
* Position in North East Down coordinates.
@@ -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);
@@ -488,14 +488,14 @@ extern void stateCalcPositionLla_f(void);
/*********************** validity test functions ******************/
/// Test if local coordinates are valid.
-static inline bool_t stateIsLocalCoordinateValid(void)
+static inline bool stateIsLocalCoordinateValid(void)
{
return ((state.ned_initialized_i || state.ned_initialized_f || state.utm_initialized_f)
&& (state.pos_status & (POS_LOCAL_COORD)));
}
/// Test if global coordinates are valid.
-static inline bool_t stateIsGlobalCoordinateValid(void)
+static inline bool stateIsGlobalCoordinateValid(void)
{
return ((state.pos_status & (POS_GLOBAL_COORD)) || stateIsLocalCoordinateValid());
}
@@ -946,7 +946,7 @@ extern void stateCalcAccelEcef_f(void);
/*********************** validity test functions ******************/
/// Test if accelerations are valid.
-static inline bool_t stateIsAccelValid(void)
+static inline bool stateIsAccelValid(void)
{
return (state.accel_status);
}
@@ -1035,7 +1035,7 @@ static inline struct EcefCoor_f *stateGetAccelEcef_f(void)
/*********************** validity test functions ******************/
/// Test if attitudes are valid.
-static inline bool_t stateIsAttitudeValid(void)
+static inline bool stateIsAttitudeValid(void)
{
return (orienationCheckValid(&state.ned_to_body_orientation));
}
@@ -1133,7 +1133,7 @@ extern void stateCalcBodyRates_f(void);
/*********************** validity test functions ******************/
/// Test if rates are valid.
-static inline bool_t stateIsRateValid(void)
+static inline bool stateIsRateValid(void)
{
return (state.rate_status);
}
@@ -1198,25 +1198,25 @@ extern void stateCalcAirspeed_f(void);
/************************ validity test function *******************/
/// test if wind speed is available.
-static inline bool_t stateIsWindspeedValid(void)
+static inline bool stateIsWindspeedValid(void)
{
return (state.wind_air_status &= ~((1 << WINDSPEED_I) | (1 << WINDSPEED_F)));
}
/// test if air speed is available.
-static inline bool_t stateIsAirspeedValid(void)
+static inline bool stateIsAirspeedValid(void)
{
return (state.wind_air_status &= ~((1 << AIRSPEED_I) | (1 << AIRSPEED_F)));
}
/// test if angle of attack is available.
-static inline bool_t stateIsAngleOfAttackValid(void)
+static inline bool stateIsAngleOfAttackValid(void)
{
return (state.wind_air_status &= ~(1 << AOA_F));
}
/// test if sideslip is available.
-static inline bool_t stateIsSideslipValid(void)
+static inline bool stateIsSideslipValid(void)
{
return (state.wind_air_status &= ~(1 << SIDESLIP_F));
}
diff --git a/sw/airborne/subsystems/actuators.c b/sw/airborne/subsystems/actuators.c
index 632af1f73b..c79a434e4b 100644
--- a/sw/airborne/subsystems/actuators.c
+++ b/sw/airborne/subsystems/actuators.c
@@ -33,16 +33,16 @@
int16_t actuators[ACTUATORS_NB];
uint32_t actuators_delay_time;
-bool_t actuators_delay_done;
+bool actuators_delay_done;
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.h b/sw/airborne/subsystems/actuators.h
index cf6845847c..0ed0343d27 100644
--- a/sw/airborne/subsystems/actuators.h
+++ b/sw/airborne/subsystems/actuators.h
@@ -42,7 +42,7 @@
extern void actuators_init(void);
extern uint32_t actuators_delay_time;
-extern bool_t actuators_delay_done;
+extern bool actuators_delay_done;
/** Actuators array.
* Temporary storage (for debugging purpose, downlinked via telemetry)
diff --git a/sw/airborne/subsystems/actuators/actuators_asctec.c b/sw/airborne/subsystems/actuators/actuators_asctec.c
index 36736168fc..5627cf17f1 100644
--- a/sw/airborne/subsystems/actuators/actuators_asctec.c
+++ b/sw/airborne/subsystems/actuators/actuators_asctec.c
@@ -53,12 +53,12 @@ void actuators_asctec_init(void)
actuators_asctec.nb_err = 0;
}
-void actuators_asctec_set(bool_t motors_on)
+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.h b/sw/airborne/subsystems/actuators/actuators_asctec.h
index 85ad1a5d4f..6a06b4e30a 100644
--- a/sw/airborne/subsystems/actuators/actuators_asctec.h
+++ b/sw/airborne/subsystems/actuators/actuators_asctec.h
@@ -75,7 +75,7 @@ extern struct ActuatorsAsctec actuators_asctec;
}
extern void actuators_asctec_init(void);
-extern void actuators_asctec_set(bool_t motors_on);
+extern void actuators_asctec_set(bool motors_on);
#define ActuatorAsctecSet(_i, _v) { actuators_asctec.cmds[_i] = _v; }
#define ActuatorsAsctecInit() actuators_asctec_init()
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 95c001e872..44fbca5a7c 100644
--- a/sw/airborne/subsystems/actuators/actuators_esc32.c
+++ b/sw/airborne/subsystems/actuators/actuators_esc32.c
@@ -61,7 +61,7 @@ static inline void actuators_esc32_disarm(uint32_t tt, uint8_t tid);
static inline void actuators_esc32_start(uint32_t tt, uint8_t tid);
static inline void actuators_esc32_duty(uint32_t tt, uint8_t tid, uint16_t *cmds);
static inline void actuators_esc32_dir(uint32_t tt, uint8_t tid);
-static bool_t actuators_esc32_play_melody(uint32_t tt, uint8_t tid, uint32_t *status_sub,
+static bool actuators_esc32_play_melody(uint32_t tt, uint8_t tid, uint32_t *status_sub,
uint16_t melody[][2], uint8_t length);
/** When receiving messages on the CAN bus */
@@ -272,7 +272,7 @@ static inline void actuators_esc32_dir(uint32_t tt, uint8_t tid)
}
/** Plays a full melody */
-static bool_t actuators_esc32_play_melody(uint32_t tt, uint8_t tid, uint32_t *status_sub,
+static bool actuators_esc32_play_melody(uint32_t tt, uint8_t tid, uint32_t *status_sub,
uint16_t melody[][2], uint8_t length)
{
uint32_t timer = (*status_sub & 0x00FFFFFF) << 8;
@@ -290,10 +290,10 @@ static bool_t actuators_esc32_play_melody(uint32_t tt, uint8_t tid, uint32_t *st
}
*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 cd96195168..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;
@@ -174,7 +174,7 @@ void motor_mixing_run_spinup(uint32_t counter, uint32_t max_counter)
}
}
-void motor_mixing_run(bool_t motors_on, bool_t override_on, pprz_t in_cmd[])
+void motor_mixing_run(bool motors_on, bool override_on, pprz_t in_cmd[])
{
uint8_t i;
#if !HITL
diff --git a/sw/airborne/subsystems/actuators/motor_mixing.h b/sw/airborne/subsystems/actuators/motor_mixing.h
index f6ac0e9b8e..90cef700ef 100644
--- a/sw/airborne/subsystems/actuators/motor_mixing.h
+++ b/sw/airborne/subsystems/actuators/motor_mixing.h
@@ -36,7 +36,7 @@
struct MotorMixing {
int32_t commands[MOTOR_MIXING_NB_MOTOR];
int32_t trim[MOTOR_MIXING_NB_MOTOR];
- bool_t override_enabled[MOTOR_MIXING_NB_MOTOR];
+ bool override_enabled[MOTOR_MIXING_NB_MOTOR];
int32_t override_value[MOTOR_MIXING_NB_MOTOR];
uint32_t nb_saturation;
uint32_t nb_failure;
@@ -45,7 +45,7 @@ struct MotorMixing {
extern struct MotorMixing motor_mixing;
extern void motor_mixing_init(void);
-extern void motor_mixing_run(bool_t motors_on, bool_t override_on, pprz_t in_cmd[]);
+extern void motor_mixing_run(bool motors_on, bool override_on, pprz_t in_cmd[]);
extern void motor_mixing_run_spinup(uint32_t counter, uint32_t max_counter);
#endif /* MOTOR_MIXING_H */
diff --git a/sw/airborne/subsystems/ahrs.h b/sw/airborne/subsystems/ahrs.h
index 617bd0b377..6a00a6cf6b 100644
--- a/sw/airborne/subsystems/ahrs.h
+++ b/sw/airborne/subsystems/ahrs.h
@@ -51,7 +51,7 @@
#include AHRS_SECONDARY_TYPE_H
#endif
-typedef bool_t (*AhrsEnableOutput)(bool_t);
+typedef bool (*AhrsEnableOutput)(bool);
/* for settings when using secondary AHRS */
extern uint8_t ahrs_output_idx;
diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c
index 3c9e5ba1d2..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;
@@ -119,18 +119,18 @@ void ahrs_fc_init(void)
ahrs_fc.mag_cnt = 0;
}
-bool_t ahrs_fc_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
+bool ahrs_fc_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
struct FloatVect3 *lp_mag)
{
#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_t 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_cmpl.h b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h
index 4844c8f0dc..9453f946b0 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h
+++ b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h
@@ -47,9 +47,9 @@ struct AhrsFloatCmpl {
struct FloatQuat ltp_to_imu_quat;
struct FloatRMat ltp_to_imu_rmat;
- bool_t correct_gravity; ///< enable gravity correction during coordinated turns
+ bool correct_gravity; ///< enable gravity correction during coordinated turns
float ltp_vel_norm; ///< velocity norm for gravity correction during coordinated turns
- bool_t ltp_vel_norm_valid;
+ bool ltp_vel_norm_valid;
float accel_omega; ///< filter cut-off frequency for correcting the attitude from accels (pseudo-gravity measurement)
float accel_zeta; ///< filter damping for correcting the gyro-bias from accels (pseudo-gravity measurement)
@@ -62,7 +62,7 @@ struct AhrsFloatCmpl {
uint8_t gravity_heuristic_factor;
float weight;
- bool_t heading_aligned;
+ bool heading_aligned;
struct FloatVect3 mag_h;
/* internal counters for the gains */
@@ -73,7 +73,7 @@ struct AhrsFloatCmpl {
struct OrientationReps ltp_to_body;
enum AhrsFCStatus status;
- bool_t is_aligned;
+ bool is_aligned;
};
extern struct AhrsFloatCmpl ahrs_fc;
@@ -82,7 +82,7 @@ extern void ahrs_fc_init(void);
extern void ahrs_fc_set_body_to_imu(struct OrientationReps *body_to_imu);
extern void ahrs_fc_set_body_to_imu_quat(struct FloatQuat *q_b2i);
extern void ahrs_fc_recompute_ltp_to_body(void);
-extern bool_t ahrs_fc_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
+extern bool ahrs_fc_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
struct FloatVect3 *lp_mag);
extern void ahrs_fc_propagate(struct FloatRates *gyro, float dt);
extern void ahrs_fc_update_accel(struct FloatVect3 *accel, float dt);
diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl_wrapper.c b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl_wrapper.c
index 0607ee9fe7..f7704fbaeb 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl_wrapper.c
+++ b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl_wrapper.c
@@ -35,7 +35,7 @@
PRINT_CONFIG_VAR(AHRS_FC_OUTPUT_ENABLED)
/** if TRUE with push the estimation results to the state interface */
-static bool_t ahrs_fc_output_enabled;
+static bool ahrs_fc_output_enabled;
static uint32_t ahrs_fc_last_stamp;
static uint8_t ahrs_fc_id = AHRS_COMP_ID_FC;
@@ -254,7 +254,7 @@ static void gps_cb(uint8_t sender_id __attribute__((unused)),
compute_body_orientation_and_rates();
}
-static bool_t ahrs_fc_enable_output(bool_t enable)
+static bool ahrs_fc_enable_output(bool enable)
{
ahrs_fc_output_enabled = enable;
return ahrs_fc_output_enabled;
diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c
index 5215ae621a..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,11 +112,11 @@ 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;
}
-bool_t ahrs_dcm_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
+bool ahrs_dcm_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
struct FloatVect3 *lp_mag)
{
/* Compute an initial orientation using euler angles */
@@ -133,9 +133,9 @@ bool_t 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_dcm.h b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.h
index 78dfe05fec..1535b5326f 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_float_dcm.h
+++ b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.h
@@ -44,13 +44,13 @@ struct AhrsFloatDCM {
float gps_speed;
float gps_acceleration;
float gps_course;
- bool_t gps_course_valid;
+ bool gps_course_valid;
uint8_t gps_age;
struct OrientationReps body_to_imu;
enum AhrsDCMStatus status;
- bool_t is_aligned;
+ bool is_aligned;
};
extern struct AhrsFloatDCM ahrs_dcm;
@@ -83,7 +83,7 @@ extern float imu_health;
extern void ahrs_dcm_init(void);
extern void ahrs_dcm_set_body_to_imu(struct OrientationReps *body_to_imu);
extern void ahrs_dcm_set_body_to_imu_quat(struct FloatQuat *q_b2i);
-extern bool_t ahrs_dcm_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
+extern bool ahrs_dcm_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
struct FloatVect3 *lp_mag);
extern void ahrs_dcm_propagate(struct FloatRates *gyro, float dt);
extern void ahrs_dcm_update_accel(struct FloatVect3 *accel);
diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_dcm_wrapper.c b/sw/airborne/subsystems/ahrs/ahrs_float_dcm_wrapper.c
index c5df92a6ce..3fd4ac4459 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_float_dcm_wrapper.c
+++ b/sw/airborne/subsystems/ahrs/ahrs_float_dcm_wrapper.c
@@ -35,7 +35,7 @@
PRINT_CONFIG_VAR(AHRS_DCM_OUTPUT_ENABLED)
/** if TRUE with push the estimation results to the state interface */
-static bool_t ahrs_dcm_output_enabled;
+static bool ahrs_dcm_output_enabled;
static uint32_t ahrs_dcm_last_stamp;
static uint8_t ahrs_dcm_id = AHRS_COMP_ID_DCM;
@@ -169,7 +169,7 @@ static void gps_cb(uint8_t sender_id __attribute__((unused)),
ahrs_dcm_update_gps(gps_s);
}
-static bool_t ahrs_dcm_enable_output(bool_t enable)
+static bool ahrs_dcm_enable_output(bool enable)
{
ahrs_dcm_output_enabled = enable;
return ahrs_dcm_output_enabled;
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_invariant.h b/sw/airborne/subsystems/ahrs/ahrs_float_invariant.h
index 212b375a4a..8c48459913 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_float_invariant.h
+++ b/sw/airborne/subsystems/ahrs/ahrs_float_invariant.h
@@ -96,13 +96,13 @@ struct AhrsFloatInv {
struct inv_correction_gains corr; ///< correction gains
struct inv_gains gains; ///< tuning gains
- bool_t reset; ///< flag to request reset/reinit the filter
+ bool reset; ///< flag to request reset/reinit the filter
/** body_to_imu rotation */
struct OrientationReps body_to_imu;
struct FloatVect3 mag_h;
- bool_t is_aligned;
+ bool is_aligned;
};
extern struct AhrsFloatInv ahrs_float_inv;
diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_invariant_wrapper.c b/sw/airborne/subsystems/ahrs/ahrs_float_invariant_wrapper.c
index cde86242ae..4ed31c934d 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_float_invariant_wrapper.c
+++ b/sw/airborne/subsystems/ahrs/ahrs_float_invariant_wrapper.c
@@ -38,7 +38,7 @@
PRINT_CONFIG_VAR(AHRS_INV_OUTPUT_ENABLED)
/** if TRUE with push the estimation results to the state interface */
-static bool_t ahrs_finv_output_enabled;
+static bool ahrs_finv_output_enabled;
/** last gyro msg timestamp */
static uint32_t ahrs_finv_last_stamp = 0;
static uint8_t ahrs_finv_id = AHRS_COMP_ID_FINV;
@@ -204,7 +204,7 @@ static void geo_mag_cb(uint8_t sender_id __attribute__((unused)), struct FloatVe
ahrs_float_inv.mag_h = *h;
}
-static bool_t ahrs_float_invariant_enable_output(bool_t enable)
+static bool ahrs_float_invariant_enable_output(bool enable)
{
ahrs_finv_output_enabled = enable;
return ahrs_finv_output_enabled;
diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c
index e72c7cf1fc..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);
@@ -104,7 +104,7 @@ void ahrs_mlkf_set_body_to_imu_quat(struct FloatQuat *q_b2i)
}
-bool_t ahrs_mlkf_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
+bool ahrs_mlkf_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
struct FloatVect3 *lp_mag)
{
@@ -114,9 +114,9 @@ bool_t 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_float_mlkf.h b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h
index 675d15eb89..1c66ff7bee 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h
+++ b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h
@@ -58,7 +58,7 @@ struct AhrsMlkf {
struct OrientationReps body_to_imu;
enum AhrsMlkfStatus status;
- bool_t is_aligned;
+ bool is_aligned;
};
extern struct AhrsMlkf ahrs_mlkf;
@@ -66,7 +66,7 @@ extern struct AhrsMlkf ahrs_mlkf;
extern void ahrs_mlkf_init(void);
extern void ahrs_mlkf_set_body_to_imu(struct OrientationReps *body_to_imu);
extern void ahrs_mlkf_set_body_to_imu_quat(struct FloatQuat *q_b2i);
-extern bool_t ahrs_mlkf_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
+extern bool ahrs_mlkf_align(struct FloatRates *lp_gyro, struct FloatVect3 *lp_accel,
struct FloatVect3 *lp_mag);
extern void ahrs_mlkf_propagate(struct FloatRates *gyro, float dt);
extern void ahrs_mlkf_update_accel(struct FloatVect3 *accel);
diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf_wrapper.c b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf_wrapper.c
index d10dc3b1bc..65ba01f4f7 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf_wrapper.c
+++ b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf_wrapper.c
@@ -36,7 +36,7 @@
PRINT_CONFIG_VAR(AHRS_MLKF_OUTPUT_ENABLED)
/** if TRUE with push the estimation results to the state interface */
-static bool_t ahrs_mlkf_output_enabled;
+static bool ahrs_mlkf_output_enabled;
static uint32_t ahrs_mlkf_last_stamp;
static uint8_t ahrs_mlkf_id = AHRS_COMP_ID_MLKF;
@@ -190,7 +190,7 @@ static void geo_mag_cb(uint8_t sender_id __attribute__((unused)), struct FloatVe
ahrs_mlkf.mag_h = *h;
}
-static bool_t ahrs_mlkf_enable_output(bool_t enable)
+static bool ahrs_mlkf_enable_output(bool enable)
{
ahrs_mlkf_output_enabled = enable;
return ahrs_mlkf_output_enabled;
diff --git a/sw/airborne/subsystems/ahrs/ahrs_gx3.c b/sw/airborne/subsystems/ahrs/ahrs_gx3.c
index c0e171c2b6..293e59ce3b 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_gx3.c
+++ b/sw/airborne/subsystems/ahrs/ahrs_gx3.c
@@ -46,7 +46,7 @@
*/
struct AhrsGX3 ahrs_gx3;
-static inline bool_t gx3_verify_chk(volatile uint8_t *buff_add);
+static inline bool gx3_verify_chk(volatile uint8_t *buff_add);
static inline float bef(volatile uint8_t *c);
/* Big Endian to Float */
@@ -62,7 +62,7 @@ static inline float bef(volatile uint8_t *c)
return f;
}
-static inline bool_t gx3_verify_chk(volatile uint8_t *buff_add)
+static inline bool gx3_verify_chk(volatile uint8_t *buff_add)
{
uint16_t i, chk_calc;
chk_calc = 0;
@@ -74,7 +74,7 @@ static inline bool_t 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 cf4aab3b8b..b444c8a5e9 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_gx3.h
+++ b/sw/airborne/subsystems/ahrs/ahrs_gx3.h
@@ -52,7 +52,7 @@ extern void gx3_packet_read_message(void);
extern void gx3_packet_parse(uint8_t c);
struct GX3Packet {
- bool_t msg_available;
+ bool msg_available;
uint32_t chksm_error;
uint32_t hdr_error;
uint8_t msg_buf[GX3_MAX_PAYLOAD];
@@ -79,7 +79,7 @@ struct AhrsGX3 {
struct FloatVect3 accel; ///< measured acceleration in IMU frame
struct FloatRates rate; ///< measured angular rates in IMU frame
struct FloatRMat rmat; ///< measured attitude in IMU frame (rotational matrix)
- bool_t is_aligned;
+ bool is_aligned;
};
extern struct AhrsGX3 ahrs_gx3;
@@ -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 ad751c447f..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)
@@ -75,7 +75,7 @@ void ahrs_ice_init(void)
ahrs_ice.mag_offset = AHRS_MAG_OFFSET;
}
-bool_t ahrs_ice_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
+bool ahrs_ice_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
struct Int32Vect3 *lp_mag)
{
@@ -94,9 +94,9 @@ bool_t 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
@@ -105,21 +105,21 @@ bool_t ahrs_ice_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
#if USE_NOISE_CUT
#include "led.h"
-static inline bool_t cut_rates(struct Int32Rates i1, struct Int32Rates i2, int32_t threshold)
+static inline bool cut_rates(struct Int32Rates i1, struct Int32Rates i2, int32_t threshold)
{
struct Int32Rates diff;
RATES_DIFF(diff, i1, i2);
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)
-static inline bool_t cut_accel(struct Int32Vect3 i1, struct Int32Vect3 i2, int32_t threshold)
+static inline bool cut_accel(struct Int32Vect3 i1, struct Int32Vect3 i2, int32_t threshold)
{
struct Int32Vect3 diff;
VECT3_DIFF(diff, i1, i2);
@@ -127,10 +127,10 @@ static inline bool_t cut_accel(struct Int32Vect3 i1, struct Int32Vect3 i2, int32
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_euler.h b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.h
index 0a0d73079d..8408f6cfbe 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.h
+++ b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.h
@@ -54,7 +54,7 @@ struct AhrsIntCmplEuler {
struct OrientationReps body_to_imu;
enum AhrsICEStatus status;
- bool_t is_aligned;
+ bool is_aligned;
};
extern struct AhrsIntCmplEuler ahrs_ice;
@@ -62,7 +62,7 @@ extern struct AhrsIntCmplEuler ahrs_ice;
extern void ahrs_ice_init(void);
extern void ahrs_ice_set_body_to_imu(struct OrientationReps *body_to_imu);
extern void ahrs_ice_set_body_to_imu_quat(struct FloatQuat *q_b2i);
-extern bool_t ahrs_ice_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
+extern bool ahrs_ice_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
struct Int32Vect3 *lp_mag);
extern void ahrs_ice_propagate(struct Int32Rates *gyro);
extern void ahrs_ice_update_accel(struct Int32Vect3 *accel);
diff --git a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler_wrapper.c b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler_wrapper.c
index 07fac1776d..635110397c 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler_wrapper.c
+++ b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler_wrapper.c
@@ -35,7 +35,7 @@
PRINT_CONFIG_VAR(AHRS_ICE_OUTPUT_ENABLED)
/** if TRUE with push the estimation results to the state interface */
-static bool_t ahrs_ice_output_enabled;
+static bool ahrs_ice_output_enabled;
static uint32_t ahrs_ice_last_stamp;
static uint8_t ahrs_ice_id = AHRS_COMP_ID_ICE;
@@ -166,7 +166,7 @@ static void body_to_imu_cb(uint8_t sender_id __attribute__((unused)),
ahrs_ice_set_body_to_imu_quat(q_b2i_f);
}
-static bool_t ahrs_ice_enable_output(bool_t enable)
+static bool ahrs_ice_enable_output(bool enable)
{
ahrs_ice_output_enabled = enable;
return ahrs_ice_output_enabled;
diff --git a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.c b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.c
index 26eaa96ba9..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),
@@ -148,7 +148,7 @@ void ahrs_icq_init(void)
}
-bool_t ahrs_icq_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
+bool ahrs_icq_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
struct Int32Vect3 *lp_mag)
{
@@ -156,11 +156,11 @@ bool_t 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_t 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/ahrs/ahrs_int_cmpl_quat.h b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.h
index 59ea681ebb..862750f22b 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.h
+++ b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.h
@@ -55,8 +55,8 @@ struct AhrsIntCmplQuat {
struct Int32Vect3 mag_h;
int32_t ltp_vel_norm;
- bool_t ltp_vel_norm_valid;
- bool_t heading_aligned;
+ bool ltp_vel_norm_valid;
+ bool heading_aligned;
float weight;
float accel_inv_kp;
float accel_inv_ki;
@@ -65,7 +65,7 @@ struct AhrsIntCmplQuat {
/* parameters/options that can be changed */
/** enable gravity vector correction by removing centrifugal acceleration */
- bool_t correct_gravity;
+ bool correct_gravity;
/** sets how strongly the gravity heuristic reduces accel correction.
* Set to zero in order to disable gravity heuristic.
@@ -101,7 +101,7 @@ struct AhrsIntCmplQuat {
struct OrientationReps body_to_imu;
enum AhrsICQStatus status; ///< status of the AHRS, AHRS_ICQ_UNINIT or AHRS_ICQ_RUNNING
- bool_t is_aligned;
+ bool is_aligned;
};
extern struct AhrsIntCmplQuat ahrs_icq;
@@ -109,7 +109,7 @@ extern struct AhrsIntCmplQuat ahrs_icq;
extern void ahrs_icq_init(void);
extern void ahrs_icq_set_body_to_imu(struct OrientationReps *body_to_imu);
extern void ahrs_icq_set_body_to_imu_quat(struct FloatQuat *q_b2i);
-extern bool_t ahrs_icq_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
+extern bool ahrs_icq_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
struct Int32Vect3 *lp_mag);
extern void ahrs_icq_propagate(struct Int32Rates *gyro, float dt);
extern void ahrs_icq_update_accel(struct Int32Vect3 *accel, float dt);
diff --git a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat_wrapper.c b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat_wrapper.c
index accd5a40f8..9530c282b6 100644
--- a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat_wrapper.c
+++ b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat_wrapper.c
@@ -35,7 +35,7 @@
PRINT_CONFIG_VAR(AHRS_ICQ_OUTPUT_ENABLED)
/** if TRUE with push the estimation results to the state interface */
-static bool_t ahrs_icq_output_enabled;
+static bool ahrs_icq_output_enabled;
static uint32_t ahrs_icq_last_stamp;
static uint8_t ahrs_icq_id = AHRS_COMP_ID_ICQ;
@@ -242,7 +242,7 @@ static void gps_cb(uint8_t sender_id __attribute__((unused)),
ahrs_icq_update_gps(gps_s);
}
-static bool_t ahrs_icq_enable_output(bool_t enable)
+static bool ahrs_icq_enable_output(bool enable)
{
ahrs_icq_output_enabled = enable;
return ahrs_icq_output_enabled;
diff --git a/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c b/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c
index 458a653f87..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)
@@ -92,7 +92,7 @@ void chibios_sdlog_init(struct chibios_sdlog *sdlog, FileDes *file)
}
-bool_t chibios_logInit(void)
+bool chibios_logInit(void)
{
nvicSetSystemHandlerPriority(HANDLER_PENDSV,
CORTEX_PRIORITY_MASK(15));
@@ -115,14 +115,14 @@ bool_t chibios_logInit(void)
launchBatterySurveyThread ();
- return TRUE;
+ return true;
error:
- return FALSE;
+ return false;
}
-void chibios_logFinish(bool_t flush)
+void chibios_logFinish(bool flush)
{
if (pprzLogFile != -1) {
sdLogCloseAllLogs(flush);
diff --git a/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.h b/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.h
index 55808d79cb..24dc62d71f 100644
--- a/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.h
+++ b/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.h
@@ -46,8 +46,8 @@ extern FileDes pprzLogFile;
extern FileDes flightRecorderLogFile;
#endif
-extern bool_t chibios_logInit(void);
-extern void chibios_logFinish(bool_t flush);
+extern bool chibios_logInit(void);
+extern void chibios_logFinish(bool flush);
struct chibios_sdlog {
FileDes *file;
diff --git a/sw/airborne/subsystems/chibios-libopencm3/printf.c b/sw/airborne/subsystems/chibios-libopencm3/printf.c
index 5428cc914e..771267e22b 100644
--- a/sw/airborne/subsystems/chibios-libopencm3/printf.c
+++ b/sw/airborne/subsystems/chibios-libopencm3/printf.c
@@ -45,14 +45,14 @@ static int intPow(int a, int b)
}
-static bool_t writeBufferWithinSize (char **buffer, const char c, size_t *size)
+static bool writeBufferWithinSize (char **buffer, const char c, size_t *size)
{
if (*size) {
**buffer = c;
(*buffer)++;
return (--(*size) == 0);
} else {
- return TRUE;
+ return true;
}
}
@@ -133,7 +133,7 @@ static char *ftoa(char *p, double num, uint32_t precision) {
void chvprintf(BaseSequentialStream *chp, const char *fmt, va_list ap) {
char *p, *s, c, filler;
int i, precision, width;
- bool_t is_long, left_align;
+ bool is_long, left_align;
long l;
#if CHPRINTF_USE_FLOAT
double d;
@@ -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++;
}
@@ -292,7 +292,7 @@ unsigned_common:
void chvsnprintf(char *buffer, size_t size, const char *fmt, va_list ap) {
char *p, *s, c, filler;
int i, precision, width;
- bool_t is_long, left_align;
+ bool is_long, left_align;
long l;
#if CHPRINTF_USE_FLOAT
double d;
@@ -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/sdLog.c b/sw/airborne/subsystems/chibios-libopencm3/sdLog.c
index 21e62e19d1..67e9e41f4a 100644
--- a/sw/airborne/subsystems/chibios-libopencm3/sdLog.c
+++ b/sw/airborne/subsystems/chibios-libopencm3/sdLog.c
@@ -163,7 +163,7 @@ SdioError sdLogFinish (void)
#ifdef SDLOG_NEED_QUEUE
SdioError sdLogOpenLog (FileDes *fd, const char* directoryName, const char* prefix,
- bool_t appendTagAtClose)
+ bool appendTagAtClose)
{
FRESULT rc; /* fatfs result code */
SdioError sde; /* sdio result code */
diff --git a/sw/airborne/subsystems/chibios-libopencm3/sdLog.h b/sw/airborne/subsystems/chibios-libopencm3/sdLog.h
index ecc2e10956..b9bd82fba5 100644
--- a/sw/airborne/subsystems/chibios-libopencm3/sdLog.h
+++ b/sw/airborne/subsystems/chibios-libopencm3/sdLog.h
@@ -119,7 +119,7 @@ SdioError sdLogFinish (void);
* files.
*/
SdioError sdLogOpenLog (FileDes *fileObject, const char* directoryName, const char* fileName,
- bool_t appendTagAtClose);
+ bool appendTagAtClose);
/**
diff --git a/sw/airborne/subsystems/chibios-libopencm3/sdio.c b/sw/airborne/subsystems/chibios-libopencm3/sdio.c
index 5c06b18de2..10d68f52c2 100644
--- a/sw/airborne/subsystems/chibios-libopencm3/sdio.c
+++ b/sw/airborne/subsystems/chibios-libopencm3/sdio.c
@@ -52,14 +52,14 @@ static enum {STOP, CONNECT} cnxState = STOP;
-bool_t sdioConnect (void)
+bool sdioConnect (void)
{
if (!sdc_lld_is_card_inserted (NULL)) {
- return FALSE;
+ return false;
}
if (cnxState == CONNECT) {
- return TRUE;
+ return true;
}
/*
@@ -85,23 +85,23 @@ bool_t sdioConnect (void)
}
cnxState = CONNECT;
- return TRUE;
+ return true;
}
-bool_t sdioDisconnect (void)
+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_t isCardInserted (void)
+bool isCardInserted (void)
{
return sdc_lld_is_card_inserted (NULL);
}
@@ -152,7 +152,7 @@ static uint8_t inbuf[MMCSD_BLOCK_SIZE * SDC_BURST_SIZE + 1];
* read.
* @retval SDC_FAILED operation failed, the state of the buffer is uncertain.
*/
-bool_t badblocks(uint32_t start, uint32_t end, uint32_t blockatonce, uint8_t pattern){
+bool badblocks(uint32_t start, uint32_t end, uint32_t blockatonce, uint8_t pattern){
uint32_t position = 0;
uint32_t i = 0;
@@ -179,10 +179,10 @@ bool_t badblocks(uint32_t start, uint32_t end, uint32_t blockatonce, uint8_t pat
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_t format = FALSE;
+ bool format = false;
chThdSleepMilliseconds(100);
diff --git a/sw/airborne/subsystems/chibios-libopencm3/sdio.h b/sw/airborne/subsystems/chibios-libopencm3/sdio.h
index ec07ffe30e..b55af11d53 100644
--- a/sw/airborne/subsystems/chibios-libopencm3/sdio.h
+++ b/sw/airborne/subsystems/chibios-libopencm3/sdio.h
@@ -1,6 +1,6 @@
#pragma once
-bool_t sdioConnect (void);
-bool_t sdioDisconnect (void);
-bool_t isCardInserted (void);
+bool sdioConnect (void);
+bool sdioDisconnect (void);
+bool isCardInserted (void);
void cmd_sdiotest(void);
diff --git a/sw/airborne/subsystems/chibios-libopencm3/usbStorage.c b/sw/airborne/subsystems/chibios-libopencm3/usbStorage.c
index a1e4eaf29e..1733c5e500 100644
--- a/sw/airborne/subsystems/chibios-libopencm3/usbStorage.c
+++ b/sw/airborne/subsystems/chibios-libopencm3/usbStorage.c
@@ -40,7 +40,7 @@ static msg_t thdUsbStorage(void *arg);
static Thread* usbStorageThreadPtr=NULL;
/* USB mass storage driver */
static USBMassStorageDriver UMSD1;
-static bool_t isRunning = false;
+static bool isRunning = false;
/* endpoint index */
#define USB_MS_DATA_EP 1
@@ -237,7 +237,7 @@ const USBConfig usbConfig =
};
/* Turns on a LED when there is I/O activity on the USB port */
-static void usbActivity(bool_t active)
+static void usbActivity(bool active)
{
if (active)
palSetPad(GPIOC, GPIOC_LED4);
@@ -298,7 +298,7 @@ static msg_t thdUsbStorage(void *arg)
// be used concurrently by chibios api
// Should be fixed when using chibios-rt branch
while (!chThdShouldTerminate() && antiBounce) {
- const bool_t usbConnected = palReadPad (GPIOA, GPIOA_OTG_FS_VBUS);
+ const bool usbConnected = palReadPad (GPIOA, GPIOA_OTG_FS_VBUS);
if (usbConnected)
antiBounce--;
else
@@ -356,7 +356,7 @@ static msg_t thdUsbStorage(void *arg)
return RDY_OK;
}
-bool_t usbStorageIsItRunning (void)
+bool usbStorageIsItRunning (void)
{
return isRunning;
}
diff --git a/sw/airborne/subsystems/chibios-libopencm3/usbStorage.h b/sw/airborne/subsystems/chibios-libopencm3/usbStorage.h
index cdb33ff53f..f6e6aa678f 100644
--- a/sw/airborne/subsystems/chibios-libopencm3/usbStorage.h
+++ b/sw/airborne/subsystems/chibios-libopencm3/usbStorage.h
@@ -28,4 +28,4 @@
void usbStorageStartPolling (void);
void usbStorageStop (void);
void usbStorageWaitForDeconnexion (void);
-bool_t usbStorageIsItRunning (void);
+bool usbStorageIsItRunning (void);
diff --git a/sw/airborne/subsystems/chibios-libopencm3/usb_msd.c b/sw/airborne/subsystems/chibios-libopencm3/usb_msd.c
index dbb7c9ed2a..b6a9e9f622 100644
--- a/sw/airborne/subsystems/chibios-libopencm3/usb_msd.c
+++ b/sw/airborne/subsystems/chibios-libopencm3/usb_msd.c
@@ -184,7 +184,7 @@ void msdConfigureHookI(USBMassStorageDriver *msdp)
* @retval TRUE Message handled internally.
* @retval FALSE Message not handled.
*/
-bool_t msdRequestsHook(USBDriver *usbp) {
+bool msdRequestsHook(USBDriver *usbp) {
/* check that the request is of type Class / Interface */
if (((usbp->setup[0] & USB_RTYPE_TYPE_MASK) == USB_RTYPE_TYPE_CLASS) &&
@@ -192,7 +192,7 @@ bool_t 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_t 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_t 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;
}
/**
@@ -291,7 +291,7 @@ static inline void msd_scsi_set_sense(USBMassStorageDriver *msdp, uint8_t key, u
/**
* @brief Processes an INQUIRY SCSI command
*/
-bool_t msd_scsi_process_inquiry(USBMassStorageDriver *msdp) {
+bool msd_scsi_process_inquiry(USBMassStorageDriver *msdp) {
msd_cbw_t *cbw = &(msdp->cbw);
@@ -305,10 +305,10 @@ bool_t 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,38 +317,38 @@ bool_t 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;
}
}
/**
* @brief Processes a REQUEST_SENSE SCSI command
*/
-bool_t msd_scsi_process_request_sense(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;
}
/**
* @brief Processes a READ_CAPACITY_10 SCSI command
*/
-bool_t msd_scsi_process_read_capacity_10(USBMassStorageDriver *msdp) {
+bool msd_scsi_process_read_capacity_10(USBMassStorageDriver *msdp) {
static msd_scsi_read_capacity_10_response_t response;
@@ -356,16 +356,16 @@ bool_t 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;
}
/**
* @brief Processes a SEND_DIAGNOSTIC SCSI command
*/
-bool_t msd_scsi_process_send_diagnostic(USBMassStorageDriver *msdp) {
+bool msd_scsi_process_send_diagnostic(USBMassStorageDriver *msdp) {
msd_cbw_t *cbw = &(msdp->cbw);
@@ -375,21 +375,21 @@ bool_t 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;
}
/**
* @brief Processes a READ_WRITE_10 SCSI command
*/
-bool_t msd_scsi_process_start_read_write_10(USBMassStorageDriver *msdp) {
+bool msd_scsi_process_start_read_write_10(USBMassStorageDriver *msdp) {
msd_cbw_t *cbw = &(msdp->cbw);
@@ -400,10 +400,10 @@ bool_t 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_t 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_t 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_t 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_t 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,16 +500,16 @@ bool_t msd_scsi_process_start_read_write_10(USBMassStorageDriver *msdp) {
}
}
- msdp->result = TRUE;
+ msdp->result = true;
/* don't wait for ISR */
- return FALSE;
+ return false;
}
/**
* @brief Processes a START_STOP_UNIT SCSI command
*/
-bool_t msd_scsi_process_start_stop_unit(USBMassStorageDriver *msdp) {
+bool msd_scsi_process_start_stop_unit(USBMassStorageDriver *msdp) {
if ((msdp->cbw.scsi_cmd_data[4] & 0x03) == 0x02) {
/* device has been ejected */
@@ -517,16 +517,16 @@ bool_t 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;
}
/**
* @brief Processes a MODE_SENSE_6 SCSI command
*/
-bool_t msd_scsi_process_mode_sense_6(USBMassStorageDriver *msdp) {
+bool msd_scsi_process_mode_sense_6(USBMassStorageDriver *msdp) {
static uint8_t response[4] = {
0x03, /* number of bytes that follow */
@@ -536,16 +536,16 @@ bool_t 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;
}
/**
* @brief Processes a READ_FORMAT_CAPACITIES SCSI command
*/
-bool_t msd_scsi_process_read_format_capacities(USBMassStorageDriver *msdp) {
+bool msd_scsi_process_read_format_capacities(USBMassStorageDriver *msdp) {
msd_scsi_read_format_capacities_response_t response;
response.capacity_list_length = 1;
@@ -553,49 +553,49 @@ bool_t 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;
}
/**
* @brief Processes a TEST_UNIT_READY SCSI command
*/
-bool_t msd_scsi_process_test_unit_ready(USBMassStorageDriver *msdp) {
+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;
}
/**
* @brief Waits for a new command block
*/
-bool_t msd_wait_for_command_block(USBMassStorageDriver *msdp) {
+bool msd_wait_for_command_block(USBMassStorageDriver *msdp) {
msd_start_receive(msdp, (uint8_t *)&msdp->cbw, sizeof(msdp->cbw));
msdp->state = MSD_READ_COMMAND_BLOCK;
/* wait for ISR */
- return TRUE;
+ return true;
}
/**
* @brief Reads a newly received command block
*/
-bool_t msd_read_command_block(USBMassStorageDriver *msdp) {
+bool msd_read_command_block(USBMassStorageDriver *msdp) {
msd_cbw_t *cbw = &(msdp->cbw);
@@ -616,10 +616,10 @@ bool_t msd_read_command_block(USBMassStorageDriver *msdp) {
chSysUnlock();
/* don't wait for ISR */
- return FALSE;
+ return false;
}
- bool_t sleep = FALSE;
+ bool sleep = false;
/* check the command */
switch (cbw->scsi_cmd_data[0]) {
@@ -657,15 +657,15 @@ bool_t 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_t 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_t 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_t 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_t 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/usb_msd.h b/sw/airborne/subsystems/chibios-libopencm3/usb_msd.h
index 249db80418..cb37a0eb42 100644
--- a/sw/airborne/subsystems/chibios-libopencm3/usb_msd.h
+++ b/sw/airborne/subsystems/chibios-libopencm3/usb_msd.h
@@ -111,7 +111,7 @@ typedef struct {
* @note The callback is called with argument TRUE when activity starts,
* and FALSE when activity stops.
*/
- void (*rw_activity_callback)(bool_t);
+ void (*rw_activity_callback)(bool);
/**
* @brief Short vendor identification
@@ -149,7 +149,7 @@ typedef struct {
msd_csw_t csw;
msd_scsi_sense_response_t sense;
msd_scsi_inquiry_response_t inquiry;
- bool_t result;
+ bool result;
} USBMassStorageDriver;
#ifdef __cplusplus
@@ -200,7 +200,7 @@ void msdConfigureHookI(USBMassStorageDriver *msdp);
* @retval TRUE Message handled internally.
* @retval FALSE Message not handled.
*/
-bool_t msdRequestsHook(USBDriver *usbp);
+bool msdRequestsHook(USBDriver *usbp);
#ifdef __cplusplus
}
diff --git a/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.c b/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.c
index 2a1801570a..c2620d950b 100644
--- a/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.c
+++ b/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.c
@@ -30,18 +30,18 @@ void varLenMsgDynamicInit (VarLenMsgQueue* que)
que->sparseChunkNumber=0;
}
-bool_t varLenMsgQueueIsFull (VarLenMsgQueue* que)
+bool varLenMsgQueueIsFull (VarLenMsgQueue* que)
{
varLenMsgQueueLock (que);
- bool_t retVal = ringBufferIsFull (&que->circBuf) || chMBGetFreeCountI (&que->mb) <= 0;
+ bool retVal = ringBufferIsFull (&que->circBuf) || chMBGetFreeCountI (&que->mb) <= 0;
varLenMsgQueueUnlock ();
return retVal;
}
-bool_t varLenMsgQueueIsEmpty (VarLenMsgQueue* que)
+bool varLenMsgQueueIsEmpty (VarLenMsgQueue* que)
{
varLenMsgQueueLock (que);
- bool_t retVal = ringBufferIsEmpty (&que->circBuf) && chMBGetUsedCountI (&que->mb) <= 0;
+ bool retVal = ringBufferIsEmpty (&que->circBuf) && chMBGetUsedCountI (&que->mb) <= 0;
varLenMsgQueueUnlock ();
return retVal;
}
@@ -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 {
@@ -391,33 +391,33 @@ static uint16_t popSparseChunkMap (VarLenMsgQueue* que, const uint16_t mplAddr)
return associatedLen;
}
-bool_t varLenMsgQueueTestIntegrityIfEmpty(VarLenMsgQueue* que)
+bool varLenMsgQueueTestIntegrityIfEmpty(VarLenMsgQueue* que)
{
- bool_t 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_t 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/chibios-libopencm3/varLengthMsgQ.h b/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.h
index 9e0e621b71..1945c10b9a 100644
--- a/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.h
+++ b/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.h
@@ -105,7 +105,7 @@ void varLenMsgDynamicInit (VarLenMsgQueue* que);
parameters : queue object
return value: TRUE if queue if full, FALSE otherwise
*/
-bool_t varLenMsgQueueIsFull (VarLenMsgQueue* que);
+bool varLenMsgQueueIsFull (VarLenMsgQueue* que);
/*
goal : test if queue is empty
@@ -113,7 +113,7 @@ bool_t varLenMsgQueueIsFull (VarLenMsgQueue* que);
parameters : queue object
return value: TRUE if queue if empty, FALSE otherwise
*/
-bool_t varLenMsgQueueIsEmpty (VarLenMsgQueue* que);
+bool varLenMsgQueueIsEmpty (VarLenMsgQueue* que);
/*
goal : return used size in circular buffer,
@@ -239,7 +239,7 @@ void varLenMsgQueueFreeChunk (VarLenMsgQueue* que, const ChunkBufferRO *cbuf);
parameters : queue object
return value: TRUE if OK, FALSE if ERROR
*/
-bool_t varLenMsgQueueTestIntegrityIfEmpty(VarLenMsgQueue* que);
+bool varLenMsgQueueTestIntegrityIfEmpty(VarLenMsgQueue* que);
/*
goal : give literal message from a status error code
@@ -271,7 +271,7 @@ typedef union {
struct VarLenMsgQueue {
const uint16_t mbAndSparseChunkSize;
- const bool_t useZeroCopyApi;
+ const bool useZeroCopyApi;
uint16_t mbReservedSlot;
Mutex mtx ;
Mailbox mb;
diff --git a/sw/airborne/subsystems/datalink/bluegiga.c b/sw/airborne/subsystems/datalink/bluegiga.c
index 82e83e41e9..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)
{
@@ -110,7 +110,7 @@ static void trans_cb(struct spi_transaction *trans)
}
/* check if character available in receive buffer */
-bool_t bluegiga_ch_available(struct bluegiga_periph *p)
+bool bluegiga_ch_available(struct bluegiga_periph *p)
{
return (p->rx_extract_idx != p->rx_insert_idx);
}
diff --git a/sw/airborne/subsystems/datalink/bluegiga.h b/sw/airborne/subsystems/datalink/bluegiga.h
index 52ac935593..5b9ef9f059 100644
--- a/sw/airborne/subsystems/datalink/bluegiga.h
+++ b/sw/airborne/subsystems/datalink/bluegiga.h
@@ -72,7 +72,7 @@ struct bluegiga_periph {
extern struct bluegiga_periph bluegiga_p;
extern signed char bluegiga_rssi[]; // values initialized with 127
-bool_t bluegiga_ch_available(struct bluegiga_periph *p);
+bool bluegiga_ch_available(struct bluegiga_periph *p);
void bluegiga_increment_buf(uint8_t *buf_idx, uint8_t len);
void bluegiga_init(struct bluegiga_periph *p);
diff --git a/sw/airborne/subsystems/datalink/datalink.c b/sw/airborne/subsystems/datalink/datalink.c
index 92916fd244..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_t 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 8d4a53c456..e8c77a6915 100644
--- a/sw/airborne/subsystems/datalink/datalink.h
+++ b/sw/airborne/subsystems/datalink/datalink.h
@@ -48,7 +48,7 @@
#define BLUEGIGA 5
/** Flag provided to control calls to ::dl_parse_msg. NOT used in this module*/
-EXTERN bool_t dl_msg_available;
+EXTERN bool dl_msg_available;
/** time in seconds since last datalink message was received */
EXTERN uint16_t datalink_time;
@@ -66,7 +66,7 @@ EXTERN void dl_parse_msg(void);
EXTERN void firmware_parse_msg(void);
#if USE_NPS
-EXTERN bool_t datalink_enabled;
+EXTERN bool datalink_enabled;
#endif
/** Convenience macro to fill dl_buffer */
@@ -75,7 +75,7 @@ EXTERN bool_t 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(); \
}
@@ -127,7 +127,7 @@ static inline void DlCheckAndParse(void)
#elif defined DATALINK && DATALINK == BLUEGIGA
#define DatalinkEvent() { \
- pprz_check_and_parse(&(DOWNLINK_DEVICE).device, &pprz_tp, dl_buffer, (uint8_t*)(&dl_msg_available)); \
+ pprz_check_and_parse(&(DOWNLINK_DEVICE).device, &pprz_tp, dl_buffer, &dl_msg_available); \
DlCheckAndParse(); \
}
diff --git a/sw/airborne/subsystems/datalink/superbitrf.c b/sw/airborne/subsystems/datalink/superbitrf.c
index f994a3b748..9bfd074e13 100644
--- a/sw/airborne/subsystems/datalink/superbitrf.c
+++ b/sw/airborne/subsystems/datalink/superbitrf.c
@@ -70,9 +70,9 @@ PRINT_CONFIG_VAR(SUPERBITRF_FORCE_DSM2)
struct SuperbitRF superbitrf;
/* The internal functions */
-static inline void superbitrf_radio_to_channels(uint8_t *data, uint8_t nb_channels, bool_t is_11bit, int16_t *channels);
-static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, uint8_t packet[]);
-static inline void superbitrf_send_packet_cb(bool_t error);
+static inline void superbitrf_radio_to_channels(uint8_t *data, uint8_t nb_channels, bool is_11bit, int16_t *channels);
+static inline void superbitrf_receive_packet_cb(bool error, uint8_t status, uint8_t packet[]);
+static inline void superbitrf_send_packet_cb(bool error);
static inline void superbitrf_gen_dsmx_channels(void);
/* The startup configuration for the cyrf6936 */
@@ -201,7 +201,7 @@ static void send_superbit(struct transport_tx *trans, struct link_device *dev)
#endif
// Functions for the generic device API
-static bool_t superbitrf_check_free_space(struct SuperbitRF *p, uint8_t len)
+static bool superbitrf_check_free_space(struct SuperbitRF *p, uint8_t len)
{
int16_t space = p->tx_extract_idx - p->tx_insert_idx;
if (space <= 0) {
@@ -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_t 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;
@@ -755,7 +755,7 @@ void superbitrf_event(void)
/**
* When we receive a packet this callback is called
*/
-static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, uint8_t packet[])
+static inline void superbitrf_receive_packet_cb(bool error, uint8_t status, uint8_t packet[])
{
int i;
uint16_t sum;
@@ -851,9 +851,9 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui
// 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_t error, uint8_t status, ui
// 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_t error, uint8_t status, ui
// 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_t error, uint8_t status, ui
// 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_t error, uint8_t status, ui
// 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_t error, uint8_t status, ui
// 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;
}
}
}
@@ -1026,7 +1026,7 @@ static inline void superbitrf_receive_packet_cb(bool_t error, uint8_t status, ui
}
}
-static inline void superbitrf_send_packet_cb(bool_t error __attribute__((unused)))
+static inline void superbitrf_send_packet_cb(bool error __attribute__((unused)))
{
/* Switch on the status of the superbitRF */
switch (superbitrf.status) {
@@ -1057,7 +1057,7 @@ static inline void superbitrf_send_packet_cb(bool_t error __attribute__((unused)
/**
* Parse a radio channel packet
*/
-static inline void superbitrf_radio_to_channels(uint8_t *data, uint8_t nb_channels, bool_t is_11bit, int16_t *channels)
+static inline void superbitrf_radio_to_channels(uint8_t *data, uint8_t nb_channels, bool is_11bit, int16_t *channels)
{
int i;
uint8_t bit_shift = (is_11bit) ? 11 : 10;
diff --git a/sw/airborne/subsystems/datalink/superbitrf.h b/sw/airborne/subsystems/datalink/superbitrf.h
index 9d194a6497..25f0d83390 100644
--- a/sw/airborne/subsystems/datalink/superbitrf.h
+++ b/sw/airborne/subsystems/datalink/superbitrf.h
@@ -78,12 +78,12 @@ struct SuperbitRF {
volatile enum SuperbitRFStatus status; /**< The status of the superbitRF */
uint8_t state; /**< The states each status can be in */
uint32_t timer; /**< The timer in microseconds */
- bool_t timer_overflow; /**< When the timer overflows */
+ bool timer_overflow; /**< When the timer overflows */
uint8_t timeouts; /**< The amount of timeouts */
uint32_t transfer_timeouts; /**< The amount of timeouts during transfer */
uint32_t resync_count; /**< The amount of resyncs needed during transfer */
uint8_t packet_loss_bit; /**< The packet loss indicating bit */
- bool_t packet_loss; /**< When we have packet loss last packet */
+ bool packet_loss; /**< When we have packet loss last packet */
uint8_t channels[23]; /**< The channels used for DSM2/DSMX */
uint8_t channel_idx; /**< The current channel index */
@@ -103,7 +103,7 @@ struct SuperbitRF {
uint8_t sop_col; /**< The sop code column number calculated with the bind MFG id */
uint8_t data_col; /**< The data code column number calculated with the bind MFG id */
- bool_t rc_frame_available; /**< When a RC frame is available */
+ bool rc_frame_available; /**< When a RC frame is available */
uint32_t timing1; /**< Time between last receive in microseconds */
uint32_t timing2; /**< Time between second last receive in microseconds */
int16_t rc_values[14]; /**< The rc values from the packet */
diff --git a/sw/airborne/subsystems/datalink/w5100.c b/sw/airborne/subsystems/datalink/w5100.c
index 4b040e0488..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; }
@@ -361,12 +361,12 @@ static void configure_socket(uint8_t _s, uint8_t _flag, uint16_t _lport, uint16_
w5100_sock_set(_s, SOCK_CR, SOCK_OPEN);
}
-bool_t w5100_ch_available()
+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 360cb695cf..9dd888831e 100644
--- a/sw/airborne/subsystems/datalink/w5100.h
+++ b/sw/airborne/subsystems/datalink/w5100.h
@@ -69,7 +69,7 @@ void w5100_transmit(uint8_t data);
uint16_t w5100_receive(uint8_t *buf, uint16_t len);
void w5100_send(void);
uint16_t w5100_rx_size(uint8_t _s);
-bool_t w5100_ch_available(void);
+bool w5100_ch_available(void);
// W5100 is using pprz_transport
@@ -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 99d376809c..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_t 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/electrical.h b/sw/airborne/subsystems/electrical.h
index b805949fb8..0580a182fc 100644
--- a/sw/airborne/subsystems/electrical.h
+++ b/sw/airborne/subsystems/electrical.h
@@ -49,8 +49,8 @@ struct Electrical {
int32_t current; ///< current in milliamps
int32_t consumed; ///< consumption in mAh
float energy; ///< consumed energy in mAh
- bool_t bat_low; ///< battery low status
- bool_t bat_critical; ///< battery critical status
+ bool bat_low; ///< battery low status
+ bool bat_critical; ///< battery critical status
};
diff --git a/sw/airborne/subsystems/gps.h b/sw/airborne/subsystems/gps.h
index afe639f616..6295f27943 100644
--- a/sw/airborne/subsystems/gps.h
+++ b/sw/airborne/subsystems/gps.h
@@ -149,11 +149,11 @@ extern void gps_inject_data(uint8_t packet_id, uint8_t length, uint8_t *data);
#define GPS_TIMEOUT 2
#endif
-static inline bool_t gps_has_been_good(void)
+static inline bool gps_has_been_good(void)
{
- static bool_t 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 7ff1b4415b..693b311f4b 100644
--- a/sw/airborne/subsystems/gps/gps_mtk.c
+++ b/sw/airborne/subsystems/gps/gps_mtk.c
@@ -100,7 +100,7 @@ struct GpsMtk gps_mtk;
#define MTK_DIY_WAAS_ON "$PSRF151,1*3F\r\n"
#define MTK_DIY_WAAS_OFF "$PSRF151,0*3E\r\n"
-bool_t gps_configuring;
+bool gps_configuring;
static uint8_t gps_status_config;
#endif
@@ -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:
@@ -442,7 +442,7 @@ void gps_configure_uart(void)
#ifdef USER_GPS_CONFIGURE
#include USER_GPS_CONFIGURE
#else
-static bool_t user_gps_configure(bool_t cpt)
+static bool user_gps_configure(bool cpt)
{
switch (cpt) {
case 0:
@@ -450,11 +450,11 @@ static bool_t user_gps_configure(bool_t 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_mtk.h b/sw/airborne/subsystems/gps/gps_mtk.h
index 26e3673e63..b20f7b3da3 100644
--- a/sw/airborne/subsystems/gps/gps_mtk.h
+++ b/sw/airborne/subsystems/gps/gps_mtk.h
@@ -43,7 +43,7 @@
#define GPS_MTK_MAX_PAYLOAD 255
struct GpsMtk {
- bool_t msg_available;
+ bool msg_available;
uint8_t msg_buf[GPS_MTK_MAX_PAYLOAD] __attribute__((aligned));
uint8_t msg_id;
uint8_t msg_class;
@@ -71,7 +71,7 @@ extern void gps_mtk_register(void);
#ifdef GPS_CONFIGURE
extern void gps_configure(void);
extern void gps_configure_uart(void);
-extern bool_t gps_configuring;
+extern bool gps_configuring;
#define GpsConfigure() { \
if (gps_configuring) \
gps_configure(); \
diff --git a/sw/airborne/subsystems/gps/gps_nmea.c b/sw/airborne/subsystems/gps/gps_nmea.c
index 105191d277..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_t 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_nmea.h b/sw/airborne/subsystems/gps/gps_nmea.h
index 43d9abb261..d0815d2cb2 100644
--- a/sw/airborne/subsystems/gps/gps_nmea.h
+++ b/sw/airborne/subsystems/gps/gps_nmea.h
@@ -46,10 +46,10 @@ extern void gps_nmea_event(void);
extern void gps_nmea_register(void);
struct GpsNmea {
- bool_t msg_available;
- bool_t pos_available;
- bool_t is_configured; ///< flag set to TRUE if configuration is finished
- bool_t have_gsv; ///< flag set to TRUE if GPGSV message received
+ bool msg_available;
+ bool pos_available;
+ bool is_configured; ///< flag set to TRUE if configuration is finished
+ bool have_gsv; ///< flag set to TRUE if GPGSV message received
uint8_t gps_nb_ovrn; ///< number if incomplete nmea-messages
char msg_buf[NMEA_MAXLEN]; ///< buffer for storing one nmea-line
int msg_len;
diff --git a/sw/airborne/subsystems/gps/gps_sim_hitl.c b/sw/airborne/subsystems/gps/gps_sim_hitl.c
index 451e65fc04..6ab0a24832 100644
--- a/sw/airborne/subsystems/gps/gps_sim_hitl.c
+++ b/sw/airborne/subsystems/gps/gps_sim_hitl.c
@@ -33,7 +33,7 @@
#include "guidance/guidance_v.h"
#include "firmwares/rotorcraft/autopilot.h"
-bool_t gps_available;
+bool gps_available;
uint32_t gps_sim_hitl_timer;
void gps_sim_hitl_init(void)
@@ -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 7ca31f7a3a..b5bddfbb63 100644
--- a/sw/airborne/subsystems/gps/gps_sim_nps.c
+++ b/sw/airborne/subsystems/gps/gps_sim_nps.c
@@ -26,7 +26,7 @@
#include "nps_fdm.h"
struct GpsState gps_nps;
-bool_t gps_has_fix;
+bool gps_has_fix;
void gps_feed_value(void)
{
@@ -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_sim_nps.h b/sw/airborne/subsystems/gps/gps_sim_nps.h
index f935277c99..ab5fe8ab3b 100644
--- a/sw/airborne/subsystems/gps/gps_sim_nps.h
+++ b/sw/airborne/subsystems/gps/gps_sim_nps.h
@@ -7,7 +7,7 @@
#define PRIMARY_GPS gps_nps
#endif
-extern bool_t gps_has_fix;
+extern bool gps_has_fix;
extern void gps_feed_value();
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_sirf.h b/sw/airborne/subsystems/gps/gps_sirf.h
index ae3f9d0b1f..d57a910a15 100644
--- a/sw/airborne/subsystems/gps/gps_sirf.h
+++ b/sw/airborne/subsystems/gps/gps_sirf.h
@@ -46,8 +46,8 @@
#define GOT_B0 3
struct GpsSirf {
- bool_t msg_available;
- bool_t pos_available;
+ bool msg_available;
+ bool pos_available;
char msg_buf[SIRF_MAXLEN]; ///< buffer for storing one nmea-line
int msg_len;
int read_state;
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_skytraq.h b/sw/airborne/subsystems/gps/gps_skytraq.h
index f8cc166f6e..45ff59c233 100644
--- a/sw/airborne/subsystems/gps/gps_skytraq.h
+++ b/sw/airborne/subsystems/gps/gps_skytraq.h
@@ -43,7 +43,7 @@ enum GpsSkytraqError {
#define GPS_SKYTRAQ_MAX_PAYLOAD 255
struct GpsSkytraq {
uint8_t msg_buf[GPS_SKYTRAQ_MAX_PAYLOAD];
- bool_t msg_available;
+ bool msg_available;
uint8_t msg_id;
uint8_t status;
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/gps/gps_ubx.h b/sw/airborne/subsystems/gps/gps_ubx.h
index f59c377364..09bbfb381b 100644
--- a/sw/airborne/subsystems/gps/gps_ubx.h
+++ b/sw/airborne/subsystems/gps/gps_ubx.h
@@ -33,6 +33,10 @@
#warning "Please use gps_ubx_ucenter.xml module instead of GPS_CONFIGURE"
#endif
+#ifdef GPS_I2C
+#include "modules/gps/gps_ubx_i2c.h"
+#endif
+
#include "mcu_periph/uart.h"
#ifndef PRIMARY_GPS
@@ -47,7 +51,7 @@ extern void gps_ubx_register(void);
#define GPS_UBX_MAX_PAYLOAD 255
struct GpsUbx {
- bool_t msg_available;
+ bool msg_available;
uint8_t msg_buf[GPS_UBX_MAX_PAYLOAD] __attribute__((aligned));
uint8_t msg_id;
uint8_t msg_class;
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.h b/sw/airborne/subsystems/imu.h
index fcea81e218..1a7f9d0506 100644
--- a/sw/airborne/subsystems/imu.h
+++ b/sw/airborne/subsystems/imu.h
@@ -55,7 +55,7 @@ struct Imu {
/** flag for adjusting body_to_imu via settings.
* if FALSE, reset to airframe values, if TRUE set current roll/pitch
*/
- bool_t b2i_set_current;
+ bool b2i_set_current;
};
/** global IMU state */
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 a248891e9d..16435fad1c 100644
--- a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c
+++ b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c
@@ -101,7 +101,7 @@ struct ImuAspirin2Spi imu_aspirin2;
void mpu_wait_slave4_ready(void);
void mpu_wait_slave4_ready_cb(struct spi_transaction *t);
-bool_t imu_aspirin2_configure_mag_slave(Mpu60x0ConfigSet mpu_set, void *mpu);
+bool imu_aspirin2_configure_mag_slave(Mpu60x0ConfigSet mpu_set, void *mpu);
void imu_impl_init(void)
{
@@ -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);
@@ -256,12 +256,12 @@ static inline void mpu_set_and_wait(Mpu60x0ConfigSet mpu_set, void *mpu, uint8_t
/** function to configure hmc5883 mag
* @return TRUE if mag configuration finished
*/
-bool_t imu_aspirin2_configure_mag_slave(Mpu60x0ConfigSet mpu_set, void *mpu)
+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_t 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_2_spi.h b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.h
index a51178da42..98da9f3564 100644
--- a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.h
+++ b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.h
@@ -41,7 +41,7 @@ struct ImuAspirin2Spi {
struct spi_transaction wait_slave4_trans;
volatile uint8_t wait_slave4_tx_buf[1];
volatile uint8_t wait_slave4_rx_buf[2];
- volatile bool_t slave4_ready;
+ volatile bool slave4_ready;
};
extern struct ImuAspirin2Spi imu_aspirin2;
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 e6979d7a0f..7e8215939c 100644
--- a/sw/airborne/subsystems/imu/imu_crista.c
+++ b/sw/airborne/subsystems/imu/imu_crista.c
@@ -22,13 +22,13 @@
#include "subsystems/imu.h"
#include "subsystems/abi.h"
-volatile bool_t ADS8344_available;
+volatile bool ADS8344_available;
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_crista.h b/sw/airborne/subsystems/imu/imu_crista.h
index 326230c0c1..1f51615115 100644
--- a/sw/airborne/subsystems/imu/imu_crista.h
+++ b/sw/airborne/subsystems/imu/imu_crista.h
@@ -27,7 +27,7 @@
#define ADS8344_NB_CHANNELS 8
extern uint16_t ADS8344_values[ADS8344_NB_CHANNELS];
-extern volatile bool_t ADS8344_available;
+extern volatile bool ADS8344_available;
/* underlying architecture */
#include "subsystems/imu/imu_crista_arch.h"
diff --git a/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.c b/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.c
index 3f495d3f74..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);
}
@@ -162,13 +162,13 @@ void imu_drotek2_event(void)
/** callback function to configure hmc5883 mag
* @return TRUE if mag configuration finished
*/
-bool_t imu_drotek2_configure_mag_slave(Mpu60x0ConfigSet mpu_set __attribute__((unused)),
+bool imu_drotek2_configure_mag_slave(Mpu60x0ConfigSet mpu_set __attribute__((unused)),
void *mpu __attribute__((unused)))
{
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_drotek_10dof_v2.h b/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.h
index bc19091d4e..3bad6832ab 100644
--- a/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.h
+++ b/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.h
@@ -81,7 +81,7 @@ struct ImuDrotek2 {
extern struct ImuDrotek2 imu_drotek2;
extern void imu_drotek2_event(void);
-extern bool_t imu_drotek2_configure_mag_slave(Mpu60x0ConfigSet mpu_set, void *mpu);
+extern bool imu_drotek2_configure_mag_slave(Mpu60x0ConfigSet mpu_set, void *mpu);
#define ImuEvent imu_drotek2_event
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 c4c24e0205..612302a288 100644
--- a/sw/airborne/subsystems/imu/imu_mpu9250_spi.c
+++ b/sw/airborne/subsystems/imu/imu_mpu9250_spi.c
@@ -116,7 +116,7 @@ struct ImuMpu9250 imu_mpu9250;
void mpu_wait_slave4_ready(void);
void mpu_wait_slave4_ready_cb(struct spi_transaction *t);
-bool_t imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set, void *mpu);
+bool imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set, void *mpu);
void imu_impl_init(void)
{
@@ -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);
@@ -227,12 +227,12 @@ static inline void mpu_set_and_wait(Mpu9250ConfigSet mpu_set, void *mpu, uint8_t
/** function to configure akm8963 mag
* @return TRUE if mag configuration finished
*/
-bool_t imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set, void *mpu)
+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_t 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_mpu9250_spi.h b/sw/airborne/subsystems/imu/imu_mpu9250_spi.h
index 50a25ae94f..4dc462db96 100644
--- a/sw/airborne/subsystems/imu/imu_mpu9250_spi.h
+++ b/sw/airborne/subsystems/imu/imu_mpu9250_spi.h
@@ -77,7 +77,7 @@ struct ImuMpu9250 {
struct spi_transaction wait_slave4_trans;
volatile uint8_t wait_slave4_tx_buf[1];
volatile uint8_t wait_slave4_rx_buf[2];
- volatile bool_t slave4_ready;
+ volatile bool slave4_ready;
};
extern struct ImuMpu9250 imu_mpu9250;
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 3893761085..a4a1efb372 100644
--- a/sw/airborne/subsystems/imu/imu_um6.c
+++ b/sw/airborne/subsystems/imu/imu_um6.c
@@ -56,9 +56,9 @@ struct FloatQuat UM6_quat;
inline void UM6_imu_align(void);
inline void UM6_send_packet(uint8_t *packet_buffer, uint8_t packet_length);
inline uint16_t UM6_calculate_checksum(uint8_t packet_buffer[], uint8_t packet_length);
-inline bool_t UM6_verify_chk(uint8_t packet_buffer[], uint8_t packet_length);
+inline bool UM6_verify_chk(uint8_t packet_buffer[], uint8_t packet_length);
-inline bool_t UM6_verify_chk(uint8_t packet_buffer[], uint8_t packet_length)
+inline bool UM6_verify_chk(uint8_t packet_buffer[], uint8_t packet_length)
{
chk_rec = (packet_buffer[packet_length - 2] << 8) | packet_buffer[packet_length - 1];
chk_calc = UM6_calculate_checksum(packet_buffer, packet_length - 2);
@@ -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 9aada3073a..68f5c39c29 100644
--- a/sw/airborne/subsystems/imu/imu_um6.h
+++ b/sw/airborne/subsystems/imu/imu_um6.h
@@ -77,7 +77,7 @@ extern struct FloatEulers UM6_eulers;
extern struct FloatQuat UM6_quat;
struct UM6Packet {
- bool_t msg_available;
+ bool msg_available;
uint32_t chksm_error;
uint32_t hdr_error;
uint8_t msg_buf[IMU_UM6_BUFFER_LENGTH];
@@ -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/hf_float.h b/sw/airborne/subsystems/ins/hf_float.h
index 3d2d01091b..7d6e43eab7 100644
--- a/sw/airborne/subsystems/ins/hf_float.h
+++ b/sw/airborne/subsystems/ins/hf_float.h
@@ -47,7 +47,7 @@ struct HfilterFloat {
float xP[HFF_STATE_SIZE][HFF_STATE_SIZE];
float yP[HFF_STATE_SIZE][HFF_STATE_SIZE];
uint8_t lag_counter;
- bool_t rollback;
+ bool rollback;
};
extern struct HfilterFloat b2_hff_state;
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_alt_float.h b/sw/airborne/subsystems/ins/ins_alt_float.h
index 5f0c147882..fba52d955d 100644
--- a/sw/airborne/subsystems/ins/ins_alt_float.h
+++ b/sw/airborne/subsystems/ins/ins_alt_float.h
@@ -38,13 +38,13 @@ struct InsAltFloat {
float alt; ///< estimated altitude above MSL in meters
float alt_dot; ///< estimated vertical speed in m/s (positive-up)
- bool_t reset_alt_ref; ///< flag to request reset of altitude reference to current alt
- bool_t origin_initialized; ///< TRUE if UTM origin was initialized
+ bool reset_alt_ref; ///< flag to request reset of altitude reference to current alt
+ bool origin_initialized; ///< TRUE if UTM origin was initialized
#if USE_BAROMETER
float qfe;
float baro_alt;
- bool_t baro_initialized;
+ bool baro_initialized;
#endif
};
diff --git a/sw/airborne/subsystems/ins/ins_float_invariant.c b/sw/airborne/subsystems/ins/ins_float_invariant.c
index 124c191d74..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_t log_started = FALSE;
+bool log_started = false;
#endif
/*------------- =*= Invariant Observers =*= -------------*
@@ -146,10 +146,10 @@ static const struct FloatVect3 A = { 0.f, 0.f, 9.81f };
#define B ins_float_inv.mag_h
/* barometer */
-bool_t ins_baro_initialized;
+bool ins_baro_initialized;
/* gps */
-bool_t ins_gps_fix_once;
+bool ins_gps_fix_once;
/* error computation */
static inline void error_output(struct InsFloatInv *_ins);
@@ -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_float_invariant.h b/sw/airborne/subsystems/ins/ins_float_invariant.h
index 02fd90403e..034764e07a 100644
--- a/sw/airborne/subsystems/ins/ins_float_invariant.h
+++ b/sw/airborne/subsystems/ins/ins_float_invariant.h
@@ -110,13 +110,13 @@ struct InsFloatInv {
struct inv_correction_gains corr; ///< correction gains
struct inv_gains gains; ///< tuning gains
- bool_t reset; ///< flag to request reset/reinit the filter
+ bool reset; ///< flag to request reset/reinit the filter
/** body_to_imu rotation */
struct OrientationReps body_to_imu;
struct FloatVect3 mag_h;
- bool_t is_aligned;
+ bool is_aligned;
};
extern struct InsFloatInv ins_float_inv;
diff --git a/sw/airborne/subsystems/ins/ins_gps_passthrough.c b/sw/airborne/subsystems/ins/ins_gps_passthrough.c
index 93bf552ffe..8a24c76ebf 100644
--- a/sw/airborne/subsystems/ins/ins_gps_passthrough.c
+++ b/sw/airborne/subsystems/ins/ins_gps_passthrough.c
@@ -47,7 +47,7 @@ PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
struct InsGpsPassthrough {
struct LtpDef_i ltp_def;
- bool_t ltp_initialized;
+ bool ltp_initialized;
/* output LTP NED */
struct NedCoor_i ltp_pos;
@@ -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_int.h b/sw/airborne/subsystems/ins/ins_int.h
index dc5f2c81fb..f6a71732db 100644
--- a/sw/airborne/subsystems/ins/ins_int.h
+++ b/sw/airborne/subsystems/ins/ins_int.h
@@ -38,19 +38,19 @@
/** Ins implementation state (fixed point) */
struct InsInt {
struct LtpDef_i ltp_def;
- bool_t ltp_initialized;
+ bool ltp_initialized;
uint32_t propagation_cnt; ///< number of propagation steps since the last measurement update
/** request to realign horizontal filter.
* Sets to current position (local origin unchanged).
*/
- bool_t hf_realign;
+ bool hf_realign;
/** request to reset vertical filter.
* Sets the z-position to zero and resets the the z-reference to current altitude.
*/
- bool_t vf_reset;
+ bool vf_reset;
/* output LTP NED */
struct NedCoor_i ltp_pos;
@@ -60,10 +60,10 @@ struct InsInt {
/* baro */
float baro_z; ///< z-position calculated from baro in meters (z-down)
float qfe;
- bool_t baro_initialized;
+ bool baro_initialized;
#if USE_SONAR
- bool_t update_on_agl; ///< use sonar to update agl if available
+ bool update_on_agl; ///< use sonar to update agl if available
#endif
};
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/ins/ins_vectornav.h b/sw/airborne/subsystems/ins/ins_vectornav.h
index 02848f2583..83654cb374 100644
--- a/sw/airborne/subsystems/ins/ins_vectornav.h
+++ b/sw/airborne/subsystems/ins/ins_vectornav.h
@@ -64,7 +64,7 @@
// Ins implementation state (fixed point)
struct InsVectornav {
struct LtpDef_i ltp_def; // initial position
- bool_t ltp_initialized; // status indicator
+ bool ltp_initialized; // status indicator
// output LTP NED for telemetry messages
struct NedCoor_i ltp_pos_i;
diff --git a/sw/airborne/subsystems/intermcu/intermcu_ap.c b/sw/airborne/subsystems/intermcu/intermcu_ap.c
index 7f4b5c68f2..3ce6e576b8 100644
--- a/sw/airborne/subsystems/intermcu/intermcu_ap.c
+++ b/sw/airborne/subsystems/intermcu/intermcu_ap.c
@@ -72,8 +72,8 @@ void intermcu_periodic(void)
}
}
-static bool_t disable_comm;
-void disable_inter_comm(bool_t value)
+static bool disable_comm;
+void disable_inter_comm(bool value)
{
disable_comm = value;
}
@@ -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_ap.h b/sw/airborne/subsystems/intermcu/intermcu_ap.h
index 6cee9f703c..aba906327e 100644
--- a/sw/airborne/subsystems/intermcu/intermcu_ap.h
+++ b/sw/airborne/subsystems/intermcu/intermcu_ap.h
@@ -33,7 +33,7 @@
void intermcu_set_actuators(pprz_t *command_values, uint8_t ap_mode);
void RadioControlEvent(void (*frame_handler)(void));
void intermcu_send_spektrum_bind(void);
-void disable_inter_comm(bool_t value);
+void disable_inter_comm(bool value);
/* We need radio defines for the Autopilot */
#define RADIO_THROTTLE 0
diff --git a/sw/airborne/subsystems/intermcu/intermcu_fbw.c b/sw/airborne/subsystems/intermcu/intermcu_fbw.c
index 97abc6407c..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_t 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.c b/sw/airborne/subsystems/navigation/common_nav.c
index 1e4abe56d1..897e390c4a 100644
--- a/sw/airborne/subsystems/navigation/common_nav.c
+++ b/sw/airborne/subsystems/navigation/common_nav.c
@@ -32,7 +32,7 @@
float dist2_to_home;
float dist2_to_wp;
-bool_t too_far_from_home;
+bool too_far_from_home;
const uint8_t nb_waypoint = NB_WAYPOINT;
struct point waypoints[NB_WAYPOINT] = WAYPOINTS_UTM;
diff --git a/sw/airborne/subsystems/navigation/common_nav.h b/sw/airborne/subsystems/navigation/common_nav.h
index b5afffd8ac..3f78ba13b8 100644
--- a/sw/airborne/subsystems/navigation/common_nav.h
+++ b/sw/airborne/subsystems/navigation/common_nav.h
@@ -34,7 +34,7 @@
extern float max_dist_from_home;
extern float dist2_to_home;
extern float dist2_to_wp;
-extern bool_t too_far_from_home;
+extern bool too_far_from_home;
struct point {
float x;
@@ -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 8aed2396d9..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_t 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 f865e3865c..4bf4f627fa 100644
--- a/sw/airborne/subsystems/navigation/waypoints.c
+++ b/sw/airborne/subsystems/navigation/waypoints.c
@@ -37,7 +37,7 @@ void waypoints_init(void)
struct EnuCoor_f wp_tmp_float[NB_WAYPOINT] = WAYPOINTS_ENU;
struct LlaCoor_i wp_tmp_lla_i[NB_WAYPOINT] = WAYPOINTS_LLA_WGS84;
/* element in array is TRUE if absolute/global waypoint */
- bool_t is_global[NB_WAYPOINT] = WAYPOINTS_GLOBAL;
+ bool is_global[NB_WAYPOINT] = WAYPOINTS_GLOBAL;
uint8_t i = 0;
for (i = 0; i < nb_waypoint; i++) {
/* clear all flags */
@@ -52,12 +52,12 @@ void waypoints_init(void)
}
}
-bool_t waypoint_is_global(uint8_t wp_id)
+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/navigation/waypoints.h b/sw/airborne/subsystems/navigation/waypoints.h
index 4be4a1971c..fca7922914 100644
--- a/sw/airborne/subsystems/navigation/waypoints.h
+++ b/sw/airborne/subsystems/navigation/waypoints.h
@@ -54,7 +54,7 @@ extern struct Waypoint waypoints[];
extern void waypoints_init(void);
-extern bool_t waypoint_is_global(uint8_t wp_id);
+extern bool waypoint_is_global(uint8_t wp_id);
extern void waypoint_set_global_flag(uint8_t wp_id);
extern void waypoint_clear_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 f6793b00fd..255d16063e 100644
--- a/sw/airborne/subsystems/radio_control/ppm.c
+++ b/sw/airborne/subsystems/radio_control/ppm.c
@@ -29,14 +29,14 @@
#include "subsystems/radio_control/ppm.h"
uint16_t ppm_pulses[RADIO_CTL_NB];
-volatile bool_t ppm_frame_available;
+volatile bool ppm_frame_available;
/*
* State machine for decoding ppm frames
*/
static uint8_t ppm_cur_pulse;
static uint32_t ppm_last_pulse_time;
-static bool_t ppm_data_valid;
+static bool ppm_data_valid;
/**
* RssiValid test macro.
@@ -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/ppm.h b/sw/airborne/subsystems/radio_control/ppm.h
index 022abb9d7c..fd7f26334e 100644
--- a/sw/airborne/subsystems/radio_control/ppm.h
+++ b/sw/airborne/subsystems/radio_control/ppm.h
@@ -58,7 +58,7 @@ extern void ppm_arch_init(void);
#define PPM_PULSE_TYPE_NEGATIVE 1
extern uint16_t ppm_pulses[RADIO_CTL_NB];
-extern volatile bool_t ppm_frame_available;
+extern volatile bool ppm_frame_available;
/**
* RC event function with handler callback.
diff --git a/sw/airborne/subsystems/radio_control/rc_datalink.c b/sw/airborne/subsystems/radio_control/rc_datalink.c
index b0214e6211..dbef64e21a 100644
--- a/sw/airborne/subsystems/radio_control/rc_datalink.c
+++ b/sw/airborne/subsystems/radio_control/rc_datalink.c
@@ -28,12 +28,12 @@
#include "subsystems/radio_control.h"
int8_t rc_dl_values[ RC_DL_NB_CHANNEL ];
-volatile bool_t rc_dl_frame_available;
+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/rc_datalink.h b/sw/airborne/subsystems/radio_control/rc_datalink.h
index 432f5fcddb..25acc0dbfc 100644
--- a/sw/airborne/subsystems/radio_control/rc_datalink.h
+++ b/sw/airborne/subsystems/radio_control/rc_datalink.h
@@ -43,7 +43,7 @@
#define RADIO_MODE 4
extern int8_t rc_dl_values[ RC_DL_NB_CHANNEL ];
-extern volatile bool_t rc_dl_frame_available;
+extern volatile bool rc_dl_frame_available;
/**
* Decode datalink message to get rc values with RC_3CH message
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 774eaae607..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)
@@ -73,7 +73,7 @@ void sbus_common_init(struct Sbus *sbus_p, struct uart_periph *dev)
/** Decode the raw buffer */
-static void decode_sbus_buffer(const uint8_t *src, uint16_t *dst, bool_t *available,
+static void decode_sbus_buffer(const uint8_t *src, uint16_t *dst, bool *available,
uint16_t *dstppm)
{
// reset counters
diff --git a/sw/airborne/subsystems/radio_control/sbus_common.h b/sw/airborne/subsystems/radio_control/sbus_common.h
index 66fc1b0c46..b47c5537b4 100644
--- a/sw/airborne/subsystems/radio_control/sbus_common.h
+++ b/sw/airborne/subsystems/radio_control/sbus_common.h
@@ -78,7 +78,7 @@
struct Sbus {
uint16_t pulses[SBUS_NB_CHANNEL]; ///< decoded values
uint16_t ppm[SBUS_NB_CHANNEL]; ///< decoded and converted values
- bool_t frame_available; ///< new frame available
+ bool frame_available; ///< new frame available
uint8_t buffer[SBUS_BUF_LENGTH]; ///< input buffer
uint8_t idx; ///< input index
uint8_t status; ///< decoder state machine status
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 82912dff7b..ff6b29c5ef 100644
--- a/sw/airborne/subsystems/sensors/infrared_i2c.c
+++ b/sw/airborne/subsystems/sensors/infrared_i2c.c
@@ -46,9 +46,9 @@
#endif
struct Infrared_raw ir_i2c;
-bool_t ir_i2c_data_hor_available, ir_i2c_data_ver_available;
+bool ir_i2c_data_hor_available, ir_i2c_data_ver_available;
uint8_t ir_i2c_conf_word;
-bool_t ir_i2c_conf_hor_done, ir_i2c_conf_ver_done;
+bool ir_i2c_conf_hor_done, ir_i2c_conf_ver_done;
// Local variables
#define IR_I2C_IDLE 0
@@ -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 9bc2611609..92a9f237f1 100644
--- a/sw/airborne/subsystems/sensors/infrared_i2c.h
+++ b/sw/airborne/subsystems/sensors/infrared_i2c.h
@@ -33,9 +33,9 @@
#include "mcu_periph/i2c.h"
extern struct Infrared_raw ir_i2c;
-extern bool_t ir_i2c_data_hor_available, ir_i2c_data_ver_available;
+extern bool ir_i2c_data_hor_available, ir_i2c_data_ver_available;
extern uint8_t ir_i2c_conf_word;
-extern bool_t ir_i2c_conf_hor_done, ir_i2c_conf_ver_done;
+extern bool ir_i2c_conf_hor_done, ir_i2c_conf_ver_done;
extern struct i2c_transaction irh_trans, irv_trans;
@@ -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 3c9070c34d..00740bd3e3 100644
--- a/sw/airborne/subsystems/settings.c
+++ b/sw/airborne/subsystems/settings.c
@@ -35,9 +35,9 @@ struct PersistentSettings pers_settings;
* Also settings still need a variable,
* pure function call not possible yet.
*/
-bool_t settings_store_flag;
+bool settings_store_flag;
-bool_t settings_clear_flag;
+bool settings_clear_flag;
void settings_init(void)
@@ -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/subsystems/settings.h b/sw/airborne/subsystems/settings.h
index e52e6037d9..4ab6b87957 100644
--- a/sw/airborne/subsystems/settings.h
+++ b/sw/airborne/subsystems/settings.h
@@ -34,8 +34,8 @@ extern void settings_init(void);
extern int32_t settings_store(void);
extern int32_t settings_clear(void);
-extern bool_t settings_store_flag;
-extern bool_t settings_clear_flag;
+extern bool settings_store_flag;
+extern bool settings_clear_flag;
#define settings_StoreSettings(_v) { settings_store_flag = _v; settings_store(); }
#define settings_ClearSettings(_v) { settings_clear_flag = _v; settings_clear(); }
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_algebra.c b/sw/airborne/test/test_algebra.c
index a5ff10c96a..5a44973ef3 100644
--- a/sw/airborne/test/test_algebra.c
+++ b/sw/airborne/test/test_algebra.c
@@ -38,7 +38,7 @@ float test_rmat_of_eulers_312(void);
float test_quat(void);
float test_quat2(void);
-float test_INT32_QUAT_OF_RMAT(struct FloatEulers *eul, bool_t display);
+float test_INT32_QUAT_OF_RMAT(struct FloatEulers *eul, bool display);
void test_of_axis_angle(void);
@@ -841,7 +841,7 @@ float test_quat2(void)
}
-float test_INT32_QUAT_OF_RMAT(struct FloatEulers *eul_f, bool_t display)
+float test_INT32_QUAT_OF_RMAT(struct FloatEulers *eul_f, bool display)
{
struct Int32Eulers eul321_i;
EULERS_BFP_OF_REAL(eul321_i, (*eul_f));
diff --git a/sw/airborne/test/test_manual.c b/sw/airborne/test/test_manual.c
index 3ae7ecd4e1..e241d6a8d3 100644
--- a/sw/airborne/test/test_manual.c
+++ b/sw/airborne/test/test_manual.c
@@ -54,7 +54,7 @@ static void on_rc_frame(void);
tid_t main_periodic_tid; ///< id for main_periodic() timer
tid_t radio_control_tid; ///< id for radio_control_periodic_task() timer
-bool_t autopilot_motors_on;
+bool autopilot_motors_on;
int main(void)
{
@@ -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)
diff --git a/sw/ext/pprzlink b/sw/ext/pprzlink
index 2b246f6480..c323e3cce1 160000
--- a/sw/ext/pprzlink
+++ b/sw/ext/pprzlink
@@ -1 +1 @@
-Subproject commit 2b246f6480ac06bb6fc58b2a7947a59cec360a04
+Subproject commit c323e3cce1adf72e5f495417a3ee7f73ab2eae91
diff --git a/sw/ground_segment/misc/natnet2ivy.c b/sw/ground_segment/misc/natnet2ivy.c
index f4e89829e9..2e37ca4833 100644
--- a/sw/ground_segment/misc/natnet2ivy.c
+++ b/sw/ground_segment/misc/natnet2ivy.c
@@ -60,8 +60,8 @@ uint8_t natnet_minor = 7;
/** Logging */
FILE *fp;
char *nameOfLogfile = "natnet_log.dat";
-bool_t log_exists = 0;
-bool_t must_log = 0;
+bool log_exists = 0;
+bool must_log = 0;
/** Ivy Bus default */
#ifdef __APPLE__
diff --git a/sw/ground_segment/misc/sbp2ivy.c b/sw/ground_segment/misc/sbp2ivy.c
index cbb5b152af..bdb256c80e 100644
--- a/sw/ground_segment/misc/sbp2ivy.c
+++ b/sw/ground_segment/misc/sbp2ivy.c
@@ -55,7 +55,7 @@ char *serial_device = "/dev/ttyUSB0";
uint32_t serial_baud = B115200;
/** Debugging options */
-bool_t verbose = FALSE;
+bool verbose = FALSE;
#define printf_debug if(verbose == TRUE) printf
/** Ivy Bus default */
diff --git a/sw/ground_segment/misc/sbs2ivy.c b/sw/ground_segment/misc/sbs2ivy.c
index 1632c875b2..14eff0ee48 100644
--- a/sw/ground_segment/misc/sbs2ivy.c
+++ b/sw/ground_segment/misc/sbs2ivy.c
@@ -503,7 +503,7 @@ gint delete_event(GtkWidget *widget,
}
-static bool_t parse_options(int argc, char **argv, struct Opts *opts)
+static bool parse_options(int argc, char **argv, struct Opts *opts)
{
opts->ac_id = 0;
opts->host = "localhost";
diff --git a/sw/include/std.h b/sw/include/std.h
index a85cd71dab..db0e984b7a 100644
--- a/sw/include/std.h
+++ b/sw/include/std.h
@@ -38,10 +38,10 @@
#define STRINGIFY(s) _STRINGIFY(s)
#ifndef FALSE
-#define FALSE 0
+#define FALSE false
#endif
#ifndef TRUE
-#define TRUE (!FALSE)
+#define TRUE true
#endif
#ifndef NULL
@@ -52,17 +52,6 @@
#endif
#endif
-/* Boolean values */
-#ifdef RTOS_IS_CHIBIOS
-/* make bool_t an alias to bool instead of uint8_t dor chibios port
- probably a bad idea since sizeof(bool) is 4, and this will break
- message coding/decoding **** FIX NEEDEED ****
-*/
-typedef bool bool_t;
-#else
-typedef uint8_t bool_t;
-#endif
-
/* Unit (void) values */
typedef uint8_t unit_t;
@@ -224,7 +213,7 @@ typedef uint8_t unit_t;
} \
}
-static inline bool_t str_equal(const char * a, const char * b) {
+static inline bool str_equal(const char * a, const char * b) {
int i = 0;
while (!(a[i] == 0 && b[i] == 0)) {
if (a[i] != b[i]) return FALSE;
diff --git a/sw/lib/ocaml/gen_common.ml b/sw/lib/ocaml/gen_common.ml
index dfa1c99a5f..318af5bc97 100644
--- a/sw/lib/ocaml/gen_common.ml
+++ b/sw/lib/ocaml/gen_common.ml
@@ -130,14 +130,23 @@ let get_module = fun m global_targets ->
* Test if [target] is allowed [targets]
* Return true if target is allowed, false if target is not in list or rejected (prefixed by !) *)
let test_targets = fun target targets ->
- List.exists (fun t ->
- let l = String.length t in
- (* test for inverted selection *)
- if l > 0 && t.[0] = '!' then
- not ((String.sub t 1 (l-1)) = target)
- else
- t = target
- ) targets
+ (* test for inverted selection
+ * FIXME: only the first target should have the invert sign ('!')
+ *)
+ let inv =
+ try
+ let hd = List.hd targets in
+ if String.get hd 0 = '!' then not
+ else (fun x -> x)
+ with _ -> (fun x -> x)
+ in
+ (* return inverted result if needed *)
+ inv (List.exists (fun t ->
+ let l = String.length t in
+ (* remove first char if invert sign *)
+ let t = if l > 0 && t.[0] = '!' then String.sub t 1 (l-1) else t in
+ t = target
+ ) targets)
(** [get_modules_of_airframe xml]
* Returns a list of module configuration from airframe file *)
@@ -250,7 +259,7 @@ let get_modules_name = fun xml ->
* Returns the list of modules directories *)
let get_modules_dir = fun modules ->
let dir = List.map (fun m -> try Xml.attrib m.xml "dir" with _ -> ExtXml.attrib m.xml "name") modules in
- singletonize (List.sort compare dir)
+ singletonize dir
(** [is_element_unselected target modules file]
* Returns True if [target] is supported in the element [file] and, if it is
diff --git a/sw/misc/rctx/main_rctx.c b/sw/misc/rctx/main_rctx.c
index 9ad792c5b3..175d174bfc 100644
--- a/sw/misc/rctx/main_rctx.c
+++ b/sw/misc/rctx/main_rctx.c
@@ -108,7 +108,7 @@ void periodic_task_rctx( void );
#define IdOfMsg(x) (x[1])
uint8_t dl_buffer[MSG_SIZE] __attribute__ ((aligned));
-bool_t dl_msg_available;
+bool dl_msg_available;
uint16_t datalink_time;
void dl_parse_msg(void) {
diff --git a/sw/simulator/nps/nps_autopilot.h b/sw/simulator/nps/nps_autopilot.h
index 0bbf425317..9957524e42 100644
--- a/sw/simulator/nps/nps_autopilot.h
+++ b/sw/simulator/nps/nps_autopilot.h
@@ -26,13 +26,13 @@
struct NpsAutopilot {
double commands[NPS_COMMANDS_NB];
- bool_t launch;
+ bool launch;
};
extern struct NpsAutopilot autopilot;
-extern bool_t nps_bypass_ahrs;
-extern bool_t nps_bypass_ins;
+extern bool nps_bypass_ahrs;
+extern bool nps_bypass_ins;
extern void sim_overwrite_ahrs(void);
extern void sim_overwrite_ins(void);
diff --git a/sw/simulator/nps/nps_autopilot_fixedwing.c b/sw/simulator/nps/nps_autopilot_fixedwing.c
index ce874d96b3..c1c0269713 100644
--- a/sw/simulator/nps/nps_autopilot_fixedwing.c
+++ b/sw/simulator/nps/nps_autopilot_fixedwing.c
@@ -56,8 +56,8 @@
#include "subsystems/datalink/datalink.h"
struct NpsAutopilot autopilot;
-bool_t nps_bypass_ahrs;
-bool_t nps_bypass_ins;
+bool nps_bypass_ahrs;
+bool nps_bypass_ins;
#ifndef NPS_BYPASS_AHRS
#define NPS_BYPASS_AHRS FALSE
diff --git a/sw/simulator/nps/nps_autopilot_rotorcraft.c b/sw/simulator/nps/nps_autopilot_rotorcraft.c
index 9df70a48a7..73d4e414bd 100644
--- a/sw/simulator/nps/nps_autopilot_rotorcraft.c
+++ b/sw/simulator/nps/nps_autopilot_rotorcraft.c
@@ -46,8 +46,8 @@
#include "subsystems/datalink/datalink.h"
struct NpsAutopilot autopilot;
-bool_t nps_bypass_ahrs;
-bool_t nps_bypass_ins;
+bool nps_bypass_ahrs;
+bool nps_bypass_ins;
#ifndef NPS_BYPASS_AHRS
#define NPS_BYPASS_AHRS FALSE
diff --git a/sw/simulator/nps/nps_fdm.h b/sw/simulator/nps/nps_fdm.h
index f67b7c3236..f76b249450 100644
--- a/sw/simulator/nps/nps_fdm.h
+++ b/sw/simulator/nps/nps_fdm.h
@@ -46,7 +46,7 @@ struct NpsFdm {
double time;
double init_dt;
double curr_dt;
- bool_t on_ground;
+ bool on_ground;
int nan_count;
/* position */
@@ -130,7 +130,7 @@ struct NpsFdm {
extern struct NpsFdm fdm;
extern void nps_fdm_init(double dt);
-extern void nps_fdm_run_step(bool_t launch, double *commands, int commands_nb);
+extern void nps_fdm_run_step(bool launch, double *commands, int commands_nb);
extern void nps_fdm_set_wind(double speed, double dir);
extern void nps_fdm_set_wind_ned(double wind_north, double wind_east, double wind_down);
extern void nps_fdm_set_turbulence(double wind_speed, int turbulence_severity);
diff --git a/sw/simulator/nps/nps_fdm_crrcsim.c b/sw/simulator/nps/nps_fdm_crrcsim.c
index 7968e9f586..a77def5fcc 100644
--- a/sw/simulator/nps/nps_fdm_crrcsim.c
+++ b/sw/simulator/nps/nps_fdm_crrcsim.c
@@ -147,7 +147,7 @@ void nps_fdm_init(double dt)
send_servo_cmd(&crrcsim, zero);
}
-void nps_fdm_run_step(bool_t launch __attribute__((unused)), double *commands, int commands_nb)
+void nps_fdm_run_step(bool launch __attribute__((unused)), double *commands, int commands_nb)
{
// read state
if (get_msg(&crrcsim, crrcsim.data_buffer) <= 0) {
diff --git a/sw/simulator/nps/nps_fdm_jsbsim.cpp b/sw/simulator/nps/nps_fdm_jsbsim.cpp
index 3b532aae6c..aab90f39b0 100644
--- a/sw/simulator/nps/nps_fdm_jsbsim.cpp
+++ b/sw/simulator/nps/nps_fdm_jsbsim.cpp
@@ -188,11 +188,11 @@ void nps_fdm_init(double dt)
}
-void nps_fdm_run_step(bool_t launch __attribute__((unused)), double *commands, int commands_nb)
+void nps_fdm_run_step(bool launch __attribute__((unused)), double *commands, int commands_nb)
{
#ifdef NPS_JSBSIM_LAUNCHSPEED
- static bool_t already_launched = FALSE;
+ static bool already_launched = FALSE;
if (launch && !already_launched) {
printf("Launching with speed of %.1f m/s!\n", (float)NPS_JSBSIM_LAUNCHSPEED);
diff --git a/sw/simulator/nps/nps_main.c b/sw/simulator/nps/nps_main.c
index ad1c5f2391..6b01a84499 100644
--- a/sw/simulator/nps/nps_main.c
+++ b/sw/simulator/nps/nps_main.c
@@ -58,7 +58,7 @@ static struct {
char *ivy_bus;
} nps_main;
-static bool_t nps_main_parse_options(int argc, char **argv);
+static bool nps_main_parse_options(int argc, char **argv);
static void nps_main_init(void);
static void nps_main_display(void);
static void nps_main_run_sim_step(void);
@@ -294,7 +294,7 @@ static gboolean nps_main_periodic(gpointer data __attribute__((unused)))
}
-static bool_t nps_main_parse_options(int argc, char **argv)
+static bool nps_main_parse_options(int argc, char **argv)
{
nps_main.fg_host = NULL;
diff --git a/sw/simulator/nps/nps_radio_control.c b/sw/simulator/nps/nps_radio_control.c
index fa35ee97b4..cfe1398739 100644
--- a/sw/simulator/nps/nps_radio_control.c
+++ b/sw/simulator/nps/nps_radio_control.c
@@ -74,7 +74,7 @@ static rc_script scripts[] = {
#define RADIO_CONTROL_TAKEOFF_TIME 8
-bool_t nps_radio_control_available(double time)
+bool nps_radio_control_available(double time)
{
if (time >= nps_radio_control.next_update) {
nps_radio_control.next_update += RADIO_CONTROL_DT;
diff --git a/sw/simulator/nps/nps_radio_control.h b/sw/simulator/nps/nps_radio_control.h
index 2fd1663dc7..b28e02ad13 100644
--- a/sw/simulator/nps/nps_radio_control.h
+++ b/sw/simulator/nps/nps_radio_control.h
@@ -36,11 +36,11 @@ enum NpsRadioControlType {
extern void nps_radio_control_init(enum NpsRadioControlType type, int num_script, char *js_dev);
-extern bool_t nps_radio_control_available(double time);
+extern bool nps_radio_control_available(double time);
struct NpsRadioControl {
double next_update;
- bool_t valid;
+ bool valid;
double throttle;
double roll;
double pitch;
diff --git a/sw/simulator/nps/nps_sensor_accel.h b/sw/simulator/nps/nps_sensor_accel.h
index 4f555b1d6d..433883650b 100644
--- a/sw/simulator/nps/nps_sensor_accel.h
+++ b/sw/simulator/nps/nps_sensor_accel.h
@@ -15,7 +15,7 @@ struct NpsSensorAccel {
struct DoubleVect3 noise_std_dev;
struct DoubleVect3 bias;
double next_update;
- bool_t data_available;
+ bool data_available;
};
diff --git a/sw/simulator/nps/nps_sensor_airspeed.h b/sw/simulator/nps/nps_sensor_airspeed.h
index b849f627d0..50f721355b 100644
--- a/sw/simulator/nps/nps_sensor_airspeed.h
+++ b/sw/simulator/nps/nps_sensor_airspeed.h
@@ -39,7 +39,7 @@ struct NpsSensorAirspeed {
double offset; ///< offset in meters/second
double noise_std_dev; ///< noise standard deviation
double next_update;
- bool_t data_available;
+ bool data_available;
};
diff --git a/sw/simulator/nps/nps_sensor_baro.h b/sw/simulator/nps/nps_sensor_baro.h
index a781adb20f..6a4a28aa83 100644
--- a/sw/simulator/nps/nps_sensor_baro.h
+++ b/sw/simulator/nps/nps_sensor_baro.h
@@ -10,7 +10,7 @@ struct NpsSensorBaro {
double value; ///< pressure in Pascal
double noise_std_dev; ///< noise standard deviation
double next_update;
- bool_t data_available;
+ bool data_available;
};
diff --git a/sw/simulator/nps/nps_sensor_gps.h b/sw/simulator/nps/nps_sensor_gps.h
index 598bd30830..62083638ca 100644
--- a/sw/simulator/nps/nps_sensor_gps.h
+++ b/sw/simulator/nps/nps_sensor_gps.h
@@ -27,7 +27,7 @@ struct NpsSensorGps {
GSList *lla_history;
GSList *speed_history;
double next_update;
- bool_t data_available;
+ bool data_available;
};
diff --git a/sw/simulator/nps/nps_sensor_gyro.h b/sw/simulator/nps/nps_sensor_gyro.h
index ddb33703da..02ab18365d 100644
--- a/sw/simulator/nps/nps_sensor_gyro.h
+++ b/sw/simulator/nps/nps_sensor_gyro.h
@@ -17,7 +17,7 @@ struct NpsSensorGyro {
struct DoubleVect3 bias_random_walk_std_dev;
struct DoubleVect3 bias_random_walk_value;
double next_update;
- bool_t data_available;
+ bool data_available;
};
diff --git a/sw/simulator/nps/nps_sensor_mag.h b/sw/simulator/nps/nps_sensor_mag.h
index d1cf6f1356..53e201f813 100644
--- a/sw/simulator/nps/nps_sensor_mag.h
+++ b/sw/simulator/nps/nps_sensor_mag.h
@@ -15,7 +15,7 @@ struct NpsSensorMag {
struct DoubleVect3 noise_std_dev;
struct DoubleRMat imu_to_sensor_rmat;
double next_update;
- bool_t data_available;
+ bool data_available;
};
diff --git a/sw/simulator/nps/nps_sensor_sonar.h b/sw/simulator/nps/nps_sensor_sonar.h
index cdae3ae3e5..2ae2fb7e86 100644
--- a/sw/simulator/nps/nps_sensor_sonar.h
+++ b/sw/simulator/nps/nps_sensor_sonar.h
@@ -39,7 +39,7 @@ struct NpsSensorSonar {
double offset; ///< offset in meters
double noise_std_dev; ///< noise standard deviation
double next_update;
- bool_t data_available;
+ bool data_available;
};
diff --git a/sw/simulator/nps/nps_sensor_temperature.h b/sw/simulator/nps/nps_sensor_temperature.h
index d640c8e159..aedf4a251f 100644
--- a/sw/simulator/nps/nps_sensor_temperature.h
+++ b/sw/simulator/nps/nps_sensor_temperature.h
@@ -10,7 +10,7 @@ struct NpsSensorTemperature {
double value; ///< temperature in degrees Celcius
double noise_std_dev; ///< noise standard deviation
double next_update;
- bool_t data_available;
+ bool data_available;
};
diff --git a/sw/simulator/nps/nps_sensors.c b/sw/simulator/nps/nps_sensors.c
index f444cedee0..1ee80a3ede 100644
--- a/sw/simulator/nps/nps_sensors.c
+++ b/sw/simulator/nps/nps_sensors.c
@@ -37,7 +37,7 @@ void nps_sensors_run_step(double time)
}
-bool_t nps_sensors_gyro_available(void)
+bool nps_sensors_gyro_available(void)
{
if (sensors.gyro.data_available) {
sensors.gyro.data_available = FALSE;
@@ -46,7 +46,7 @@ bool_t nps_sensors_gyro_available(void)
return FALSE;
}
-bool_t nps_sensors_mag_available(void)
+bool nps_sensors_mag_available(void)
{
if (sensors.mag.data_available) {
sensors.mag.data_available = FALSE;
@@ -55,7 +55,7 @@ bool_t nps_sensors_mag_available(void)
return FALSE;
}
-bool_t nps_sensors_baro_available(void)
+bool nps_sensors_baro_available(void)
{
if (sensors.baro.data_available) {
sensors.baro.data_available = FALSE;
@@ -64,7 +64,7 @@ bool_t nps_sensors_baro_available(void)
return FALSE;
}
-bool_t nps_sensors_gps_available(void)
+bool nps_sensors_gps_available(void)
{
if (sensors.gps.data_available) {
sensors.gps.data_available = FALSE;
@@ -73,7 +73,7 @@ bool_t nps_sensors_gps_available(void)
return FALSE;
}
-bool_t nps_sensors_sonar_available(void)
+bool nps_sensors_sonar_available(void)
{
if (sensors.sonar.data_available) {
sensors.sonar.data_available = FALSE;
@@ -82,7 +82,7 @@ bool_t nps_sensors_sonar_available(void)
return FALSE;
}
-bool_t nps_sensors_airspeed_available(void)
+bool nps_sensors_airspeed_available(void)
{
if (sensors.airspeed.data_available) {
sensors.airspeed.data_available = FALSE;
@@ -91,7 +91,7 @@ bool_t nps_sensors_airspeed_available(void)
return FALSE;
}
-bool_t nps_sensors_temperature_available(void)
+bool nps_sensors_temperature_available(void)
{
if (sensors.temp.data_available) {
sensors.temp.data_available = FALSE;
diff --git a/sw/simulator/nps/nps_sensors.h b/sw/simulator/nps/nps_sensors.h
index decc63e907..4f67a864c6 100644
--- a/sw/simulator/nps/nps_sensors.h
+++ b/sw/simulator/nps/nps_sensors.h
@@ -28,13 +28,13 @@ extern struct NpsSensors sensors;
extern void nps_sensors_init(double time);
extern void nps_sensors_run_step(double time);
-extern bool_t nps_sensors_gyro_available();
-extern bool_t nps_sensors_mag_available();
-extern bool_t nps_sensors_baro_available();
-extern bool_t nps_sensors_gps_available();
-extern bool_t nps_sensors_sonar_available();
-extern bool_t nps_sensors_airspeed_available();
-extern bool_t nps_sensors_temperature_available();
+extern bool nps_sensors_gyro_available();
+extern bool nps_sensors_mag_available();
+extern bool nps_sensors_baro_available();
+extern bool nps_sensors_gps_available();
+extern bool nps_sensors_sonar_available();
+extern bool nps_sensors_airspeed_available();
+extern bool nps_sensors_temperature_available();
#endif /* NPS_SENSORS_H */
diff --git a/sw/tools/generators/gen_aircraft.ml b/sw/tools/generators/gen_aircraft.ml
index 699ff17d43..a21e008f44 100644
--- a/sw/tools/generators/gen_aircraft.ml
+++ b/sw/tools/generators/gen_aircraft.ml
@@ -103,7 +103,6 @@ let file_xml2mk = fun f ?(arch = false) dir_name target xml ->
fprintf f fmt target dir_name name
let module_xml2mk = fun f target firmware m ->
- if not (List.mem target m.targets) then () else
let name = ExtXml.attrib m.xml "name" in
let dir = try Xml.attrib m.xml "dir" with Xml.No_attribute _ -> name in
let dir_name = String.uppercase dir ^ "_DIR" in
diff --git a/sw/tools/generators/gen_flight_plan.ml b/sw/tools/generators/gen_flight_plan.ml
index f48841f4d5..486f4e2a5e 100644
--- a/sw/tools/generators/gen_flight_plan.ml
+++ b/sw/tools/generators/gen_flight_plan.ml
@@ -747,7 +747,7 @@ let print_inside_polygon = fun pts ->
let print_inside_polygon_global = fun pts ->
lprintf "uint8_t i, j;\n";
- lprintf "bool_t c = FALSE;\n";
+ lprintf "bool c = false;\n";
(* build array of wp id *)
let (ids, _) = List.split pts in
lprintf "const uint8_t nb_pts = %d;\n" (List.length pts);
@@ -769,7 +769,7 @@ let print_inside_polygon_global = fun pts ->
type sector_type = StaticSector | DynamicSector
let print_inside_sector = fun t (s, pts) ->
- lprintf "static inline bool_t %s(float _x, float _y) {\n" (inside_function s);
+ lprintf "static inline bool %s(float _x, float _y) {\n" (inside_function s);
right ();
begin
match t with
diff --git a/sw/tools/parrot/bebop.py b/sw/tools/parrot/bebop.py
index 13923e32f7..d28fc0a9a5 100755
--- a/sw/tools/parrot/bebop.py
+++ b/sw/tools/parrot/bebop.py
@@ -57,7 +57,7 @@ def bebop_status():
# Parse the arguments
-parser = argparse.ArgumentParser(description='Bebop python helper. Use bebop.py -h for help')
+parser = argparse.ArgumentParser(description='Bebop helper tool. Use bebop.py -h for help')
parser.add_argument('--host', metavar='HOST', default='192.168.42.1',
help='the ip address of bebop')
subparsers = parser.add_subparsers(title='Command to execute', metavar='command', dest='command')
@@ -131,7 +131,7 @@ elif args.command == 'upload_file_and_run':
sleep(0.5)
parrot_utils.execute_command(tn, "chmod 777 /data/ftp/" + args.folder + "/" + f[1])
parrot_utils.execute_command(tn, "/data/ftp/" + args.folder + "/" + f[1] + " > /dev/null 2>&1 &")
- print("#pragma message: Upload and Start of ap.elf to Bebop Succes!")
+ print("#pragma message: Upload and Start of ap.elf to Bebop succesful !")
elif args.command == 'upload_file':
# Split filename and path
@@ -140,7 +140,7 @@ elif args.command == 'upload_file':
parrot_utils.execute_command(tn, "mkdir -p /data/ftp/" + args.folder)
print('Uploading \'' + f[1] + "\' from " + f[0] + " to /data/ftp/" + args.folder)
parrot_utils.uploadfile(ftp, args.folder + "/" + f[1], file(args.file, "rb"))
- print("#pragma message: Upload of " + f[1] + " to Bebop Succes!")
+ print("#pragma message: Upload of " + f[1] + " to Bebop succesful !")
elif args.command == 'download_file':
# Split filename and path
diff --git a/sw/tools/parrot/parrot_utils.py b/sw/tools/parrot/parrot_utils.py
index 8c450ca64f..4f4ff5a068 100644
--- a/sw/tools/parrot/parrot_utils.py
+++ b/sw/tools/parrot/parrot_utils.py
@@ -79,10 +79,10 @@ def uploadfile(ftp, filename, content):
try:
ftp.storbinary("STOR " + filename, content)
except ftplib.error_temp:
- print("FTP UPLOAD ERROR: Uploading FAILED: Probably your ARDrone memory is full.")
+ print("FTP UPLOAD ERROR: Uploading FAILED: Probably your drone onboard storage memory is full. Remove old JPG or other data?")
sys.exit()
except:
- print("FTP UPLOAD ERROR: Maybe your ARDrone memory is full?", sys.exc_info()[0])
+ print("FTP UPLOAD ERROR: Maybe your drone onboard storage memory is full? Remove old JPG or other data?)", sys.exc_info()[0])
sys.exit()