32 #include "pprzlink/messages.h"
35 #if PERIODIC_TELEMETRY
39 #ifndef USE_AIRSPEED_SDP3X
41 #define USE_AIRSPEED_SDP3X TRUE
42 PRINT_CONFIG_MSG(
"USE_AIRSPEED_SDP3X set to TRUE since this is set USE_AIRSPEED")
48 #ifndef USE_AIRSPEED_LOWPASS_FILTER
49 #define USE_AIRSPEED_LOWPASS_FILTER TRUE
54 #define SDP3X_SCALE_TEMPERATURE 200.0f
55 #define SDP3X_RESET_ADDR 0x00
56 #define SDP3X_RESET_CMD 0x06
58 #define SDP3X_CONT_MEAS_AVG_MODE 0x3615
59 #define SDP3X_CONT_NONE_MODE 0x361E
61 #define SDP3X_SCALE_PRESSURE_SDP31 60
62 #define SDP3X_SCALE_PRESSURE_SDP32 240
63 #define SDP3X_SCALE_PRESSURE_SDP33 20
67 #ifndef SDP3X_I2C_ADDR
68 #define SDP3X_I2C_ADDR 0x42
74 #define SDP3X_MODE SDP3X_CONT_MEAS_AVG_MODE
79 #ifndef SDP3X_PRESSURE_SCALE
80 #define SDP3X_PRESSURE_SCALE SDP3X_SCALE_PRESSURE_SDP31
85 #ifndef SDP3X_PRESSURE_OFFSET
86 #define SDP3X_PRESSURE_OFFSET 0.f
95 #ifndef SDP3X_SYNC_SEND
96 #define SDP3X_SYNC_SEND FALSE
104 #ifndef SDP3X_AIRSPEED_SCALE
105 #define SDP3X_AIRSPEED_SCALE 1.6327
111 #ifndef SDP3X_LOWPASS_TAU
112 #define SDP3X_LOWPASS_TAU 0.15
118 #ifdef USE_AIRSPEED_LOWPASS_FILTER
127 for (
unsigned i = 0; i < size; i++) {
128 crc_value ^= (data[i]);
130 for (
int bit = 8; bit > 0; --bit) {
131 if (crc_value & 0x80) {
132 crc_value = (crc_value << 1) ^ 0x31;
135 crc_value = (crc_value << 1);
147 pprz_msg_send_AIRSPEED_RAW(trans,
dev,AC_ID,
170 #ifdef USE_AIRSPEED_LOWPASS_FILTER
172 SDP3X_PERIODIC_PERIOD, 0);
175 #if PERIODIC_TELEMETRY
199 #define AUTOSET_NB_MAX 20
207 static int autoset_nb = 0;
208 static float autoset_offset = 0.f;
210 for (
uint8_t i = 0; i < 6; i++) {
226 #ifdef USE_AIRSPEED_LOWPASS_FILTER
238 autoset_offset = 0.f;
254 #if USE_AIRSPEED_SDP3X
Main include for ABI (AirBorneInterface).
#define AIRSPEED_SDP3X_ID
#define SDP3X_SCALE_TEMPERATURE
Commands and scales.
#define SDP3X_LOWPASS_TAU
Time constant for second order Butterworth low pass filter Default of 0.15 should give cut-off freq o...
struct AirspeedSdp3x sdp3x
#define SDP3X_MODE
Default operation mode.
static void sdp3x_downlink(struct transport_tx *trans, struct link_device *dev)
#define SDP3X_AIRSPEED_SCALE
Quadratic scale factor for indicated airspeed.
#define SDP3X_PRESSURE_OFFSET
#define SDP3X_PRESSURE_SCALE
Default scale for SDP31.
void sdp3x_periodic(void)
#define SDP3X_SYNC_SEND
Send a AIRSPEED_MS45XX message with every new measurement.
static struct i2c_transaction sdp3x_trans
static Butterworth2LowPass sdp3x_filter
#define SDP3X_I2C_ADDR
Sensor I2C slave address (existing defaults 0x42, 0x44 and 0x46)
static bool sdp3x_crc(const uint8_t data[], unsigned size, uint8_t checksum)
Airspeed driver for the SDP3X pressure sensor via I2C.
bool sync_send
Flag to enable sending every new measurement via telemetry for debugging purpose.
float pressure
(differential) pressure in Pascal
float airspeed_scale
Quadratic scale factor to convert (differential) pressure to airspeed.
bool initialized
init flag
float temperature
Temperature in deg Celcius.
uint16_t raw_p
raw value from chip
bool autoset_offset
Set offset value from current filtered value.
float pressure_scale
Scaling factor from raw measurement to Pascal.
float airspeed
Airspeed in m/s estimated from (differential) pressure.
float pressure_offset
Offset in Pascal.
Common code for AP and FBW telemetry.
volatile uint8_t buf[I2C_BUF_LEN]
Transaction buffer With I2C_BUF_LEN number of bytes.
enum I2CTransactionStatus status
Transaction status.
bool i2c_transmit(struct i2c_periph *p, struct i2c_transaction *t, uint8_t s_addr, uint8_t len)
Submit a write only transaction.
bool i2c_receive(struct i2c_periph *p, struct i2c_transaction *t, uint8_t s_addr, uint16_t len)
Submit a read only transaction.
@ I2CTransSuccess
transaction successfully finished by I2C driver
@ I2CTransFailed
transaction failed
@ I2CTransDone
transaction set to done by user level
I2C transaction structure.
Architecture independent I2C (Inter-Integrated Circuit Bus) API.
PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
Simple first order low pass filter with bilinear transform.
static void init_butterworth_2_low_pass(Butterworth2LowPass *filter, float tau, float sample_time, float value)
Init a second order Butterworth filter.
static float update_butterworth_2_low_pass(Butterworth2LowPass *filter, float value)
Update second order Butterworth low pass filter state with a new value.
Second order low pass filter structure.
PRINT_CONFIG_VAR(ONELOOP_ANDI_FILT_CUTOFF)
static const struct usb_device_descriptor dev
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Periodic telemetry system header (includes downlink utility and generated code).
#define DefaultPeriodic
Set default periodic telemetry.
arch independent UART (Universal Asynchronous Receiver/Transmitter) API
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
short int16_t
Typedef defining 16 bit short type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.