PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Public Member Functions | |
PX4FLOW (int bus, int address=I2C_FLOW_ADDRESS_DEFAULT, enum Rotation rotation=(enum Rotation) 0, int conversion_interval=PX4FLOW_CONVERSION_INTERVAL_DEFAULT, uint8_t sonar_rotation=distance_sensor_s::ROTATION_DOWNWARD_FACING) | |
virtual | ~PX4FLOW () |
virtual int | init () |
void | print_info () |
Diagnostics - print some basic information about the driver. More... | |
Protected Member Functions | |
virtual int | probe () |
Private Member Functions | |
int | probe_address (uint8_t address) |
Test whether the device supported by the driver is present at a specific address. More... | |
void | start () |
Initialise the automatic measurement state machine and start it. More... | |
void | stop () |
Stop the automatic measurement state machine. More... | |
void | Run () override |
Perform a poll cycle; collect from the previous measurement and start a new one. More... | |
int | measure () |
int | collect () |
Private Attributes | |
uint8_t | _sonar_rotation |
bool | _sensor_ok {false} |
bool | _collect_phase {false} |
int | _class_instance {-1} |
int | _orb_class_instance {-1} |
orb_advert_t | _px4flow_topic {nullptr} |
orb_advert_t | _distance_sensor_topic {nullptr} |
perf_counter_t | _sample_perf |
perf_counter_t | _comms_errors |
enum Rotation | _sensor_rotation |
float | _sensor_min_range {0.0f} |
float | _sensor_max_range {0.0f} |
float | _sensor_max_flow_rate {0.0f} |
i2c_frame | _frame |
i2c_integral_frame | _frame_integral |
Definition at line 77 of file px4flow.cpp.
PX4FLOW::PX4FLOW | ( | int | bus, |
int | address = I2C_FLOW_ADDRESS_DEFAULT , |
||
enum Rotation | rotation = (enum Rotation)0 , |
||
int | conversion_interval = PX4FLOW_CONVERSION_INTERVAL_DEFAULT , |
||
uint8_t | sonar_rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING |
||
) |
Definition at line 154 of file px4flow.cpp.
Referenced by px4flow::start().
|
virtual |
Definition at line 164 of file px4flow.cpp.
References _comms_errors, _sample_perf, perf_free(), and stop().
|
private |
Definition at line 283 of file px4flow.cpp.
References _comms_errors, _distance_sensor_topic, _frame, _frame_integral, _px4flow_topic, _sample_perf, _sensor_max_flow_rate, _sensor_max_range, _sensor_min_range, _sensor_rotation, _sonar_rotation, DEVICE_DEBUG, f(), i2c_integral_frame::frame_count_since_last_readout, i2c_integral_frame::ground_distance, i2c_integral_frame::gyro_temperature, i2c_integral_frame::gyro_x_rate_integral, i2c_integral_frame::gyro_y_rate_integral, i2c_integral_frame::gyro_z_rate_integral, hrt_absolute_time(), I2C_FRAME_SIZE, I2C_INTEGRAL_FRAME_SIZE, i2c_integral_frame::integration_timespan, orb_advertise(), ORB_ID, orb_publish(), perf_begin(), perf_count(), perf_end(), i2c_integral_frame::pixel_flow_x_integral, i2c_integral_frame::pixel_flow_y_integral, PX4FLOW_MAX_DISTANCE, PX4FLOW_MIN_DISTANCE, PX4FLOW_REG, i2c_integral_frame::qual, rotate_3f(), i2c_integral_frame::sonar_timestamp, optical_flow_s::timestamp, and distance_sensor_s::timestamp.
Referenced by Run().
|
virtual |
Definition at line 174 of file px4flow.cpp.
References _class_instance, _distance_sensor_topic, _orb_class_instance, _sensor_max_flow_rate, _sensor_max_range, _sensor_min_range, _sensor_ok, _sensor_rotation, CLASS_DEVICE_PRIMARY, DEVICE_LOG, ToneAlarmInterface::init(), OK, orb_advertise_multi(), ORB_ID, ORB_PRIO_HIGH, param_find(), param_get(), PARAM_INVALID, RANGE_FINDER_BASE_DEVICE_PATH, and start().
Referenced by px4flow::start().
|
private |
Definition at line 265 of file px4flow.cpp.
References _comms_errors, DEVICE_DEBUG, OK, perf_count(), and PX4FLOW_REG.
Referenced by probe(), and Run().
void PX4FLOW::print_info | ( | ) |
Diagnostics - print some basic information about the driver.
Definition at line 405 of file px4flow.cpp.
References _comms_errors, _sample_perf, and perf_print_counter().
Referenced by px4flow::info().
|
protectedvirtual |
Definition at line 248 of file px4flow.cpp.
References I2C_FRAME_SIZE, measure(), and OK.
|
private |
Test whether the device supported by the driver is present at a specific address.
address | The I2C bus address to probe. |
|
overrideprivate |
Perform a poll cycle; collect from the previous measurement and start a new one.
Definition at line 387 of file px4flow.cpp.
References collect(), DEVICE_DEBUG, measure(), OK, PX4FLOW_CONVERSION_INTERVAL_DEFAULT, and start().
|
private |
Initialise the automatic measurement state machine and start it.
Definition at line 371 of file px4flow.cpp.
References _collect_phase.
Referenced by init(), and Run().
|
private |
Stop the automatic measurement state machine.
Definition at line 381 of file px4flow.cpp.
Referenced by ~PX4FLOW().
|
private |
Definition at line 100 of file px4flow.cpp.
Referenced by init().
|
private |
Definition at line 99 of file px4flow.cpp.
Referenced by start().
|
private |
Definition at line 106 of file px4flow.cpp.
Referenced by collect(), measure(), print_info(), and ~PX4FLOW().
|
private |
Definition at line 103 of file px4flow.cpp.
|
private |
Definition at line 113 of file px4flow.cpp.
Referenced by collect().
|
private |
Definition at line 114 of file px4flow.cpp.
Referenced by collect().
|
private |
Definition at line 101 of file px4flow.cpp.
Referenced by init().
|
private |
Definition at line 102 of file px4flow.cpp.
Referenced by collect().
|
private |
Definition at line 105 of file px4flow.cpp.
Referenced by collect(), print_info(), and ~PX4FLOW().
|
private |
Definition at line 111 of file px4flow.cpp.
|
private |
Definition at line 110 of file px4flow.cpp.
|
private |
Definition at line 109 of file px4flow.cpp.
|
private |
Definition at line 98 of file px4flow.cpp.
Referenced by init().
|
private |
Definition at line 108 of file px4flow.cpp.
|
private |
Definition at line 97 of file px4flow.cpp.
Referenced by collect().