From 5c1e4260fe67fae502c6300ba0871f3de20b1c6a Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 22 Mar 2016 18:37:54 +0100 Subject: [PATCH] replace bool_t with C99 bool from stdbool.h --- sw/airborne/arch/linux/mcu_periph/i2c_arch.c | 4 +-- sw/airborne/arch/linux/mcu_periph/spi_arch.c | 6 ++-- sw/airborne/arch/linux/mcu_periph/udp_arch.c | 2 +- sw/airborne/arch/linux/udp_socket.c | 2 +- sw/airborne/arch/linux/udp_socket.h | 2 +- sw/airborne/arch/lpc21/ADS8344.c | 2 +- sw/airborne/arch/lpc21/ADS8344.h | 2 +- sw/airborne/arch/lpc21/mcu_periph/i2c_arch.c | 6 ++-- sw/airborne/arch/lpc21/mcu_periph/spi_arch.c | 10 +++--- .../arch/lpc21/modules/sensors/trig_ext_hw.c | 2 +- .../arch/lpc21/modules/sensors/trig_ext_hw.h | 2 +- .../subsystems/radio_control/spektrum_arch.c | 2 +- .../subsystems/radio_control/spektrum_arch.h | 2 +- sw/airborne/arch/lpc21/usb_ser_hw.c | 2 +- sw/airborne/arch/sim/baro_MS5534A.h | 6 ++-- sw/airborne/arch/sim/mcu_periph/i2c_arch.c | 4 +-- sw/airborne/arch/sim/mcu_periph/spi_arch.c | 6 ++-- .../arch/sim/modules/ins/ins_arduimu_basic.c | 2 +- sw/airborne/arch/sim/sim_ap.c | 4 +-- .../subsystems/radio_control/spektrum_arch.c | 2 +- sw/airborne/arch/stm32/mcu_periph/adc_arch.c | 2 +- sw/airborne/arch/stm32/mcu_periph/gpio_arch.c | 4 +-- sw/airborne/arch/stm32/mcu_periph/gpio_arch.h | 4 +-- sw/airborne/arch/stm32/mcu_periph/i2c_arch.c | 8 ++--- sw/airborne/arch/stm32/mcu_periph/spi_arch.c | 16 +++++----- sw/airborne/arch/stm32/mcu_periph/uart_arch.c | 2 +- .../subsystems/radio_control/spektrum_arch.c | 2 +- sw/airborne/arch/stm32/usb_ser_hw.c | 12 +++---- sw/airborne/boards/apogee/baro_board.c | 2 +- .../boards/apogee/chibios-libopencm3/board.c | 8 ++--- .../boards/apogee/chibios-libopencm3/chconf.h | 2 +- sw/airborne/boards/apogee/imu_apogee.c | 8 ++--- sw/airborne/boards/ardrone/actuators.c | 4 +-- sw/airborne/boards/ardrone/navdata.c | 8 ++--- sw/airborne/boards/ardrone/navdata.h | 10 +++--- sw/airborne/boards/bebop/video.c | 4 +-- sw/airborne/boards/krooz/imu_krooz.h | 4 +-- sw/airborne/boards/krooz/imu_krooz_memsic.h | 4 +-- sw/airborne/boards/lisa_l/baro_board.c | 2 +- sw/airborne/boards/lisa_m/baro_board.c | 2 +- sw/airborne/boards/lisa_mx/baro_board.c | 2 +- sw/airborne/boards/umarim/imu_umarim.h | 4 +-- sw/airborne/firmwares/fixedwing/autopilot.c | 8 ++--- sw/airborne/firmwares/fixedwing/autopilot.h | 8 ++--- .../chibios-libopencm3/chibios_init.c | 4 +-- .../chibios-libopencm3/chibios_init.h | 2 +- sw/airborne/firmwares/fixedwing/main_ap.c | 6 ++-- .../fixedwing/main_chibios_libopencm3.c | 4 +-- sw/airborne/firmwares/fixedwing/main_fbw.h | 2 +- sw/airborne/firmwares/fixedwing/nav.c | 16 +++++----- sw/airborne/firmwares/fixedwing/nav.h | 14 ++++----- .../stabilization/stabilization_adaptive.c | 6 ++-- .../stabilization/stabilization_adaptive.h | 2 +- .../stabilization/stabilization_attitude.c | 4 +-- .../stabilization/stabilization_attitude.h | 4 +-- .../firmwares/motor_bench/main_motor_bench.c | 2 +- .../motor_bench/mb_twi_controller_asctech.c | 2 +- .../motor_bench/mb_twi_controller_asctech.h | 2 +- sw/airborne/firmwares/rotorcraft/autopilot.c | 31 ++++++++++--------- sw/airborne/firmwares/rotorcraft/autopilot.h | 26 ++++++++-------- .../rotorcraft/autopilot_arming_switch.h | 4 +-- .../rotorcraft/autopilot_arming_throttle.h | 4 +-- .../rotorcraft/autopilot_arming_yaw.h | 2 +- .../rotorcraft/autopilot_rc_helpers.h | 6 ++-- .../rotorcraft/guidance/guidance_flip.c | 2 +- .../rotorcraft/guidance/guidance_h.c | 18 +++++------ .../rotorcraft/guidance/guidance_h.h | 14 ++++----- .../rotorcraft/guidance/guidance_indi.c | 4 +-- .../rotorcraft/guidance/guidance_indi.h | 4 +-- .../rotorcraft/guidance/guidance_module.h | 4 +-- .../rotorcraft/guidance/guidance_v.c | 16 +++++----- .../rotorcraft/guidance/guidance_v.h | 12 +++---- sw/airborne/firmwares/rotorcraft/main_fbw.c | 4 +-- sw/airborne/firmwares/rotorcraft/navigation.c | 26 ++++++++-------- sw/airborne/firmwares/rotorcraft/navigation.h | 24 +++++++------- .../stabilization/stabilization_attitude.h | 4 +-- .../stabilization_attitude_euler_float.c | 4 +-- .../stabilization_attitude_euler_int.c | 4 +-- .../stabilization_attitude_passthrough.c | 4 +-- .../stabilization_attitude_quat_float.c | 4 +-- .../stabilization_attitude_quat_indi.c | 4 +-- .../stabilization_attitude_quat_int.c | 4 +-- .../stabilization_attitude_rc_setpoint.c | 16 +++++----- .../stabilization_attitude_rc_setpoint.h | 16 +++++----- .../stabilization/stabilization_indi.c | 8 ++--- .../stabilization/stabilization_indi.h | 6 ++-- .../stabilization/stabilization_none.c | 2 +- .../stabilization/stabilization_none.h | 2 +- .../stabilization/stabilization_rate.c | 2 +- .../stabilization/stabilization_rate.h | 2 +- .../stabilization/stabilization_rate_indi.c | 2 +- .../stabilization/stabilization_rate_indi.h | 2 +- sw/airborne/firmwares/tutorial/main_demo5.c | 2 +- sw/airborne/firmwares/wind_tunnel/main.c | 2 +- sw/airborne/firmwares/wind_tunnel/main_mb.c | 2 +- sw/airborne/firmwares/wind_tunnel/wt_baro.c | 4 +-- sw/airborne/firmwares/wind_tunnel/wt_baro.h | 2 +- sw/airborne/inter_mcu.c | 6 ++-- sw/airborne/inter_mcu.h | 6 ++-- sw/airborne/link_mcu_can.h | 2 +- sw/airborne/link_mcu_spi.c | 2 +- sw/airborne/link_mcu_spi.h | 2 +- sw/airborne/link_mcu_usart.c | 2 +- sw/airborne/link_mcu_usart.h | 2 +- .../math/pprz_orientation_conversion.h | 2 +- sw/airborne/mcu_periph/i2c.c | 6 ++-- sw/airborne/mcu_periph/i2c.h | 10 +++--- sw/airborne/mcu_periph/spi.h | 10 +++--- sw/airborne/mcu_periph/sys_time.h | 6 ++-- sw/airborne/mcu_periph/uart.c | 2 +- sw/airborne/mcu_periph/uart.h | 4 +-- sw/airborne/mcu_periph/udp.c | 4 +-- sw/airborne/mcu_periph/udp.h | 6 ++-- sw/airborne/mcu_periph/usb_serial.h | 2 +- sw/airborne/modules/air_data/air_data.h | 10 +++--- .../airborne_ant_track/airborne_ant_track.c | 2 +- .../modules/benchmark/flight_benchmark.c | 4 +-- .../modules/benchmark/flight_benchmark.h | 4 +-- sw/airborne/modules/cam_control/cam.c | 2 +- sw/airborne/modules/cam_control/cam.h | 2 +- sw/airborne/modules/cam_control/point.c | 2 +- sw/airborne/modules/cartography/cartography.c | 22 ++++++------- sw/airborne/modules/cartography/cartography.h | 16 +++++----- sw/airborne/modules/com/generic_com.c | 2 +- .../modules/com/usb_serial_stm32_example1.c | 2 +- .../computer_vision/bebop_front_camera.c | 2 +- .../computer_vision/bebop_front_camera.h | 8 ++--- .../modules/computer_vision/cv_blob_locator.c | 6 ++-- .../modules/computer_vision/cv_georeference.c | 2 +- .../modules/computer_vision/cv_georeference.h | 2 +- .../computer_vision/lib/encoding/jpeg.c | 2 +- .../computer_vision/lib/encoding/jpeg.h | 2 +- .../modules/computer_vision/lib/v4l/v4l2.c | 8 ++--- .../modules/computer_vision/lib/v4l/v4l2.h | 8 ++--- .../computer_vision/lib/vision/fast_rosten.c | 2 +- .../computer_vision/lib/vision/lucas_kanade.c | 2 +- .../opticflow/opticflow_calculator.h | 4 +-- .../computer_vision/opticflow_module.c | 2 +- .../modules/computer_vision/qrcode/qr_code.h | 2 +- .../modules/computer_vision/video_thread.c | 2 +- .../modules/computer_vision/video_thread.h | 6 ++-- .../computer_vision/video_thread_nps.c | 2 +- .../modules/computer_vision/viewvideo.h | 4 +-- .../modules/computer_vision/viewvideo_nps.c | 2 +- sw/airborne/modules/core/trigger_ext.c | 2 +- sw/airborne/modules/core/trigger_ext.h | 2 +- sw/airborne/modules/ctrl/ctrl_module_demo.c | 8 ++--- sw/airborne/modules/ctrl/ctrl_module_demo.h | 4 +-- .../modules/ctrl/vertical_ctrl_module_demo.c | 6 ++-- .../modules/ctrl/vertical_ctrl_module_demo.h | 2 +- sw/airborne/modules/display/max7456.c | 6 ++-- sw/airborne/modules/enose/anemotaxis.c | 6 ++-- sw/airborne/modules/enose/anemotaxis.h | 6 ++-- sw/airborne/modules/enose/chemotaxis.c | 4 +-- sw/airborne/modules/enose/chemotaxis.h | 4 +-- sw/airborne/modules/enose/enose.c | 2 +- sw/airborne/modules/geo_mag/geo_mag.h | 4 +-- sw/airborne/modules/gps/gps_ubx_i2c.c | 4 +-- sw/airborne/modules/gps/gps_ubx_i2c.h | 4 +-- sw/airborne/modules/gps/gps_ubx_ucenter.c | 8 ++--- .../guidance_opticflow_hover.c | 2 +- .../guidance_opticflow_hover.h | 2 +- .../gumstix_interface/qr_code_spi_link.c | 2 +- .../modules/helicopter/throttle_curve.c | 2 +- .../modules/helicopter/throttle_curve.h | 2 +- sw/airborne/modules/hott/hott.c | 10 +++--- sw/airborne/modules/ins/ahrs_chimu.h | 4 +-- sw/airborne/modules/ins/ahrs_chimu_spi.c | 2 +- sw/airborne/modules/ins/ahrs_chimu_uart.c | 2 +- sw/airborne/modules/ins/ins_arduimu_basic.c | 6 ++-- sw/airborne/modules/ins/ins_arduimu_basic.h | 2 +- sw/airborne/modules/ins/ins_vn100.c | 2 +- sw/airborne/modules/ins/xsens.h | 12 +++---- sw/airborne/modules/ins/xsens700.h | 12 +++---- .../loggers/high_speed_logger_direct_memory.c | 2 +- .../loggers/high_speed_logger_spi_link.c | 2 +- .../modules/loggers/sdlogger_spi_direct.c | 2 +- .../modules/loggers/sdlogger_spi_direct.h | 2 +- sw/airborne/modules/meteo/humid_sht.c | 4 +-- sw/airborne/modules/meteo/humid_sht.h | 2 +- sw/airborne/modules/meteo/meteo_france_DAQ.c | 2 +- sw/airborne/modules/meteo/meteo_stick.c | 2 +- sw/airborne/modules/meteo/meteo_stick.h | 2 +- sw/airborne/modules/meteo/mf_ptu.c | 2 +- sw/airborne/modules/meteo/temp_temod.c | 2 +- sw/airborne/modules/mission/mission_common.c | 4 +-- sw/airborne/modules/mission/mission_common.h | 6 ++-- sw/airborne/modules/mission/mission_fw_nav.c | 12 +++---- .../modules/mission/mission_rotorcraft_nav.c | 14 ++++----- sw/airborne/modules/nav/nav_bungee_takeoff.c | 4 +-- sw/airborne/modules/nav/nav_bungee_takeoff.h | 4 +-- sw/airborne/modules/nav/nav_catapult.c | 10 +++--- sw/airborne/modules/nav/nav_catapult.h | 10 +++--- sw/airborne/modules/nav/nav_cube.c | 4 +-- sw/airborne/modules/nav/nav_cube.h | 4 +-- sw/airborne/modules/nav/nav_drop.c | 2 +- sw/airborne/modules/nav/nav_drop.h | 2 +- sw/airborne/modules/nav/nav_flower.c | 6 ++-- sw/airborne/modules/nav/nav_flower.h | 4 +-- sw/airborne/modules/nav/nav_gls.c | 8 ++--- sw/airborne/modules/nav/nav_gls.h | 4 +-- sw/airborne/modules/nav/nav_line.c | 4 +-- sw/airborne/modules/nav/nav_line.h | 4 +-- sw/airborne/modules/nav/nav_line_border.c | 4 +-- sw/airborne/modules/nav/nav_line_border.h | 4 +-- sw/airborne/modules/nav/nav_line_osam.c | 4 +-- sw/airborne/modules/nav/nav_line_osam.h | 4 +-- sw/airborne/modules/nav/nav_smooth.c | 10 +++--- sw/airborne/modules/nav/nav_smooth.h | 10 +++--- sw/airborne/modules/nav/nav_spiral.c | 4 +-- sw/airborne/modules/nav/nav_spiral.h | 4 +-- sw/airborne/modules/nav/nav_survey_disc.c | 4 +-- sw/airborne/modules/nav/nav_survey_disc.h | 4 +-- .../modules/nav/nav_survey_poly_osam.c | 12 +++---- .../modules/nav/nav_survey_poly_osam.h | 6 ++-- .../modules/nav/nav_survey_poly_rotorcraft.c | 10 +++--- .../modules/nav/nav_survey_poly_rotorcraft.h | 6 ++-- sw/airborne/modules/nav/nav_survey_polygon.c | 8 ++--- sw/airborne/modules/nav/nav_survey_polygon.h | 4 +-- .../nav/nav_survey_rectangle_rotorcraft.c | 16 +++++----- .../nav/nav_survey_rectangle_rotorcraft.h | 6 ++-- sw/airborne/modules/nav/nav_survey_zamboni.c | 4 +-- sw/airborne/modules/nav/nav_survey_zamboni.h | 4 +-- sw/airborne/modules/nav/nav_vertical_raster.c | 4 +-- sw/airborne/modules/nav/nav_vertical_raster.h | 4 +-- .../modules/obstacle_avoidance/guidance_OA.c | 2 +- .../modules/obstacle_avoidance/guidance_OA.h | 2 +- sw/airborne/modules/optical_flow/px4flow.c | 2 +- sw/airborne/modules/optical_flow/px4flow.h | 2 +- sw/airborne/modules/px4_flash/px4_flash.c | 10 +++--- sw/airborne/modules/sensors/airspeed_amsys.c | 6 ++-- sw/airborne/modules/sensors/airspeed_ets.c | 10 +++--- sw/airborne/modules/sensors/airspeed_ets.h | 2 +- .../modules/sensors/airspeed_ms45xx_i2c.h | 2 +- sw/airborne/modules/sensors/alt_srf08.c | 2 +- sw/airborne/modules/sensors/alt_srf08.h | 2 +- sw/airborne/modules/sensors/aoa_pwm.c | 2 +- sw/airborne/modules/sensors/baro_MS5534A.c | 8 ++--- sw/airborne/modules/sensors/baro_MS5534A.h | 6 ++-- sw/airborne/modules/sensors/baro_amsys.c | 6 ++-- sw/airborne/modules/sensors/baro_amsys.h | 4 +-- sw/airborne/modules/sensors/baro_bmp.c | 2 +- sw/airborne/modules/sensors/baro_bmp.h | 2 +- sw/airborne/modules/sensors/baro_ets.c | 8 ++--- sw/airborne/modules/sensors/baro_ets.h | 4 +-- sw/airborne/modules/sensors/baro_hca.c | 2 +- sw/airborne/modules/sensors/baro_ms5611_i2c.c | 4 +-- sw/airborne/modules/sensors/baro_ms5611_i2c.h | 4 +-- sw/airborne/modules/sensors/baro_ms5611_spi.c | 4 +-- sw/airborne/modules/sensors/baro_ms5611_spi.h | 4 +-- sw/airborne/modules/sensors/baro_scp.c | 2 +- sw/airborne/modules/sensors/baro_scp.h | 2 +- sw/airborne/modules/sensors/mag_hmc5843.c | 2 +- .../modules/sensors/pressure_board_navarro.h | 2 +- sw/airborne/modules/sensors/temp_adc.h | 2 +- .../modules/servo_switch/servo_switch.c | 2 +- .../modules/servo_switch/servo_switch.h | 2 +- .../stereocam/droplet/stereocam_droplet.c | 2 +- .../nav_line_avoid/avoid_navigation.c | 2 +- .../nav_line_avoid/avoid_navigation.h | 2 +- sw/airborne/modules/vehicle_interface/vi.c | 2 +- sw/airborne/modules/vehicle_interface/vi.h | 8 ++--- .../modules/vehicle_interface/vi_datalink.c | 2 +- .../vehicle_interface/vi_test_signal.c | 2 +- sw/airborne/peripherals/ads1114.h | 4 +-- sw/airborne/peripherals/ads1220.h | 4 +-- sw/airborne/peripherals/adxl345.h | 12 +++---- sw/airborne/peripherals/adxl345_i2c.h | 4 +-- sw/airborne/peripherals/adxl345_spi.h | 4 +-- sw/airborne/peripherals/ak8963.h | 4 +-- sw/airborne/peripherals/ak8975.c | 6 ++-- sw/airborne/peripherals/ak8975.h | 4 +-- sw/airborne/peripherals/bmp085.c | 2 +- sw/airborne/peripherals/bmp085.h | 6 ++-- sw/airborne/peripherals/cyrf6936.c | 26 ++++++++-------- sw/airborne/peripherals/cyrf6936.h | 12 +++---- sw/airborne/peripherals/eeprom25AA256.h | 2 +- sw/airborne/peripherals/hmc58xx.h | 4 +-- sw/airborne/peripherals/itg3200.h | 4 +-- sw/airborne/peripherals/l3g4200.h | 4 +-- sw/airborne/peripherals/l3gd20.h | 2 +- sw/airborne/peripherals/l3gd20_spi.h | 4 +-- sw/airborne/peripherals/lis302dl.h | 6 ++-- sw/airborne/peripherals/lis302dl_spi.h | 4 +-- sw/airborne/peripherals/lsm303dlhc.h | 4 +-- sw/airborne/peripherals/mcp355x.c | 2 +- sw/airborne/peripherals/mcp355x.h | 2 +- sw/airborne/peripherals/mpl3115.h | 8 ++--- sw/airborne/peripherals/mpu60x0.h | 10 +++--- sw/airborne/peripherals/mpu60x0_i2c.c | 2 +- sw/airborne/peripherals/mpu60x0_i2c.h | 2 +- sw/airborne/peripherals/mpu60x0_spi.c | 2 +- sw/airborne/peripherals/mpu60x0_spi.h | 2 +- sw/airborne/peripherals/mpu9250.h | 10 +++--- sw/airborne/peripherals/mpu9250_i2c.c | 6 ++-- sw/airborne/peripherals/mpu9250_i2c.h | 2 +- sw/airborne/peripherals/mpu9250_spi.c | 2 +- sw/airborne/peripherals/mpu9250_spi.h | 2 +- sw/airborne/peripherals/ms5611.c | 6 ++-- sw/airborne/peripherals/ms5611.h | 6 ++-- sw/airborne/peripherals/ms5611_i2c.c | 2 +- sw/airborne/peripherals/ms5611_i2c.h | 8 ++--- sw/airborne/peripherals/ms5611_spi.c | 2 +- sw/airborne/peripherals/ms5611_spi.h | 8 ++--- sw/airborne/peripherals/vn200_serial.h | 2 +- sw/airborne/rc_settings.c | 2 +- sw/airborne/rc_settings.h | 2 +- sw/airborne/state.h | 24 +++++++------- sw/airborne/subsystems/actuators.c | 2 +- sw/airborne/subsystems/actuators.h | 2 +- .../subsystems/actuators/actuators_asctec.c | 2 +- .../subsystems/actuators/actuators_asctec.h | 2 +- .../subsystems/actuators/actuators_esc32.c | 4 +-- .../subsystems/actuators/motor_mixing.c | 2 +- .../subsystems/actuators/motor_mixing.h | 4 +-- sw/airborne/subsystems/ahrs.h | 2 +- sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c | 2 +- sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h | 10 +++--- .../subsystems/ahrs/ahrs_float_cmpl_wrapper.c | 4 +-- sw/airborne/subsystems/ahrs/ahrs_float_dcm.c | 2 +- sw/airborne/subsystems/ahrs/ahrs_float_dcm.h | 6 ++-- .../subsystems/ahrs/ahrs_float_dcm_wrapper.c | 4 +-- .../subsystems/ahrs/ahrs_float_invariant.h | 4 +-- .../ahrs/ahrs_float_invariant_wrapper.c | 4 +-- sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c | 2 +- sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h | 4 +-- .../subsystems/ahrs/ahrs_float_mlkf_wrapper.c | 4 +-- sw/airborne/subsystems/ahrs/ahrs_gx3.c | 4 +-- sw/airborne/subsystems/ahrs/ahrs_gx3.h | 4 +-- .../subsystems/ahrs/ahrs_int_cmpl_euler.c | 6 ++-- .../subsystems/ahrs/ahrs_int_cmpl_euler.h | 4 +-- .../ahrs/ahrs_int_cmpl_euler_wrapper.c | 4 +-- .../subsystems/ahrs/ahrs_int_cmpl_quat.c | 2 +- .../subsystems/ahrs/ahrs_int_cmpl_quat.h | 10 +++--- .../ahrs/ahrs_int_cmpl_quat_wrapper.c | 4 +-- .../chibios-libopencm3/chibios_sdlog.c | 4 +-- .../chibios-libopencm3/chibios_sdlog.h | 4 +-- .../subsystems/chibios-libopencm3/printf.c | 6 ++-- .../subsystems/chibios-libopencm3/sdLog.c | 2 +- .../subsystems/chibios-libopencm3/sdLog.h | 2 +- .../subsystems/chibios-libopencm3/sdio.c | 10 +++--- .../subsystems/chibios-libopencm3/sdio.h | 6 ++-- .../chibios-libopencm3/usbStorage.c | 8 ++--- .../chibios-libopencm3/usbStorage.h | 2 +- .../subsystems/chibios-libopencm3/usb_msd.c | 28 ++++++++--------- .../subsystems/chibios-libopencm3/usb_msd.h | 6 ++-- .../chibios-libopencm3/varLengthMsgQ.c | 12 +++---- .../chibios-libopencm3/varLengthMsgQ.h | 8 ++--- sw/airborne/subsystems/datalink/bluegiga.c | 2 +- sw/airborne/subsystems/datalink/bluegiga.h | 2 +- sw/airborne/subsystems/datalink/datalink.c | 2 +- sw/airborne/subsystems/datalink/datalink.h | 6 ++-- sw/airborne/subsystems/datalink/superbitrf.c | 16 +++++----- sw/airborne/subsystems/datalink/superbitrf.h | 6 ++-- sw/airborne/subsystems/datalink/w5100.c | 2 +- sw/airborne/subsystems/datalink/w5100.h | 2 +- sw/airborne/subsystems/electrical.c | 2 +- sw/airborne/subsystems/electrical.h | 4 +-- sw/airborne/subsystems/gps.h | 4 +-- sw/airborne/subsystems/gps/gps_mtk.c | 4 +-- sw/airborne/subsystems/gps/gps_mtk.h | 4 +-- sw/airborne/subsystems/gps/gps_nmea.c | 2 +- sw/airborne/subsystems/gps/gps_nmea.h | 8 ++--- sw/airborne/subsystems/gps/gps_sim_hitl.c | 2 +- sw/airborne/subsystems/gps/gps_sim_nps.c | 2 +- sw/airborne/subsystems/gps/gps_sim_nps.h | 2 +- sw/airborne/subsystems/gps/gps_sirf.h | 4 +-- sw/airborne/subsystems/gps/gps_skytraq.h | 2 +- sw/airborne/subsystems/gps/gps_ubx.h | 2 +- sw/airborne/subsystems/imu.h | 2 +- .../subsystems/imu/imu_aspirin_2_spi.c | 4 +-- .../subsystems/imu/imu_aspirin_2_spi.h | 2 +- sw/airborne/subsystems/imu/imu_crista.c | 2 +- sw/airborne/subsystems/imu/imu_crista.h | 2 +- .../subsystems/imu/imu_drotek_10dof_v2.c | 2 +- .../subsystems/imu/imu_drotek_10dof_v2.h | 2 +- sw/airborne/subsystems/imu/imu_mpu9250_spi.c | 4 +-- sw/airborne/subsystems/imu/imu_mpu9250_spi.h | 2 +- sw/airborne/subsystems/imu/imu_um6.c | 4 +-- sw/airborne/subsystems/imu/imu_um6.h | 2 +- sw/airborne/subsystems/ins/hf_float.h | 2 +- sw/airborne/subsystems/ins/ins_alt_float.h | 6 ++-- .../subsystems/ins/ins_float_invariant.c | 6 ++-- .../subsystems/ins/ins_float_invariant.h | 4 +-- .../subsystems/ins/ins_gps_passthrough.c | 2 +- sw/airborne/subsystems/ins/ins_int.h | 10 +++--- sw/airborne/subsystems/ins/ins_vectornav.h | 2 +- sw/airborne/subsystems/intermcu/intermcu_ap.c | 4 +-- sw/airborne/subsystems/intermcu/intermcu_ap.h | 2 +- .../subsystems/intermcu/intermcu_fbw.c | 2 +- .../subsystems/navigation/common_nav.c | 2 +- .../subsystems/navigation/common_nav.h | 2 +- .../navigation/nav_survey_rectangle.c | 2 +- sw/airborne/subsystems/navigation/waypoints.c | 4 +-- sw/airborne/subsystems/navigation/waypoints.h | 2 +- sw/airborne/subsystems/radio_control/ppm.c | 4 +-- sw/airborne/subsystems/radio_control/ppm.h | 2 +- .../subsystems/radio_control/rc_datalink.c | 2 +- .../subsystems/radio_control/rc_datalink.h | 2 +- .../subsystems/radio_control/sbus_common.c | 2 +- .../subsystems/radio_control/sbus_common.h | 2 +- sw/airborne/subsystems/sensors/infrared_i2c.c | 4 +-- sw/airborne/subsystems/sensors/infrared_i2c.h | 4 +-- sw/airborne/subsystems/settings.c | 4 +-- sw/airborne/subsystems/settings.h | 4 +-- sw/airborne/test/test_algebra.c | 4 +-- sw/airborne/test/test_manual.c | 2 +- sw/ext/pprzlink | 2 +- sw/ground_segment/misc/natnet2ivy.c | 4 +-- sw/ground_segment/misc/sbp2ivy.c | 2 +- sw/ground_segment/misc/sbs2ivy.c | 2 +- sw/include/std.h | 17 ++-------- sw/misc/rctx/main_rctx.c | 2 +- sw/simulator/nps/nps_autopilot.h | 6 ++-- sw/simulator/nps/nps_autopilot_fixedwing.c | 4 +-- sw/simulator/nps/nps_autopilot_rotorcraft.c | 4 +-- sw/simulator/nps/nps_fdm.h | 4 +-- sw/simulator/nps/nps_fdm_crrcsim.c | 2 +- sw/simulator/nps/nps_fdm_jsbsim.cpp | 4 +-- sw/simulator/nps/nps_main.c | 4 +-- sw/simulator/nps/nps_radio_control.c | 2 +- sw/simulator/nps/nps_radio_control.h | 4 +-- sw/simulator/nps/nps_sensor_accel.h | 2 +- sw/simulator/nps/nps_sensor_airspeed.h | 2 +- sw/simulator/nps/nps_sensor_baro.h | 2 +- sw/simulator/nps/nps_sensor_gps.h | 2 +- sw/simulator/nps/nps_sensor_gyro.h | 2 +- sw/simulator/nps/nps_sensor_mag.h | 2 +- sw/simulator/nps/nps_sensor_sonar.h | 2 +- sw/simulator/nps/nps_sensor_temperature.h | 2 +- sw/simulator/nps/nps_sensors.c | 14 ++++----- sw/simulator/nps/nps_sensors.h | 14 ++++----- sw/tools/generators/gen_flight_plan.ml | 4 +-- 433 files changed, 1025 insertions(+), 1035 deletions(-) diff --git a/sw/airborne/arch/linux/mcu_periph/i2c_arch.c b/sw/airborne/arch/linux/mcu_periph/i2c_arch.c index 46617bb1472..9ded62d3436 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; } #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; diff --git a/sw/airborne/arch/linux/mcu_periph/spi_arch.c b/sw/airborne/arch/linux/mcu_periph/spi_arch.c index 1fe3dd09272..deb5d85081e 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; @@ -102,13 +102,13 @@ bool_t spi_submit(struct spi_periph *p, struct spi_transaction *t) } #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; } -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; diff --git a/sw/airborne/arch/linux/mcu_periph/udp_arch.c b/sw/airborne/arch/linux/mcu_periph/udp_arch.c index 4308a0e4932..d020bcbc3fe 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 93b7b8c76bc..ae61cdd3c03 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 89bdbe62c95..2f26886985d 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 685094a5460..5e620418ba7 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) diff --git a/sw/airborne/arch/lpc21/ADS8344.h b/sw/airborne/arch/lpc21/ADS8344.h index 186b00802c5..8e7131787fe 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 9940fc6e625..5884c72c949 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; diff --git a/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c b/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c index 548e588a9a3..cb7609a0f59 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; @@ -560,7 +560,7 @@ 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); @@ -573,7 +573,7 @@ bool_t spi_lock(struct spi_periph *p, uint8_t slave) 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); @@ -676,7 +676,7 @@ 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) { @@ -700,7 +700,7 @@ bool_t spi_slave_register(struct spi_periph *p, struct spi_transaction *t) 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 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 bd51061a9dd..a2b6609819d 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() 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 8a03f4935bd..b06f0801c47 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/radio_control/spektrum_arch.c b/sw/airborne/arch/lpc21/subsystems/radio_control/spektrum_arch.c index d2d89cedc25..5a49f7303cb 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 50601186ae8..f3f9c7cf85a 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 973db689846..471fb7bfe45 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 d4b54443164..50db3a05edf 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 e84743c9aa7..f2c4085092b 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 bd5b72659f4..978d37f292d 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/modules/ins/ins_arduimu_basic.c b/sw/airborne/arch/sim/modules/ins/ins_arduimu_basic.c index 010fd189f14..88d744b7398 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 ad6e5a39f4e..f92ba99e1f3 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; 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 805d54eb771..63bb31bdcc7 100644 --- a/sw/airborne/arch/sim/subsystems/radio_control/spektrum_arch.c +++ b/sw/airborne/arch/sim/subsystems/radio_control/spektrum_arch.c @@ -37,7 +37,7 @@ #include #endif -static bool_t spektrum_available; +static bool spektrum_available; void radio_control_spektrum_try_bind(void) {} diff --git a/sw/airborne/arch/stm32/mcu_periph/adc_arch.c b/sw/airborne/arch/stm32/mcu_periph/adc_arch.c index 75ec2b1c604..942da244717 100644 --- a/sw/airborne/arch/stm32/mcu_periph/adc_arch.c +++ b/sw/airborne/arch/stm32/mcu_periph/adc_arch.c @@ -596,7 +596,7 @@ void adc_isr(void) at least 500 hz, but we inject adc value in sampling buffer only at 50hz */ const uint32_t timeStampDiff = get_sys_time_msec() - adc_watchdog.timeStamp; - const bool_t shouldAccumulateValue = timeStampDiff > 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 f05b23970dd..dfe2cd86931 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 35a9a9918fd..ee8e7b48f25 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 ef4b29b7587..1e0f3ca4b16 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,7 +1415,7 @@ 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; @@ -1465,7 +1465,7 @@ bool_t i2c_submit(struct i2c_periph *periph, struct i2c_transaction *t) 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 diff --git a/sw/airborne/arch/stm32/mcu_periph/spi_arch.c b/sw/airborne/arch/stm32/mcu_periph/spi_arch.c index 011ff210823..e3bfa18d23a 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,7 +260,7 @@ 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; @@ -290,7 +290,7 @@ bool_t spi_submit(struct spi_periph *p, struct spi_transaction *t) 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) { @@ -302,7 +302,7 @@ bool_t spi_lock(struct spi_periph *p, uint8_t slave) 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) { @@ -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 @@ -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 */ diff --git a/sw/airborne/arch/stm32/mcu_periph/uart_arch.c b/sw/airborne/arch/stm32/mcu_periph/uart_arch.c index 861a9423237..c09f5c5d171 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) { 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 fd925cec8ce..e016973889b 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) { diff --git a/sw/airborne/arch/stm32/usb_ser_hw.c b/sw/airborne/arch/stm32/usb_ser_hw.c index 02b5d44fa05..7c31ddf7369 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,7 +286,7 @@ 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) @@ -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; @@ -344,7 +344,7 @@ bool_t fifo_put(fifo_t *fifo, uint8_t c) } -bool_t fifo_get(fifo_t *fifo, uint8_t *pc) +bool fifo_get(fifo_t *fifo, uint8_t *pc) { int next; @@ -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); } diff --git a/sw/airborne/boards/apogee/baro_board.c b/sw/airborne/boards/apogee/baro_board.c index 00d1368b866..afd23116abd 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 diff --git a/sw/airborne/boards/apogee/chibios-libopencm3/board.c b/sw/airborne/boards/apogee/chibios-libopencm3/board.c index 760b3fc3025..e05c47d014b 100644 --- a/sw/airborne/boards/apogee/chibios-libopencm3/board.c +++ b/sw/airborne/boards/apogee/chibios-libopencm3/board.c @@ -64,7 +64,7 @@ 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; } @@ -72,7 +72,7 @@ bool_t sdc_lld_is_write_protected(SDCDriver *sdcp) { /** * */ -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,7 +86,7 @@ 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.*/ @@ -96,7 +96,7 @@ bool_t mmc_lld_is_card_inserted(MMCDriver *mmcp) { /** * @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.*/ diff --git a/sw/airborne/boards/apogee/chibios-libopencm3/chconf.h b/sw/airborne/boards/apogee/chibios-libopencm3/chconf.h index e7929309bac..34158a3b85c 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 19b6fdfe1c6..d48560658cd 100644 --- a/sw/airborne/boards/apogee/imu_apogee.c +++ b/sw/airborne/boards/apogee/imu_apogee.c @@ -81,8 +81,8 @@ 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; } @@ -92,8 +92,8 @@ 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; } diff --git a/sw/airborne/boards/ardrone/actuators.c b/sw/airborne/boards/ardrone/actuators.c index 3ce4531815e..b3f7e2386ce 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/navdata.c b/sw/airborne/boards/ardrone/navdata.c index ec816bad16f..1031f9b08cf 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); @@ -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); diff --git a/sw/airborne/boards/ardrone/navdata.h b/sw/airborne/boards/ardrone/navdata.h index 6df78b6a2b4..256ab7b20bb 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/bebop/video.c b/sw/airborne/boards/bebop/video.c index 7940705445c..0262c287a8b 100644 --- a/sw/airborne/boards/bebop/video.c +++ b/sw/airborne/boards/bebop/video.c @@ -59,7 +59,7 @@ 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; @@ -82,7 +82,7 @@ static bool_t write_reg(int fd, char *addr_val, uint8_t cnt) 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"); diff --git a/sw/airborne/boards/krooz/imu_krooz.h b/sw/airborne/boards/krooz/imu_krooz.h index 88136fb6806..ef06085db9a 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.h b/sw/airborne/boards/krooz/imu_krooz_memsic.h index fc110b874d9..f384639de7f 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 0722d18512e..57663ceb858 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; }; diff --git a/sw/airborne/boards/lisa_m/baro_board.c b/sw/airborne/boards/lisa_m/baro_board.c index 43b272e484b..cb34bd2a4fa 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); } diff --git a/sw/airborne/boards/lisa_mx/baro_board.c b/sw/airborne/boards/lisa_mx/baro_board.c index 244a689502e..9f2711f9f76 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); } diff --git a/sw/airborne/boards/umarim/imu_umarim.h b/sw/airborne/boards/umarim/imu_umarim.h index d3155d2ccfe..13edc9a1491 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 2994f4678c2..6d8cc899eed 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" diff --git a/sw/airborne/firmwares/fixedwing/autopilot.h b/sw/airborne/firmwares/fixedwing/autopilot.h index bc823b8cd62..9e2d754fae5 100644 --- a/sw/airborne/firmwares/fixedwing/autopilot.h +++ b/sw/airborne/firmwares/fixedwing/autopilot.h @@ -59,7 +59,7 @@ 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. */ @@ -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 a81759e64c2..4eb1f83c285 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 7660a5360fb..6b8aa793086 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/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index ded4e50f937..2f8dfecd00e 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -361,7 +361,7 @@ 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; } @@ -408,10 +408,10 @@ static inline void telecommand_task(void) } } 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 diff --git a/sw/airborne/firmwares/fixedwing/main_chibios_libopencm3.c b/sw/airborne/firmwares/fixedwing/main_chibios_libopencm3.c index 2452c6ccfaf..d9880d852cd 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) { diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.h b/sw/airborne/firmwares/fixedwing/main_fbw.h index 67752e7d0d1..b3b715d1767 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 c48fea15b51..5b1b30b5ab2 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; @@ -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; @@ -239,7 +239,7 @@ bool_t nav_compute_baseleg(uint8_t wp_af, uint8_t wp_td, uint8_t wp_baseleg, flo 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; @@ -262,7 +262,7 @@ bool_t nav_compute_final_from_glide(uint8_t wp_af, uint8_t wp_td, float glide) /* 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); @@ -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; @@ -481,7 +481,7 @@ 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; diff --git a/sw/airborne/firmwares/fixedwing/nav.h b/sw/airborne/firmwares/fixedwing/nav.h index 3e8848498be..f80821c2a64 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 da861845843..eb7e4dbd167 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. diff --git a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.h b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_adaptive.h index aaa2bfc72d8..5175ef7a26f 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 724dd9647c9..6dfa04044f0 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 */ diff --git a/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.h b/sw/airborne/firmwares/fixedwing/stabilization/stabilization_attitude.h index 42c1f7b6057..e583f271698 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 011407ed5a9..6fae8fe56ff 100644 --- a/sw/airborne/firmwares/motor_bench/main_motor_bench.c +++ b/sw/airborne/firmwares/motor_bench/main_motor_bench.c @@ -110,7 +110,7 @@ static inline void main_event_task(void) } } -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_twi_controller_asctech.c b/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.c index 1a77ff92d75..6881d804144 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 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 b65af55d57b..ed10fa9dd3d 100644 --- a/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.h +++ b/sw/airborne/firmwares/motor_bench/mb_twi_controller_asctech.h @@ -13,7 +13,7 @@ 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; diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.c b/sw/airborne/firmwares/rotorcraft/autopilot.c index 374f1f5865f..765594548bb 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 @@ -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); } @@ -521,7 +522,7 @@ 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); @@ -532,7 +533,7 @@ bool_t autopilot_guided_goto_ned(float x, float y, float z, float heading) 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; @@ -544,7 +545,7 @@ bool_t autopilot_guided_goto_ned_relative(float dx, float dy, float dz, float dy 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; @@ -557,7 +558,7 @@ bool_t autopilot_guided_goto_body_relative(float dx, float dy, float dz, float d 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); @@ -568,7 +569,7 @@ bool_t autopilot_guided_move_ned(float vx, float vy, float vz, float heading) 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) { @@ -603,7 +604,7 @@ 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; diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.h b/sw/airborne/firmwares/rotorcraft/autopilot.h index 7e1ddeeace4..c6cfa98974d 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; @@ -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 015165793ad..7d915021dd6 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot_arming_switch.h +++ b/sw/airborne/firmwares/rotorcraft/autopilot_arming_switch.h @@ -43,7 +43,7 @@ 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) { @@ -51,7 +51,7 @@ static inline void autopilot_arming_init(void) 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; diff --git a/sw/airborne/firmwares/rotorcraft/autopilot_arming_throttle.h b/sw/airborne/firmwares/rotorcraft/autopilot_arming_throttle.h index 9ba5021f5e9..3483dd2dd46 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot_arming_throttle.h +++ b/sw/airborne/firmwares/rotorcraft/autopilot_arming_throttle.h @@ -44,7 +44,7 @@ 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) { @@ -53,7 +53,7 @@ static inline void autopilot_arming_init(void) 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; diff --git a/sw/airborne/firmwares/rotorcraft/autopilot_arming_yaw.h b/sw/airborne/firmwares/rotorcraft/autopilot_arming_yaw.h index 25ad60e9c9d..db72278387c 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; diff --git a/sw/airborne/firmwares/rotorcraft/autopilot_rc_helpers.h b/sw/airborne/firmwares/rotorcraft/autopilot_rc_helpers.h index 43482ccb1ab..5e5aabab830 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot_rc_helpers.h +++ b/sw/airborne/firmwares/rotorcraft/autopilot_rc_helpers.h @@ -52,13 +52,13 @@ (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; @@ -67,7 +67,7 @@ static inline bool_t kill_switch_is_on(void) } } #else -static inline bool_t kill_switch_is_on(void) +static inline bool kill_switch_is_on(void) { return FALSE; } diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_flip.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_flip.c index e28bf47c921..7ee46e8ba22 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 99ab6078981..b3e481a5637 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,7 +636,7 @@ 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); @@ -648,7 +648,7 @@ bool_t guidance_h_set_guided_pos(float x, float y) 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); @@ -659,7 +659,7 @@ bool_t guidance_h_set_guided_heading(float heading) 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); diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.h index 22344e3f75f..3a592a1e2b4 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 1a788828003..e2d3ebe7ae7 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 eeca34b5c7d..5eac0f542da 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 d24eda6d8aa..125e6aa2ec8 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 d11416d6934..fdb66130724 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" @@ -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 @@ -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,7 +460,7 @@ 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; @@ -470,7 +470,7 @@ bool_t guidance_v_set_guided_z(float z) 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; diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.h index f38f55046c9..3803faee817 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_fbw.c b/sw/airborne/firmwares/rotorcraft/main_fbw.c index 35c758c5a5c..30dda611b97 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 diff --git a/sw/airborne/firmwares/rotorcraft/navigation.c b/sw/airborne/firmwares/rotorcraft/navigation.c index eeeb26f4622..658d7423f2d 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; @@ -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; @@ -343,12 +343,12 @@ bool_t nav_approaching_from(struct EnuCoor_i *wp, struct EnuCoor_i *from, int16_ 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; @@ -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; } -bool_t nav_is_in_flight(void) +bool nav_is_in_flight(void) { return autopilot_in_flight; } @@ -506,7 +506,7 @@ 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); @@ -514,13 +514,13 @@ bool_t nav_set_heading_rad(float rad) } /** 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; @@ -536,13 +536,13 @@ bool_t nav_set_heading_towards(float x, float y) } /** 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; diff --git a/sw/airborne/firmwares/rotorcraft/navigation.h b/sw/airborne/firmwares/rotorcraft/navigation.h index e7dfb04702f..52ea5254626 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,17 +84,17 @@ 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 @@ -155,12 +155,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 diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_attitude.h index 8faecf40e2f..6fe498da215 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 a22cdadc902..a1f223ef565 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 c1bb520681f..064492a1c67 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 d5ec9ffeb7c..1fa401d10f9 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 b21c32e2dc7..fb0f2076010 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 82fb77d1ead..d171907d469 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 ba3069cb714..ef97ae00813 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 5f275665fb0..7e1f3c1ea0f 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 80a5834df82..af7726b7ffd 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 cdf45625b6c..dc283914c43 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_indi.c @@ -75,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); @@ -200,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(); @@ -283,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; @@ -308,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 4b0d1bad87a..c703f50de82 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 a3aca85b226..b300c0584f4 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 07ddd22aca1..0b41b971e17 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 9316a00bfe9..dfac8bbe7e4 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 5263e4dd310..608b0b0bfa4 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 7b25db30b86..195e24139bc 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 2fa0e919bfb..64fad42cdf4 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 ea56b03cabf..514e5d128be 100644 --- a/sw/airborne/firmwares/tutorial/main_demo5.c +++ b/sw/airborne/firmwares/tutorial/main_demo5.c @@ -58,7 +58,7 @@ static inline void main_event_task(void) 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 ee1d7606eaf..b0a30bafa8a 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) diff --git a/sw/airborne/firmwares/wind_tunnel/main_mb.c b/sw/airborne/firmwares/wind_tunnel/main_mb.c index 48cd7172a25..ff7122cf1a2 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 92d5d2ed919..29d6587a189 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 diff --git a/sw/airborne/firmwares/wind_tunnel/wt_baro.h b/sw/airborne/firmwares/wind_tunnel/wt_baro.h index eae620f47ce..804b189e962 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 09b463da87f..c5c52464467 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 25a7e32ebf8..74eca348d66 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 diff --git a/sw/airborne/link_mcu_can.h b/sw/airborne/link_mcu_can.h index 6cab3833d76..82aa28b5810 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 88a48a90b69..70418f52abd 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; diff --git a/sw/airborne/link_mcu_spi.h b/sw/airborne/link_mcu_spi.h index 9967bc5f71c..5eeff0b527b 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 a9189e7cbee..565e8b835d3 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; diff --git a/sw/airborne/link_mcu_usart.h b/sw/airborne/link_mcu_usart.h index 375717d2f18..558e17d578b 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 f2ce4b5b9db..5c5d3fadbed 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 9698d367a17..88be61853d3 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 0bae71c5492..35f09c56772 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.h b/sw/airborne/mcu_periph/spi.h index a49345caded..a82b164d37f 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.h b/sw/airborne/mcu_periph/sys_time.h index afee1b835f0..d5acd582d9d 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,7 +108,7 @@ 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; diff --git a/sw/airborne/mcu_periph/uart.c b/sw/airborne/mcu_periph/uart.c index bbb98f4246f..7bde2745b6c 100644 --- a/sw/airborne/mcu_periph/uart.c +++ b/sw/airborne/mcu_periph/uart.c @@ -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 3a847a3a567..177bfd42b68 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 bac4e0d009b..b064d9a1cb9 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 1d33f03325d..636adf91b66 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 85126dc0f19..17582a967bc 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.h b/sw/airborne/modules/air_data/air_data.h index 95dcd523c31..e8578068f1f 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 92114ea3774..df897793f85 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 05b931d8050..256e6caa199 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 d2cc190ae5f..0aa9c83258b 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 e4cb371a514..768d47fe472 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 3ebd0396bed..71db7b93788 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 37d6d5662c3..ad93e6d1ac3 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; diff --git a/sw/airborne/modules/cartography/cartography.c b/sw/airborne/modules/cartography/cartography.c index 2ecd2c3c7de..1fa61c8b968 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,13 +165,13 @@ void stop_carto(void) /////////////////////////////////////////////////////////////////////////////////////////////// -bool_t nav_survey_Inc_railnumberSinceBoot(void) +bool nav_survey_Inc_railnumberSinceBoot(void) { railnumberSinceBoot++; return FALSE; } /////////////////////////////////////////////////////////////////////////////////////////////// -bool_t nav_survey_Snapshoot(void) +bool nav_survey_Snapshoot(void) { camera_snapshot_image_number = railnumberSinceBoot; PRTDEBSTR(SNAPSHOT) @@ -180,7 +180,7 @@ bool_t nav_survey_Snapshoot(void) } /////////////////////////////////////////////////////////////////////////////////////////////// -bool_t nav_survey_Snapshoot_Continu(void) +bool nav_survey_Snapshoot_Continu(void) { camera_snapshot_image_number = railnumberSinceBoot; PRTDEBSTR(SNAPSHOT) @@ -189,7 +189,7 @@ bool_t nav_survey_Snapshoot_Continu(void) } /////////////////////////////////////////////////////////////////////////////////////////////// -bool_t nav_survey_StopSnapshoot(void) +bool nav_survey_StopSnapshoot(void) { camera_snapshot_image_number = 0; PRTDEBSTR(STOP SNAPSHOT) @@ -199,7 +199,7 @@ bool_t nav_survey_StopSnapshoot(void) } /////////////////////////////////////////////////////////////////////////////////////////////// -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; @@ -211,11 +211,11 @@ bool_t nav_survey_computefourth_corner(uint8_t wp1, uint8_t wp2, uint8_t wp3, u } //////////////////////////////////////////////////////////////////////////////////////////////// -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,7 +310,7 @@ 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; @@ -411,7 +411,7 @@ bool_t nav_survey_losange_carto_init(uint8_t wp1, uint8_t wp2, uint8_t wp3, flo // NextStageAndBreak(); } //////////////////////////////////////////////////////////////////////////////////////////////// -bool_t nav_survey_losange_carto(void) +bool nav_survey_losange_carto(void) { //test pour modifier en vol la valeur distrail diff --git a/sw/airborne/modules/cartography/cartography.h b/sw/airborne/modules/cartography/cartography.h index 578b1d04d00..b4c3233bf86 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 bc14d467efd..fced0efecf0 100644 --- a/sw/airborne/modules/com/generic_com.c +++ b/sw/airborne/modules/com/generic_com.c @@ -47,7 +47,7 @@ struct i2c_transaction com_trans; -bool_t active_com; +bool active_com; void generic_com_init(void) { diff --git a/sw/airborne/modules/com/usb_serial_stm32_example1.c b/sw/airborne/modules/com/usb_serial_stm32_example1.c index 714e55180bd..b5c3af2df80 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 = '$'; /** diff --git a/sw/airborne/modules/computer_vision/bebop_front_camera.c b/sw/airborne/modules/computer_vision/bebop_front_camera.c index 8fd65156176..10e5c33410d 100644 --- a/sw/airborne/modules/computer_vision/bebop_front_camera.c +++ b/sw/airborne/modules/computer_vision/bebop_front_camera.c @@ -70,7 +70,7 @@ 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; } diff --git a/sw/airborne/modules/computer_vision/bebop_front_camera.h b/sw/airborne/modules/computer_vision/bebop_front_camera.h index 2643f28be34..afaf5255afc 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 03e65456d82..16d5fc96301 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); diff --git a/sw/airborne/modules/computer_vision/cv_georeference.c b/sw/airborne/modules/computer_vision/cv_georeference.c index 6d43c3437cf..b589e10797b 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 c016e33986f..9978065e410 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 a957574fb94..bfa375eeca8 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 1895cb3eb1f..263feecb4d1 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 857da3174e8..55d5afafc0e 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); @@ -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; @@ -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; @@ -443,7 +443,7 @@ 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; diff --git a/sw/airborne/modules/computer_vision/lib/v4l/v4l2.h b/sw/airborne/modules/computer_vision/lib/v4l/v4l2.h index 3d211a94486..29c2174f5d0 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/fast_rosten.c b/sw/airborne/modules/computer_vision/lib/vision/fast_rosten.c index 2444140b66a..60c8370614c 100644 --- a/sw/airborne/modules/computer_vision/lib/vision/fast_rosten.c +++ b/sw/airborne/modules/computer_vision/lib/vision/fast_rosten.c @@ -67,7 +67,7 @@ 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++) { 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 042cc8c2643..b60fab3d6c6 100644 --- a/sw/airborne/modules/computer_vision/lib/vision/lucas_kanade.c +++ b/sw/airborne/modules/computer_vision/lib/vision/lucas_kanade.c @@ -124,7 +124,7 @@ struct flow_t *opticFlowLK(struct image_t *new_img, struct image_t *old_img, str // (a * Ax + (1-a) * Ax+1) - (a * Bx + (1-a) * Bx+1) // (4) iterate over taking steps in the image to minimize the error: - bool_t tracked = TRUE; + bool tracked = TRUE; for (uint8_t it = 0; it < max_iterations; it++) { struct point_t new_point = { vectors[new_p].pos.x + vectors[new_p].flow_x, diff --git a/sw/airborne/modules/computer_vision/opticflow/opticflow_calculator.h b/sw/airborne/modules/computer_vision/opticflow/opticflow_calculator.h index 1a642601f6e..e5bef0df601 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 @@ -53,7 +53,7 @@ struct opticflow_t { uint8_t threshold_vec; ///< The threshold in x, y subpixels which the algorithm should stop 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 9a3f7a2576c..9896eca86c5 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; diff --git a/sw/airborne/modules/computer_vision/qrcode/qr_code.h b/sw/airborne/modules/computer_vision/qrcode/qr_code.h index 907422d34f5..b0bb60a71e0 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 209d1b01c95..6254cc1ccc6 100644 --- a/sw/airborne/modules/computer_vision/video_thread.c +++ b/sw/airborne/modules/computer_vision/video_thread.c @@ -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 818f2f257d6..2f9a3e4f431 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 042bf5c3f8f..4940c2c819e 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.h b/sw/airborne/modules/computer_vision/viewvideo.h index 64d1dba6db0..cb44ee57850 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 ad6acaa3daa..cd1120521dd 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 afdc0036162..3b60e712c47 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 d1fdf07ad75..790cfd9ec52 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 a86bc71713d..b24607938b0 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 67d20c03dd4..4d84ae68914 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 3b33cd489be..14ce2bddf74 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 00ce243323f..d5f834c3c74 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/display/max7456.c b/sw/airborne/modules/display/max7456.c index a66bdaff7ad..373b2039fc8 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; @@ -90,7 +90,7 @@ uint8_t max7456_osd_status = OSD_UNINIT; 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) { @@ -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 ba9589009f0..d94470ee753 100644 --- a/sw/airborne/modules/enose/anemotaxis.c +++ b/sw/airborne/modules/enose/anemotaxis.c @@ -18,7 +18,7 @@ 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); @@ -27,7 +27,7 @@ bool_t nav_anemotaxis_downwind(uint8_t c, float radius) return FALSE; } -bool_t nav_anemotaxis_init(uint8_t c) +bool nav_anemotaxis_init(uint8_t c) { status = UTURN; sign = 1; @@ -39,7 +39,7 @@ bool_t nav_anemotaxis_init(uint8_t c) 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(); diff --git a/sw/airborne/modules/enose/anemotaxis.h b/sw/airborne/modules/enose/anemotaxis.h index 16e571b252f..19b55962ade 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 7733a4b94be..dcf242e8abe 100644 --- a/sw/airborne/modules/enose/chemotaxis.c +++ b/sw/airborne/modules/enose/chemotaxis.c @@ -15,7 +15,7 @@ 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; @@ -25,7 +25,7 @@ bool_t nav_chemotaxis_init(uint8_t c, uint8_t plume) 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) { diff --git a/sw/airborne/modules/enose/chemotaxis.h b/sw/airborne/modules/enose/chemotaxis.h index ad0c26e5872..629017098f9 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 47bb5d1bc86..47bfd8da7e9 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; diff --git a/sw/airborne/modules/geo_mag/geo_mag.h b/sw/airborne/modules/geo_mag/geo_mag.h index bc3ca491457..cedee8dbe8b 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_ubx_i2c.c b/sw/airborne/modules/gps/gps_ubx_i2c.c index 781ab1ba158..8ec8c6fd6d1 100644 --- a/sw/airborne/modules/gps/gps_ubx_i2c.c +++ b/sw/airborne/modules/gps/gps_ubx_i2c.c @@ -49,7 +49,7 @@ PRINT_CONFIG_VAR(GPS_UBX_I2C_DEV) struct GpsUbxI2C gps_i2c; // Local variables -bool_t gps_ubx_i2c_ucenter_done; ///< ucenter finished configuring flag +bool gps_ubx_i2c_ucenter_done; ///< ucenter finished configuring flag uint16_t gps_ubx_i2c_bytes_to_read; ///< ublox bytes to read /** null function @@ -114,7 +114,7 @@ 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_t gps_i2c_tx_is_ready(void) +bool gps_i2c_tx_is_ready(void) { return gps_i2c.tx_rdy; } diff --git a/sw/airborne/modules/gps/gps_ubx_i2c.h b/sw/airborne/modules/gps/gps_ubx_i2c.h index 1a691fda961..c5c0884fb24 100644 --- a/sw/airborne/modules/gps/gps_ubx_i2c.h +++ b/sw/airborne/modules/gps/gps_ubx_i2c.h @@ -70,7 +70,7 @@ struct GpsUbxI2C uint16_t rx_buf_idx; ///< rx buf index uint16_t tx_buf_idx; ///< tx buf index - bool_t tx_rdy; ///< are we ready to transmit + bool tx_rdy; ///< are we ready to transmit struct i2c_transaction trans; ///< i2c transaction @@ -91,7 +91,7 @@ extern void gps_ubx_i2c_periodic(void); extern void gps_ubx_i2c_read_event(void); /** is driver ready to send a message */ -extern bool_t gps_i2c_tx_is_ready(void); +extern bool gps_i2c_tx_is_ready(void); /** config is done, begin reading messages */ extern void gps_i2c_begin(void); diff --git a/sw/airborne/modules/gps/gps_ubx_ucenter.c b/sw/airborne/modules/gps/gps_ubx_ucenter.c index 0ea9de2bc2f..869f86f2475 100644 --- a/sw/airborne/modules/gps/gps_ubx_ucenter.c +++ b/sw/airborne/modules/gps/gps_ubx_ucenter.c @@ -44,9 +44,9 @@ // // UCENTER: init, periodic and event #ifndef GPS_I2C -static bool_t gps_ubx_ucenter_autobaud(uint8_t nr); +static bool gps_ubx_ucenter_autobaud(uint8_t nr); #endif -static bool_t gps_ubx_ucenter_configure(uint8_t nr); +static bool gps_ubx_ucenter_configure(uint8_t nr); #define GPS_UBX_UCENTER_STATUS_STOPPED 0 #define GPS_UBX_UCENTER_STATUS_AUTOBAUD 1 @@ -247,7 +247,7 @@ static inline void gps_ubx_ucenter_enable_msg(uint8_t class, uint8_t id, uint8_t * @return FALSE when completed */ #ifndef GPS_I2C -static bool_t gps_ubx_ucenter_autobaud(uint8_t nr) +static bool gps_ubx_ucenter_autobaud(uint8_t nr) { switch (nr) { case 0: @@ -463,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); diff --git a/sw/airborne/modules/guidance_opticflow/guidance_opticflow_hover.c b/sw/airborne/modules/guidance_opticflow/guidance_opticflow_hover.c index 62e3dbef046..e6daa87ba83 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 93fbe665a29..08a1e954e17 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 47081b186ed..bf7a9bfcdd1 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}; diff --git a/sw/airborne/modules/helicopter/throttle_curve.c b/sw/airborne/modules/helicopter/throttle_curve.c index b709d99e5ff..6304a281a1b 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 8fb4fef2f20..9c7324f29b6 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 b5b14675522..d603493ddc6 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 diff --git a/sw/airborne/modules/ins/ahrs_chimu.h b/sw/airborne/modules/ins/ahrs_chimu.h index 6f47e2c6388..0bc40c4e579 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 a52c2bdadf0..21ee99e57db 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; diff --git a/sw/airborne/modules/ins/ahrs_chimu_uart.c b/sw/airborne/modules/ins/ahrs_chimu_uart.c index 27aed008f6b..22d042cb89b 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; diff --git a/sw/airborne/modules/ins/ins_arduimu_basic.c b/sw/airborne/modules/ins/ins_arduimu_basic.c index f9e319fa1fd..1aa526a1f8a 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) { diff --git a/sw/airborne/modules/ins/ins_arduimu_basic.h b/sw/airborne/modules/ins/ins_arduimu_basic.h index ddb207539ce..5a6b887a8ab 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_vn100.c b/sw/airborne/modules/ins/ins_vn100.c index 15bf8cbce6e..3ba8db07500 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; diff --git a/sw/airborne/modules/ins/xsens.h b/sw/airborne/modules/ins/xsens.h index b8a3f07930d..9e7fd48f796 100644 --- a/sw/airborne/modules/ins/xsens.h +++ b/sw/airborne/modules/ins/xsens.h @@ -60,16 +60,16 @@ struct Xsens { struct FloatQuat quat; struct FloatEulers euler; - volatile bool_t msg_received; - volatile bool_t new_attitude; + volatile bool msg_received; + volatile bool new_attitude; - bool_t gyro_available; - bool_t accel_available; - bool_t mag_available; + bool gyro_available; + bool accel_available; + bool mag_available; #if USE_GPS_XSENS struct GpsState gps; - bool_t gps_available; + bool gps_available; #endif }; diff --git a/sw/airborne/modules/ins/xsens700.h b/sw/airborne/modules/ins/xsens700.h index b5d0009feca..ef221d76fc4 100644 --- a/sw/airborne/modules/ins/xsens700.h +++ b/sw/airborne/modules/ins/xsens700.h @@ -60,16 +60,16 @@ struct Xsens { struct FloatQuat quat; struct FloatEulers euler; - volatile bool_t msg_received; - volatile bool_t new_attitude; + volatile bool msg_received; + volatile bool new_attitude; - bool_t gyro_available; - bool_t accel_available; - bool_t mag_available; + bool gyro_available; + bool accel_available; + bool mag_available; #if USE_GPS_XSENS struct GpsState gps; - bool_t gps_available; + bool gps_available; #endif }; 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 d245082cf10..cbae93c8781 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 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 fd8993d0d8a..1307acddca2 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); diff --git a/sw/airborne/modules/loggers/sdlogger_spi_direct.c b/sw/airborne/modules/loggers/sdlogger_spi_direct.c index 7e02d7eaaaa..8ed873e074a 100644 --- a/sw/airborne/modules/loggers/sdlogger_spi_direct.c +++ b/sw/airborne/modules/loggers/sdlogger_spi_direct.c @@ -344,7 +344,7 @@ 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 */ diff --git a/sw/airborne/modules/loggers/sdlogger_spi_direct.h b/sw/airborne/modules/loggers/sdlogger_spi_direct.h index 2d55fa744e8..251b8c84a6f 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 884cb3a5dc2..2c1a7f34f36 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); diff --git a/sw/airborne/modules/meteo/humid_sht.h b/sw/airborne/modules/meteo/humid_sht.h index 68436a66466..c3cd97344a0 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 59db68ba775..d7b9c21c53b 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 diff --git a/sw/airborne/modules/meteo/meteo_stick.c b/sw/airborne/modules/meteo/meteo_stick.c index ff0a8369509..05dc6347101 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 diff --git a/sw/airborne/modules/meteo/meteo_stick.h b/sw/airborne/modules/meteo/meteo_stick.h index 6360c379656..33b94fd91d6 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 45ebadb974e..f34bfe98093 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 diff --git a/sw/airborne/modules/meteo/temp_temod.c b/sw/airborne/modules/meteo/temp_temod.c index 6883409669f..b60875ffa10 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; diff --git a/sw/airborne/modules/mission/mission_common.c b/sw/airborne/modules/mission/mission_common.c index fb949fc25b4..4a9bf692c64 100644 --- a/sw/airborne/modules/mission/mission_common.c +++ b/sw/airborne/modules/mission/mission_common.c @@ -44,7 +44,7 @@ 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 @@ -84,7 +84,7 @@ bool_t mission_insert(enum MissionInsertMode insert, struct _mission_element *el // 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 diff --git a/sw/airborne/modules/mission/mission_common.h b/sw/airborne/modules/mission/mission_common.h index a9c41e35851..10c7aa45918 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 473aef46e2f..712a0c3f284 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; @@ -71,7 +71,7 @@ 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 @@ -86,7 +86,7 @@ static inline bool_t mission_nav_wp(struct _mission_wp *wp) /** 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.); @@ -96,7 +96,7 @@ static inline bool_t mission_nav_circle(struct _mission_circle *circle) /** 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)) { @@ -111,7 +111,7 @@ static inline bool_t mission_nav_segment(struct _mission_segment *segment) /** 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 @@ -148,7 +148,7 @@ int mission_run() 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)); diff --git a/sw/airborne/modules/mission/mission_rotorcraft_nav.c b/sw/airborne/modules/mission/mission_rotorcraft_nav.c index 4b6db2f238b..6f3f4bb9005 100644 --- a/sw/airborne/modules/mission/mission_rotorcraft_nav.c +++ b/sw/airborne/modules/mission/mission_rotorcraft_nav.c @@ -38,7 +38,7 @@ #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) { @@ -76,7 +76,7 @@ bool_t mission_point_of_lla(struct EnuCoor_f *point, struct LlaCoor_i *lla) } //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; @@ -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); @@ -138,7 +138,7 @@ static inline bool_t mission_nav_wp(struct _mission_element *el) /** 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; @@ -158,7 +158,7 @@ static inline bool_t mission_nav_circle(struct _mission_element *el) /** 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); @@ -184,7 +184,7 @@ static inline bool_t mission_nav_segment(struct _mission_element *el) /** 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 @@ -230,7 +230,7 @@ int mission_run() 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); diff --git a/sw/airborne/modules/nav/nav_bungee_takeoff.c b/sw/airborne/modules/nav/nav_bungee_takeoff.c index f93a46c282e..b818b6657ca 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 ? @@ -158,7 +158,7 @@ bool_t nav_bungee_takeoff_setup(uint8_t bungee_wp) return FALSE; } -bool_t nav_bungee_takeoff_run(void) +bool nav_bungee_takeoff_run(void) { float cross = 0.; diff --git a/sw/airborne/modules/nav/nav_bungee_takeoff.h b/sw/airborne/modules/nav/nav_bungee_takeoff.h index d7c9c50b6e8..70beeebacab 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 bf01285cd81..38d0791aade 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,7 +131,7 @@ 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; @@ -142,7 +142,7 @@ bool_t nav_catapult_setup(void) -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); @@ -195,7 +195,7 @@ bool_t nav_catapult_run(uint8_t _to, uint8_t _climb) } -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; diff --git a/sw/airborne/modules/nav/nav_catapult.h b/sw/airborne/modules/nav/nav_catapult.h index 08ef05f0d87..4074c867cb8 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 cd1cb1e05c4..1b518f61937 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; @@ -141,7 +141,7 @@ bool_t nav_cube_setup(uint8_t center, uint8_t tb, uint8_t te) 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) { diff --git a/sw/airborne/modules/nav/nav_cube.h b/sw/airborne/modules/nav/nav_cube.h index 590cfb7fedd..54767604d89 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 aa0573ef1c0..fe774178391 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; diff --git a/sw/airborne/modules/nav/nav_drop.h b/sw/airborne/modules/nav/nav_drop.h index 0f873501a19..78e62a3be70 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 4653d3dffd0..f7215ae09ae 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; @@ -88,13 +88,13 @@ bool_t nav_flower_setup(uint8_t CenterWP, uint8_t EdgeWP) 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) { diff --git a/sw/airborne/modules/nav/nav_flower.h b/sw/airborne/modules/nav/nav_flower.h index 527f0a551ea..520e70e3590 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 6bd541c4118..8072955b463 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))) { @@ -132,7 +132,7 @@ static inline bool_t gls_compute_TOD(uint8_t _af, uint8_t _sd, uint8_t _tod, uin } /* 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; @@ -156,7 +156,7 @@ bool_t gls_start(uint8_t _af, uint8_t _sd, uint8_t _tod, uint8_t _td) } /* 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) { diff --git a/sw/airborne/modules/nav/nav_gls.h b/sw/airborne/modules/nav/nav_gls.h index 126cab0034d..8d5db00be1f 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 3569638affd..0605cfd3eec 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; } -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; diff --git a/sw/airborne/modules/nav/nav_line.h b/sw/airborne/modules/nav/nav_line.h index a255fa58b6b..a157516359b 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 52c846e802f..22662e1e44d 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; } -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; diff --git a/sw/airborne/modules/nav/nav_line_border.h b/sw/airborne/modules/nav/nav_line_border.h index fce937c0e4a..804c34c1286 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 2dbc6be4840..1bfe4e66a8c 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; @@ -173,7 +173,7 @@ bool_t nav_line_osam_run(uint8_t From_WP, uint8_t To_WP, float radius, float Spa 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); diff --git a/sw/airborne/modules/nav/nav_line_osam.h b/sw/airborne/modules/nav/nav_line_osam.h index 70dda5297f2..d6ae48cbf12 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 34390125809..c3eaf4f6a12 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); @@ -118,7 +118,7 @@ bool_t snav_init(uint8_t a, float desired_course_rad, float radius) } -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 cfece53816f..ad70a3d7989 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 f42394c846d..86e264b33a0 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; @@ -84,7 +84,7 @@ bool_t nav_spiral_setup(uint8_t center_wp, uint8_t edge_wp, float radius_start, return FALSE; } -bool_t nav_spiral_run(void) +bool nav_spiral_run(void) { struct EnuCoor_f pos_enu = *stateGetPositionEnu_f(); diff --git a/sw/airborne/modules/nav/nav_spiral.h b/sw/airborne/modules/nav/nav_spiral.h index 51ddf0ec110..ee6c3dd2c11 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 9ec01faa276..d135b16d931 100644 --- a/sw/airborne/modules/nav/nav_survey_disc.c +++ b/sw/airborne/modules/nav/nav_survey_disc.c @@ -46,7 +46,7 @@ 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; @@ -56,7 +56,7 @@ bool_t nav_survey_disc_setup(float grid) 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; diff --git a/sw/airborne/modules/nav/nav_survey_disc.h b/sw/airborne/modules/nav/nav_survey_disc.h index 385268ce817..60403830500 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 4edd3acfcd1..d5302905758 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; @@ -332,7 +332,7 @@ bool_t nav_survey_poly_osam_setup(uint8_t EntryWP, uint8_t Size, float sw, float 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; diff --git a/sw/airborne/modules/nav/nav_survey_poly_osam.h b/sw/airborne/modules/nav/nav_survey_poly_osam.h index cb3f8455f90..8f00714d2c3 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 301e2b75c1c..8f79dd5f167 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; @@ -313,7 +313,7 @@ bool_t nav_survey_poly_setup(uint8_t EntryWP, uint8_t Size, float sw, float Orie } //========================================================================================================================= -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; diff --git a/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.h b/sw/airborne/modules/nav/nav_survey_poly_rotorcraft.h index 1981ecf8715..d5a865604cb 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 609f1d07c6d..54dcd25ba76 100644 --- a/sw/airborne/modules/nav/nav_survey_polygon.c +++ b/sw/airborne/modules/nav/nav_survey_polygon.c @@ -52,7 +52,7 @@ 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; @@ -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; @@ -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; @@ -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); diff --git a/sw/airborne/modules/nav/nav_survey_polygon.h b/sw/airborne/modules/nav/nav_survey_polygon.h index 3e67c54d523..f15237c0330 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 ef47a6823a2..9651604757b 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)); @@ -155,9 +155,9 @@ bool_t nav_survey_rectangle_rotorcraft_setup(uint8_t wp1, uint8_t wp2, float gri } -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; diff --git a/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.h b/sw/airborne/modules/nav/nav_survey_rectangle_rotorcraft.h index 162c8c2da30..22c60047bcb 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 c35d6013fb3..1e7c2132f91 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; @@ -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); diff --git a/sw/airborne/modules/nav/nav_survey_zamboni.h b/sw/airborne/modules/nav/nav_survey_zamboni.h index 4b5153253fb..c7dea17347c 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 be29c3afd59..abe24d79933 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; } -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; diff --git a/sw/airborne/modules/nav/nav_vertical_raster.h b/sw/airborne/modules/nav/nav_vertical_raster.h index 150c5140305..dcb8e602eef 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/obstacle_avoidance/guidance_OA.c b/sw/airborne/modules/obstacle_avoidance/guidance_OA.c index 10460e700af..cab84a9cd17 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 f266772e637..98f85116f57 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 56c863328ce..ac836f6d897 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 diff --git a/sw/airborne/modules/optical_flow/px4flow.h b/sw/airborne/modules/optical_flow/px4flow.h index 57c0fcff23a..4bd1738eb16 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/px4_flash/px4_flash.c b/sw/airborne/modules/px4_flash/px4_flash.c index b16383b41f4..7aa81f17e2e 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 37821539829..22fb30fb1ee 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; diff --git a/sw/airborne/modules/sensors/airspeed_ets.c b/sw/airborne/modules/sensors/airspeed_ets.c index eceb9d25aab..15b9629a190 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) { diff --git a/sw/airborne/modules/sensors/airspeed_ets.h b/sw/airborne/modules/sensors/airspeed_ets.h index de9565d5c3b..4fe58fafbc7 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 6b95c3c863b..e6e1d84aa26 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 b950db614c6..c7ec23666d5 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; diff --git a/sw/airborne/modules/sensors/alt_srf08.h b/sw/airborne/modules/sensors/alt_srf08.h index 06a5f82051a..871f5ebdc1d 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 ae11c4c6c5d..0f1a25f9b60 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 diff --git a/sw/airborne/modules/sensors/baro_MS5534A.c b/sw/airborne/modules/sensors/baro_MS5534A.c index c6e1d4ef668..228e44545d3 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) diff --git a/sw/airborne/modules/sensors/baro_MS5534A.h b/sw/airborne/modules/sensors/baro_MS5534A.h index c141b127608..bd3705aad35 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 28e6123990a..a1549dfa996 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; diff --git a/sw/airborne/modules/sensors/baro_amsys.h b/sw/airborne/modules/sensors/baro_amsys.h index f6a3817d341..3afd01b3bee 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 eaa2d147cd6..4ea1e406bd6 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; diff --git a/sw/airborne/modules/sensors/baro_bmp.h b/sw/airborne/modules/sensors/baro_bmp.h index aa56e102669..cd79f038930 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 a5d667c2e12..c95171ed2a1 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) { diff --git a/sw/airborne/modules/sensors/baro_ets.h b/sw/airborne/modules/sensors/baro_ets.h index 3af6a94fb3f..7da4e011b23 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 4c36172083d..77415bab6d6 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; diff --git a/sw/airborne/modules/sensors/baro_ms5611_i2c.c b/sw/airborne/modules/sensors/baro_ms5611_i2c.c index 2aeca5c956d..3b710329c61 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; diff --git a/sw/airborne/modules/sensors/baro_ms5611_i2c.h b/sw/airborne/modules/sensors/baro_ms5611_i2c.h index ac57cf2d8d0..71615bdc464 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 768c8aa4d92..0503f8c1e4e 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; diff --git a/sw/airborne/modules/sensors/baro_ms5611_spi.h b/sw/airborne/modules/sensors/baro_ms5611_spi.h index 43eb997e020..784b2111404 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 05a819dc52e..6a3dbde434a 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); diff --git a/sw/airborne/modules/sensors/baro_scp.h b/sw/airborne/modules/sensors/baro_scp.h index c69534ec0fc..96bd0388e08 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/mag_hmc5843.c b/sw/airborne/modules/sensors/mag_hmc5843.c index a47f5830b62..64d30e1bb88 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/pressure_board_navarro.h b/sw/airborne/modules/sensors/pressure_board_navarro.h index f8f1eb65934..efa352dbfd7 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 4de27274fbb..64da048e49a 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/servo_switch/servo_switch.c b/sw/airborne/modules/servo_switch/servo_switch.c index b3025728fcf..5054870fad3 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) diff --git a/sw/airborne/modules/servo_switch/servo_switch.h b/sw/airborne/modules/servo_switch/servo_switch.h index 2c2a1871319..1d7bf0bc705 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 diff --git a/sw/airborne/modules/stereocam/droplet/stereocam_droplet.c b/sw/airborne/modules/stereocam/droplet/stereocam_droplet.c index c958d71d09a..06383b2a2f8 100644 --- a/sw/airborne/modules/stereocam/droplet/stereocam_droplet.c +++ b/sw/airborne/modules/stereocam/droplet/stereocam_droplet.c @@ -113,7 +113,7 @@ 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) || 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 35104332cf7..0912145d02a 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 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 094f2bbb7e7..c1734b5d73a 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 3665570a85d..78a52c2beae 100644 --- a/sw/airborne/modules/vehicle_interface/vi.c +++ b/sw/airborne/modules/vehicle_interface/vi.c @@ -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 576ce96d9a8..c2f6403350b 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 183740f5178..ba581623441 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 ee2615a0c05..6af01bc9449 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.h b/sw/airborne/peripherals/ads1114.h index 42107279cb5..96b1d2eb428 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 diff --git a/sw/airborne/peripherals/ads1220.h b/sw/airborne/peripherals/ads1220.h index 40e5279273a..6e687f899eb 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 cfedad8bd86..ec8ed868050 100644 --- a/sw/airborne/peripherals/adxl345.h +++ b/sw/airborne/peripherals/adxl345.h @@ -43,12 +43,12 @@ 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 }; diff --git a/sw/airborne/peripherals/adxl345_i2c.h b/sw/airborne/peripherals/adxl345_i2c.h index 2bbd51f7095..bd14e77d508 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.h b/sw/airborne/peripherals/adxl345_spi.h index fc4139a7542..bb391ea3e76 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.h b/sw/airborne/peripherals/ak8963.h index 92db595306a..3ab7a7eee42 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 4a2f972c8d4..800bd00aaa2 100644 --- a/sw/airborne/peripherals/ak8975.c +++ b/sw/airborne/peripherals/ak8975.c @@ -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; diff --git a/sw/airborne/peripherals/ak8975.h b/sw/airborne/peripherals/ak8975.h index bf06c8fcc53..02e03a17b3b 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 0d3d55f1dc1..d88e6818b67 100644 --- a/sw/airborne/peripherals/bmp085.c +++ b/sw/airborne/peripherals/bmp085.c @@ -64,7 +64,7 @@ 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; } diff --git a/sw/airborne/peripherals/bmp085.h b/sw/airborne/peripherals/bmp085.h index eab6924d034..3722d743f57 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 ef7593bf271..0431a9950dd 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 @@ -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,7 +275,7 @@ 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; @@ -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,7 +309,7 @@ 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; @@ -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,7 +338,7 @@ 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 */ @@ -370,7 +370,7 @@ bool_t cyrf6936_multi_write(struct Cyrf6936 *cyrf, const uint8_t data[][2], cons /** * 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; @@ -409,7 +409,7 @@ bool_t cyrf6936_write_chan_sop_data_crc(struct Cyrf6936 *cyrf, const uint8_t cha /** * 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) { @@ -429,7 +429,7 @@ bool_t cyrf6936_read_rx_irq_status_packet(struct Cyrf6936 *cyrf) /** * 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; diff --git a/sw/airborne/peripherals/cyrf6936.h b/sw/airborne/peripherals/cyrf6936.h index 111de18e0c4..680263155a4 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.h b/sw/airborne/peripherals/eeprom25AA256.h index 7f5e9760cf9..48c43363449 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/hmc58xx.h b/sw/airborne/peripherals/hmc58xx.h index 30769864f4a..c91cd9f004e 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.h b/sw/airborne/peripherals/itg3200.h index 4648f581243..5971b1ab3e0 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.h b/sw/airborne/peripherals/l3g4200.h index cb94932bbfd..11bc530d72e 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 23676eb9bcc..d0843a310d5 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 diff --git a/sw/airborne/peripherals/l3gd20_spi.h b/sw/airborne/peripherals/l3gd20_spi.h index 42d50c4bb56..0bff591ee52 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 a71fabc96af..114b68e1234 100644 --- a/sw/airborne/peripherals/lis302dl.h +++ b/sw/airborne/peripherals/lis302dl.h @@ -42,13 +42,13 @@ 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 }; diff --git a/sw/airborne/peripherals/lis302dl_spi.h b/sw/airborne/peripherals/lis302dl_spi.h index 3fb9851fb9f..99794e4f36d 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.h b/sw/airborne/peripherals/lsm303dlhc.h index bfea938f9ec..2f4da82ddd4 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 a8ddc27eddc..5d38d2aaf30 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]; diff --git a/sw/airborne/peripherals/mcp355x.h b/sw/airborne/peripherals/mcp355x.h index cbc94e021f9..6134e3a7b64 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.h b/sw/airborne/peripherals/mpl3115.h index 096f91c4ce1..a7804e2f4bf 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.h b/sw/airborne/peripherals/mpu60x0.h index 693068ad3c7..4293cb6b26a 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 1a403896ccd..b2e1a40bcfe 100644 --- a/sw/airborne/peripherals/mpu60x0_i2c.c +++ b/sw/airborne/peripherals/mpu60x0_i2c.c @@ -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); diff --git a/sw/airborne/peripherals/mpu60x0_i2c.h b/sw/airborne/peripherals/mpu60x0_i2c.h index 07e3de42555..f372ce1101a 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 b85885f069c..e3611d6e2d2 100644 --- a/sw/airborne/peripherals/mpu60x0_spi.c +++ b/sw/airborne/peripherals/mpu60x0_spi.c @@ -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); diff --git a/sw/airborne/peripherals/mpu60x0_spi.h b/sw/airborne/peripherals/mpu60x0_spi.h index fa7e5ab039c..2baae15f015 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.h b/sw/airborne/peripherals/mpu9250.h index fd8daa80572..2ad631df5c4 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 9cd52538a3e..eaeb610d0f2 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) @@ -151,7 +151,7 @@ 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); @@ -164,7 +164,7 @@ bool_t imu_mpu9250_configure_mag_slave(Mpu9250ConfigSet mpu_set __attribute__((u } /** 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); diff --git a/sw/airborne/peripherals/mpu9250_i2c.h b/sw/airborne/peripherals/mpu9250_i2c.h index dd22192fc34..0d6a9bc2c55 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 ac6ed5667f3..2b02d57407e 100644 --- a/sw/airborne/peripherals/mpu9250_spi.c +++ b/sw/airborne/peripherals/mpu9250_spi.c @@ -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); diff --git a/sw/airborne/peripherals/mpu9250_spi.h b/sw/airborne/peripherals/mpu9250_spi.h index 2b8866c7423..30cb5c2a485 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 99ed156f105..27894cf892d 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; @@ -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; @@ -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; diff --git a/sw/airborne/peripherals/ms5611.h b/sw/airborne/peripherals/ms5611.h index dd51cff1e86..14ace57d285 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 ccc2c9017ee..32827f87d0f 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; diff --git a/sw/airborne/peripherals/ms5611_i2c.h b/sw/airborne/peripherals/ms5611_i2c.h index 8954e66a8cb..11f55233803 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 a3b8d0e988e..983d38f6bdd 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; diff --git a/sw/airborne/peripherals/ms5611_spi.h b/sw/airborne/peripherals/ms5611_spi.h index 5e8b809d291..d007edb9a02 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.h b/sw/airborne/peripherals/vn200_serial.h index dd57948477d..8228e420474 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 1e880f9ae76..fa5a60e2433 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 ee03721831e..9ce3360e61b 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.h b/sw/airborne/state.h index 80fd8da0c52..5a70e723eae 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. @@ -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 632af1f73bc..17ac5a19035 100644 --- a/sw/airborne/subsystems/actuators.c +++ b/sw/airborne/subsystems/actuators.c @@ -33,7 +33,7 @@ int16_t actuators[ACTUATORS_NB]; uint32_t actuators_delay_time; -bool_t actuators_delay_done; +bool actuators_delay_done; void actuators_init(void) { diff --git a/sw/airborne/subsystems/actuators.h b/sw/airborne/subsystems/actuators.h index cf6845847c8..0ed0343d277 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 36736168fc8..b93566b1ced 100644 --- a/sw/airborne/subsystems/actuators/actuators_asctec.c +++ b/sw/airborne/subsystems/actuators/actuators_asctec.c @@ -53,7 +53,7 @@ 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) { diff --git a/sw/airborne/subsystems/actuators/actuators_asctec.h b/sw/airborne/subsystems/actuators/actuators_asctec.h index 85ad1a5d4ff..6a06b4e30aa 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_esc32.c b/sw/airborne/subsystems/actuators/actuators_esc32.c index 95c001e8729..08d6d304cb1 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; diff --git a/sw/airborne/subsystems/actuators/motor_mixing.c b/sw/airborne/subsystems/actuators/motor_mixing.c index cd961951687..b23dd707bf0 100644 --- a/sw/airborne/subsystems/actuators/motor_mixing.c +++ b/sw/airborne/subsystems/actuators/motor_mixing.c @@ -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 f6ac0e9b8e1..90cef700ef1 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 617bd0b3775..6a00a6cf6be 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 3c9e5ba1d2c..643790ebaff 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c @@ -119,7 +119,7 @@ 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) { diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h index 4844c8f0dcf..9453f946b0f 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 0607ee9fe71..f7704fbaebb 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 5215ae621aa..cc27684fb09 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c @@ -116,7 +116,7 @@ void ahrs_dcm_init(void) 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 */ diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_dcm.h b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.h index 78dfe05fec5..1535b5326f3 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 c5df92a6cee..3fd4ac4459b 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.h b/sw/airborne/subsystems/ahrs/ahrs_float_invariant.h index 212b375a4af..8c48459913f 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 cde86242ae6..4ed31c934d1 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 e72c7cf1fc1..bc69cd5773d 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.c @@ -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) { diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h b/sw/airborne/subsystems/ahrs/ahrs_float_mlkf.h index 675d15eb890..1c66ff7bee0 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 d10dc3b1bcf..65ba01f4f74 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 c0e171c2b63..3a96a97efe3 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; diff --git a/sw/airborne/subsystems/ahrs/ahrs_gx3.h b/sw/airborne/subsystems/ahrs/ahrs_gx3.h index cf4aab3b8b7..be1dca40033 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; diff --git a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.c b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.c index ad751c447f8..ef688c14b99 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.c +++ b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.c @@ -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) { @@ -105,7 +105,7 @@ 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); @@ -119,7 +119,7 @@ static inline bool_t cut_rates(struct Int32Rates i1, struct Int32Rates i2, int32 } #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); diff --git a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.h b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.h index 0a0d73079de..8408f6cfbe3 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 07fac1776db..635110397ce 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 26eaa96ba95..73399869241 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.c +++ b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.c @@ -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) { diff --git a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.h b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.h index 59ea681ebb7..862750f22b0 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 accd5a40f84..9530c282b66 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 458a653f877..764138489c3 100644 --- a/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c +++ b/sw/airborne/subsystems/chibios-libopencm3/chibios_sdlog.c @@ -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)); @@ -122,7 +122,7 @@ bool_t chibios_logInit(void) } -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 55808d79cb9..24dc62d71f4 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 5428cc914e7..6bdfedeccf3 100644 --- a/sw/airborne/subsystems/chibios-libopencm3/printf.c +++ b/sw/airborne/subsystems/chibios-libopencm3/printf.c @@ -45,7 +45,7 @@ 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; @@ -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; @@ -292,7 +292,7 @@ void chvprintf(BaseSequentialStream *chp, const char *fmt, va_list ap) { 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; diff --git a/sw/airborne/subsystems/chibios-libopencm3/sdLog.c b/sw/airborne/subsystems/chibios-libopencm3/sdLog.c index 21e62e19d18..67e9e41f4a2 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 ecc2e109560..b9bd82fba5a 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 5c06b18de22..8144b683b95 100644 --- a/sw/airborne/subsystems/chibios-libopencm3/sdio.c +++ b/sw/airborne/subsystems/chibios-libopencm3/sdio.c @@ -52,7 +52,7 @@ static enum {STOP, CONNECT} cnxState = STOP; -bool_t sdioConnect (void) +bool sdioConnect (void) { if (!sdc_lld_is_card_inserted (NULL)) { return FALSE; @@ -89,7 +89,7 @@ bool_t sdioConnect (void) } -bool_t sdioDisconnect (void) +bool sdioDisconnect (void) { if (cnxState == STOP) return TRUE; @@ -101,7 +101,7 @@ bool_t sdioDisconnect (void) 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; @@ -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 ec07ffe30ef..b55af11d533 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 a1e4eaf29ea..1733c5e500b 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 cdb33ff53f0..f6e6aa678f1 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 dbb7c9ed2ab..e3be6d159ca 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) && @@ -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); @@ -333,7 +333,7 @@ bool_t msd_scsi_process_inquiry(USBMassStorageDriver *msdp) { /** * @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; @@ -348,7 +348,7 @@ bool_t msd_scsi_process_request_sense(USBMassStorageDriver *msdp) { /** * @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; @@ -365,7 +365,7 @@ bool_t msd_scsi_process_read_capacity_10(USBMassStorageDriver *msdp) { /** * @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); @@ -389,7 +389,7 @@ bool_t msd_scsi_process_send_diagnostic(USBMassStorageDriver *msdp) { /** * @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); @@ -509,7 +509,7 @@ bool_t msd_scsi_process_start_read_write_10(USBMassStorageDriver *msdp) { /** * @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 */ @@ -526,7 +526,7 @@ bool_t msd_scsi_process_start_stop_unit(USBMassStorageDriver *msdp) { /** * @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 */ @@ -545,7 +545,7 @@ bool_t msd_scsi_process_mode_sense_6(USBMassStorageDriver *msdp) { /** * @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; @@ -562,7 +562,7 @@ bool_t msd_scsi_process_read_format_capacities(USBMassStorageDriver *msdp) { /** * @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 */ @@ -583,7 +583,7 @@ bool_t msd_scsi_process_test_unit_ready(USBMassStorageDriver *msdp) { /** * @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; @@ -595,7 +595,7 @@ bool_t msd_wait_for_command_block(USBMassStorageDriver *msdp) { /** * @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); @@ -619,7 +619,7 @@ bool_t msd_read_command_block(USBMassStorageDriver *msdp) { return FALSE; } - bool_t sleep = FALSE; + bool sleep = FALSE; /* check the command */ switch (cbw->scsi_cmd_data[0]) { @@ -730,7 +730,7 @@ 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); diff --git a/sw/airborne/subsystems/chibios-libopencm3/usb_msd.h b/sw/airborne/subsystems/chibios-libopencm3/usb_msd.h index 249db804186..cb37a0eb429 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 2a1801570ae..002be05c238 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; } @@ -391,9 +391,9 @@ 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; diff --git a/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.h b/sw/airborne/subsystems/chibios-libopencm3/varLengthMsgQ.h index 9e0e621b712..1945c10b9a3 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 82e83e41e92..ba851ffd753 100644 --- a/sw/airborne/subsystems/datalink/bluegiga.c +++ b/sw/airborne/subsystems/datalink/bluegiga.c @@ -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 52ac9355938..5b9ef9f059a 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 92916fd2448..bdaaf8be111 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 8d4a53c4567..61fa4a710cb 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 */ @@ -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 f994a3b7482..2bc0f94dcf0 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; @@ -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; @@ -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 9d194a6497b..25f0d83390d 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 4b040e04885..ccdb06a8d1b 100644 --- a/sw/airborne/subsystems/datalink/w5100.c +++ b/sw/airborne/subsystems/datalink/w5100.c @@ -361,7 +361,7 @@ 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; diff --git a/sw/airborne/subsystems/datalink/w5100.h b/sw/airborne/subsystems/datalink/w5100.h index 360cb695cfe..aa0464f04db 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 diff --git a/sw/airborne/subsystems/electrical.c b/sw/airborne/subsystems/electrical.c index 99d376809c9..3d3295aef68 100644 --- a/sw/airborne/subsystems/electrical.c +++ b/sw/airborne/subsystems/electrical.c @@ -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 / diff --git a/sw/airborne/subsystems/electrical.h b/sw/airborne/subsystems/electrical.h index b805949fb82..0580a182fcc 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 afe639f616d..58c8ce550fd 100644 --- a/sw/airborne/subsystems/gps.h +++ b/sw/airborne/subsystems/gps.h @@ -149,9 +149,9 @@ 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; } diff --git a/sw/airborne/subsystems/gps/gps_mtk.c b/sw/airborne/subsystems/gps/gps_mtk.c index 7ff1b4415bf..56c1686af0c 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 @@ -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: diff --git a/sw/airborne/subsystems/gps/gps_mtk.h b/sw/airborne/subsystems/gps/gps_mtk.h index 26e3673e637..b20f7b3da3f 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 105191d2770..2c6dbd10588 100644 --- a/sw/airborne/subsystems/gps/gps_nmea.c +++ b/sw/airborne/subsystems/gps/gps_nmea.c @@ -492,7 +492,7 @@ 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; } diff --git a/sw/airborne/subsystems/gps/gps_nmea.h b/sw/airborne/subsystems/gps/gps_nmea.h index 43d9abb2619..d0815d2cb2f 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 451e65fc049..1d112619925 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) diff --git a/sw/airborne/subsystems/gps/gps_sim_nps.c b/sw/airborne/subsystems/gps/gps_sim_nps.c index 7ca31f7a3a5..e6a88ee6790 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) { diff --git a/sw/airborne/subsystems/gps/gps_sim_nps.h b/sw/airborne/subsystems/gps/gps_sim_nps.h index f935277c992..ab5fe8ab3bb 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.h b/sw/airborne/subsystems/gps/gps_sirf.h index ae3f9d0b1ff..d57a910a153 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.h b/sw/airborne/subsystems/gps/gps_skytraq.h index f8cc166f6e1..45ff59c233c 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.h b/sw/airborne/subsystems/gps/gps_ubx.h index 2f7dabc2541..09bbfb381b5 100644 --- a/sw/airborne/subsystems/gps/gps_ubx.h +++ b/sw/airborne/subsystems/gps/gps_ubx.h @@ -51,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.h b/sw/airborne/subsystems/imu.h index fcea81e2183..1a7f9d05065 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_2_spi.c b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.c index a248891e9df..b24a6593e04 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) { @@ -256,7 +256,7 @@ 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 diff --git a/sw/airborne/subsystems/imu/imu_aspirin_2_spi.h b/sw/airborne/subsystems/imu/imu_aspirin_2_spi.h index a51178da42a..98da9f35645 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_crista.c b/sw/airborne/subsystems/imu/imu_crista.c index e6979d7a0f1..1234fc91359 100644 --- a/sw/airborne/subsystems/imu/imu_crista.c +++ b/sw/airborne/subsystems/imu/imu_crista.c @@ -22,7 +22,7 @@ #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) diff --git a/sw/airborne/subsystems/imu/imu_crista.h b/sw/airborne/subsystems/imu/imu_crista.h index 326230c0c1a..1f516151150 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 3f495d3f74f..a67275083da 100644 --- a/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.c +++ b/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.c @@ -162,7 +162,7 @@ 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); diff --git a/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.h b/sw/airborne/subsystems/imu/imu_drotek_10dof_v2.h index bc19091d4e9..3bad6832abe 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_mpu9250_spi.c b/sw/airborne/subsystems/imu/imu_mpu9250_spi.c index c4c24e0205a..f32fe6b2904 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) { @@ -227,7 +227,7 @@ 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 diff --git a/sw/airborne/subsystems/imu/imu_mpu9250_spi.h b/sw/airborne/subsystems/imu/imu_mpu9250_spi.h index 50a25ae94f0..4dc462db96f 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_um6.c b/sw/airborne/subsystems/imu/imu_um6.c index 38937610855..77b1d858de0 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); diff --git a/sw/airborne/subsystems/imu/imu_um6.h b/sw/airborne/subsystems/imu/imu_um6.h index 9aada3073ad..a8fbf532b27 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]; diff --git a/sw/airborne/subsystems/ins/hf_float.h b/sw/airborne/subsystems/ins/hf_float.h index 3d2d01091b6..7d6e43eab79 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.h b/sw/airborne/subsystems/ins/ins_alt_float.h index 5f0c1478825..fba52d955d1 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 124c191d74c..870201f6042 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); diff --git a/sw/airborne/subsystems/ins/ins_float_invariant.h b/sw/airborne/subsystems/ins/ins_float_invariant.h index 02fd90403e4..034764e07a9 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 93bf552ffe5..534e127ecb0 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; diff --git a/sw/airborne/subsystems/ins/ins_int.h b/sw/airborne/subsystems/ins/ins_int.h index dc5f2c81fb1..f6a71732dbe 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.h b/sw/airborne/subsystems/ins/ins_vectornav.h index 02848f2583b..83654cb374c 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 7f4b5c68f26..678595428f3 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; } diff --git a/sw/airborne/subsystems/intermcu/intermcu_ap.h b/sw/airborne/subsystems/intermcu/intermcu_ap.h index 6cee9f703c7..aba906327e3 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 97abc6407c6..7b32f62107e 100644 --- a/sw/airborne/subsystems/intermcu/intermcu_fbw.c +++ b/sw/airborne/subsystems/intermcu/intermcu_fbw.c @@ -37,7 +37,7 @@ #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; +static bool px4RebootTimeout = FALSE; uint8_t autopilot_motors_on = FALSE; tid_t px4bl_tid; ///< id for time out of the px4 bootloader reset #endif diff --git a/sw/airborne/subsystems/navigation/common_nav.c b/sw/airborne/subsystems/navigation/common_nav.c index 1e4abe56d16..897e390c4a6 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 b5afffd8ac1..4d7895533cb 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; diff --git a/sw/airborne/subsystems/navigation/nav_survey_rectangle.c b/sw/airborne/subsystems/navigation/nav_survey_rectangle.c index 8aed2396d93..c05c8cde6eb 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)) diff --git a/sw/airborne/subsystems/navigation/waypoints.c b/sw/airborne/subsystems/navigation/waypoints.c index f865e3865ce..11a398f6629 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,7 +52,7 @@ 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); diff --git a/sw/airborne/subsystems/navigation/waypoints.h b/sw/airborne/subsystems/navigation/waypoints.h index 4be4a1971c1..fca79229146 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 f6793b00fd2..22b58e1e6bf 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. diff --git a/sw/airborne/subsystems/radio_control/ppm.h b/sw/airborne/subsystems/radio_control/ppm.h index 022abb9d7c7..fd7f26334e7 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 b0214e62111..d059bbafa30 100644 --- a/sw/airborne/subsystems/radio_control/rc_datalink.c +++ b/sw/airborne/subsystems/radio_control/rc_datalink.c @@ -28,7 +28,7 @@ #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) diff --git a/sw/airborne/subsystems/radio_control/rc_datalink.h b/sw/airborne/subsystems/radio_control/rc_datalink.h index 432f5fcddb5..25acc0dbfc7 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_common.c b/sw/airborne/subsystems/radio_control/sbus_common.c index 774eaae6079..929bee16701 100644 --- a/sw/airborne/subsystems/radio_control/sbus_common.c +++ b/sw/airborne/subsystems/radio_control/sbus_common.c @@ -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 66fc1b0c468..b47c5537b4c 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/sensors/infrared_i2c.c b/sw/airborne/subsystems/sensors/infrared_i2c.c index 82912dff7be..09f253f586f 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 diff --git a/sw/airborne/subsystems/sensors/infrared_i2c.h b/sw/airborne/subsystems/sensors/infrared_i2c.h index 9bc26116097..214fc9cd299 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; diff --git a/sw/airborne/subsystems/settings.c b/sw/airborne/subsystems/settings.c index 3c9070c34d8..3897b84ab36 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) diff --git a/sw/airborne/subsystems/settings.h b/sw/airborne/subsystems/settings.h index e52e6037d96..4ab6b87957d 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/test_algebra.c b/sw/airborne/test/test_algebra.c index a5ff10c96a7..5a44973ef31 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 3ae7ecd4e15..6d43a9f3ba8 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) { diff --git a/sw/ext/pprzlink b/sw/ext/pprzlink index 2b246f6480a..c323e3cce1a 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 f4e89829e99..2e37ca4833e 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 cbb5b152af0..bdb256c80e4 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 1632c875b26..14eff0ee482 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 a85cd71dab8..db0e984b7a7 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/misc/rctx/main_rctx.c b/sw/misc/rctx/main_rctx.c index 9ad792c5b3e..175d174bfc3 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 0bbf4253172..9957524e428 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 ce874d96b3b..c1c02697135 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 9df70a48a7e..73d4e414bd4 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 f67b7c3236a..f76b249450d 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 7968e9f586c..a77def5fcc0 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 3b532aae6c6..aab90f39b07 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 ad1c5f23912..6b01a84499f 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 fa35ee97b44..cfe1398739c 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 2fd1663dc77..b28e02ad13b 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 4f555b1d6d2..433883650bf 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 b849f627d08..50f721355bb 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 a781adb20f6..6a4a28aa838 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 598bd308306..62083638cab 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 ddb33703da8..02ab18365dd 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 d1cf6f1356e..53e201f813b 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 cdae3ae3e5f..2ae2fb7e86f 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 d640c8e159c..aedf4a251f0 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 f444cedee0b..1ee80a3eded 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 decc63e907d..4f67a864c6f 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_flight_plan.ml b/sw/tools/generators/gen_flight_plan.ml index f48841f4d59..486f4e2a5ea 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