bmi160: Initial implementation

The Bosch BMI160 is a 3-axis Accelerometer and Gyroscope.
Additionally it supports an external Magnetometer, accessed through
the BMI160's register interface.  This driver was developed with a
BMI160 "Shuttle" board, which included a BMM150 Magnetometer.

The device is driven by either 1.8v or 3.3vdc.  This driver
incorporates the Bosch BMI160 driver code at
https://github.com/BoschSensortec/BMI160_driver .

While not all of the functionality of this device is supported
initially, the inclusion of the Bosch driver in the source code
makes it possible to support whatever features are required that
the driver bosch driver itself can support.

Signed-off-by: Jon Trulson <jtrulson@ics.com>
Signed-off-by: Abhishek Malik <abhishek.malik@intel.com>
This commit is contained in:
Jon Trulson 2016-03-10 12:18:56 -07:00 committed by Abhishek Malik
parent b778476597
commit e062b9b85c
16 changed files with 33628 additions and 0 deletions

View File

@ -252,6 +252,7 @@ add_example (cwlsxxa)
add_example (teams)
add_example (apa102)
add_example (tex00)
add_example (bmi160)
# These are special cases where you specify example binary, source file and module(s)
include_directories (${PROJECT_SOURCE_DIR}/src)

82
examples/c++/bmi160.cxx Normal file
View File

@ -0,0 +1,82 @@
/*
* 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.
*/
#include <unistd.h>
#include <iostream>
#include <signal.h>
#include "bmi160.h"
using namespace std;
int shouldRun = true;
void sig_handler(int signo)
{
if (signo == SIGINT)
shouldRun = false;
}
int main(int argc, char **argv)
{
signal(SIGINT, sig_handler);
//! [Interesting]
// Instantiate a BMI160 instance using default i2c bus and address
upm::BMI160 *sensor = new upm::BMI160();
while (shouldRun)
{
// update our values from the sensor
sensor->update();
float dataX, dataY, dataZ;
sensor->getAccelerometer(&dataX, &dataY, &dataZ);
cout << "Accelerometer: ";
cout << "AX: " << dataX << " AY: " << dataY << " AZ: "
<< dataZ << endl;
sensor->getGyroscope(&dataX, &dataY, &dataZ);
cout << "Gryoscope: ";
cout << "GX: " << dataX << " GY: " << dataY << " GZ: "
<< dataZ << endl;
sensor->getMagnetometer(&dataX, &dataY, &dataZ);
cout << "Magnetometer: ";
cout << "MX: " << dataX << " MY: " << dataY << " MZ: "
<< dataZ << endl;
cout << endl;
usleep(500000);
}
//! [Interesting]
cout << "Exiting..." << endl;
delete sensor;
return 0;
}

View File

@ -0,0 +1,78 @@
/*
* 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.
*/
import upm_bmi160.BMI160;
public class BMI160_Example
{
public static void main(String[] args) throws InterruptedException
{
// ! [Interesting]
System.out.println("Initializing...");
// Instantiate a BMI160 instance using default i2c bus and address
BMI160 sensor = new BMI160();
while (true)
{
// update our values from the sensor
sensor.update();
float dataA[] = sensor.getAccelerometer();
System.out.println("Accelerometer: "
+ "AX: "
+ dataA[0]
+ " AY: "
+ dataA[1]
+ " AZ: "
+ dataA[2]);
float dataG[] = sensor.getGyroscope();
System.out.println("Gryoscope: "
+ "GX: "
+ dataG[0]
+ " GY: "
+ dataG[1]
+ " GZ: "
+ dataG[2]);
float dataM[] = sensor.getMagnetometer();
System.out.println("Magnetometer: "
+ "MX: "
+ dataM[0]
+ " MY: "
+ dataM[1]
+ " MZ: "
+ dataM[2]);
System.out.println();
Thread.sleep(500);
}
// ! [Interesting]
}
}

View File

