Paparazzi UAS
v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
|
Go to the source code of this file.
Data Structures | |
struct | px4flow_i2c_frame |
struct | px4flow_i2c_integral_frame |
struct | px4flow_data |
Enumerations | |
enum | Px4FlowStatus { PX4FLOW_FRAME_REQ , PX4FLOW_FRAME_REC , PX4FLOW_INT_FRAME_REQ , PX4FLOW_INT_FRAME_REC , PX4FLOW_INT_FRAME_REC_OK } |
Functions | |
void | px4flow_i2c_init (void) |
Initialization function. More... | |
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 150Hz (faster rate won't bring any finer resolution) More... | |
void | px4flow_i2c_downlink (void) |
Downlink message for debug Copy volatile variables from the px4_i2c_frame for safety. More... | |
Variables | |
struct px4flow_data | px4flow |
struct px4flow_i2c_frame |
Definition at line 44 of file px4flow_i2c.h.
Data Fields | ||
---|---|---|
int16_t | flow_comp_m_x | |
int16_t | flow_comp_m_y | |
uint16_t | frame_count | |
int16_t | ground_distance | |
uint8_t | gyro_range | |
int16_t | gyro_x_rate | |
int16_t | gyro_y_rate | |
int16_t | gyro_z_rate | |
int16_t | pixel_flow_x_sum | |
int16_t | pixel_flow_y_sum | |
int16_t | qual | |
uint8_t | sonar_timestamp |
struct px4flow_i2c_integral_frame |
Definition at line 60 of file px4flow_i2c.h.
Data Fields | ||
---|---|---|
uint16_t | frame_count_since_last_readout | |
int16_t | ground_distance | |
int16_t | gyro_temperature | |
int16_t | gyro_x_rate_integral | |
int16_t | gyro_y_rate_integral | |
int16_t | gyro_z_rate_integral | |
uint32_t | integration_timespan | |
int16_t | pixel_flow_x_integral | |
int16_t | pixel_flow_y_integral | |
uint8_t | qual | |
uint32_t | sonar_timestamp |
struct px4flow_data |
Definition at line 75 of file px4flow_i2c.h.
Data Fields | ||
---|---|---|
uint8_t | addr | |
bool | compensate_rotation | |
struct px4flow_i2c_frame | i2c_frame | |
struct px4flow_i2c_integral_frame | i2c_int_frame | |
enum Px4FlowStatus | status | |
float | stddev | |
struct i2c_transaction | trans | |
bool | update_agl |
enum Px4FlowStatus |
Enumerator | |
---|---|
PX4FLOW_FRAME_REQ | |
PX4FLOW_FRAME_REC | |
PX4FLOW_INT_FRAME_REQ | |
PX4FLOW_INT_FRAME_REC | |
PX4FLOW_INT_FRAME_REC_OK |
Definition at line 36 of file px4flow_i2c.h.
void px4flow_i2c_downlink | ( | void | ) |
Downlink message for debug Copy volatile variables from the px4_i2c_frame for safety.
Definition at line 264 of file px4flow_i2c.c.
References DefaultChannel, DefaultDevice, px4flow_i2c_frame::flow_comp_m_x, px4flow_i2c_frame::flow_comp_m_y, get_sys_time_float(), px4flow_i2c_frame::ground_distance, px4flow_i2c_integral_frame::ground_distance, px4flow_data::i2c_frame, px4flow_data::i2c_int_frame, px4flow_i2c_integral_frame::pixel_flow_x_integral, px4flow_i2c_frame::pixel_flow_x_sum, px4flow_i2c_integral_frame::pixel_flow_y_integral, px4flow_i2c_frame::pixel_flow_y_sum, px4flow, PX4FLOW_I2C_ID, px4flow_i2c_frame::qual, and px4flow_i2c_integral_frame::qual.
void px4flow_i2c_init | ( | void | ) |
Initialization function.
Definition at line 134 of file px4flow_i2c.c.
References px4flow_data::addr, px4flow_data::compensate_rotation, I2CTransDone, init_median_filter_i(), px4flow, PX4FLOW_FRAME_REQ, PX4FLOW_INT_FRAME_REQ, sonar_filter, i2c_transaction::status, px4flow_data::status, px4flow_data::stddev, px4flow_data::trans, and px4flow_data::update_agl.
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 150Hz (faster rate won't bring any finer resolution)
Definition at line 155 of file px4flow_i2c.c.
References px4flow_data::addr, i2c_transaction::buf, px4flow_i2c_frame::flow_comp_m_x, px4flow_i2c_frame::flow_comp_m_y, px4flow_i2c_frame::frame_count, px4flow_i2c_integral_frame::frame_count_since_last_readout, px4flow_i2c_frame::ground_distance, px4flow_i2c_integral_frame::ground_distance, px4flow_i2c_frame::gyro_range, px4flow_i2c_integral_frame::gyro_temperature, px4flow_i2c_frame::gyro_x_rate, px4flow_i2c_integral_frame::gyro_x_rate_integral, px4flow_i2c_frame::gyro_y_rate, px4flow_i2c_integral_frame::gyro_y_rate_integral, px4flow_i2c_frame::gyro_z_rate, px4flow_i2c_integral_frame::gyro_z_rate_integral, px4flow_data::i2c_frame, px4flow_data::i2c_int_frame, i2c_transceive(), i2c_transmit(), I2CTransSuccess, idx, px4flow_i2c_integral_frame::integration_timespan, px4flow_i2c_integral_frame::pixel_flow_x_integral, px4flow_i2c_frame::pixel_flow_x_sum, px4flow_i2c_integral_frame::pixel_flow_y_integral, px4flow_i2c_frame::pixel_flow_y_sum, px4flow, PX4FLOW_FRAME_REC, PX4FLOW_FRAME_REQ, PX4FLOW_I2C_FRAME, px4flow_i2c_frame_cb(), PX4FLOW_I2C_FRAME_LENGTH, px4flow_i2c_int_frame_cb(), PX4FLOW_I2C_INTEGRAL_FRAME, PX4FLOW_I2C_INTEGRAL_FRAME_LENGTH, PX4FLOW_INT_FRAME_REC, PX4FLOW_INT_FRAME_REC_OK, PX4FLOW_INT_FRAME_REQ, px4flow_i2c_frame::qual, px4flow_i2c_integral_frame::qual, px4flow_i2c_frame::sonar_timestamp, px4flow_i2c_integral_frame::sonar_timestamp, i2c_transaction::status, px4flow_data::status, and px4flow_data::trans.
|
extern |
Definition at line 1 of file px4flow_i2c.c.
Referenced by px4flow_i2c_downlink(), px4flow_i2c_frame_cb(), px4flow_i2c_init(), and px4flow_i2c_periodic().