bmx055: remove bmm150, use new bmm150 library

Signed-off-by: Jon Trulson <jtrulson@ics.com>
This commit is contained in:
Jon Trulson 2017-03-29 14:09:35 -06:00
parent aeaf84ccc6
commit c014ffddcd
15 changed files with 398 additions and 1718 deletions

View File

@ -6,6 +6,24 @@ compatibility between releases:
# current master # current master
* **bmx055, bmi055, bmc150, bma250e, bmg160, bmm150** This driver has
been split up. The *bma250e*, *bmg160*, *bmm150* drivers have been
rewritten in C (with C++ wrappers) and now reside in their own
libraries. The versions of these drivers that used to be present in
*bmx055* have been removed, and *bmx055* now uses the new libraries
for it's functionality. The other two composite devices, *bmi055*,
and *bmc150* are still contained within the *bmx055* library, and
also use the new libraries for their functionality.
In addition, for all of these drivers some private methods are no
longer exposed (such as the compensation routines).
The C++ driver methods that once returned pointers to a floating
point array now return *std::vectors* of the appropriate type. The
SWIG language examples for these drivers have been modified to use
these methods instead of the C pointer based SWIG methods previously
used.
* **sainsmartks** This driver has been renamed to *lcdks* (LCD Keypad * **sainsmartks** This driver has been renamed to *lcdks* (LCD Keypad
Shield) and moved into it's own library. It uses the *lcm1602* Shield) and moved into it's own library. It uses the *lcm1602*
library to do most of it's work. In addition, an additional argument library to do most of it's work. In addition, an additional argument
@ -33,8 +51,8 @@ compatibility between releases:
used previously. This should make it easier to use with the SWIG used previously. This should make it easier to use with the SWIG
language bindings (Python, Javascript, and especially Java). language bindings (Python, Javascript, and especially Java).
* **bmp280/bme280** Some private methods are no longer exposed * **bmp280/bme280** Some private methods are no longer exposed (such
(such as the calibration and compensation routines). In addition, as the calibration and compensation routines). In addition,
the *getHumidity()* method no longer accepts an argument representing the *getHumidity()* method no longer accepts an argument representing
pressure at sea level. A separate method is provided to set this now. pressure at sea level. A separate method is provided to set this now.

View File

@ -40,18 +40,18 @@ public class BMC150_Example
// update our values from the sensor // update our values from the sensor
sensor.update(); sensor.update();
upm_bmx055.floatVector dataA = sensor.getAccelerometer(); upm_bmx055.floatVector data = sensor.getAccelerometer();
System.out.println("Accelerometer x: " + dataA.get(0) System.out.println("Accelerometer x: " + data.get(0)
+ " y: " + dataA.get(1) + " y: " + data.get(1)
+ " z: " + dataA.get(2) + " z: " + data.get(2)
+ " g"); + " g");
float data[] = sensor.getMagnetometer(); data = sensor.getMagnetometer();
System.out.println("Magnetometer x: " + data[0] System.out.println("Magnetometer x: " + data.get(0)
+ " y: " + data[1] + " y: " + data.get(1)
+ " z: " + data[2] + " z: " + data.get(2)
+ " uT"); + " uT");
System.out.println(); System.out.println();

View File

@ -54,11 +54,11 @@ public class BMX055_Example
+ " z: " + data.get(2) + " z: " + data.get(2)
+ " degrees/s"); + " degrees/s");
float dataM[] = sensor.getMagnetometer(); data = sensor.getMagnetometer();
System.out.println("Magnetometer x: " + dataM[0] System.out.println("Magnetometer x: " + data.get(0)
+ " y: " + dataM[1] + " y: " + data.get(1)
+ " z: " + dataM[2] + " z: " + data.get(2)
+ " uT"); + " uT");
System.out.println(); System.out.println();

View File

@ -1,5 +1,5 @@
upm_mixed_module_init (NAME bmx055 upm_mixed_module_init (NAME bmx055
DESCRIPTION "Bosch IMU Sensor Library" DESCRIPTION "Bosch IMU Sensor Library"
CPP_HDR bmx055.hpp bmm150.hpp bmc150.cxx bmi055.hpp CPP_HDR bmx055.hpp bmc150.cxx bmi055.hpp
CPP_SRC bmx055.cxx bmm150.cxx bmc150.cxx bmi055.cxx CPP_SRC bmx055.cxx bmc150.cxx bmi055.cxx
REQUIRES mraa bmg160 bma250e) REQUIRES mraa bmg160 bma250e bmm150)

View File

@ -72,7 +72,7 @@ void BMC150::initAccelerometer(BMA250E_POWER_MODE_T pwr,
m_accel->init(pwr, range, bw); m_accel->init(pwr, range, bw);
} }
void BMC150::initMagnetometer(BMM150::USAGE_PRESETS_T usage) void BMC150::initMagnetometer(BMM150_USAGE_PRESETS_T usage)
{ {
if (m_mag) if (m_mag)
m_mag->init(usage); m_mag->init(usage);
@ -107,13 +107,10 @@ void BMC150::getMagnetometer(float *x, float *y, float *z)
m_mag->getMagnetometer(x, y, z); m_mag->getMagnetometer(x, y, z);
} }
float *BMC150::getMagnetometer() std::vector<float> BMC150::getMagnetometer()
{ {
if (m_mag) if (m_mag)
return m_mag->getMagnetometer(); return m_mag->getMagnetometer();
else else
{ return {0, 0, 0};
static float v[3] = {0.0f, 0.0f, 0.0f};
return v;
}
} }

View File

