![]() |
Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
Handling of the MS5534a pressure sensor. More...
#include "modules/sensors/baro_MS5534A.h"
#include "mcu_periph/spi.h"
#include "mcu_periph/uart.h"
#include "modules/datalink/downlink.h"
#include "modules/core/abi.h"
#include "firmwares/fixedwing/nav.h"
#include "state.h"
Go to the source code of this file.
Macros | |
#define | STATUS_INIT1 0 |
#define | STATUS_INIT2 1 |
#define | STATUS_INIT3 2 |
#define | STATUS_INIT4 3 |
#define | STATUS_MEASURE_PRESSURE 4 |
#define | STATUS_MEASURE_TEMPERATURE 5 |
#define | STATUS_RESET 6 |
#define | InitStatus() (status <= STATUS_INIT4) |
#define | NextStatus() |
#define | CMD_INIT 0x1D |
#define | CMD_MEASUREMENT 0x0F |
#define | CMD_W1 0x50 |
#define | CMD_W2 0x60 |
#define | CMD_W3 0x90 |
#define | CMD_W4 0xA0 |
#define | CMD_PRESSURE 0x40 |
#define | CMD_TEMPERATURE 0x20 |
#define | Uint16(buf_input) (buf_input[0] << 8 | buf_input[1]) |
#define | MS5534A_MCLK 32768 |
#define | PWM_PERIOD ((PCLK / PWM_PRESCALER) / MS5534A_MCLK) |
#define | PWM_DUTY (PWM_PERIOD / 2) |
Functions | |
static void | calibration (void) |
void | baro_MS5534A_init (void) |
void | baro_MS5534A_reset (void) |
void | baro_MS5534A_send (void) |
void | baro_MS5534A_event_task (void) |
void | baro_MS5534A_event (void) |
Handling of the MS5534a pressure sensor.
uses: MOSI, MISO, SCK and 32kHz @ P0.7 with 5V for the -A type
Definition in file baro_MS5534A.c.
#define CMD_INIT 0x1D |
Definition at line 73 of file baro_MS5534A.c.
#define CMD_MEASUREMENT 0x0F |
Definition at line 74 of file baro_MS5534A.c.
#define CMD_PRESSURE 0x40 |
Definition at line 80 of file baro_MS5534A.c.
#define CMD_TEMPERATURE 0x20 |
Definition at line 81 of file baro_MS5534A.c.
#define CMD_W1 0x50 |
Definition at line 76 of file baro_MS5534A.c.
#define CMD_W2 0x60 |
Definition at line 77 of file baro_MS5534A.c.
#define CMD_W3 0x90 |
Definition at line 78 of file baro_MS5534A.c.
#define CMD_W4 0xA0 |
Definition at line 79 of file baro_MS5534A.c.
#define InitStatus | ( | ) | (status <= STATUS_INIT4) |
Definition at line 64 of file baro_MS5534A.c.
#define MS5534A_MCLK 32768 |
Definition at line 111 of file baro_MS5534A.c.
#define NextStatus | ( | ) |
Definition at line 66 of file baro_MS5534A.c.
#define PWM_DUTY (PWM_PERIOD / 2) |
Definition at line 113 of file baro_MS5534A.c.
#define PWM_PERIOD ((PCLK / PWM_PRESCALER) / MS5534A_MCLK) |
Definition at line 112 of file baro_MS5534A.c.
#define STATUS_INIT1 0 |
Definition at line 52 of file baro_MS5534A.c.
#define STATUS_INIT2 1 |
Definition at line 53 of file baro_MS5534A.c.
#define STATUS_INIT3 2 |
Definition at line 54 of file baro_MS5534A.c.
#define STATUS_INIT4 3 |
Definition at line 55 of file baro_MS5534A.c.
#define STATUS_MEASURE_PRESSURE 4 |
Definition at line 56 of file baro_MS5534A.c.
#define STATUS_MEASURE_TEMPERATURE 5 |
Definition at line 57 of file baro_MS5534A.c.
#define STATUS_RESET 6 |
Definition at line 58 of file baro_MS5534A.c.
Definition at line 90 of file baro_MS5534A.c.
Definition at line 267 of file baro_MS5534A.c.
References baro_MS5534A_available, baro_MS5534A_event_task(), baro_MS5534A_ground_pressure, baro_MS5534A_pressure, BARO_MS5534A_SENDER_ID, baro_MS5534A_temp, baro_MS5534A_z, DefaultChannel, DefaultDevice, foo, get_sys_time_usec(), and ground_alt.
Definition at line 230 of file baro_MS5534A.c.
References baro_MS5534A_available, baro_MS5534A_pressure, baro_MS5534A_send(), baro_MS5534A_temp, buf_input, c1, c2, c3, c4, c6, calibration(), d1, d2, foo, NextStatus, status, STATUS_INIT4, STATUS_MEASURE_PRESSURE, STATUS_MEASURE_TEMPERATURE, status_read_data, STATUS_RESET, Uint16, ut1, and words.
Referenced by baro_MS5534A_event().
Definition at line 118 of file baro_MS5534A.c.
References alt_baro_enabled, baro_MS5534A_available, baro_MS5534A_do_reset, baro_MS5534A_ground_pressure, baro_MS5534A_r, baro_MS5534A_sigma2, calibration(), foo, PWM_DUTY, PWM_PERIOD, status, STATUS_INIT1, STATUS_MEASURE_PRESSURE, status_read_data, and words.
Definition at line 162 of file baro_MS5534A.c.
References status, STATUS_INIT1, and status_read_data.
Definition at line 169 of file baro_MS5534A.c.
References buf_input, buf_output, CMD_INIT, CMD_MEASUREMENT, cmds, foo, InitStatus, reset, status, status_read_data, and STATUS_RESET.
Referenced by baro_MS5534A_event_task().
Definition at line 206 of file baro_MS5534A.c.
References c1, c2, c3, c4, c6, DefaultChannel, DefaultDevice, foo, ut1, and words.
Referenced by baro_MS5534A_event_task(), and baro_MS5534A_init().
bool alt_baro_enabled |
Definition at line 45 of file baro_MS5534A.c.
Referenced by alt_kalman(), and baro_MS5534A_init().
bool baro_MS5534A_available |
Definition at line 44 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event(), baro_MS5534A_event_task(), and baro_MS5534A_init().
bool baro_MS5534A_do_reset |
Definition at line 41 of file baro_MS5534A.c.
Referenced by baro_MS5534A_init().
uint32_t baro_MS5534A_ground_pressure |
Definition at line 46 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event(), and baro_MS5534A_init().
uint32_t baro_MS5534A_pressure |
Definition at line 42 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event(), and baro_MS5534A_event_task().
float baro_MS5534A_r |
Definition at line 47 of file baro_MS5534A.c.
Referenced by alt_kalman(), and baro_MS5534A_init().
float baro_MS5534A_sigma2 |
Definition at line 48 of file baro_MS5534A.c.
Referenced by alt_kalman(), and baro_MS5534A_init().
uint16_t baro_MS5534A_temp |
Definition at line 43 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event(), and baro_MS5534A_event_task().
float baro_MS5534A_z |
Definition at line 49 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event().
|
static |
Definition at line 87 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event_task(), and baro_MS5534A_send().
|
static |
Definition at line 88 of file baro_MS5534A.c.
Referenced by baro_MS5534A_send().
|
static |
Definition at line 203 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event_task(), calibration(), distributed_circular(), float_mat_minor_4d(), int32_atan2(), int32_atan2_2(), jpeg_DCT(), manage_flow_features(), nav_eight(), and xsens_ask_message_rate().
|
static |
Definition at line 203 of file baro_MS5534A.c.
Referenced by ahrs_fc_update_accel(), ahrs_icq_update_accel(), baro_MS5534A_event_task(), calibration(), distributed_circular(), float_mat_minor_4d(), float_quat_differential(), gc_of_gd_lat_d(), int32_atan2(), int32_atan2_2(), jpeg_DCT(), nav_eight(), and xsens_ask_message_rate().
|
static |
Definition at line 203 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event_task(), calibration(), and jpeg_DCT().
|
static |
Definition at line 203 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event_task(), and calibration().
|
static |
Definition at line 203 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event_task(), calibration(), and jpeg_DCT().
|
static |
Definition at line 82 of file baro_MS5534A.c.
Referenced by actuators_esc32_config_cmd(), actuators_esc32_duty(), baro_MS5534A_send(), and throttle_curve_run().
|
static |
Definition at line 202 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event_task(), gvf_segment_loop_wp1_wp2(), gvf_segment_loop_XY1_XY2(), and out_of_segment_area().
|
static |
Definition at line 202 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event_task(), gvf_segment_loop_wp1_wp2(), gvf_segment_loop_XY1_XY2(), out_of_segment_area(), and trilateration_compute().
|
static |
Definition at line 83 of file baro_MS5534A.c.
Referenced by baro_MS5534A_send(), cloud_sim_reset(), gps_ubx_event(), nav_return(), and rxSpiCheckBindRequested().
|
static |
Definition at line 60 of file baro_MS5534A.c.
Referenced by _vl53l5cx_poll_for_answer(), _vl53l5cx_poll_for_mcu_boot(), _vl53l5cx_send_offset_data(), _vl53l5cx_send_xtalk_data(), acInfoCalcPositionEnu_f(), acInfoCalcPositionEnu_i(), acInfoCalcPositionLla_f(), acInfoCalcPositionLla_i(), acInfoCalcPositionUtm_f(), acInfoCalcPositionUtm_i(), acInfoCalcVelocityEnu_f(), acInfoCalcVelocityEnu_i(), acInfoGetPositionEnu_f(), acInfoGetPositionEnu_i(), acInfoGetPositionLla_f(), acInfoGetPositionLla_i(), acInfoGetPositionUtm_f(), acInfoGetPositionUtm_i(), acInfoGetVelocityEnu_f(), acInfoGetVelocityEnu_i(), baro_MS5534A_event_task(), baro_MS5534A_init(), baro_MS5534A_reset(), baro_MS5534A_send(), can_thd_rx(), formation_flight(), jevois_mavlink_event(), lidar_lite_downlink(), lidar_sf11_downlink(), mavlink_event(), microrl_get_complite(), ms45xx_i2c_event(), msgqueue_pop_timeout(), new_line_handler(), parseFormationStatus(), power_uavcan_send_power_device(), py_check_status(), python_init(), rxSpiFrameStatus(), sdlog_check_free_space(), send_rotating_wing_state(), send_sdlog_status(), send_superbit(), set_ac_info_lla(), set_ac_info_utm(), slcan_handle_cmd(), start_formation(), stop_formation(), superbitrf_receive_packet_cb(), tcas_periodic_task_1Hz(), tfmini_send_lidar(), thd_lidar_vl53l5cx(), updateFormationStatus(), VL53L1X_BootState(), VL53L1X_CheckForDataReady(), VL53L1X_ClearInterrupt(), VL53L1X_GetAmbientPerSpad(), VL53L1X_GetAmbientRate(), VL53L1X_GetDistance(), VL53L1X_GetDistanceMode(), VL53L1X_GetDistanceThresholdHigh(), VL53L1X_GetDistanceThresholdLow(), VL53L1X_GetDistanceThresholdWindow(), VL53L1X_GetInterMeasurementInMs(), VL53L1X_GetInterruptPolarity(), VL53L1X_GetOffset(), VL53L1X_GetRangeStatus(), VL53L1X_GetResult(), VL53L1X_GetROI_XY(), VL53L1X_GetROICenter(), VL53L1X_GetSensorId(), VL53L1X_GetSigmaThreshold(), VL53L1X_GetSignalPerSpad(), VL53L1X_GetSignalRate(), VL53L1X_GetSignalThreshold(), VL53L1X_GetSpadNb(), VL53L1X_GetTimingBudgetInMs(), VL53L1X_GetXtalk(), VL53L1X_SensorInit(), VL53L1X_SetDistanceMode(), VL53L1X_SetDistanceThreshold(), VL53L1X_SetI2CAddress(), VL53L1X_SetInterMeasurementInMs(), VL53L1X_SetInterruptPolarity(), VL53L1X_SetOffset(), VL53L1X_SetROI(), VL53L1X_SetROICenter(), VL53L1X_SetSigmaThreshold(), VL53L1X_SetSignalThreshold(), VL53L1X_SetTimingBudgetInMs(), VL53L1X_SetXtalk(), VL53L1X_StartRanging(), VL53L1X_StartTemperatureUpdate(), VL53L1X_StopRanging(), vl53l5cx_check_data_ready(), vl53l5cx_dci_read_data(), vl53l5cx_dci_replace_data(), vl53l5cx_dci_write_data(), vl53l5cx_disable_internal_cp(), vl53l5cx_enable_internal_cp(), vl53l5cx_get_integration_time_ms(), vl53l5cx_get_power_mode(), vl53l5cx_get_ranging_data(), vl53l5cx_get_ranging_frequency_hz(), vl53l5cx_get_ranging_mode(), vl53l5cx_get_resolution(), vl53l5cx_get_sharpener_percent(), vl53l5cx_get_target_order(), vl53l5cx_init(), vl53l5cx_is_alive(), vl53l5cx_set_i2c_address(), vl53l5cx_set_integration_time_ms(), vl53l5cx_set_power_mode(), vl53l5cx_set_ranging_frequency_hz(), vl53l5cx_set_ranging_mode(), vl53l5cx_set_resolution(), vl53l5cx_set_sharpener_percent(), vl53l5cx_set_target_order(), vl53l5cx_start_ranging(), and vl53l5cx_stop_ranging().
|
static |
Definition at line 61 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event_task(), baro_MS5534A_init(), baro_MS5534A_reset(), and baro_MS5534A_send().
|
static |
Definition at line 203 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event_task(), and calibration().
|
static |
Definition at line 62 of file baro_MS5534A.c.
Referenced by baro_MS5534A_event_task(), baro_MS5534A_init(), calibration(), and fletcher32().