| 
    PX4 Firmware
    
   PX4 Autopilot Software http://px4.io 
   | 
 
#include <LSM303D.hpp>
Public Member Functions | |
| LSM303D (int bus, uint32_t device, enum Rotation rotation) | |
| virtual | ~LSM303D () | 
| int | init () override | 
| void | print_info () | 
| Diagnostics - print some basic information about the driver.  More... | |
Protected Member Functions | |
| virtual int | probe () | 
Private Member Functions | |
| void | Run () override | 
| void | start () | 
| void | stop () | 
| void | reset () | 
| void | disable_i2c () | 
| disable I2C on the chip  More... | |
| void | check_registers (void) | 
| check key registers for correct values  More... | |
| void | measureAccelerometer () | 
| Fetch accel measurements from the sensor and update the report ring.  More... | |
| void | measureMagnetometer () | 
| Fetch mag measurements from the sensor and update the report ring.  More... | |
| uint8_t | read_reg (unsigned reg) | 
| Read a register from the LSM303D.  More... | |
| void | write_reg (unsigned reg, uint8_t value) | 
| Write a register in the LSM303D.  More... | |
| void | modify_reg (unsigned reg, uint8_t clearbits, uint8_t setbits) | 
| Modify a register in the LSM303D.  More... | |
| void | write_checked_reg (unsigned reg, uint8_t value) | 
| Write a register in the LSM303D, updating _checked_values.  More... | |
| int | accel_set_range (unsigned max_g) | 
| Set the LSM303D accel measurement range.  More... | |
| int | mag_set_range (unsigned max_g) | 
| Set the LSM303D mag measurement range.  More... | |
| int | accel_set_onchip_lowpass_filter_bandwidth (unsigned bandwidth) | 
| Set the LSM303D on-chip anti-alias filter bandwith.  More... | |
| int | accel_set_samplerate (unsigned frequency) | 
| Set the LSM303D internal accel sampling frequency.  More... | |
| int | mag_set_samplerate (unsigned frequency) | 
| Set the LSM303D internal mag sampling frequency.  More... | |
Private Attributes | |
| PX4Accelerometer | _px4_accel | 
| PX4Magnetometer | _px4_mag | 
| unsigned | _call_accel_interval {1000000 / LSM303D_ACCEL_DEFAULT_RATE} | 
| unsigned | _call_mag_interval {1000000 / LSM303D_MAG_DEFAULT_RATE} | 
| perf_counter_t | _accel_sample_perf | 
| perf_counter_t | _mag_sample_perf | 
| perf_counter_t | _bad_registers | 
| perf_counter_t | _bad_values | 
| perf_counter_t | _accel_duplicates | 
| uint8_t | _register_wait {0} | 
| int16_t | _last_accel [3] {} | 
| uint8_t | _constant_accel_count {0} | 
| hrt_abstime | _mag_last_measure {0} | 
| float | _last_temperature {0.0f} | 
| uint8_t | _checked_values [LSM303D_NUM_CHECKED_REGISTERS] {} | 
| uint8_t | _checked_next {0} | 
Static Private Attributes | |
| static constexpr int | LSM303D_NUM_CHECKED_REGISTERS {8} | 
Definition at line 143 of file LSM303D.hpp.
| LSM303D::LSM303D | ( | int | bus, | 
| uint32_t | device, | ||
| enum Rotation | rotation | ||
| ) | 
Definition at line 56 of file LSM303D.cpp.
References _px4_accel, _px4_mag, DRV_ACC_DEVTYPE_LSM303D, DRV_MAG_DEVTYPE_LSM303D, PX4Magnetometer::set_device_type(), PX4Accelerometer::set_device_type(), and PX4Magnetometer::set_external().
      
  | 
  virtual | 
Definition at line 72 of file LSM303D.cpp.
References _accel_duplicates, _accel_sample_perf, _bad_registers, _bad_values, _mag_sample_perf, perf_free(), and stop().
      
  | 
  private | 
Set the LSM303D on-chip anti-alias filter bandwith.
| bandwidth | The anti-alias filter bandwidth in Hz Zero selects the highest bandwidth | 
Definition at line 295 of file LSM303D.cpp.
References ADDR_CTRL_REG2, modify_reg(), OK, REG2_AA_FILTER_BW_194HZ_A, REG2_AA_FILTER_BW_362HZ_A, REG2_AA_FILTER_BW_50HZ_A, REG2_AA_FILTER_BW_773HZ_A, and REG2_ANTIALIAS_FILTER_BW_BITS_A.
Referenced by reset().
      
  | 
  private | 
Set the LSM303D accel measurement range.
| max_g | The measurement range of the accel is in g (9.81m/s^2) Zero selects the maximum supported range. | 
Definition at line 204 of file LSM303D.cpp.
References _px4_accel, ADDR_CTRL_REG2, CONSTANTS_ONE_G, f(), modify_reg(), OK, REG2_FULL_SCALE_16G_A, REG2_FULL_SCALE_2G_A, REG2_FULL_SCALE_4G_A, REG2_FULL_SCALE_6G_A, REG2_FULL_SCALE_8G_A, REG2_FULL_SCALE_BITS_A, and PX4Accelerometer::set_scale().
Referenced by reset().
      
  | 
  private | 