@ -109,6 +109,7 @@ add_example(CWLSXXA_Example cwlsxxa)
add_example(TEAMS_Example teams)
add_example(APA102Sample apa102)
add_example(TEX00_Example tex00)
add_example(BMI160_Example bmi160)
add_example_with_path(Jhd1313m1_lcdSample lcd/upm_i2clcd.jar)
add_example_with_path(Jhd1313m1Sample lcd/upm_i2clcd.jar)

View File

@ -0,0 +1,71 @@
/*jslint node:true, vars:true, bitwise:true, unparam:true */
/*jshint unused:true */
/*
* 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.
*/
var sensorObj = require('jsupm_bmi160');
// Instantiate a BMI160 instance using default i2c bus and address
var sensor = new sensorObj.BMI160();
var x = new sensorObj.new_floatp();
var y = new sensorObj.new_floatp();
var z = new sensorObj.new_floatp();
// Output data every half second until interrupted
setInterval(function()
{
// update our values from the sensor
sensor.update();
sensor.getAccelerometer(x, y, z);
console.log("Accelerometer: AX: " + sensorObj.floatp_value(x) +
" AY: " + sensorObj.floatp_value(y) +
" AZ: " + sensorObj.floatp_value(z));
sensor.getGyroscope(x, y, z);
console.log("Gyroscope: GX: " + sensorObj.floatp_value(x) +
" AY: " + sensorObj.floatp_value(y) +
" AZ: " + sensorObj.floatp_value(z));
sensor.getMagnetometer(x, y, z);
console.log("Magnetometer: MX: " + sensorObj.floatp_value(x) +
" MY: " + sensorObj.floatp_value(y) +
" MZ: " + sensorObj.floatp_value(z));
console.log();
}, 500);
// exit on ^C
process.on('SIGINT', function()
{
sensor = null;
sensorObj.cleanUp();
sensorObj = null;
console.log("Exiting.");
process.exit(0);
});

66
examples/python/bmi160.py Normal file
View File

@ -0,0 +1,66 @@
#!/usr/bin/python
# 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.
import time, sys, signal, atexit
import pyupm_bmi160 as sensorObj
# Instantiate a BMI160 instance using default i2c bus and address
sensor = sensorObj.BMI160()
## Exit handlers ##
# This function stops python from printing a stacktrace when you hit control-C
def SIGINTHandler(signum, frame):
raise SystemExit
# This function lets you run code on exit
def exitHandler():
print "Exiting"
sys.exit(0)
# Register exit handlers
atexit.register(exitHandler)
signal.signal(signal.SIGINT, SIGINTHandler)
x = sensorObj.new_floatp()
y = sensorObj.new_floatp()
z = sensorObj.new_floatp()
while (1):
sensor.update()
sensor.getAccelerometer(x, y, z)
print "Accelerometer: AX: ", sensorObj.floatp_value(x),
print " AY: ", sensorObj.floatp_value(y),
print " AZ: ", sensorObj.floatp_value(z)
sensor.getGyroscope(x, y, z)
print "Gyroscope: GX: ", sensorObj.floatp_value(x),
print " GY: ", sensorObj.floatp_value(y),
print " GZ: ", sensorObj.floatp_value(z)
sensor.getMagnetometer(x, y, z)
print "Magnetometer: MX: ", sensorObj.floatp_value(x),
print " MY: ", sensorObj.floatp_value(y),
print " MZ: ", sensorObj.floatp_value(z)
print
time.sleep(.5)

View File

@ -0,0 +1,5 @@
set (libname "bmi160")
set (libdescription "Bosch BMI160 Accelerometer, Gyroscope and BMM150 Magnetometer")
set (module_src ${libname}.cxx bosch_bmi160.c)
set (module_h ${libname}.h)
upm_module_init()

433
src/bmi160/bmi160.cxx Normal file
View File

