a bmg160 driver that implements the device's main capabilities. More...
#include <bmg160.hpp>

| Public Member Functions | |
| BMG160 (bosch_hardware_interface *hw) | |
| bool | changeBandwidth () | 
| changes the gyro's bandwidth by writing to the appropriate sensor register. | |
| bool | changeRange () | 
| a method that changes the accelerometer's range by writing to the appropriate sensor register. The range is specified by the setRange(range) in the inheritted parameter's class. | |
| void | computeOffsets (uint8_t *raw_offset_data, int16_t *clean_offset_data) | 
| bool | filterData (bool request) | 
| writes to the sensor's register in memory to choose whether or not to filter the gyro data. | |
| uint8_t | getDeviceAddress () | 
| An invalid request. It is necessary, since this driver inherits from the sensor_driver class. | |
| double | getGyroX () | 
| retrieves the raw gyro x-axis data and stores the calculated value to the class variable: GyroX_ | |
| double | getGyroY () | 
| retrieves the raw gyro y-axis data and stores the calculated value to the class variable: GyroY_ | |
| double | getGyroZ () | 
| retrieves the raw gyro z-axis data and stores the calculated value to the class variable: GyroZ_ | |
| double | getTemperature () | 
| retreives the raw gyro temperature and stores the calculated value in the class variable Temperature_. | |
| bool | initialize () | 
| Initializes the sensor with all user-defined preferences indicated in the parameters. | |
| bool | printOffsets () | 
| read the offset registers, format the 12-bit values correctly, and print the values for all three axes. | |
| bool | readSensorData (uint8_t reg, uint8_t *data, uint8_t num_bytes) | 
| reads num_bytes starting at register reg and stores the data into the array data_array. | |
| void | SimpleCalibration () | 
| calibrates the sensor assuming it is in a static position. | |
| bool | softReset () | 
| resets the accelerometer, putting it back into normal mode and clearing its image. | |
| bool | takeMeasurement () | 
| Retrieves all available raw gyro data and stores the calculated value to class variables: GyroX_, GyroY_, GyroZ_, Temperature_. | |
| ~BMG160 () | |
| Public Attributes | |
| double | GyroX_ | 
| double | GyroY_ | 
| double | GyroZ_ | 
| double | Temperature_ | 
| double | TempSlope_ | 
| Static Public Attributes | |
| static const uint8_t | ADDRESS_BANDWIDTH = 0x10 | 
| static const uint8_t | ADDRESS_ENABLE_CAL = 0x31 | 
| static const uint8_t | ADDRESS_ENABLE_FAST_CAL = 0x32 | 
| static const uint8_t | ADDRESS_FILTER = 0x13 | 
| static const uint8_t | ADDRESS_FILTERED_CAL = 0x1A | 
| static const uint8_t | ADDRESS_FILTERED_CAL_FAST = 0x1B | 
| static const uint8_t | ADDRESS_GYRO_X_LSB = 0x02 | 
| static const uint8_t | ADDRESS_GYRO_Y_LSB = 0x04 | 
| static const uint8_t | ADDRESS_GYRO_Z_LSB = 0x06 | 
| static const uint8_t | ADDRESS_NVM = 0x33 | 
| static const uint8_t | ADDRESS_OFFSETS = 0x36 | 
| the starting address of the offset values that are adjusted in calibration. | |
| static const uint8_t | ADDRESS_RANGE = 0x0F | 
| static const uint8_t | ADDRESS_SOFTRESET = 0x14 | 
| static const uint8_t | ADDRESS_TEMPERATURE = 0x08 | 
| static const uint8_t | DATA_HIGH_BW = 7 | 
| ADDRESS_FILTER bitflags. | |
| static const uint8_t | fast_offset_en = 3 | 
| ADDRESS_ENABLE_FAST_CAL bitflags. | |
| static const uint8_t | fast_offset_en_x = 0 | 
| static const uint8_t | fast_offset_en_y = 1 | 
| static const uint8_t | fast_offset_en_z = 2 | 
| static const uint8_t | fast_offset_unfilt = 7 | 
| ADDRESS_FILTERED_CAL_FAST bitflags. | |
| static const uint8_t | nvm_load = 3 | 
| ADDRESS_NVM bitflags. | |
| static const uint8_t | SLAVE_ADDRESS0 = 0x68 | 
| BMG160 REGISTER ADDRESSES. | |
| static const uint8_t | SLAVE_ADDRESS1 = 0x69 | 
| the i2c device address with the chip's SDO pin connected to VDD. | |
| static const uint8_t | slow_offset_dur = 3 | 
| static const uint8_t | slow_offset_en_x = 0 | 
| static const uint8_t | slow_offset_en_y = 1 | 
| static const uint8_t | slow_offset_en_z = 2 | 
| static const uint8_t | slow_offset_th = 6 | 
| ADDRESS_ENABLE_CAL bitflags. | |
| static const uint8_t | slow_offset_unfilt = 5 | 
| ADDRESS_FILTERED_CAL bitflags. | |
| static const uint8_t | SOFTRESET_CMD = 0xB6 | 
| Register bitflags and commands: | |
| Private Member Functions | |
| bool | readReg (uint8_t reg, uint8_t *value) | 
| bool | writeToReg (uint8_t reg, uint8_t value) | 
| bool | writeToRegAndVerify (uint8_t reg, uint8_t value, uint8_t expected) | 
a bmg160 driver that implements the device's main capabilities.
This class provides access to the acceleration temperature, and Magnetic field data. Routines have been written to change settings, such as bandwidth and range, but not all capabilities of the sensor have been implemented.
Definition at line 82 of file bmg160.hpp.
Definition at line 56 of file bmg160.cpp.
| BMG160::~BMG160 | ( | ) | 
Definition at line 67 of file bmg160.cpp.
| bool BMG160::changeBandwidth | ( | ) | 
changes the gyro's bandwidth by writing to the appropriate sensor register.
The bandwidth is specified by the setBandwidth(bandwidth) method in the inheritted parameters class. The bandwidth will be changed to the default bandwidth if the user has not specified a bandwidth with setBandwidth(bandwidth) in the parameters class. See the datasheet for more details on register 0x10
Definition at line 216 of file bmg160.cpp.
| bool BMG160::changeRange | ( | ) | 
a method that changes the accelerometer's range by writing to the appropriate sensor register. The range is specified by the setRange(range) in the inheritted parameter's class.
The range will be changed to the default range if the user has not specified a range.
Definition at line 133 of file bmg160.cpp.
| void BMG160::computeOffsets | ( | uint8_t * | raw_offset_data, | 
| int16_t * | clean_offset_data | ||
| ) | 
| uint8_t* | raw_offset_data the name of the input array starting at ADDRESS_OFFSETS. | 
| uint8_t* | clean_offset_data the name of the output array of 3 unsigned 16-bit ints containing the 12-bit offset values. | 
Definition at line 579 of file bmg160.cpp.
| bool BMG160::filterData | ( | bool | request | ) | 
writes to the sensor's register in memory to choose whether or not to filter the gyro data.
The data will be set as unfiltered if the user has not specified an alternate request. See the datasheet (page 40) for more details on register 0x13.
| request | a boolean indicating the user's choice of filtered (true ) or unfiltered ( false ). | 
Definition at line 174 of file bmg160.cpp.
| uint8_t BMG160::getDeviceAddress | ( | ) |  [virtual] | 
An invalid request. It is necessary, since this driver inherits from the sensor_driver class.
See the getAccelAddress() and getCompassAddress() methods in the corresponding parameters class.
Implements bosch_drivers_common::sensor_driver.
Definition at line 443 of file bmg160.cpp.
| double BMG160::getGyroX | ( | ) | 
retrieves the raw gyro x-axis data and stores the calculated value to the class variable: GyroX_
If the application requires more than just one axis of data, use the takeMeasurement() instead, as it is much more efficient.
Definition at line 369 of file bmg160.cpp.
| double BMG160::getGyroY | ( | ) | 
retrieves the raw gyro y-axis data and stores the calculated value to the class variable: GyroY_
If the application requires more than just one axis of data, use the takeMeasurement() instead, as it is much more efficient.
Definition at line 388 of file bmg160.cpp.
| double BMG160::getGyroZ | ( | ) | 
retrieves the raw gyro z-axis data and stores the calculated value to the class variable: GyroZ_
If the application requires more than just one axis of data, use the takeMeasurement() instead, as it is much more efficient.
Definition at line 407 of file bmg160.cpp.
| double BMG160::getTemperature | ( | ) | 
retreives the raw gyro temperature and stores the calculated value in the class variable Temperature_.
If the application requires more than just the temperature, use the takeMeasurement() method instead, as it is much more efficient.
Definition at line 426 of file bmg160.cpp.
| bool BMG160::initialize | ( | ) | 
Initializes the sensor with all user-defined preferences indicated in the parameters.
Definition at line 75 of file bmg160.cpp.
| bool BMG160::printOffsets | ( | ) | 
read the offset registers, format the 12-bit values correctly, and print the values for all three axes.
Definition at line 602 of file bmg160.cpp.
| bool BMG160::readReg | ( | uint8_t | reg, | 
| uint8_t * | value | ||
| ) |  [private] | 
Definition at line 467 of file bmg160.cpp.
| bool BMG160::readSensorData | ( | uint8_t | reg, | 
| uint8_t * | data, | ||
| uint8_t | num_bytes | ||
| ) | 
reads num_bytes starting at register reg and stores the data into the array data_array.
Definition at line 549 of file bmg160.cpp.
| void BMG160::SimpleCalibration | ( | ) | 
calibrates the sensor assuming it is in a static position.
Calibration parameters are defaults, which are as follows: A calibration should be necessary only if the gyro does not produce accurate measurements. The sensor should already come from the factory with well-defined pre-calibrated constants.
Definition at line 254 of file bmg160.cpp.
| bool BMG160::softReset | ( | ) | 
resets the accelerometer, putting it back into normal mode and clearing its image.
Definition at line 110 of file bmg160.cpp.
| bool BMG160::takeMeasurement | ( | ) | 
Retrieves all available raw gyro data and stores the calculated value to class variables: GyroX_, GyroY_, GyroZ_, Temperature_.
Definition at line 343 of file bmg160.cpp.
| bool BMG160::writeToReg | ( | uint8_t | reg, | 
| uint8_t | value | ||
| ) |  [private] | 
Definition at line 497 of file bmg160.cpp.
| bool BMG160::writeToRegAndVerify | ( | uint8_t | reg, | 
| uint8_t | value, | ||
| uint8_t | expected | ||
| ) |  [private] | 
Definition at line 528 of file bmg160.cpp.
| const uint8_t BMG160::ADDRESS_BANDWIDTH = 0x10  [static] | 
Definition at line 326 of file bmg160.hpp.
| const uint8_t BMG160::ADDRESS_ENABLE_CAL = 0x31  [static] | 
Definition at line 331 of file bmg160.hpp.
| const uint8_t BMG160::ADDRESS_ENABLE_FAST_CAL = 0x32  [static] | 
Definition at line 332 of file bmg160.hpp.
| const uint8_t BMG160::ADDRESS_FILTER = 0x13  [static] | 
Definition at line 327 of file bmg160.hpp.
| const uint8_t BMG160::ADDRESS_FILTERED_CAL = 0x1A  [static] | 
Definition at line 329 of file bmg160.hpp.
| const uint8_t BMG160::ADDRESS_FILTERED_CAL_FAST = 0x1B  [static] | 
Definition at line 330 of file bmg160.hpp.
| const uint8_t BMG160::ADDRESS_GYRO_X_LSB = 0x02  [static] | 
Definition at line 320 of file bmg160.hpp.
| const uint8_t BMG160::ADDRESS_GYRO_Y_LSB = 0x04  [static] | 
Definition at line 321 of file bmg160.hpp.
| const uint8_t BMG160::ADDRESS_GYRO_Z_LSB = 0x06  [static] | 
Definition at line 322 of file bmg160.hpp.
| const uint8_t BMG160::ADDRESS_NVM = 0x33  [static] | 
Definition at line 333 of file bmg160.hpp.
| static const uint8_t BMG160::ADDRESS_OFFSETS = 0x36  [static] | 
the starting address of the offset values that are adjusted in calibration.
Definition at line 346 of file bmg160.hpp.
| const uint8_t BMG160::ADDRESS_RANGE = 0x0F  [static] | 
Definition at line 325 of file bmg160.hpp.
| const uint8_t BMG160::ADDRESS_SOFTRESET = 0x14  [static] | 
Definition at line 328 of file bmg160.hpp.
| const uint8_t BMG160::ADDRESS_TEMPERATURE = 0x08  [static] | 
Definition at line 323 of file bmg160.hpp.
| const uint8_t BMG160::DATA_HIGH_BW = 7  [static] | 
ADDRESS_FILTER bitflags.
The following members are the relevant bitflag offsets of the ADDRESS_FILTER register:
Definition at line 96 of file bmg160.hpp.
| const uint8_t BMG160::fast_offset_en = 3  [static] | 
ADDRESS_ENABLE_FAST_CAL bitflags.
The following members are the relevant bitflag offsets of the ADDRESS_ENABLE_FAST_CAL register:
Definition at line 104 of file bmg160.hpp.
| const uint8_t BMG160::fast_offset_en_x = 0  [static] | 
Definition at line 107 of file bmg160.hpp.
| const uint8_t BMG160::fast_offset_en_y = 1  [static] | 
Definition at line 106 of file bmg160.hpp.
| const uint8_t BMG160::fast_offset_en_z = 2  [static] | 
Definition at line 105 of file bmg160.hpp.
| const uint8_t BMG160::fast_offset_unfilt = 7  [static] | 
ADDRESS_FILTERED_CAL_FAST bitflags.
The following members are the relevant bitflag offsets of the ADDRESS_FILTERED_CAL_FAST register:
Definition at line 115 of file bmg160.hpp.
| double BMG160::GyroX_ | 
Definition at line 348 of file bmg160.hpp.
| double BMG160::GyroY_ | 
Definition at line 349 of file bmg160.hpp.
| double BMG160::GyroZ_ | 
Definition at line 350 of file bmg160.hpp.
| const uint8_t BMG160::nvm_load = 3  [static] | 
ADDRESS_NVM bitflags.
The following members are the relevant bitflag offsets of the ADDRESS_NVM register:
Definition at line 143 of file bmg160.hpp.
| static const uint8_t BMG160::SLAVE_ADDRESS0 = 0x68  [static] | 
BMG160 REGISTER ADDRESSES.
the i2c device address with the chip's SDO pin connected to GND .
Definition at line 314 of file bmg160.hpp.
| static const uint8_t BMG160::SLAVE_ADDRESS1 = 0x69  [static] | 
the i2c device address with the chip's SDO pin connected to VDD.
Definition at line 318 of file bmg160.hpp.
| const uint8_t BMG160::slow_offset_dur = 3  [static] | 
Definition at line 124 of file bmg160.hpp.
| const uint8_t BMG160::slow_offset_en_x = 0  [static] | 
Definition at line 125 of file bmg160.hpp.
| const uint8_t BMG160::slow_offset_en_y = 1  [static] | 
Definition at line 126 of file bmg160.hpp.
| const uint8_t BMG160::slow_offset_en_z = 2  [static] | 
Definition at line 127 of file bmg160.hpp.
| const uint8_t BMG160::slow_offset_th = 6  [static] | 
ADDRESS_ENABLE_CAL bitflags.
The following members are the relevant bitflag offsets of the ADDRESS_ENABLE_CAL register:
Definition at line 123 of file bmg160.hpp.
| const uint8_t BMG160::slow_offset_unfilt = 5  [static] | 
ADDRESS_FILTERED_CAL bitflags.
The following members are the relevant bitflag offsets of the ADDRESS_FILTERED_CAL register:
Definition at line 135 of file bmg160.hpp.
| const uint8_t BMG160::SOFTRESET_CMD = 0xB6  [static] | 
Register bitflags and commands:
Definition at line 88 of file bmg160.hpp.
| double BMG160::Temperature_ | 
Definition at line 351 of file bmg160.hpp.
| double BMG160::TempSlope_ | 
Definition at line 352 of file bmg160.hpp.