Set the LSM303D internal accel sampling frequency.
| frequency | The internal accel sampling frequency is set to not less than this value. Zero selects the maximum rate supported. | 
Definition at line 330 of file LSM303D.cpp.
References _call_accel_interval, _px4_accel, ADDR_CTRL_REG1, modify_reg(), OK, REG1_RATE_100HZ_A, REG1_RATE_1600HZ_A, REG1_RATE_200HZ_A, REG1_RATE_400HZ_A, REG1_RATE_800HZ_A, REG1_RATE_BITS_A, and PX4Accelerometer::set_sample_rate().
Referenced by reset().
      
  | 
  private | 
check key registers for correct values
Definition at line 436 of file LSM303D.cpp.
References _bad_registers, _checked_next, _checked_registers, _checked_values, _register_wait, LSM303D_NUM_CHECKED_REGISTERS, perf_count(), read_reg(), and write_reg().
Referenced by measureAccelerometer().
      
  | 
  private | 
disable I2C on the chip
Definition at line 104 of file LSM303D.cpp.
References read_reg(), and write_reg().
Referenced by reset().
      
  | 
  override | 
Definition at line 86 of file LSM303D.cpp.
References ToneAlarmInterface::init(), OK, reset(), and start().
Referenced by lsm303d::start().
      
  | 
  private | 
Set the LSM303D mag measurement range.
| max_ga | The measurement range of the mag is in Ga Zero selects the maximum supported range. | 
Definition at line 253 of file LSM303D.cpp.
References _px4_mag, ADDR_CTRL_REG6, f(), modify_reg(), OK, REG6_FULL_SCALE_12GA_M, REG6_FULL_SCALE_2GA_M, REG6_FULL_SCALE_4GA_M, REG6_FULL_SCALE_8GA_M, REG6_FULL_SCALE_BITS_M, and PX4Magnetometer::set_scale().
Referenced by reset().
      
  | 
  private | 
Set the LSM303D internal mag sampling frequency.
| frequency | The internal mag sampling frequency is set to not less than this value. Zero selects the maximum rate supported. | 
Definition at line 374 of file LSM303D.cpp.
References _call_mag_interval, ADDR_CTRL_REG5, modify_reg(), OK, REG5_RATE_100HZ_M, REG5_RATE_25HZ_M, REG5_RATE_50HZ_M, and REG5_RATE_BITS_M.
Referenced by reset().
      
  | 
  private | 
Fetch accel measurements from the sensor and update the report ring.
Definition at line 466 of file LSM303D.cpp.
References _accel_duplicates, _accel_sample_perf, _bad_registers, _bad_values, _constant_accel_count, _last_accel, _px4_accel, _register_wait, ADDR_INCREMENT, ADDR_STATUS_A, check_registers(), DIR_READ, hrt_absolute_time(), hrt_abstime, perf_begin(), perf_count(), perf_end(), perf_event_count(), REG_STATUS_A_NEW_ZYXADA, PX4Accelerometer::set_error_count(), status, and PX4Accelerometer::update().
Referenced by Run().
      
  | 
  private | 
Fetch mag measurements from the sensor and update the report ring.
Definition at line 547 of file LSM303D.cpp.
References _bad_registers, _bad_values, _last_temperature, _mag_last_measure, _mag_sample_perf, _px4_accel, _px4_mag, ADDR_INCREMENT, ADDR_OUT_TEMP_L, DIR_READ, hrt_absolute_time(), hrt_abstime, perf_begin(), perf_end(), perf_event_count(), PX4Magnetometer::set_error_count(), PX4Magnetometer::set_external(), PX4Magnetometer::set_temperature(), PX4Accelerometer::set_temperature(), status, and PX4Magnetometer::update().
Referenced by Run().
      
  | 
  private | 
Modify a register in the LSM303D.
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 195 of file LSM303D.cpp.
References read_reg(), and write_checked_reg().
Referenced by accel_set_onchip_lowpass_filter_bandwidth(), accel_set_range(), accel_set_samplerate(), mag_set_range(), and mag_set_samplerate().
| void LSM303D::print_info | ( | ) | 
Diagnostics - print some basic information about the driver.
Definition at line 585 of file LSM303D.cpp.
References _accel_duplicates, _accel_sample_perf, _bad_registers, _bad_values, _checked_next, _checked_registers, _checked_values, _mag_sample_perf, LSM303D_NUM_CHECKED_REGISTERS, perf_print_counter(), and read_reg().
Referenced by lsm303d::info().
      
  | 
  protectedvirtual | 
Definition at line 146 of file LSM303D.cpp.
References _checked_values, ADDR_WHO_AM_I, OK, read_reg(), and WHO_I_AM.
      
  | 
  private | 