@ -0,0 +1,433 @@
/*
* 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.
*/
#include <unistd.h>
#include <iostream>
#include <stdexcept>
#include <string>
// we have to do it the old skool way
#include <mraa/i2c.h>
#include "bmi160.h"
extern "C" {
#include "bosch_bmi160.h"
}
// We do not need this define anyway. It conflicts with mraa::SUCCESS.
#undef SUCCESS
using namespace upm;
using namespace std;
static mraa_i2c_context i2cContext = NULL;
// Our bmi160 info structure
struct bmi160_t s_bmi160;
// bus read and write functions for use with the bmi driver code
s8 bmi160_i2c_bus_read(u8 dev_addr, u8 reg_addr, u8 *reg_data, u8 cnt)
{
if (!i2cContext)
{
throw std::runtime_error(std::string(__FUNCTION__) +
": i2c context is NULL");
}
int retries = 10;
// There seems to be some occasional flakyness with reads when
// moving the sensor around
while (retries >= 0)
{
int rv = mraa_i2c_read_bytes_data(i2cContext, reg_addr, reg_data, cnt);
if (rv < 0)
{
usleep(100000);
retries--;
}
else
return 0;
}
throw std::runtime_error(std::string(__FUNCTION__) +
": mraa_i2c_read_bytes_data() failed");
return 0;
}
s8 bmi160_i2c_bus_write(u8 dev_addr, u8 reg_addr, u8 *reg_data, u8 cnt)
{
if (!i2cContext)
{
throw std::runtime_error(std::string(__FUNCTION__) +
": i2c context is NULL");
}
// FIXME fprintf(stderr, "%s: %02x: cnt %d\n", __FUNCTION__, reg_addr, cnt);
uint8_t buffer[cnt + 1];
buffer[0] = reg_addr;
for (int i=0; i<cnt; i++)
buffer[i+1] = reg_data[i];
mraa_result_t rv = mraa_i2c_write(i2cContext, buffer, cnt+1);
if (rv != MRAA_SUCCESS)
{
throw std::runtime_error(std::string(__FUNCTION__) +
": mraa_i2c_write() failed");
}
return 0;
}
// delay for some milliseconds
void bmi160_delay_ms(u32 msek)
{
usleep(msek * 1000);
}
BMI160::BMI160(int bus, uint8_t address)
{
m_addr = address;
// We need to use the C MRAA interface to avoid issue with C++ <-> C
// calling convention issues, also we need a global
// mraa_i2c_context
if (!(i2cContext = mraa_i2c_init(bus)))
{
throw std::invalid_argument(std::string(__FUNCTION__) +
": mraa_i2c_init() failed");
}
if (mraa_i2c_address(i2cContext, m_addr) != MRAA_SUCCESS)
{
throw std::runtime_error(std::string(__FUNCTION__) +
": mraa_i2c_address() failed");
return;
}
// init the driver interface functions
s_bmi160.bus_write = bmi160_i2c_bus_write;
s_bmi160.bus_read = bmi160_i2c_bus_read;
s_bmi160.delay_msec = bmi160_delay_ms;
s_bmi160.dev_addr = m_addr;
// Init our driver interface pointers
bmi160_init(&s_bmi160);
m_accelX = 0.0;
m_accelY = 0.0;
m_accelZ = 0.0;
m_gyroX = 0.0;
m_gyroY = 0.0;
m_gyroZ = 0.0;
m_magX = 0.0;
m_magY = 0.0;
m_magZ = 0.0;
m_accelScale = 1.0;
m_gyroScale = 1.0;
m_magEnabled = false;
if (!init())
{
throw std::runtime_error(std::string(__FUNCTION__) +
": init() failed");
}
}
BMI160::~BMI160()
{
mraa_i2c_stop(i2cContext);
i2cContext = NULL;
}
bool BMI160::init()
{
// This should be interesting...
const u32 C_BMI160_THIRTY_U8X = 30;
enableMagnetometer(true);
/*Set the accel mode as Normal write in the register 0x7E*/
bmi160_set_command_register(ACCEL_MODE_NORMAL);
/* bmi160_delay_ms in ms*/
bmi160_delay_ms(C_BMI160_THIRTY_U8X);
/*Set the gyro mode as Normal write in the register 0x7E*/
bmi160_set_command_register(GYRO_MODE_NORMAL);
/* bmi160_delay_ms in ms*/
bmi160_delay_ms(C_BMI160_THIRTY_U8X);
/* Set the accel bandwidth as OSRS4 */
bmi160_set_accel_bw(BMI160_ACCEL_OSR4_AVG1);
bmi160_delay_ms(BMI160_GEN_READ_WRITE_DELAY);
/* Set the gryo bandwidth as Normal */
bmi160_set_gyro_bw(BMI160_GYRO_NORMAL_MODE);
bmi160_delay_ms(BMI160_GEN_READ_WRITE_DELAY);
/* set gyro data rate as 200Hz*/
bmi160_set_gyro_output_data_rate(BMI160_GYRO_OUTPUT_DATA_RATE_200HZ);
bmi160_delay_ms(BMI160_GEN_READ_WRITE_DELAY);
/* set accel data rate as 200Hz*/
bmi160_set_accel_output_data_rate(BMI160_ACCEL_OUTPUT_DATA_RATE_200HZ,
BMI160_ACCEL_OSR4_AVG1);
bmi160_delay_ms(BMI160_GEN_READ_WRITE_DELAY);
setAccelerometerScale(ACCEL_RANGE_2G);
setGyroscopeScale(GYRO_RANGE_125);
return true;
}
void BMI160::update()
{
struct bmi160_gyro_t gyroxyz;
struct bmi160_accel_t accelxyz;
struct bmi160_mag_xyz_s32_t magxyz;
// read gyro data
bmi160_read_gyro_xyz(&gyroxyz);
// read accel data
bmi160_read_accel_xyz(&accelxyz);
// read mag data
if (m_magEnabled)
bmi160_bmm150_mag_compensate_xyz(&magxyz);
// read the sensor time
u32 v_sensor_time;
bmi160_get_sensor_time(&v_sensor_time);
m_sensorTime = (unsigned int)v_sensor_time;
m_accelX = float(accelxyz.x);
m_accelY = float(accelxyz.y);
m_accelZ = float(accelxyz.z);
m_gyroX = float(gyroxyz.x);
m_gyroY = float(gyroxyz.y);
m_gyroZ = float(gyroxyz.z);
if (m_magEnabled)
{
m_magX = float(magxyz.x);
m_magY = float(magxyz.y);
m_magZ = float(magxyz.z);
}
}
void BMI160::setAccelerometerScale(ACCEL_RANGE_T scale)
{
s8 v_range = BMI160_ACCEL_RANGE_2G;
// store scaling factor
switch (scale)
{
case ACCEL_RANGE_2G:
v_range = BMI160_ACCEL_RANGE_2G;
m_accelScale = 16384.0;
break;
case ACCEL_RANGE_4G:
v_range = BMI160_ACCEL_RANGE_4G;
m_accelScale = 8192.0;
break;
case ACCEL_RANGE_8G:
v_range = BMI160_ACCEL_RANGE_8G;
m_accelScale = 4096.0;
break;
case ACCEL_RANGE_16G:
v_range = BMI160_ACCEL_RANGE_16G;
m_accelScale = 2048.0;
break;
default: // should never occur, but...
m_accelScale = 1.0; // set a safe, though incorrect value
throw std::logic_error(string(__FUNCTION__) +
": internal error, unsupported scale");
break;
}
bmi160_set_accel_range(v_range);
return;
}
void BMI160::setGyroscopeScale(GYRO_RANGE_T scale)
{
u8 v_range = BMI160_GYRO_RANGE_2000_DEG_SEC;
// store scaling factor
switch (scale)
{
case GYRO_RANGE_125:
v_range = BMI160_GYRO_RANGE_125_DEG_SEC;
m_gyroScale = 262.4;
break;
case GYRO_RANGE_250:
v_range = BMI160_GYRO_RANGE_250_DEG_SEC;
m_gyroScale = 131.2;
break;
case GYRO_RANGE_500:
v_range = BMI160_GYRO_RANGE_500_DEG_SEC;
m_gyroScale = 65.6;
break;
case GYRO_RANGE_1000:
v_range = BMI160_GYRO_RANGE_1000_DEG_SEC;
m_gyroScale = 32.8;
break;
case GYRO_RANGE_2000:
v_range = BMI160_GYRO_RANGE_2000_DEG_SEC;
m_gyroScale = 16.4;
break;
default: // should never occur, but...
m_gyroScale = 1.0; // set a safe, though incorrect value
throw std::logic_error(string(__FUNCTION__) +
": internal error, unsupported scale");
break;
}
bmi160_set_gyro_range(v_range);
return;
}
void BMI160::getAccelerometer(float *x, float *y, float *z)
{
if (x)
*x = m_accelX / m_accelScale;
if (y)
*y = m_accelY / m_accelScale;
if (z)
*z = m_accelZ / m_accelScale;
}
void BMI160::getGyroscope(float *x, float *y, float *z)
{
if (x)
*x = m_gyroX / m_gyroScale;
if (y)
*y = m_gyroY / m_gyroScale;
if (z)
*z = m_gyroZ / m_gyroScale;
}
void BMI160::getMagnetometer(float *x, float *y, float *z)
{
if (x)
*x = m_magX;
if (y)
*y = m_magY;
if (z)
*z = m_magZ;
}
float *BMI160::getAccelerometer()
{
float *values = new float[3]; // x, y, and then z
getAccelerometer(&values[0], &values[1], &values[2]);
return values;
}
float *BMI160::getGyroscope()
{
float *values = new float[3]; // x, y, and then z
getGyroscope(&values[0], &values[1], &values[2]);
return values;
}
float *BMI160::getMagnetometer()
{
float *values = new float[3]; // x, y, and then z
getMagnetometer(&values[0], &values[1], &values[2]);
return values;
}
void BMI160::enableMagnetometer(bool enable)
{
// butchered from support example
if (!enable)
{
bmi160_set_bmm150_mag_and_secondary_if_power_mode(MAG_SUSPEND_MODE);
bmi160_delay_ms(BMI160_GEN_READ_WRITE_DELAY);
bmi160_set_if_mode(0x00);
bmi160_delay_ms(BMI160_GEN_READ_WRITE_DELAY);
m_magEnabled = false;
m_magX = 0;
m_magY = 0;
m_magZ = 0;
}
else
{
u8 v_bmm_chip_id_u8 = BMI160_INIT_VALUE;
/* Init the magnetometer */
bmi160_bmm150_mag_interface_init(&v_bmm_chip_id_u8);
/* bmi160_delay_ms in ms*/
bmi160_delay_ms(BMI160_GEN_READ_WRITE_DELAY);
m_magEnabled = true;
}
}
unsigned int BMI160::getSensorTime()
{
return m_sensorTime;
}

