PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Public Member Functions | |
BMA180 (int bus, uint32_t device) | |
virtual | ~BMA180 () |
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 () |
Start automatic measurement. More... | |
void | stop () |
Stop automatic measurement. More... | |
void | Run () override |
void | measure () |
Fetch measurements from the sensor and update the report ring. More... | |
uint8_t | read_reg (unsigned reg) |
Read a register from the BMA180. More... | |
void | write_reg (unsigned reg, uint8_t value) |
Write a register in the BMA180. More... | |
void | modify_reg (unsigned reg, uint8_t clearbits, uint8_t setbits) |
Modify a register in the BMA180. More... | |
int | set_range (unsigned max_g) |
Set the BMA180 measurement range. More... | |
int | set_lowpass (unsigned frequency) |
Set the BMA180 internal lowpass filter frequency. More... | |
Private Attributes | |
unsigned | _call_interval |
ringbuffer::RingBuffer * | _reports |
struct accel_calibration_s | _accel_scale |
float | _accel_range_scale |
float | _accel_range_m_s2 |
orb_advert_t | _accel_topic |
int | _class_instance |
unsigned | _current_lowpass |
unsigned | _current_range |
perf_counter_t | _sample_perf |
Definition at line 125 of file bma180.cpp.
BMA180::BMA180 | ( | int | bus, |
uint32_t | device | ||
) |
Definition at line 224 of file bma180.cpp.
References _accel_scale, DRV_ACC_DEVTYPE_BMA180, accel_calibration_s::x_offset, accel_calibration_s::x_scale, accel_calibration_s::y_offset, accel_calibration_s::y_scale, accel_calibration_s::z_offset, and accel_calibration_s::z_scale.
Referenced by bma180::start().
|
virtual |
Definition at line 248 of file bma180.cpp.
References _reports, _sample_perf, perf_free(), and stop().
|
virtual |
Definition at line 263 of file bma180.cpp.
References _accel_topic, _class_instance, _reports, ACCEL_DEVICE_PATH, ADDR_CHIP_ID, ADDR_CTRL_REG0, ADDR_GAIN_Y, ADDR_HIGH_DUR, ADDR_OFFSET_T, ADDR_RESET, ADDR_TCO_Z, CHIP_ID, CLASS_DEVICE_PRIMARY, GAIN_Y_SHADOW_DIS, HIGH_DUR_DIS_I2C, ToneAlarmInterface::init(), measure(), modify_reg(), OFFSET_T_READOUT_12BIT, OK, orb_advertise(), ORB_ID, read_reg(), REG0_WRITE_ENABLE, set_lowpass(), set_range(), SOFT_RESET, TCO_Z_MODE_MASK, warnx, and write_reg().
Referenced by bma180::start().
|
virtual |
Definition at line 388 of file bma180.cpp.
References _accel_scale, _call_interval, ACCELIOCSSCALE, OK, SENSOR_POLLRATE_DEFAULT, SENSORIOCRESET, SENSORIOCSPOLLRATE, and start().
Referenced by bma180::reset(), and bma180::start().
|
private |
Fetch measurements from the sensor and update the report ring.
Definition at line 606 of file bma180.cpp.
References _accel_range_scale, _accel_scale, _accel_topic, _reports, _sample_perf, ADDR_ACC_X_LSB, sensor_accel_s::error_count, hrt_absolute_time(), ORB_ID, orb_publish(), perf_begin(), perf_end(), read_reg(), sensor_accel_s::scaling, sensor_accel_s::timestamp, sensor_accel_s::x, accel_calibration_s::x_offset, sensor_accel_s::x_raw, accel_calibration_s::x_scale, sensor_accel_s::y, accel_calibration_s::y_offset, sensor_accel_s::y_raw, accel_calibration_s::y_scale, sensor_accel_s::z, accel_calibration_s::z_offset, sensor_accel_s::z_raw, and accel_calibration_s::z_scale.
Referenced by init(), read(), and Run().
|
private |
Modify a register in the BMA180.
Bits are cleared before bits are set.
reg | The register to modify. |
clearbits | Bits in the register to clear. |
setbits | Bits in the register to set. |
Definition at line 467 of file bma180.cpp.
References read_reg(), and write_reg().
Referenced by init(), set_lowpass(), and set_range().
void BMA180::print_info | ( | ) |
Diagnostics - print some basic information about the driver.
Definition at line 680 of file bma180.cpp.
References _reports, _sample_perf, and perf_print_counter().
Referenced by bma180::info().
|
protectedvirtual |
Definition at line 332 of file bma180.cpp.
References ADDR_CHIP_ID, CHIP_ID, OK, and read_reg().
|
virtual |
Definition at line 345 of file bma180.cpp.
References _call_interval, _reports, and measure().
Referenced by bma180::test().
|
private |
Read a register from the BMA180.
The | register to read. |
Definition at line 444 of file bma180.cpp.
References DIR_READ.
Referenced by init(), measure(), modify_reg(), probe(), set_lowpass(), and set_range().
|
overrideprivate |
Definition at line 599 of file bma180.cpp.
References measure().
|
private |
Set the BMA180 internal lowpass filter frequency.
frequency | The internal lowpass filter frequency is set to a value equal or greater to this. Zero selects the highest frequency supported. |
Definition at line 533 of file bma180.cpp.
References ADDR_BW_TCS, ADDR_CTRL_REG0, BW_TCS_BW_10HZ, BW_TCS_BW_1200HZ, BW_TCS_BW_150HZ, BW_TCS_BW_20HZ, BW_TCS_BW_300HZ, BW_TCS_BW_40HZ, BW_TCS_BW_600HZ, BW_TCS_BW_75HZ, BW_TCS_BW_MASK, modify_reg(), read_reg(), and REG0_WRITE_ENABLE.
Referenced by init().
|
private |
Set the BMA180 measurement range.
max_g | The maximum G value the range must support. |
Definition at line 478 of file bma180.cpp.
References _accel_range_m_s2, _accel_range_scale, _current_range, ADDR_CTRL_REG0, ADDR_OFFSET_LSB1, CONSTANTS_ONE_G, modify_reg(), OFFSET_LSB1_RANGE_16G, OFFSET_LSB1_RANGE_2G, OFFSET_LSB1_RANGE_3G, OFFSET_LSB1_RANGE_4G, OFFSET_LSB1_RANGE_8G, OFFSET_LSB1_RANGE_MASK, read_reg(), and REG0_WRITE_ENABLE.
Referenced by init().
|
private |
Start automatic measurement.
Definition at line 580 of file bma180.cpp.
References _call_interval, _reports, and stop().
Referenced by ioctl().
|
private |
Stop automatic measurement.
Definition at line 593 of file bma180.cpp.
Referenced by start(), and ~BMA180().
|
private |
Write a register in the BMA180.
reg | The register to write. |
value | The new value to write. |
Definition at line 456 of file bma180.cpp.
References DIR_WRITE.
Referenced by init(), and modify_reg().
|
private |
Definition at line 152 of file bma180.cpp.
Referenced by set_range().
|
private |
Definition at line 151 of file bma180.cpp.
Referenced by measure(), and set_range().
|
private |
Definition at line 150 of file bma180.cpp.
|
private |
Definition at line 153 of file bma180.cpp.
|
private |
Definition at line 146 of file bma180.cpp.
|
private |
Definition at line 154 of file bma180.cpp.
Referenced by init().
|
private |
Definition at line 156 of file bma180.cpp.
|
private |
Definition at line 157 of file bma180.cpp.
Referenced by set_range().
|
private |
Definition at line 148 of file bma180.cpp.
Referenced by init(), measure(), print_info(), read(), start(), and ~BMA180().
|
private |
Definition at line 159 of file bma180.cpp.
Referenced by measure(), print_info(), and ~BMA180().