Read a register from the LSM303D.
| The | register to read. | 
Definition at line 161 of file LSM303D.cpp.
References DIR_READ.
Referenced by check_registers(), disable_i2c(), modify_reg(), print_info(), and probe().
      
  | 
  private | 
Definition at line 117 of file LSM303D.cpp.
References accel_set_onchip_lowpass_filter_bandwidth(), accel_set_range(), accel_set_samplerate(), ADDR_CTRL_REG1, ADDR_CTRL_REG3, ADDR_CTRL_REG4, ADDR_CTRL_REG5, ADDR_CTRL_REG7, disable_i2c(), LSM303D_ACCEL_DEFAULT_ONCHIP_FILTER_FREQ, LSM303D_ACCEL_DEFAULT_RANGE_G, LSM303D_ACCEL_DEFAULT_RATE, LSM303D_MAG_DEFAULT_RANGE_GA, LSM303D_MAG_DEFAULT_RATE, mag_set_range(), mag_set_samplerate(), REG1_BDU_UPDATE, REG1_RATE_800HZ_A, REG1_X_ENABLE_A, REG1_Y_ENABLE_A, REG1_Z_ENABLE_A, REG5_ENABLE_T, REG5_RES_HIGH_M, REG7_CONT_MODE_M, and write_checked_reg().
Referenced by init().
      
  | 
  overrideprivate | 
Definition at line 425 of file LSM303D.cpp.
References _call_mag_interval, _mag_last_measure, hrt_elapsed_time(), measureAccelerometer(), and measureMagnetometer().
      
  | 
  private | 
Definition at line 409 of file LSM303D.cpp.
References _call_accel_interval, LSM303D_TIMER_REDUCTION, and stop().
Referenced by init().
      
  | 
  private | 
Definition at line 419 of file LSM303D.cpp.
Referenced by start(), and ~LSM303D().
      
  | 
  private | 
Write a register in the LSM303D, updating _checked_values.
| reg | The register to write. | 
| value | The new value to write. | 
Definition at line 183 of file LSM303D.cpp.
References _checked_registers, _checked_values, LSM303D_NUM_CHECKED_REGISTERS, and write_reg().
Referenced by modify_reg(), and reset().
      
  | 
  private | 
Write a register in the LSM303D.
| reg | The register to write. | 
| value | The new value to write. | 
Definition at line 172 of file LSM303D.cpp.
References DIR_WRITE.
Referenced by check_registers(), disable_i2c(), and write_checked_reg().
      
  | 
  private | 
Definition at line 280 of file LSM303D.hpp.
Referenced by measureAccelerometer(), print_info(), and ~LSM303D().
      
  | 
  private | 
Definition at line 276 of file LSM303D.hpp.
Referenced by measureAccelerometer(), print_info(), and ~LSM303D().
      
  | 
  private | 
Definition at line 278 of file LSM303D.hpp.
Referenced by check_registers(), measureAccelerometer(), measureMagnetometer(), print_info(), and ~LSM303D().
      
  | 
  private | 
Definition at line 279 of file LSM303D.hpp.
Referenced by measureAccelerometer(), measureMagnetometer(), print_info(), and ~LSM303D().
      
  | 
  private | 
Definition at line 273 of file LSM303D.hpp.
Referenced by accel_set_samplerate(), and start().
      
  | 
  private | 
Definition at line 274 of file LSM303D.hpp.
Referenced by mag_set_samplerate(), and Run().
      
  | 
  private | 
Definition at line 296 of file LSM303D.hpp.
Referenced by check_registers(), and print_info().
      
  | 
  private | 
Definition at line 295 of file LSM303D.hpp.
Referenced by check_registers(), print_info(), probe(), and write_checked_reg().
      
  | 
  private | 
Definition at line 285 of file LSM303D.hpp.
Referenced by measureAccelerometer().
      
  | 
  private | 
Definition at line 284 of file LSM303D.hpp.
Referenced by measureAccelerometer().
      
  | 
  private | 
Definition at line 289 of file LSM303D.hpp.
Referenced by measureMagnetometer().
      
  | 
  private | 
Definition at line 287 of file LSM303D.hpp.
Referenced by measureMagnetometer(), and Run().
      
  | 
  private | 
Definition at line 277 of file LSM303D.hpp.
Referenced by measureMagnetometer(), print_info(), and ~LSM303D().
      
  | 
  private | 
Definition at line 270 of file LSM303D.hpp.
Referenced by accel_set_range(), accel_set_samplerate(), LSM303D(), measureAccelerometer(), and measureMagnetometer().
      
  | 
  private | 
Definition at line 271 of file LSM303D.hpp.
Referenced by LSM303D(), mag_set_range(), and measureMagnetometer().
      
  | 
  private | 
Definition at line 282 of file LSM303D.hpp.
Referenced by check_registers(), and measureAccelerometer().
      
  | 
  staticprivate | 
Definition at line 294 of file LSM303D.hpp.
Referenced by check_registers(), print_info(), and write_checked_reg().