251
src/bmi160/bmi160.h Normal file
View File

@ -0,0 +1,251 @@
/*
* 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 <stdint.h>
#define BMI160_I2C_BUS 0
#define BMI160_DEFAULT_I2C_ADDR 0x69
namespace upm {
/**
* @brief BMI160 3-axis Accelerometer, Gyroscope and Magnetometer
* @defgroup bmi160 libupm-bmi160
* @ingroup i2c accelerometer compass
*/
/**
* @library bmi160
* @sensor bmi160
* @comname UPM API for the BMI160 3-axis Accelerometer, Gyroscope
* and Magnetometer
* @type accelerometer compass
* @man mouser
* @con i2c
* @web http://www.mouser.com/ProductDetail/Bosch-Sensortec/0330SB2187/?qs=sGAEpiMZZMvi6wO7nhr1L9JELKA6cYRX60mAGNTn0fQ%3d
*
* @brief UPM API for the BMI160 3-axis Accelerometer, Gyroscope and
* Magnetometer
*
* The Bosch BMI160 is a 3-axis Accelerometer and Gyroscope.
* Additionally it supports an external Magnetometer, accessed
* through the BMI160's register interface. This driver was
* developed with a BMI160 "Shuttle" board, which included a BMM150
* Magnetometer.
*
* The device is driven by either 1.8v or 3.3vdc. This driver
* incorporates the Bosch BMI160 driver code at
* https://github.com/BoschSensortec/BMI160_driver .
*
* While not all of the functionality of this device is supported
* initially, the inclusion of the Bosch driver in the source code
* makes it possible to support whatever features are required that
* the driver can support.
*
* @snippet bmi160.cxx Interesting
*/
class BMI160 {
public:
typedef enum {
ACCEL_RANGE_2G = 0, // 2 Gravities
ACCEL_RANGE_4G,
ACCEL_RANGE_8G,
ACCEL_RANGE_16G
} ACCEL_RANGE_T;
typedef enum {
GYRO_RANGE_125 = 0, // 125 degrees/sec
GYRO_RANGE_250,
GYRO_RANGE_500,
GYRO_RANGE_1000,
GYRO_RANGE_2000
} GYRO_RANGE_T;
/**
* bmi160 constructor
*
* @param bus i2c bus to use
* @param address the address for this device
*/
BMI160(int bus=BMI160_I2C_BUS, uint8_t address=BMI160_DEFAULT_I2C_ADDR);
/**
* BMI160 Destructor
*/
~BMI160();
/**
* Take a measurement and store the current sensor values
* internally. This function must be called prior to retrieving
* any sensor values, for example getAccelerometer().
*
*/
void update();
/**
* set the scaling mode of the accelerometer
*
* @param scale one of the ACCEL_RANGE_T values
*/
void setAccelerometerScale(ACCEL_RANGE_T scale);
/**
* set the scaling mode of the gyroscope
*
* @param scale one of the GYRO_RANGE_T values
*/
void setGyroscopeScale(GYRO_RANGE_T scale);
/**
* Get the Accelerometer values. This function returns a pointer
* to 3 floating point values: X, Y, and Z, in that order. The
* values returned are in gravities. update() must have been
* called prior to calling this method.
*
* The caller is reponsible for freeing the returned pointer.
*
* @return Pointer to 3 floating point values: X, Y, and Z in
* gravities.
*/
float *getAccelerometer();
/**
* Get the Accelerometer values. The values returned are in
* gravities. update() must have been called prior to calling
* this method.
*
* @param x A pointer into which the X value will be returned
* @param y A pointer into which the Y value will be returned
* @param z A pointer into which the Z value will be returned
*/
void getAccelerometer(float *x, float *y, float *z);
/**
* Get the Gyroscope values. This function returns a pointer to 3
* floating point values: X, Y, and Z, in that order. The values
* values returned are in degrees per second. update() must have
* been called prior to calling this method.
*
* The caller is reponsible for freeing the returned pointer.
*
* @return Pointer to 3 floating point values: X, Y, and Z in
* degrees per second.
*/
float *getGyroscope();
/**
* Get the Gyroscope values. The values returned are in degrees
* per second. update() must have been called prior to calling
* this method.
*
* @param x A pointer into which the X value will be returned
* @param y A pointer into which the Y value will be returned
* @param z A pointer into which the Z value will be returned
*/
void getGyroscope(float *x, float *y, float *z);
/**
* Get the Magnetometer values. This function returns a pointer
* to 3 floating point values: X, Y, and Z, in that order. The
* values values returned are in micro Teslas. update() must have
* been called prior to calling this method. If the Magnetometer
* has been disabled, the return values will always be 0, 0, and
* 0.
*
* The caller is reponsible for freeing the returned pointer.
*
* @return Pointer to 3 floating point values: X, Y, and Z in
* micro Teslas.
*/
float *getMagnetometer();
/**
* Get the Magnetometer values. The values returned are in micro
* Teslas. update() must have been called prior to calling this
* method.
*
* @param x A pointer into which the X value will be returned
* @param y A pointer into which the Y value will be returned
* @param z A pointer into which the Z value will be returned
*/
void getMagnetometer(float *x, float *y, float *z);
/**
* Enable or disable the Magnetometer. By default, the
* magnetometer is enabled.
*
* @param enable true to enable the magnetometer, false to disable.
*/
void enableMagnetometer(bool enable);
/**
* Return the sensor time. This is a 24bit value that increments
* every 39us. It will wrap around once the 24b resolution is
* exceeded.
*
* @return The current sensor time.
*/
unsigned int getSensorTime();
protected:
// uncompensated accelerometer and gyroscope values
float m_accelX;
float m_accelY;
float m_accelZ;
float m_gyroX;
float m_gyroY;
float m_gyroZ;
float m_magX;
float m_magY;
float m_magZ;
unsigned int m_sensorTime;
// accelerometer and gyro scaling factors, depending on their Full
// Scale (Range) settings.
float m_accelScale;
float m_gyroScale;
// is the magnetometer enabled?
bool m_magEnabled;
/**
* set up initial values and start operation
*
* @return true if successful
*/
virtual bool init();
private:
// due to the way we need to 'hook' into the bmi driver, the i2c
// context is a static variable defined in the .cxx implmentation.
uint8_t m_addr;
};
}