@ -123,7 +123,8 @@ namespace upm {
* @param bw One of the filtering BMA250E_BW_T values. The default is * @param bw One of the filtering BMA250E_BW_T values. The default is
* BMA250E_BW_250. * BMA250E_BW_250.
*/ */
void initAccelerometer(BMA250E_POWER_MODE_T pwr=BMA250E_POWER_MODE_NORMAL, void initAccelerometer(
BMA250E_POWER_MODE_T pwr=BMA250E_POWER_MODE_NORMAL,
BMA250E_RANGE_T range=BMA250E_RANGE_2G, BMA250E_RANGE_T range=BMA250E_RANGE_2G,
BMA250E_BW_T bw=BMA250E_BW_250); BMA250E_BW_T bw=BMA250E_BW_250);
@ -134,10 +135,11 @@ namespace upm {
* change these values. This method will call * change these values. This method will call
* BMM150::setPresetMode() with the passed parameter. * BMM150::setPresetMode() with the passed parameter.
* *
* @param usage One of the BMM150::USAGE_PRESETS_T values. The default is * @param usage One of the BMM150_USAGE_PRESETS_T values.
* BMM150::USAGE_HIGH_ACCURACY. * The default is BMM150_USAGE_HIGH_ACCURACY.
*/ */
void initMagnetometer(BMM150::USAGE_PRESETS_T usage=BMM150::USAGE_HIGH_ACCURACY); void initMagnetometer(
BMM150_USAGE_PRESETS_T usage=BMM150_USAGE_HIGH_ACCURACY);
/** /**
* Return accelerometer data in gravities. update() must have * Return accelerometer data in gravities. update() must have
@ -176,15 +178,14 @@ namespace upm {
void getMagnetometer(float *x, float *y, float *z); void getMagnetometer(float *x, float *y, float *z);
/** /**
* Return magnetometer data in micro-Teslas (uT) in the form of a * Return magnetometer data in micro-Teslas (uT) in the form
* floating point array. The pointer returned by this function is * of a floating point vector. update() must have been called
* statically allocated and will be rewritten on each call. * prior to calling this method.
* update() must have been called prior to calling this method.
* *
* @return A floating point array containing x, y, and z in * @return A floating point vector containing x, y, and z in
* that order. * that order.
*/ */
float *getMagnetometer(); std::vector<float> getMagnetometer();
protected: protected:

View File

@ -117,7 +117,8 @@ namespace upm {
* @param bw One of the filtering BMA250E_BW_T values. The default is * @param bw One of the filtering BMA250E_BW_T values. The default is
* BMA250E_BW_250. * BMA250E_BW_250.
*/ */
void initAccelerometer(BMA250E_POWER_MODE_T pwr=BMA250E_POWER_MODE_NORMAL, void initAccelerometer(
BMA250E_POWER_MODE_T pwr=BMA250E_POWER_MODE_NORMAL,
BMA250E_RANGE_T range=BMA250E_RANGE_2G, BMA250E_RANGE_T range=BMA250E_RANGE_2G,
BMA250E_BW_T bw=BMA250E_BW_250); BMA250E_BW_T bw=BMA250E_BW_250);

View File

@ -1,688 +0,0 @@
/*
* Author: Jon Trulson <jtrulson@ics.com>
* Copyright (c) 2016 Intel Corporation.
*
* Permission is hereby granted, free of charge, to any person obtaining
* a copy of this software and associated documentation files (the
* "Software"), to deal in the Software without restriction, including
* without limitation the rights to use, copy, modify, merge, publish,
* distribute, sublicense, and/or sell copies of the Software, and to
* permit persons to whom the Software is furnished to do so, subject to
* the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE
* LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION
* OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
* WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/
// The trimming algorithms are taken from the Bosch BMM050 driver code
/****************************************************************************
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* File : bmm050.h
*
* Date : 2016/03/17
*
* Revision : 2.0.5 $
*
* Usage: Sensor Driver for BMM050 and BMM150 sensor
*
****************************************************************************
*
* section License
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* Neither the name of the copyright holder nor the names of the
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER
* OR CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY,
* OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO,
* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE
*
* The information provided is believed to be accurate and reliable.
* The copyright holder assumes no responsibility
* for the consequences of use
* of such information nor for any infringement of patents or
* other rights of third parties which may result from its use.
* No license is granted by implication or otherwise under any patent or
* patent rights of the copyright holder.
**************************************************************************/
#include <unistd.h>
#include <iostream>
#include <stdexcept>
#include <string>
#include <string.h>
#include "bmm150.hpp"
#define BMM150_DEFAULT_CHIPID 0x32
using namespace upm;
using namespace std;
BMM150::BMM150(int bus, int addr, int cs) :
m_i2c(0), m_spi(0), m_gpioIntr(0), m_gpioDR(0), m_gpioCS(0)
{
m_magX = 0;
m_magY = 0;
m_magZ = 0;
m_hall = 0;
m_dig_x1 = 0;
m_dig_y1 = 0;
m_dig_z4 = 0;
m_dig_x2 = 0;
m_dig_y2 = 0;
m_dig_z2 = 0;
m_dig_z1 = 0;
m_dig_xyz1 = 0;
m_dig_z3 = 0;
m_dig_xy2 = 0;
m_dig_xy1 = 0;
if (addr < 0)
{
m_addr = 0;
m_isSPI = true;
}
else
{
m_addr = uint8_t(addr);
m_isSPI = false;
}
if (m_isSPI)
{
m_spi = new mraa::Spi(bus);
// Only create cs context if we are actually using a valid pin.
// A hardware controlled pin should specify cs as -1.
if (cs >= 0)
{
m_gpioCS = new mraa::Gpio(cs);
m_gpioCS->dir(mraa::DIR_OUT);
}
m_spi->mode(mraa::SPI_MODE0);
m_spi->frequency(5000000);
}
else
{
// I2C
m_i2c = new mraa::I2c(bus);
mraa::Result rv;
if ((rv = m_i2c->address(m_addr)) != mraa::SUCCESS)
{
throw std::runtime_error(string(__FUNCTION__) +
": I2c.address() failed");
}
}
// power bit must be on for chip ID to be accessable
setPowerBit(true);
m_opmode = OPERATION_MODE_SLEEP;
usleep(50000);
// check the chip id
uint8_t chipID = getChipID();
if (chipID != BMM150_DEFAULT_CHIPID)
{
throw std::runtime_error(string(__FUNCTION__)
+ ": invalid chip ID. Expected "
+ std::to_string(int(BMM150_DEFAULT_CHIPID))
+ ", got "
+ std::to_string(int(chipID)));
}
// get trim data
readTrimData();
// call init with default options
init();
}
BMM150::~BMM150()
{
uninstallISR(INTERRUPT_INT);
uninstallISR(INTERRUPT_DR);
if (m_i2c)
delete m_i2c;
if (m_spi)
delete m_spi;
if(m_gpioCS)
delete m_gpioCS;
}
void BMM150::init(USAGE_PRESETS_T usage)
{
setPowerBit(true);
setOpmode(OPERATION_MODE_NORMAL);
usleep(50000); // 50ms, in case we are waking up
setPresetMode(usage);
// settle
usleep(50000);
}
void BMM150::update()
{
// special care when in a forced mode - need to trigger a
// measurement, and wait for the opmode to return to OPMODE_SLEEP,
// then we can read the values.
if (m_opmode == OPERATION_MODE_FORCED)
{
// trigger measurement
setOpmode(OPERATION_MODE_FORCED);
// opmode will return to sleep after measurement is complete
do {
usleep(5000);
} while (getOpmode() == OPERATION_MODE_FORCED);
}
const int bufLen = 8;
uint8_t buf[bufLen];
if (readRegs(REG_MAG_X_LSB, buf, bufLen) != bufLen)
{
throw std::runtime_error(string(__FUNCTION__)
+ ": readRegs() failed to read "
+ std::to_string(bufLen)
+ " bytes");
}
// we need to get the hall data first, since it's needed for the
// bosch compensation functions for each of the xyz axes
m_hall = uint16_t(buf[7] << 8 | (buf[6] &
(_MAG_RHALL_LSB_LSB_MASK <<
_MAG_RHALL_LSB_LSB_SHIFT)));
m_hall /= 4;
int16_t val;
// x
val = int16_t(buf[1] << 8 | (buf[0] & (_MAG_XY_LSB_LSB_MASK <<
_MAG_XY_LSB_LSB_SHIFT)));
val /= 8;
m_magX = bmm050_compensate_X_float(val, m_hall);
// y
val = int16_t(buf[3] << 8 | (buf[2] & (_MAG_XY_LSB_LSB_MASK <<
_MAG_XY_LSB_LSB_SHIFT)));
val /= 8;
m_magY = bmm050_compensate_Y_float(val, m_hall);
// z
val = int16_t(buf[5] << 8 | (buf[4] & (_MAG_Z_LSB_LSB_MASK <<
_MAG_Z_LSB_LSB_SHIFT)));
val /= 2;
m_magZ = bmm050_compensate_Z_float(val, m_hall);
}
uint8_t BMM150::readReg(uint8_t reg)
{
if (m_isSPI)
{
reg |= 0x80; // needed for read
uint8_t pkt[2] = {reg, 0};
csOn();
if (m_spi->transfer(pkt, pkt, 2))
{
csOff();
throw std::runtime_error(string(__FUNCTION__)
+ ": Spi.transfer() failed");
}
csOff();
return pkt[1];
}
else
return m_i2c->readReg(reg);
}
int BMM150::readRegs(uint8_t reg, uint8_t *buffer, int len)
{
if (m_isSPI)
{
reg |= 0x80; // needed for read
uint8_t sbuf[len + 1];
memset((char *)sbuf, 0, len + 1);
sbuf[0] = reg;
// We need to do it this way for edison - ie: use a single
// transfer rather than breaking it up into two like we used to.
// This means a buffer copy is now required, but that's the way
// it goes.
csOn();
if (m_spi->transfer(sbuf, sbuf, len + 1))
{
csOff();
throw std::runtime_error(string(__FUNCTION__)
+ ": Spi.transfer(buf) failed");
}
csOff();
// now copy it into user buffer
for (int i=0; i<len; i++)
buffer[i] = sbuf[i + 1];
return len;
}
else
return m_i2c->readBytesReg(reg, buffer, len);
}
void BMM150::writeReg(uint8_t reg, uint8_t val)
{
if (m_isSPI)
{
reg &= 0x7f; // mask off 0x80 for writing
uint8_t pkt[2] = {reg, val};
csOn();
if (m_spi->transfer(pkt, NULL, 2))
{
csOff();
throw std::runtime_error(string(__FUNCTION__)
+ ": Spi.transfer() failed");
}
csOff();
}
else
{
mraa::Result rv;
if ((rv = m_i2c->writeReg(reg, val)) != mraa::SUCCESS)
{
throw std::runtime_error(std::string(__FUNCTION__)
+ ": I2c.writeReg() failed");
}
}
}
void BMM150::csOn()
{
if (m_gpioCS)
m_gpioCS->write(0);
}
void BMM150::csOff()
{
if (m_gpioCS)
m_gpioCS->write(1);
}
uint8_t BMM150::getChipID()
{
return readReg(REG_CHIP_ID);
}
void BMM150::getMagnetometer(float *x, float *y, float *z)
{
if (x)
*x = m_magX;
if (y)
*y = m_magY;
if (z)
*z = m_magZ;
}
float *BMM150::getMagnetometer()
{
static float v[3];
getMagnetometer(&v[0], &v[1], &v[2]);
return v;
}
void BMM150::reset()
{
// mask off reserved bits
uint8_t reg = readReg(REG_POWER_CTRL) & ~_POWER_CTRL_RESERVED_BITS;
reg |= POWER_CTRL_SOFT_RESET0 | POWER_CTRL_SOFT_RESET1;
writeReg(REG_POWER_CTRL, reg);
sleep(1);
// device will return to SLEEP mode...
}
void BMM150::setOutputDataRate(DATA_RATE_T odr)
{
uint8_t reg = readReg(REG_OPMODE);
reg &= ~(_OPMODE_DATA_RATE_MASK << _OPMODE_DATA_RATE_SHIFT);
reg |= (odr << _OPMODE_DATA_RATE_SHIFT);
writeReg(REG_OPMODE, reg);
}
void BMM150::setPowerBit(bool power)
{
// mask off reserved bits
uint8_t reg = readReg(REG_POWER_CTRL) & ~_POWER_CTRL_RESERVED_BITS;
if (power)
reg |= POWER_CTRL_POWER_CTRL_BIT;
else
reg &= ~POWER_CTRL_POWER_CTRL_BIT;
writeReg(REG_POWER_CTRL, reg);
}
void BMM150::setOpmode(OPERATION_MODE_T opmode)
{
uint8_t reg = readReg(REG_OPMODE);
reg &= ~(_OPMODE_OPERATION_MODE_MASK << _OPMODE_OPERATION_MODE_SHIFT);
reg |= (opmode << _OPMODE_OPERATION_MODE_SHIFT);
writeReg(REG_OPMODE, reg);
m_opmode = opmode;
}
BMM150::OPERATION_MODE_T BMM150::getOpmode()
{
uint8_t reg = readReg(REG_OPMODE);
reg &= (_OPMODE_OPERATION_MODE_MASK << _OPMODE_OPERATION_MODE_SHIFT);
reg >>= _OPMODE_OPERATION_MODE_SHIFT;
return static_cast<OPERATION_MODE_T>(reg);
}
uint8_t BMM150::getInterruptEnable()
{
return readReg(REG_INT_EN);
}
void BMM150::setInterruptEnable(uint8_t bits)
{
writeReg(REG_INT_EN, bits);
}
uint8_t BMM150::getInterruptConfig()
{
return readReg(REG_INT_CONFIG);
}
void BMM150::setInterruptConfig(uint8_t bits)
{
writeReg(REG_INT_CONFIG, bits);
}
uint8_t BMM150::getInterruptStatus()
{
return readReg(REG_INT_STATUS);
}
void BMM150::readTrimData()
{
int bufLen = 10;
uint8_t calibData[bufLen];
// 2 bytes first
readRegs(REG_TRIM_DIG_X1, calibData, 2);
m_dig_x1 = int8_t(calibData[0]);
m_dig_y1 = int8_t(calibData[1]);
// next block of 4 bytes
readRegs(REG_TRIM_DIG_Z4_LSB, calibData, 4);
m_dig_z4 = int16_t((calibData[1] << 8) | calibData[0]);
m_dig_x2 = int8_t(calibData[2]);
m_dig_y2 = int8_t(calibData[3]);
// final block of 10 bytes
readRegs(REG_TRIM_DIG_Z2_LSB, calibData, 10);
m_dig_z2 = int16_t((calibData[1] << 8) | calibData[0]);
m_dig_z1 = uint16_t((calibData[3] << 8) | calibData[2]);
m_dig_xyz1 = uint16_t((calibData[5] << 8) | calibData[4]);
m_dig_z3 = int16_t((calibData[7] << 8) | calibData[6]);
m_dig_xy2 = int8_t(calibData[8]);
m_dig_xy1 = calibData[9];
}
void BMM150::setRepetitionsXY(uint8_t reps)
{
writeReg(REG_REP_XY, reps);
}
void BMM150::setRepetitionsZ(uint8_t reps)
{
writeReg(REG_REP_Z, reps);
}
void BMM150::setPresetMode(USAGE_PRESETS_T usage)
{
// these recommended presets come from the datasheet, Table 3,
// Section 4.2
switch (usage)
{
case USAGE_LOW_POWER:
setRepetitionsXY(3);
setRepetitionsZ(3);
setOutputDataRate(DATA_RATE_10HZ);
break;
case USAGE_REGULAR:
setRepetitionsXY(9);
setRepetitionsZ(15);
setOutputDataRate(DATA_RATE_10HZ);
break;
case USAGE_ENHANCED_REGULAR:
setRepetitionsXY(15);
setRepetitionsZ(27);
setOutputDataRate(DATA_RATE_10HZ);
break;
case USAGE_HIGH_ACCURACY:
setRepetitionsXY(47);
setRepetitionsZ(83);
setOutputDataRate(DATA_RATE_20HZ);
break;
default:
throw std::out_of_range(string(__FUNCTION__) +
": Invalid usage enum passed");
}
}
#if defined(SWIGJAVA) || (JAVACALLBACK)
void BMM150::installISR(INTERRUPT_PINS_T intr, int gpio, mraa::Edge level,
jobject runnable)
{
// delete any existing ISR and GPIO context
uninstallISR(intr);
// create gpio context
getPin(intr) = new mraa::Gpio(gpio);
getPin(intr)->dir(mraa::DIR_IN);
getPin(intr)->isr(level, runnable);
}
#else
void BMM150::installISR(INTERRUPT_PINS_T intr, int gpio, mraa::Edge level,
void (*isr)(void *), void *arg)
{
// delete any existing ISR and GPIO context
uninstallISR(intr);
// create gpio context
getPin(intr) = new mraa::Gpio(gpio);
getPin(intr)->dir(mraa::DIR_IN);
getPin(intr)->isr(level, isr, arg);
}
#endif
void BMM150::uninstallISR(INTERRUPT_PINS_T intr)
{
if (getPin(intr))
{
getPin(intr)->isrExit();
delete getPin(intr);
getPin(intr) = 0;
}
}
mraa::Gpio*& BMM150::getPin(INTERRUPT_PINS_T intr)
{
switch(intr)
{
case INTERRUPT_INT:
return m_gpioIntr;
break;
case INTERRUPT_DR:
return m_gpioDR;
break;
default:
throw std::out_of_range(string(__FUNCTION__) +
": Invalid interrupt enum passed");
}
}
// Bosch compensation functions
float BMM150::bmm050_compensate_X_float(int16_t mag_data_x, uint16_t data_r)
{
float inter_retval = 0;
if (mag_data_x != -4096 /* no overflow */
) {
if ((data_r != 0)
&& (m_dig_xyz1 != 0)) {
inter_retval = ((((float)m_dig_xyz1)
* 16384.0 / data_r) - 16384.0);
} else {
inter_retval = 0.0f;
return inter_retval;
}
inter_retval = (((mag_data_x * ((((((float)m_dig_xy2) *
(inter_retval*inter_retval /
268435456.0) +
inter_retval * ((float)m_dig_xy1)
/ 16384.0)) + 256.0) *
(((float)m_dig_x2) + 160.0)))
/ 8192.0)
+ (((float)m_dig_x1) *
8.0)) / 16.0;
} else {
inter_retval = 0.0f;
}
return inter_retval;
}
float BMM150::bmm050_compensate_Y_float(int16_t mag_data_y, uint16_t data_r)
{
float inter_retval = 0;
if (mag_data_y != -4096 /* no overflow */
) {
if ((data_r != 0)
&& (m_dig_xyz1 != 0)) {
inter_retval = ((((float)m_dig_xyz1)
* 16384.0
/data_r) - 16384.0);
} else {
inter_retval = 0.0f;
return inter_retval;
}
inter_retval = (((mag_data_y * ((((((float)m_dig_xy2) *
(inter_retval*inter_retval
/ 268435456.0) +
inter_retval * ((float)m_dig_xy1)
/ 16384.0)) +
256.0) *
(((float)m_dig_y2) + 160.0)))
/ 8192.0) +
(((float)m_dig_y1) * 8.0))
/ 16.0;
} else {
/* overflow, set output to 0.0f */
inter_retval = 0.0f;
}
return inter_retval;
}
float BMM150::bmm050_compensate_Z_float(int16_t mag_data_z, uint16_t data_r)
{
float inter_retval = 0;
/* no overflow */
if (mag_data_z != -16384) {
if ((m_dig_z2 != 0)
&& (m_dig_z1 != 0)
&& (m_dig_xyz1 != 0)
&& (data_r != 0)) {
inter_retval = ((((((float)mag_data_z)-
((float)m_dig_z4)) * 131072.0)-
(((float)m_dig_z3)*(((float)data_r)
-((float)m_dig_xyz1))))
/((((float)m_dig_z2)+
((float)m_dig_z1)*((float)data_r) /
32768.0) * 4.0)) / 16.0;
}
} else {
/* overflow, set output to 0.0f */
inter_retval = 0.0f;
}
return inter_retval;
}

View File

@ -1,613 +0,0 @@
/*
* Author: Jon Trulson <jtrulson@ics.com>
* Copyright (c) 2016 Intel Corporation.
*
* Permission is hereby granted, free of charge, to any person obtaining
* a copy of this software and associated documentation files (the
* "Software"), to deal in the Software without restriction, including
* without limitation the rights to use, copy, modify, merge, publish,
* distribute, sublicense, and/or sell copies of the Software, and to
* permit persons to whom the Software is furnished to do so, subject to
* the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE
* LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION
* OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
* WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/
#pragma once
#include <string>
#include <mraa/i2c.hpp>
#include <mraa/spi.hpp>
#include <mraa/gpio.hpp>
#define BMM150_I2C_BUS 0
#define BMM150_SPI_BUS 0
#define BMM150_DEFAULT_ADDR 0x10
namespace upm {
/**
* @library bmx050
* @sensor bmm150
* @comname 3-axis Geomagnetic Sensor
* @altname bmm050
* @type compass
* @man bosch
* @con i2c spi gpio
* @web https://www.bosch-sensortec.com/bst/products/all_products/bmm150
*
* @brief API for the BMM150 3-Axis Geomagnetic Sensor
*
* The BMM150 is a standalone geomagnetic sensor for consumer market
* applications. It allows measurements of the magnetic field in
* three perpendicular axes. Based on Bosch's proprietary FlipCore
* technology, performance and features of BMM150 are carefully
* tuned and perfectly match the demanding requirements of all
* 3-axis mobile applications such as electronic compass, navigation
* or augmented reality.
*
* An evaluation circuitry (ASIC) converts the output of the
* geomagnetic sensor to digital results which can be read out over
* the industry standard digital interfaces (SPI and I2C).
*
* Not all functionality of this chip has been implemented in this
* driver, however all the pieces are present to add any desired
* functionality. This driver supports both I2C (default) and SPI
* operation.
*
* This device requires 3.3v operation.
*
* @snippet bmm150.cxx Interesting
*/
class BMM150 {
public:
// NOTE: Reserved registers must not be written into. Reading
// from them may return indeterminate values. Registers
// containing reserved bitfields must be written as 0. Reading
// reserved bitfields may return indeterminate values.
/**
* BMM150 registers
*/
typedef enum : uint8_t {
REG_CHIP_ID = 0x40,
// 0x41 reserved
REG_MAG_X_LSB = 0x42,
REG_MAG_X_MSB = 0x43,
REG_MAG_Y_LSB = 0x44,
REG_MAG_Y_MSB = 0x45,
REG_MAG_Z_LSB = 0x46,
REG_MAG_Z_MSB = 0x47,
REG_RHALL_LSB = 0x48,
REG_RHALL_MSB = 0x49,
REG_INT_STATUS = 0x4a,
REG_POWER_CTRL = 0x4b,
REG_OPMODE = 0x4c,
REG_INT_EN = 0x4d,
REG_INT_CONFIG = 0x4e,
REG_LOW_THRES = 0x4f,
REG_HIGH_THRES = 0x50,
REG_REP_XY = 0x51,
REG_REP_Z = 0x52,
// 0x53-0x71 reserved (mostly)
// TRIM registers from Bosch BMM050 driver
REG_TRIM_DIG_X1 = 0x5d,
REG_TRIM_DIG_Y1 = 0x5e,
REG_TRIM_DIG_Z4_LSB = 0x62,
REG_TRIM_DIG_Z4_MSB = 0x63,
REG_TRIM_DIG_X2 = 0x64,
REG_TRIM_DIG_Y2 = 0x65,
REG_TRIM_DIG_Z2_LSB = 0x68,
REG_TRIM_DIG_Z2_MSB = 0x69,
REG_TRIM_DIG_Z1_LSB = 0x6a,
REG_TRIM_DIG_Z1_MSB = 0x6b,
REG_TRIM_DIG_XYZ1_LSB = 0x6c,
REG_TRIM_DIG_XYZ1_MSB = 0x6d,
REG_TRIM_DIG_Z3_LSB = 0x6e,
REG_TRIM_DIG_Z3_MSB = 0x6f,
REG_TRIM_DIG_XY2 = 0x70,
REG_TRIM_DIG_XY1 = 0x71
} BMM150_REGS_T;
/**
* REG_MAG_XY_LSB bits (for X and Y mag data LSB's only)
*/
typedef enum {
_MAG_XY_LSB_RESERVED_BITS = 0x02 | 0x04,
MAG_XY_LSB_SELFTEST_XY = 0x01,
MAG_XY_LSB_LSB0 = 0x08,
MAG_XY_LSB_LSB1 = 0x10,
MAG_XY_LSB_LSB2 = 0x20,
MAG_XY_LSB_LSB3 = 0x40,
MAG_XY_LSB_LSB4 = 0x80,
_MAG_XY_LSB_LSB_MASK = 31,
_MAG_XY_LSB_LSB_SHIFT = 3
} MAG_XY_LSB_BITS_T;
/**
* REG_MAG_Z_LSB bits (for Z LSB only)
*/
typedef enum {
MAG_Z_LSB_SELFTEST_Z = 0x01,
MAG_Z_LSB_LSB0 = 0x02,
MAG_Z_LSB_LSB1 = 0x04,
MAG_Z_LSB_LSB2 = 0x08,
MAG_Z_LSB_LSB3 = 0x10,
MAG_Z_LSB_LSB4 = 0x20,
MAG_Z_LSB_LSB5 = 0x40,
MAG_Z_LSB_LSB6 = 0x80,
_MAG_Z_LSB_LSB_MASK = 127,
_MAG_Z_LSB_LSB_SHIFT = 1
} MAG_Z_LSB_BITS_T;
/**
* REG_MAG_RHALL_LSB bits (for RHALL LSB only)
*/
typedef enum {
_MAG_RHALL_LSB_RESERVED_BITS = 0x02,
MAG_RHALL_LSB_DATA_READY_STATUS = 0x01,
MAG_RHALL_LSB_LSB0 = 0x04,
MAG_RHALL_LSB_LSB1 = 0x08,
MAG_RHALL_LSB_LSB2 = 0x10,
MAG_RHALL_LSB_LSB3 = 0x20,
MAG_RHALL_LSB_LSB4 = 0x40,
MAG_RHALL_LSB_LSB5 = 0x80,
_MAG_RHALL_LSB_LSB_MASK = 63,
_MAG_RHALL_LSB_LSB_SHIFT = 2
} MAG_RHALL_LSB_BITS_T;
/**
* REG_INT_STATUS bits
*/
typedef enum {
INT_STATUS_LOW_INT_X = 0x01,
INT_STATUS_LOW_INT_Y = 0x02,
INT_STATUS_LOW_INT_Z = 0x04,
INT_STATUS_HIGH_INT_X = 0x08,
INT_STATUS_HIGH_INT_Y = 0x10,
INT_STATUS_HIGH_INT_Z = 0x20,
INT_STATUS_OVERFLOW = 0x40,
INT_STATUS_DATA_OVERRUN = 0x80
} INT_STATUS_BITS_T;
/**
* REG_POWER_CTRL bits
*/
typedef enum {
_POWER_CTRL_RESERVED_BITS = 0x40 | 0x20 | 0x10 | 0x08,
POWER_CTRL_POWER_CTRL_BIT = 0x01,
POWER_CTRL_SOFT_RESET0 = 0x02,
POWER_CTRL_SPI3EN = 0x04, // not supported
POWER_CTRL_SOFT_RESET1 = 0x80
} POWER_CTRL_BITS_T;
/**
* REG_OPMODE bits
*/
typedef enum {
OPMODE_SELFTTEST = 0x01,
OPMODE_OPERATION_MODE0 = 0x02,
OPMODE_OPERATION_MODE1 = 0x04,
_OPMODE_OPERATION_MODE_MASK = 3,
_OPMODE_OPERATION_MODE_SHIFT = 1,
OPMODE_DATA_RATE0 = 0x08,
OPMODE_DATA_RATE1 = 0x10,
OPMODE_DATA_RATE2 = 0x20,
_OPMODE_DATA_RATE_MASK = 7,
_OPMODE_DATA_RATE_SHIFT = 3,
OPMODE_ADV_SELFTEST0 = 0x40,
OPMODE_ADV_SELFTEST1 = 0x80,
_OPMODE_ADV_SELFTEST_MASK = 3,
_OPMODE_ADV_SELFTEST_SHIFT = 6
} OPMODE_BITS_T;
/**
* OPMODE_OPERATION_MODE values
*/
typedef enum {
OPERATION_MODE_NORMAL = 0,
OPERATION_MODE_FORCED = 1,
OPERATION_MODE_SLEEP = 3
} OPERATION_MODE_T;
/**
* OPMODE_DATA_RATE values
*/
typedef enum {
DATA_RATE_10HZ = 0,
DATA_RATE_2HZ = 1,
DATA_RATE_6HZ = 2,
DATA_RATE_8HZ = 3,
DATA_RATE_15HZ = 4,
DATA_RATE_20HZ = 5,
DATA_RATE_25HZ = 6,
DATA_RATE_30HZ = 7
} DATA_RATE_T;
/**
* REG_INT_EN bits
*/
typedef enum {
INT_EN_LOW_INT_X_EN = 0x01,
INT_EN_LOW_INT_Y_EN = 0x02,
INT_EN_LOW_INT_Z_EN = 0x04,
INT_EN_HIGH_INT_X_EN = 0x08,
INT_EN_HIGH_INT_Y_EN = 0x10,
INT_EN_HIGH_INT_Z_EN = 0x20,
INT_EN_OVERFLOW_INT_EN = 0x40,
INT_EN_DATA_OVERRUN_INT_EN = 0x80
} INT_EN_T;
/**
* REG_INT_CONFIG bits
*/
typedef enum {
INT_CONFIG_INT_POLARITY = 0x01,
INT_CONFIG_INT_LATCH = 0x02,
INT_CONFIG_DR_POLARITY = 0x04,
INT_CONFIG_CHANNEL_X = 0x08,
INT_CONFIG_CHANNEL_Y = 0x10,
INT_CONFIG_CHANNEL_Z = 0x20,
INT_CONFIG_INT_PIN_EN = 0x40,
INT_CONFIG_DR_PIN_EN = 0x80
} INT_CONFIG_T;
/**
* Interrupt selection for installISR() and uninstallISR()
*/
typedef enum {
INTERRUPT_INT,
INTERRUPT_DR
} INTERRUPT_PINS_T;
/**
* Bosch recommended usage preset modes
*/
typedef enum {
USAGE_LOW_POWER,
USAGE_REGULAR,
USAGE_ENHANCED_REGULAR,
USAGE_HIGH_ACCURACY
} USAGE_PRESETS_T;
/**
* BMM150 constructor.
*
* This device can support both I2C and SPI. For SPI, set the addr
* to -1, and specify a positive integer representing the Chip
* Select (CS) pin for the cs argument. If you are using a
* hardware CS pin (like edison with arduino breakout), then you
* can connect the proper pin to the hardware CS pin on your MCU
* and supply -1 for cs. The default operating mode is I2C.
*
* @param bus I2C or SPI bus to use.
* @param addr The address for this device. -1 for SPI.
* @param cs The gpio pin to use for the SPI Chip Select. -1 for
* I2C or for SPI with a hardware controlled pin.
* @param theChipID The chip ID to use for validation
*/
BMM150(int bus=BMM150_I2C_BUS, int addr=BMM150_DEFAULT_ADDR,
int cs=-1);
/**
* BMM150 Destructor.
*/
~BMM150();
/**
* Update the internal stored values from sensor data.
*/
void update();
/**
* Return the chip ID.
*
* @return The chip ID (BMM150_CHIPID).
*/
uint8_t getChipID();
/**
* Return magnetometer data in micro-Teslas (uT). update() must
* have been called prior to calling this method.
*
* @param x Pointer to a floating point value that will have the
* current x component placed into it.
* @param y Pointer to a floating point value that will have the
* current y component placed into it.
* @param z Pointer to a floating point value that will have the
* current z component placed into it.
*/
void getMagnetometer(float *x, float *y, float *z);
/**
* Return magnetometer data in micro-Teslas (uT) in the form of a
* floating point array. The pointer returned by this function is
* statically allocated and will be rewritten on each call.
* update() must have been called prior to calling this method.
*
* @return A floating point array containing x, y, and z in
* that order.
*/
float *getMagnetometer();
/**
* Initialize the device and start operation. This function is
* called from the constructor so will not typically need to be
* called by a user unless the device is reset. This method will
* call setPresetMode() with the passed parameter.
*
* @param usage One of the USAGE_PRESETS_T values. The default is
* USAGE_HIGH_ACCURACY.
*/
void init(USAGE_PRESETS_T usage=USAGE_HIGH_ACCURACY);
/**
* Set one of the Bosch recommended preset modes. These modes
* configure the sensor for varying use cases.
*
* @param usage One of the USAGE_PRESETS_T values. The default is
* USAGE_HIGH_ACCURACY.
*/
void setPresetMode(USAGE_PRESETS_T usage);
/**
* Perform a device soft-reset. The device will be placed in
* SUSPEND mode afterward with all configured setting lost, so
* some re-initialization will be required to get data from the
* sensor. Calling init() will get everything running again.
*/
void reset();
/**
* Set the magnetometer Output Data Rate. See the datasheet for
* details.
*
* @param odr One of the DATA_RATE_T values.
*/
void setOutputDataRate(DATA_RATE_T odr);
/**
* Set or clear the Power bit. When the power bit is cleared, the
* device enters a deep suspend mode where only the REG_POWER_CTRL
* register can be accessed. This bit needs to be enabled for the
* device to operate. See the datasheet for details. The
* constructor enables this by default. After a deep suspend mode
* has been entered, all configured data is lost and the device
* must be reconfigured (as via init()).
*
* @param power true to enable the bit, false otherwise.
*/
void setPowerBit(bool power);
/**
* Set the operating mode of the device. See the datasheet for
* details.
*
* @param power One of the POWER_MODE_T values.
*/
void setOpmode(OPERATION_MODE_T opmode);
/**
* Get the current operating mode of the device. See the datasheet for
* details. The power bit must be one for this method to succeed.
*
* @return One of the OPERATION_MODE_T values.
*/
OPERATION_MODE_T getOpmode();
/**
* Return the Interrupt Enables register. This register
* allows you to enable various interrupt conditions. See the
* datasheet for details.
*
* @return A bitmask of INT_EN_BITS_T bits.
*/
uint8_t getInterruptEnable();
/**
* Set the Interrupt Enables register. See the datasheet for
* details.
*
* @param bits A bitmask of INT_EN_BITS_T bits.
*/
void setInterruptEnable(uint8_t bits);
/**
* Return the Interrupt Config register. This register allows
* determining the electrical characteristics of the 2 interrupt
* pins (open-drain/push-pull and level/edge triggering) as well
* as other options. See the datasheet for details.
*
* @return A bitmask of INT_CONFIG_BITS_T bits.
*/
uint8_t getInterruptConfig();
/**
* Set the Interrupt Config register. This register
* allows determining the electrical characteristics of the 2
* interrupt pins (open-drain/push-pull and level/edge
* triggering). See the datasheet for details.
*
* @param bits A bitmask of INT_CONFIG_BITS_T bits.
*/
void setInterruptConfig(uint8_t bits);
/**
* Return the interrupt status register. This register
* indicates which interrupts have been triggered. See the
* datasheet for details.
*
* @return a bitmask of INT_STATUS_BITS_T bits.
*/
uint8_t getInterruptStatus();
/**
* Set the repetition counter for the X and Y axes. This allows the
* device to average a number of measurements for a more stable
* output. See the datasheet for details.
*
* @param reps A coefficient for specifying the number of
* repititions to perform. (1 + 2(reps))
*/
void setRepetitionsXY(uint8_t reps);
/**
* Set the repetition counter for the Z axis. This allows the
* device to average a number of measurements for a more stable
* output. See the datasheet for details.
*
* @param reps A coefficient for specifying the number of
* repititions to perform. (1 + (reps))
*/
void setRepetitionsZ(uint8_t reps);
#if defined(SWIGJAVA) || defined(JAVACALLBACK)
void installISR(INTERRUPT_PINS_T intr, int gpio, mraa::Edge level,
jobject runnable);
#else
/**
* install an interrupt handler.
*
* @param intr one of the INTERRUPT_PINS_T values specifying which
* interrupt pin you are installing.
* @param gpio gpio pin to use as interrupt pin
* @param level the interrupt trigger level (one of mraa::Edge
* values). Make sure that you have configured the interrupt pin
* properly for whatever level you choose.
* @param isr the interrupt handler, accepting a void * argument
* @param arg the argument to pass the the interrupt handler
*/
void installISR(INTERRUPT_PINS_T intr, int gpio, mraa::Edge level,
void (*isr)(void *), void *arg);
#endif
/**
* uninstall a previously installed interrupt handler
*
* @param intr one of the INTERRUPT_PINS_T values specifying which
* interrupt pin you are removing.
*/
void uninstallISR(INTERRUPT_PINS_T intr);
/**
* Read a register.
*
* @param reg The register to read.
* @return The value of the register.
*/
uint8_t readReg(uint8_t reg);
/**
* Read contiguous registers into a buffer.
*
* @param buffer The buffer to store the results.
* @param len The number of registers to read.
* @return The number of bytes read.
*/
int readRegs(uint8_t reg, uint8_t *buffer, int len);
/**
* Write to a register
*
* @param reg The register to write to.
* @param val The value to write.
*/
void writeReg(uint8_t reg, uint8_t val);
protected:
mraa::I2c *m_i2c;
mraa::Spi *m_spi;
mraa::Gpio *m_gpioIntr;
mraa::Gpio *m_gpioDR;
// spi chip select
mraa::Gpio *m_gpioCS;
uint8_t m_addr;
OPERATION_MODE_T m_opmode;
// SPI chip select
void csOn();
void csOff();
// acc data
float m_magX;
float m_magY;
float m_magZ;
// hall resistance
uint16_t m_hall;
// trimming data
int8_t m_dig_x1;
int8_t m_dig_y1;
int16_t m_dig_z4;
int8_t m_dig_x2;
int8_t m_dig_y2;
int16_t m_dig_z2;
uint16_t m_dig_z1;
uint16_t m_dig_xyz1;
int16_t m_dig_z3;
int8_t m_dig_xy2;
uint8_t m_dig_xy1;
// read trim data for compensation
void readTrimData();
private:
bool m_isSPI;
// return a reference to a gpio pin pointer depending on intr
mraa::Gpio*& getPin(INTERRUPT_PINS_T intr);
// Adding a private function definition for java bindings
#if defined(SWIGJAVA) || defined(JAVACALLBACK)
void installISR(INTERRUPT_PINS_T intr, int gpio, mraa::Edge level,
void (*isr)(void *), void *arg);
#endif
// bosch compensation algorithms
float bmm050_compensate_X_float(int16_t mag_data_x, uint16_t data_r);
float bmm050_compensate_Y_float(int16_t mag_data_y, uint16_t data_r);
float bmm050_compensate_Z_float(int16_t mag_data_z, uint16_t data_r);
};
}

View File

@ -50,16 +50,6 @@ BMX055::BMX055(int accelBus, int accelAddr, int accelCS,
if (magBus >= 0) if (magBus >= 0)
m_mag = new BMM150(magBus, magAddr, magCS); m_mag = new BMM150(magBus, magAddr, magCS);
// now initialize them...
if (m_accel)
m_accel->init();
if (m_gyro)
m_gyro->init();
if (m_mag)
m_mag->init();
} }
BMX055::~BMX055() BMX055::~BMX055()
@ -90,7 +80,7 @@ void BMX055::initGyroscope(BMG160_POWER_MODE_T pwr,
m_gyro->init(pwr, range, bw); m_gyro->init(pwr, range, bw);
} }
void BMX055::initMagnetometer(BMM150::USAGE_PRESETS_T usage) void BMX055::initMagnetometer(BMM150_USAGE_PRESETS_T usage)
{ {
if (m_mag) if (m_mag)
m_mag->init(usage); m_mag->init(usage);
@ -169,13 +159,10 @@ void BMX055::getMagnetometer(float *x, float *y, float *z)
} }
} }
float *BMX055::getMagnetometer() std::vector<float> BMX055::getMagnetometer()
{ {
if (m_mag) if (m_mag)
return m_mag->getMagnetometer(); return m_mag->getMagnetometer();
else else
{ return {0, 0, 0};
static float v[3] = {0.0f, 0.0f, 0.0f};
return v;
}
} }

