PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Classes | |
struct | _scale |
Public Member Functions | |
IST8310 (int bus_number, int address, const char *path, enum Rotation rotation) | |
virtual | ~IST8310 () |
virtual int | init () |
virtual ssize_t | read (struct file *filp, char *buffer, size_t buflen) |
virtual int | ioctl (struct file *filp, int cmd, unsigned long arg) |
void | print_info () |
Diagnostics - print some basic information about the driver. More... | |
Protected Member Functions | |
virtual int | probe () |
Private Member Functions | |
void | start () |
Initialise the automatic measurement state machine and start it. More... | |
void | stop () |
Stop the automatic measurement state machine. More... | |
int | reset () |
Reset the device. More... | |
int | calibrate (struct file *filp, unsigned enable) |
Perform the on-sensor scale calibration routine. More... | |
void | check_conf (void) |
check the sensor configuration. More... | |
void | Run () override |
Perform a poll cycle; collect from the previous measurement and start a new one. More... | |
int | write_reg (uint8_t reg, uint8_t val) |
Write a register. More... | |
int | write (unsigned address, void *data, unsigned count) |
Write to a register block. More... | |
int | read_reg (uint8_t reg, uint8_t &val) |
Read a register. More... | |
int | read (unsigned address, void *data, unsigned count) |
read register block. More... | |
int | measure () |
Issue a measurement command. More... | |
int | collect () |
Collect the result of the most recent measurement. More... | |
float | meas_to_float (uint8_t in[2]) |
Convert a big-endian signed 16-bit value to a float. More... | |
int | check_scale () |
Check the current scale calibration. More... | |
int | check_offset () |
Check the current offset calibration. More... | |
int | set_selftest (unsigned enable) |
Place the device in self test mode. More... | |
IST8310 (const IST8310 &) | |
IST8310 | operator= (const IST8310 &) |
Private Attributes | |
unsigned | _measure_interval {0} |
ringbuffer::RingBuffer * | _reports {nullptr} |
float | _range_scale {0.003f} |
bool | _collect_phase {false} |
int | _class_instance {-1} |
int | _orb_class_instance {-1} |
orb_advert_t | _mag_topic {nullptr} |
perf_counter_t | _sample_perf |
perf_counter_t | _comms_errors |
perf_counter_t | _range_errors |
perf_counter_t | _conf_errors |
bool | _sensor_ok {false} |
sensor was found and reports ok More... | |
bool | _calibrated {false} |
the calibration is valid More... | |
enum Rotation | _rotation |
sensor_mag_s | _last_report {} |
used for info() More... | |
uint8_t | _ctl3_reg {0} |
uint8_t | _ctl4_reg {0} |
Definition at line 186 of file ist8310.cpp.
IST8310::IST8310 | ( | int | bus_number, |
int | address, | ||
const char * | path, | ||
enum Rotation | rotation | ||
) |
Definition at line 378 of file ist8310.cpp.
References DRV_MAG_DEVTYPE_IST8310.
|
virtual |
Definition at line 398 of file ist8310.cpp.
References _class_instance, _comms_errors, _conf_errors, _range_errors, _reports, _sample_perf, MAG_BASE_DEVICE_PATH, perf_free(), and stop().
|
private |
|
private |
Perform the on-sensor scale calibration routine.
enable | set to 1 to enable self-test strap, 0 to disable |
Definition at line 900 of file ist8310.cpp.
References check_scale(), fd, ioctl(), mag_report, MAGIOCEXSTRAP, MAGIOCGSCALE, MAGIOCSSCALE, OK, read(), SENSORIOCSPOLLRATE, mag_calibration_s::x_offset, mag_calibration_s::x_scale, mag_calibration_s::y_offset, mag_calibration_s::y_scale, mag_calibration_s::z_offset, and mag_calibration_s::z_scale.
Referenced by ioctl(), and ist8310_main().
|
private |
check the sensor configuration.
check that the configuration register has the right value.
checks that the config of the sensor is correctly set, to cope with communication errors causing the configuration to change
This is done periodically to cope with I2C bus noise causing the configuration of the compass to change.
Definition at line 477 of file ist8310.cpp.
References _comms_errors, _conf_errors, _ctl3_reg, _ctl4_reg, ADDR_CTRL3, ADDR_CTRL4, OK, perf_count(), read_reg(), and write_reg().
Referenced by collect().
|
private |
Check the current offset calibration.
Definition at line 1034 of file ist8310.cpp.
References f(), and FLT_EPSILON.
|
private |
Check the current scale calibration.
Definition at line 1029 of file ist8310.cpp.
References OK.
Referenced by calibrate().
|
private |
Collect the result of the most recent measurement.
Definition at line 767 of file ist8310.cpp.
References _comms_errors, _last_report, _mag_topic, _orb_class_instance, _range_errors, _range_scale, _reports, _rotation, _sample_perf, ADDR_DATA_OUT_X_LSB, check_conf(), DEVICE_DEBUG, hrt_absolute_time(), IST8310_MAX_VAL_XY, IST8310_MAX_VAL_Z, IST8310_MIN_VAL_XY, IST8310_MIN_VAL_Z, mag_report, OK, orb_advertise_multi(), ORB_ID, ORB_PRIO_HIGH, ORB_PRIO_MAX, orb_publish(), perf_begin(), perf_count(), perf_end(), perf_event_count(), read(), and rotate_3f().
Referenced by read(), and Run().
|
virtual |
Definition at line 419 of file ist8310.cpp.
References _class_instance, _reports, _sensor_ok, DEVICE_DEBUG, ToneAlarmInterface::init(), MAG_BASE_DEVICE_PATH, mag_report, OK, and reset().
|
virtual |
Definition at line 574 of file ist8310.cpp.
References _measure_interval, calibrate(), IST8310_CONVERSION_INTERVAL, MAGIOCCALIBRATE, MAGIOCEXSTRAP, MAGIOCGEXTERNAL, MAGIOCGSCALE, MAGIOCSSCALE, OK, reset(), SENSOR_POLLRATE_DEFAULT, SENSORIOCRESET, SENSORIOCSPOLLRATE, set_selftest(), and start().
Referenced by calibrate(), ist8310::calibrate(), ist8310::reset(), ist8310::start_bus(), and ist8310::test().
|
private |
Convert a big-endian signed 16-bit value to a float.
in | A signed 16-bit big-endian value. |
Definition at line 1100 of file ist8310.cpp.
|
private |
Issue a measurement command.
Definition at line 752 of file ist8310.cpp.
References _comms_errors, ADDR_CTRL1, CTRL1_MODE_SINGLE, OK, perf_count(), and write_reg().
Referenced by read(), and Run().
void IST8310::print_info | ( | ) |
Diagnostics - print some basic information about the driver.
Definition at line 1114 of file ist8310.cpp.
References _comms_errors, _last_report, _measure_interval, _reports, _sample_perf, and perf_print_counter().
Referenced by ist8310::info().
|
protectedvirtual |
Definition at line 689 of file ist8310.cpp.
References ADDR_WAI, data, DEVICE_DEBUG, OK, read(), and WAI_EXPECTED_VALUE.
|
virtual |
Definition at line 516 of file ist8310.cpp.
References _measure_interval, _reports, collect(), IST8310_CONVERSION_INTERVAL, mag_report, measure(), and OK.
Referenced by calibrate(), collect(), probe(), read_reg(), and ist8310::test().
|
private |
read register block.
address | The register address to read from. |
data | The buffer to read into. |
count | The number of bytes to read. |
Definition at line 465 of file ist8310.cpp.
|
private |
Read a register.
reg | The register to read. |
val | The value read. |
Definition at line 1091 of file ist8310.cpp.
References read().
Referenced by check_conf(), and set_selftest().
|
private |
Reset the device.
Definition at line 672 of file ist8310.cpp.
References _ctl3_reg, _ctl4_reg, ADDR_CTRL2, ADDR_CTRL3, ADDR_CTRL4, CTRL2_SRST, CTRL3_SAMPLEAVG_16, CTRL4_SRPD, OK, and write_reg().
Referenced by init(), and ioctl().
|
overrideprivate |
Perform a poll cycle; collect from the previous measurement and start a new one.
This is the heart of the measurement state machine. This function alternately starts a measurement, or collects the data from the previous measurement.
When the interval between measurements is greater than the minimum measurement interval, a gap is inserted between collection and measurement to provide the most recent measurement possible at the next interval.
Definition at line 711 of file ist8310.cpp.
References _collect_phase, _measure_interval, collect(), DEVICE_DEBUG, IST8310_CONVERSION_INTERVAL, measure(), OK, and start().
|
private |
Place the device in self test mode.
Definition at line 1053 of file ist8310.cpp.
References _comms_errors, ADDR_STR, OK, perf_count(), read_reg(), STR_SELF_TEST_ON, and write_reg().
Referenced by ioctl().
|
private |
Initialise the automatic measurement state machine and start it.
Definition at line 655 of file ist8310.cpp.
References _collect_phase, and _reports.
Referenced by ioctl(), and Run().
|
private |
Stop the automatic measurement state machine.
Definition at line 666 of file ist8310.cpp.
Referenced by ~IST8310().
|
private |
Write to a register block.
address | The register address to write to. |
data | The buffer to write from. |
count | The number of bytes to write. |
Definition at line 450 of file ist8310.cpp.
Referenced by write_reg().
|
private |
Write a register.
reg | The register to write. |
val | The value to write. |
Definition at line 1084 of file ist8310.cpp.
References write().
Referenced by check_conf(), measure(), reset(), and set_selftest().
|
private |
the calibration is valid
Definition at line 227 of file ist8310.cpp.
|
private |
Definition at line 215 of file ist8310.cpp.
Referenced by init(), and ~IST8310().
|
private |
Definition at line 214 of file ist8310.cpp.
|
private |
Definition at line 221 of file ist8310.cpp.
Referenced by check_conf(), collect(), measure(), print_info(), set_selftest(), and ~IST8310().
|
private |
Definition at line 223 of file ist8310.cpp.
Referenced by check_conf(), and ~IST8310().
|
private |
Definition at line 232 of file ist8310.cpp.
Referenced by check_conf(), and reset().
|
private |
Definition at line 233 of file ist8310.cpp.
Referenced by check_conf(), and reset().
|
private |
used for info()
Definition at line 230 of file ist8310.cpp.
Referenced by collect(), and print_info().
|
private |
Definition at line 218 of file ist8310.cpp.
Referenced by collect().
|
private |
Definition at line 207 of file ist8310.cpp.
Referenced by ioctl(), print_info(), read(), and Run().
|
private |
Definition at line 216 of file ist8310.cpp.
Referenced by collect().
|
private |
Definition at line 222 of file ist8310.cpp.
Referenced by collect(), and ~IST8310().
|
private |
Definition at line 212 of file ist8310.cpp.
Referenced by collect().
|
private |
Definition at line 209 of file ist8310.cpp.
Referenced by collect(), init(), print_info(), read(), start(), and ~IST8310().
|
private |
Definition at line 228 of file ist8310.cpp.
Referenced by collect().
|
private |
Definition at line 220 of file ist8310.cpp.
Referenced by collect(), print_info(), and ~IST8310().
|
private |