Paparazzi UAS
v5.15_devel-230-gc96ce27
Paparazzi is a free software Unmanned Aircraft System.
|
Airspeed driver for the SDP3X pressure sensor via I2C. More...
#include "std.h"
#include "mcu_periph/i2c.h"
#include "modules/sensors/airspeed_sdp3x.h"
#include "filters/low_pass_filter.h"
#include "subsystems/abi.h"
#include "mcu_periph/uart.h"
#include "pprzlink/messages.h"
#include "subsystems/datalink/downlink.h"
#include "subsystems/datalink/telemetry.h"
Go to the source code of this file.
Macros | |
#define | USE_AIRSPEED_LOWPASS_FILTER TRUE |
Use low pass filter on pressure values. More... | |
#define | SDP3X_SCALE_TEMPERATURE 200.0f |
Commands and scales. More... | |
#define | SDP3X_RESET_ADDR 0x00 |
#define | SDP3X_RESET_CMD 0x06 |
#define | SDP3X_CONT_MEAS_AVG_MODE 0x3615 |
#define | SDP3X_CONT_NONE_MODE 0x361E |
#define | SDP3X_SCALE_PRESSURE_SDP31 60 |
#define | SDP3X_SCALE_PRESSURE_SDP32 240 |
#define | SDP3X_SCALE_PRESSURE_SDP33 20 |
#define | SDP3X_I2C_ADDR 0x42 |
Sensor I2C slave address (existing defaults 0x42, 0x44 and 0x46) More... | |
#define | SDP3X_MODE SDP3X_CONT_MEAS_AVG_MODE |
Default operation mode. More... | |
#define | SDP3X_PRESSURE_SCALE SDP3X_SCALE_PRESSURE_SDP31 |
Default scale for SDP31. More... | |
#define | SDP3X_PRESSURE_OFFSET 0.f |
#define | SDP3X_SYNC_SEND FALSE |
Send a AIRSPEED_MS45XX message with every new measurement. More... | |
#define | SDP3X_AIRSPEED_SCALE 1.6327 |
Quadratic scale factor for indicated airspeed. More... | |
#define | SDP3X_LOWPASS_TAU 0.15 |
Time constant for second order Butterworth low pass filter Default of 0.15 should give cut-off freq of 1/(2*pi*tau) ~= 1Hz. More... | |
#define | AUTOSET_NB_MAX 20 |
Functions | |
static bool | sdp3x_crc (const uint8_t data[], unsigned size, uint8_t checksum) |
static void | sdp3x_downlink (struct transport_tx *trans, struct link_device *dev) |
void | sdp3x_init (void) |
void | sdp3x_periodic (void) |
void | sdp3x_event (void) |
Variables | |
struct AirspeedSdp3x | sdp3x |
static struct i2c_transaction | sdp3x_trans |
static Butterworth2LowPass | sdp3x_filter |
Airspeed driver for the SDP3X pressure sensor via I2C.
Definition in file airspeed_sdp3x.c.
#define AUTOSET_NB_MAX 20 |
Definition at line 196 of file airspeed_sdp3x.c.
Referenced by sdp3x_event().
#define SDP3X_AIRSPEED_SCALE 1.6327 |
Quadratic scale factor for indicated airspeed.
airspeed = sqrt(2*p_diff/density) With p_diff in Pa and standard air density of 1.225 kg/m^3, default airspeed scale is 2/1.225
Definition at line 105 of file airspeed_sdp3x.c.
Referenced by sdp3x_init().
#define SDP3X_CONT_MEAS_AVG_MODE 0x3615 |
Definition at line 58 of file airspeed_sdp3x.c.
#define SDP3X_CONT_NONE_MODE 0x361E |
Definition at line 59 of file airspeed_sdp3x.c.
#define SDP3X_I2C_ADDR 0x42 |
Sensor I2C slave address (existing defaults 0x42, 0x44 and 0x46)
Definition at line 68 of file airspeed_sdp3x.c.
Referenced by sdp3x_periodic().
#define SDP3X_LOWPASS_TAU 0.15 |
Time constant for second order Butterworth low pass filter Default of 0.15 should give cut-off freq of 1/(2*pi*tau) ~= 1Hz.
Definition at line 112 of file airspeed_sdp3x.c.
Referenced by sdp3x_init().
#define SDP3X_MODE SDP3X_CONT_MEAS_AVG_MODE |
Default operation mode.
Definition at line 74 of file airspeed_sdp3x.c.
Referenced by sdp3x_periodic().
#define SDP3X_PRESSURE_OFFSET 0.f |
Definition at line 86 of file airspeed_sdp3x.c.
Referenced by sdp3x_init().
#define SDP3X_PRESSURE_SCALE SDP3X_SCALE_PRESSURE_SDP31 |
Default scale for SDP31.
Definition at line 80 of file airspeed_sdp3x.c.
Referenced by sdp3x_init().
#define SDP3X_RESET_ADDR 0x00 |
Definition at line 55 of file airspeed_sdp3x.c.
#define SDP3X_RESET_CMD 0x06 |
Definition at line 56 of file airspeed_sdp3x.c.
#define SDP3X_SCALE_PRESSURE_SDP31 60 |
Definition at line 61 of file airspeed_sdp3x.c.
#define SDP3X_SCALE_PRESSURE_SDP32 240 |
Definition at line 62 of file airspeed_sdp3x.c.
#define SDP3X_SCALE_PRESSURE_SDP33 20 |
Definition at line 63 of file airspeed_sdp3x.c.
#define SDP3X_SCALE_TEMPERATURE 200.0f |
#define SDP3X_SYNC_SEND FALSE |
Send a AIRSPEED_MS45XX message with every new measurement.
FIXME Mainly for debugging, use with caution, sends message at ~100Hz.
Definition at line 96 of file airspeed_sdp3x.c.
Referenced by sdp3x_init().
#define USE_AIRSPEED_LOWPASS_FILTER TRUE |
Use low pass filter on pressure values.
Definition at line 49 of file airspeed_sdp3x.c.
Definition at line 122 of file airspeed_sdp3x.c.
Referenced by sdp3x_event().
|
static |
Definition at line 144 of file airspeed_sdp3x.c.
References AirspeedSdp3x::airspeed, AirspeedSdp3x::pressure, sdp3x, and AirspeedSdp3x::temperature.
Referenced by sdp3x_event(), and sdp3x_init().
void sdp3x_event | ( | void | ) |
Definition at line 198 of file airspeed_sdp3x.c.
References AirspeedSdp3x::airspeed, AirspeedSdp3x::airspeed_scale, AIRSPEED_SDP3X_ID, AUTOSET_NB_MAX, AirspeedSdp3x::autoset_offset, i2c_transaction::buf, DefaultChannel, DefaultDevice, I2CTransDone, I2CTransFailed, I2CTransSuccess, AirspeedSdp3x::initialized, Max, AirspeedSdp3x::pressure, AirspeedSdp3x::pressure_offset, AirspeedSdp3x::pressure_scale, sdp3x, sdp3x_crc(), sdp3x_downlink(), SDP3X_SCALE_TEMPERATURE, SDP3X_SENDER_ID, sdp3x_trans, i2c_transaction::status, AirspeedSdp3x::sync_send, AirspeedSdp3x::temperature, and update_butterworth_2_low_pass().
void sdp3x_init | ( | void | ) |
Definition at line 153 of file airspeed_sdp3x.c.
References AirspeedSdp3x::airspeed, AirspeedSdp3x::airspeed_scale, AirspeedSdp3x::autoset_offset, DefaultPeriodic, I2CTransDone, init_butterworth_2_low_pass(), AirspeedSdp3x::initialized, AirspeedSdp3x::pressure, AirspeedSdp3x::pressure_offset, AirspeedSdp3x::pressure_scale, register_periodic_telemetry(), sdp3x, SDP3X_AIRSPEED_SCALE, sdp3x_downlink(), SDP3X_LOWPASS_TAU, SDP3X_PRESSURE_OFFSET, SDP3X_PRESSURE_SCALE, SDP3X_SYNC_SEND, sdp3x_trans, i2c_transaction::status, AirspeedSdp3x::sync_send, and AirspeedSdp3x::temperature.
void sdp3x_periodic | ( | void | ) |
Definition at line 177 of file airspeed_sdp3x.c.
References i2c_transaction::buf, i2c_receive(), i2c_transmit(), I2CTransDone, AirspeedSdp3x::initialized, sdp3x, SDP3X_I2C_ADDR, SDP3X_MODE, sdp3x_trans, and i2c_transaction::status.
struct AirspeedSdp3x sdp3x |
Definition at line 115 of file airspeed_sdp3x.c.
Referenced by sdp3x_downlink(), sdp3x_event(), sdp3x_init(), and sdp3x_periodic().
|
static |
Definition at line 119 of file airspeed_sdp3x.c.
|
static |
Definition at line 116 of file airspeed_sdp3x.c.
Referenced by sdp3x_event(), sdp3x_init(), and sdp3x_periodic().