View File

@ -110,7 +110,7 @@ namespace upm {
int gyroBus=BMG160_DEFAULT_I2C_BUS, int gyroBus=BMG160_DEFAULT_I2C_BUS,
int gyroAddr=BMG160_DEFAULT_ADDR, int gyroAddr=BMG160_DEFAULT_ADDR,
int gyroCS=-1, int gyroCS=-1,
int magBus=BMM150_I2C_BUS, int magBus=BMM150_DEFAULT_I2C_BUS,
int magAddr=BMX055_DEFAULT_MAG_I2C_ADDR, int magAddr=BMX055_DEFAULT_MAG_I2C_ADDR,
int magCS=-1); int magCS=-1);
@ -137,7 +137,8 @@ namespace upm {
* @param bw One of the filtering BMA250E_BW_T values. The default is * @param bw One of the filtering BMA250E_BW_T values. The default is
* BMA250E_BW_250. * BMA250E_BW_250.
*/ */
void initAccelerometer(BMA250E_POWER_MODE_T pwr=BMA250E_POWER_MODE_NORMAL, void initAccelerometer(
BMA250E_POWER_MODE_T pwr=BMA250E_POWER_MODE_NORMAL,
BMA250E_RANGE_T range=BMA250E_RANGE_2G, BMA250E_RANGE_T range=BMA250E_RANGE_2G,
BMA250E_BW_T bw=BMA250E_BW_250); BMA250E_BW_T bw=BMA250E_BW_250);
@ -165,10 +166,11 @@ namespace upm {
* change these values. This method will call * change these values. This method will call
* BMM150::setPresetMode() with the passed parameter. * BMM150::setPresetMode() with the passed parameter.
* *
* @param usage One of the BMM150::USAGE_PRESETS_T values. The default is * @param usage One of the BMM150_USAGE_PRESETS_T values.
* BMM150::USAGE_HIGH_ACCURACY. * The default is BMM150_USAGE_HIGH_ACCURACY.
*/ */
void initMagnetometer(BMM150::USAGE_PRESETS_T usage=BMM150::USAGE_HIGH_ACCURACY); void initMagnetometer(
BMM150_USAGE_PRESETS_T usage=BMM150_USAGE_HIGH_ACCURACY);
/** /**
* Return accelerometer data in gravities. update() must have * Return accelerometer data in gravities. update() must have
@ -208,11 +210,10 @@ namespace upm {
/** /**
* Return gyroscope data in degrees per second in the form of a * Return gyroscope data in degrees per second in the form of a
* floating point array. The pointer returned by this function is * floating point vector. update() must have been called prior to
* statically allocated and will be rewritten on each call. * calling this method.
* update() must have been called prior to calling this method.
* *
* @return A floating point array containing x, y, and z in * @return A floating point vector containing x, y, and z in
* that order. * that order.
*/ */
std::vector<float> getGyroscope(); std::vector<float> getGyroscope();
@ -238,8 +239,7 @@ namespace upm {
* @return A floating point vector containing x, y, and z in * @return A floating point vector containing x, y, and z in
* that order. * that order.
*/ */
float *getMagnetometer(); std::vector<float> getMagnetometer();
protected: protected:
BMA250E *m_accel; BMA250E *m_accel;

View File

@ -2,25 +2,9 @@
%include "../upm.i" %include "../upm.i"
%include "cpointer.i" %include "cpointer.i"
%include "typemaps.i" %include "typemaps.i"
%include "arrays_java.i";
%include "../java_buffer.i"
%include "../upm_vectortypes.i" %include "../upm_vectortypes.i"
%apply int {mraa::Edge}; %apply int {mraa::Edge};
%apply float *INOUT { float *x, float *y, float *z };
%typemap(jni) float* "jfloatArray"
%typemap(jstype) float* "float[]"
%typemap(jtype) float* "float[]"
%typemap(javaout) float* {
return $jnicall;
}
%typemap(out) float *getMagnetometer {
$result = JCALL1(NewFloatArray, jenv, 3);
JCALL4(SetFloatArrayRegion, jenv, $result, 0, 3, $1);
}
%ignore getAccelerometer(float *, float *, float *); %ignore getAccelerometer(float *, float *, float *);
%ignore getMagnetometer(float *, float *, float *); %ignore getMagnetometer(float *, float *, float *);
@ -28,11 +12,7 @@
%include "bmg160_defs.h" %include "bmg160_defs.h"
%include "bma250e_defs.h" %include "bma250e_defs.h"
%include "bmm150_defs.h"
%include "bmm150.hpp"
%{
#include "bmm150.hpp"
%}
%include "bmx055.hpp" %include "bmx055.hpp"
%{ %{

View File

@ -9,11 +9,7 @@
%include "bmg160_defs.h" %include "bmg160_defs.h"
%include "bma250e_defs.h" %include "bma250e_defs.h"
%include "bmm150_defs.h"
%include "bmm150.hpp"
%{
#include "bmm150.hpp"
%}
%include "bmx055.hpp" %include "bmx055.hpp"
%{ %{

View File

@ -17,6 +17,7 @@
%include "bmg160_defs.h" %include "bmg160_defs.h"
%include "bma250e_defs.h" %include "bma250e_defs.h"
%include "bmm150_defs.h"
%include "bmm150.hpp" %include "bmm150.hpp"
%{ %{