|
Paparazzi UAS
v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
|
Go to the documentation of this file.
38 #include "pprzlink/messages.h"
48 #ifndef PX4FLOW_QUALITY_THRESHOLD
49 #define PX4FLOW_QUALITY_THRESHOLD 0.1
56 #define PX4FLOW_I2C_FRAME 0x0
57 #define PX4FLOW_I2C_INTEGRAL_FRAME 0x16
58 #define PX4FLOW_I2C_FRAME_LENGTH 22
59 #define PX4FLOW_I2C_INTEGRAL_FRAME_LENGTH 25
60 #define PX4FLOW_I2C_ID 0x4D
67 static float quality = 0;
68 static float noise = 0;
72 noise = noise * noise;
74 static float timestamp = 0;
77 static float flow_comp_m_x = 0.0;
78 static float flow_comp_m_y = 0.0;
82 time_usec = (
uint32_t)(timestamp * 1e6);
100 static int32_t ground_distance = 0;
101 static float ground_distance_float = 0.0;
105 ground_distance_float = ((float)ground_distance) / 1000.0;
111 float gain = (float)fabs( (
double) (cosf(phi) * cosf(theta)));
112 ground_distance_float = ground_distance_float / gain;
138 #if REQUEST_INT_FRAME
270 static uint8_t distance_quality = 0;
272 #if REQUEST_INT_FRAME
276 float flow_comp_m_x = 0.0;
277 float flow_comp_m_y = 0.0;
uint16_t frame_count_since_last_readout
volatile uint8_t buf[I2C_BUF_LEN]
Transaction buffer With I2C_BUF_LEN number of bytes.
static void px4flow_i2c_frame_cb(void)
Propagate optical flow information.
@ PX4FLOW_INT_FRAME_REC_OK
static float get_sys_time_float(void)
Get the time in seconds since startup.
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
struct i2c_transaction trans
int16_t pixel_flow_y_integral
int16_t gyro_x_rate_integral
void px4flow_i2c_downlink(void)
Downlink message for debug Copy volatile variables from the px4_i2c_frame for safety.
#define PX4FLOW_I2C_FRAME_LENGTH
@ I2CTransSuccess
transaction successfully finished by I2C driver
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
#define PX4FLOW_I2C_INTEGRAL_FRAME
int16_t pixel_flow_x_integral
bool i2c_transmit(struct i2c_periph *p, struct i2c_transaction *t, uint8_t s_addr, uint8_t len)
Submit a write only transaction.
struct px4flow_data px4flow
void px4flow_i2c_init(void)
Initialization function.
bool i2c_transceive(struct i2c_periph *p, struct i2c_transaction *t, uint8_t s_addr, uint8_t len_w, uint16_t len_r)
Submit a write/read transaction.
struct MedianFilterInt sonar_filter
enum I2CTransactionStatus status
Transaction status.
#define PX4FLOW_I2C_FRAME
if(GpsFixValid() &&e_identification_started)
uint16_t f
Camera baseline, in meters (i.e. horizontal distance between the two cameras of the stereo setup)
Common code for AP and FBW telemetry.
#define AGL_SONAR_PX4FLOW_ID
#define PX4FLOW_QUALITY_THRESHOLD
uint32_t integration_timespan
@ I2CTransDone
transaction set to done by user level
int16_t gyro_z_rate_integral
struct px4flow_i2c_integral_frame i2c_int_frame
static void px4flow_i2c_int_frame_cb(void)
Propagate itegral frame.
#define PX4FLOW_I2C_INTEGRAL_FRAME_LENGTH
struct px4flow_i2c_frame i2c_frame
void px4flow_i2c_periodic(void)
Poll px4flow for data 152 i2c frames are created per second, so the PX4FLOW can be polled at up to 15...
enum Px4FlowStatus status
int16_t gyro_y_rate_integral