20467
src/bmi160/bosch_bmi160.c Normal file

File diff suppressed because it is too large Load Diff

12045
src/bmi160/bosch_bmi160.h Normal file

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,41 @@
%module javaupm_bmi160
%include "../upm.i"
%include "typemaps.i"
%include "arrays_java.i"
%include "../java_buffer.i"
%{
#include "bmi160.h"
%}
%typemap(jni) float * "jfloatArray"
%typemap(jstype) float * "float[]"
%typemap(jtype) float * "float[]"
%typemap(javaout) float * {
return $jnicall;
}
%typemap(out) float * {
$result = JCALL1(NewFloatArray, jenv, 3);
JCALL4(SetFloatArrayRegion, jenv, $result, 0, 3, $1);
delete [] $1;
}
%ignore getAccelerometer(float *, float *, float *);
%ignore getGyroscope(float *, float *, float *);
%ignore getMagnetometer(float *, float *, float *);
%include "bmi160.h"
%pragma(java) jniclasscode=%{
static {
try {
System.loadLibrary("javaupm_bmi160");
} catch (UnsatisfiedLinkError e) {
System.err.println("Native code library failed to load. \n" + e);
System.exit(1);
}
}
%}

10
src/bmi160/jsupm_bmi160.i Normal file
View File

@ -0,0 +1,10 @@
%module jsupm_bmi160
%include "../upm.i"
%include "cpointer.i"
%pointer_functions(float, floatp);
%include "bmi160.h"
%{
#include "bmi160.h"
%}

55
src/bmi160/license.txt Normal file
View File

@ -0,0 +1,55 @@
/** \mainpage
*
****************************************************************************
* Copyright (C) 2014 Bosch Sensortec GmbH
*
* File : bmi160.h
*
* Date : 2014/10/27
*
* Revision : 2.0.6 $
*
* Usage: Sensor Driver for BMI160 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.
**************************************************************************/

16
src/bmi160/pyupm_bmi160.i Normal file
View File

@ -0,0 +1,16 @@
// Include doxygen-generated documentation
%include "pyupm_doxy2swig.i"
%module pyupm_bmi160
%include "../upm.i"
%include "cpointer.i"
%include "stdint.i"
%feature("autodoc", "3");
%pointer_functions(float, floatp);
%include "bmi160.h"
%{
#include "bmi160.h"
%}

View File

@ -372,6 +372,12 @@
* @ingroup byman
*/
/**
* @brief Mouser
* @defgroup mouser Mouser
* @ingroup byman
*/
/**
* @brief Omega
* @defgroup omega Omega