mirror of
https://github.com/eclipse/upm.git
synced 2025-03-15 04:57:30 +03:00
mma7361: Initial implementation
This driver implements support for the DFRobot MMA7361 analog accelerometer. It supports 3 axes with a selectable 1.5G and 6G sensitivity. It is not really meant for navigation, but rather for uses such as orientation and freefall detection. Signed-off-by: Jon Trulson <jtrulson@ics.com>
This commit is contained in:
parent
3cb80093e0
commit
d1aa4b62f2
@ -275,6 +275,7 @@ add_example (l3gd20-i2c)
|
||||
add_example (bmx055)
|
||||
add_example (ms5611)
|
||||
add_example (vk2828u7)
|
||||
add_example (mma7361)
|
||||
|
||||
# These are special cases where you specify example binary, source file and module(s)
|
||||
include_directories (${PROJECT_SOURCE_DIR}/src)
|
||||
|
94
examples/c++/mma7361.cxx
Normal file
94
examples/c++/mma7361.cxx
Normal file
@ -0,0 +1,94 @@
|
||||
/*
|
||||
* 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 <signal.h>
|
||||
#include <iostream>
|
||||
|
||||
#include "mma7361.hpp"
|
||||
|
||||
using namespace std;
|
||||
|
||||
bool shouldRun = true;
|
||||
|
||||
void sig_handler(int signo)
|
||||
{
|
||||
if (signo == SIGINT)
|
||||
shouldRun = false;
|
||||
}
|
||||
|
||||
int main()
|
||||
{
|
||||
signal(SIGINT, sig_handler);
|
||||
|
||||
//! [Interesting]
|
||||
|
||||
// Instantiate a MMA7361 sensor on analog pins A0 (X), A1 (Y) A2
|
||||
// (Z), selftest pin on D2, sleep pin on D3 nd an analog reference
|
||||
// value of 5.0. The freefall pin and the range pin are unused
|
||||
// (-1).
|
||||
upm::MMA7361 *sensor = new upm::MMA7361(0, 1, 2, 2, 3, -1, -1, 5.0);
|
||||
|
||||
// 1.5g (true = 6g)
|
||||
sensor->setRange(false);
|
||||
|
||||
// Every 10th of a second, update and print values
|
||||
|
||||
while (shouldRun)
|
||||
{
|
||||
sensor->update();
|
||||
|
||||
float x, y, z;
|
||||
|
||||
sensor->getAcceleration(&x, &y, &z);
|
||||
cout << "Acceleration x = "
|
||||
<< x
|
||||
<< " y = "
|
||||
<< y
|
||||
<< "z = "
|
||||
<< z
|
||||
<< endl;
|
||||
|
||||
sensor->getVolts(&x, &y, &z);
|
||||
cout << "Volts x = "
|
||||
<< x
|
||||
<< " y = "
|
||||
<< y
|
||||
<< "z = "
|
||||
<< z
|
||||
<< endl;
|
||||
|
||||
cout << endl;
|
||||
|
||||
usleep(100000);
|
||||
}
|
||||
|
||||
//! [Interesting]
|
||||
|
||||
printf("Exiting...\n");
|
||||
|
||||
delete sensor;
|
||||
|
||||
return 0;
|
||||
}
|
@ -88,3 +88,4 @@ link_directories (${MRAA_LIBDIR})
|
||||
# grove* will use module grove
|
||||
add_example (dfrph)
|
||||
add_example (vk2828u7)
|
||||
add_example (mma7361)
|
||||
|
85
examples/c/mma7361.c
Normal file
85
examples/c/mma7361.c
Normal file
@ -0,0 +1,85 @@
|
||||
/*
|
||||
* 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 <signal.h>
|
||||
|
||||
#include "mma7361.h"
|
||||
|
||||
bool shouldRun = true;
|
||||
|
||||
void sig_handler(int signo)
|
||||
{
|
||||
if (signo == SIGINT)
|
||||
shouldRun = false;
|
||||
}
|
||||
|
||||
int main()
|
||||
{
|
||||
signal(SIGINT, sig_handler);
|
||||
|
||||
//! [Interesting]
|
||||
|
||||
// Instantiate a MMA7361 sensor on analog pins A0 (X), A1 (Y) A2
|
||||
// (Z), selftest pin on D2, sleep pin on D3 nd an analog reference
|
||||
// value of 5.0. The freefall pin and the range pin are unused
|
||||
// (-1).
|
||||
mma7361_context sensor = mma7361_init(0, 1, 2, 2, 3, -1, -1, 5.0);
|
||||
|
||||
if (!sensor)
|
||||
{
|
||||
printf("mma7361_init() failed.\n");
|
||||
return(1);
|
||||
}
|
||||
|
||||
// 1.5g (true = 6g)
|
||||
mma7361_set_range(sensor, false);
|
||||
|
||||
// Every 10th of a second, update and print values
|
||||
|
||||
while (shouldRun)
|
||||
{
|
||||
mma7361_update(sensor);
|
||||
|
||||
float x, y, z;
|
||||
|
||||
mma7361_get_acceleration(sensor, &x, &y, &z);
|
||||
printf("Acceleration x = %f y = %f z = %f\n",
|
||||
x, y, z);
|
||||
|
||||
mma7361_get_volts(sensor, &x, &y, &z);
|
||||
printf("Volts x = %f y = %f z = %f\n\n",
|
||||
x, y, z);
|
||||
|
||||
usleep(100000);
|
||||
}
|
||||
|
||||
//! [Interesting]
|
||||
|
||||
printf("Exiting...\n");
|
||||
|
||||
mma7361_close(sensor);
|
||||
|
||||
return 0;
|
||||
}
|
@ -132,6 +132,7 @@ add_example(BMP280_Example bmp280)
|
||||
add_example(BNO055_Example bno055)
|
||||
add_example(BMX055_Example bmx055)
|
||||
add_example(VK2828U7_Example vk2828u7)
|
||||
add_example(MMA7361_Example mma7361)
|
||||
|
||||
add_example_with_path(Jhd1313m1_lcdSample lcd i2clcd)
|
||||
add_example_with_path(Jhd1313m1Sample lcd i2clcd)
|
||||
|
66
examples/java/MMA7361_Example.java
Normal file
66
examples/java/MMA7361_Example.java
Normal file
@ -0,0 +1,66 @@
|
||||
/*
|
||||
* 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_mma7361.MMA7361;
|
||||
|
||||
public class MMA7361_Example
|
||||
{
|
||||
public static void main(String[] args) throws InterruptedException
|
||||
{
|
||||
// ! [Interesting]
|
||||
|
||||
// Instantiate a MMA7361 sensor on analog pins A0 (X), A1 (Y)
|
||||
// A2 (Z), selftest pin on D2, sleep pin on D3 nd an analog
|
||||
// reference value of 5.0. The freefall pin and the range pin
|
||||
// are unused (-1).
|
||||
MMA7361 sensor = new MMA7361(0, 1, 2, 2, 3, -1, -1, 5.0f);
|
||||
|
||||
// 1.5g (true = 6g)
|
||||
sensor.setRange(false);
|
||||
|
||||
// Every 10th of a second, update and print values
|
||||
while (true)
|
||||
{
|
||||
// update our values from the sensor
|
||||
sensor.update();
|
||||
|
||||
float dataA[] = sensor.getAcceleration();
|
||||
|
||||
System.out.println("Accelerometer x: " + dataA[0]
|
||||
+ " y: " + dataA[1]
|
||||
+ " z: " + dataA[2]);
|
||||
|
||||
float dataV[] = sensor.getVolts();
|
||||
|
||||
System.out.println("Volts x: " + dataV[0]
|
||||
+ " y: " + dataV[1]
|
||||
+ " z: " + dataV[2]);
|
||||
|
||||
System.out.println();
|
||||
Thread.sleep(100);
|
||||
}
|
||||
|
||||
// ! [Interesting]
|
||||
}
|
||||
}
|
73
examples/javascript/mma7361.js
Normal file
73
examples/javascript/mma7361.js
Normal file
@ -0,0 +1,73 @@
|
||||
/*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_mma7361');
|
||||
|
||||
// Instantiate a MMA7361 sensor on analog pins A0 (X), A1 (Y) A2
|
||||
// (Z), selftest pin on D2, sleep pin on D3 nd an analog reference
|
||||
// value of 5.0. The freefall pin and the range pin are unused
|
||||
// (-1).
|
||||
var sensor = new sensorObj.MMA7361(0, 1, 2, 2, 3, -1, -1, 5.0);
|
||||
|
||||
var x = new sensorObj.new_floatp();
|
||||
var y = new sensorObj.new_floatp();
|
||||
var z = new sensorObj.new_floatp();
|
||||
|
||||
// 1.5g (true = 6g)
|
||||
sensor.setRange(false);
|
||||
|
||||
// Every 10th of a second, update and print values
|
||||
setInterval(function()
|
||||
{
|
||||
// update our values from the sensor
|
||||
sensor.update();
|
||||
|
||||
sensor.getAcceleration(x, y, z);
|
||||
console.log("Accelerometer x: "
|
||||
+ sensorObj.floatp_value(x)
|
||||
+ " y: " + sensorObj.floatp_value(y)
|
||||
+ " z: " + sensorObj.floatp_value(z));
|
||||
|
||||
sensor.getVolts(x, y, z);
|
||||
console.log("Volts x: "
|
||||
+ sensorObj.floatp_value(x)
|
||||
+ " y: " + sensorObj.floatp_value(y)
|
||||
+ " z: " + sensorObj.floatp_value(z));
|
||||
|
||||
console.log();
|
||||
|
||||
}, 100);
|
||||
|
||||
// exit on ^C
|
||||
process.on('SIGINT', function()
|
||||
{
|
||||
sensor = null;
|
||||
sensorObj.cleanUp();
|
||||
sensorObj = null;
|
||||
console.log("Exiting.");
|
||||
process.exit(0);
|
||||
});
|
69
examples/python/mma7361.py
Normal file
69
examples/python/mma7361.py
Normal file
@ -0,0 +1,69 @@
|
||||
#!/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_mma7361 as sensorObj
|
||||
|
||||
# Instantiate a MMA7361 sensor on analog pins A0 (X), A1 (Y) A2
|
||||
# (Z), selftest pin on D2, sleep pin on D3 nd an analog reference
|
||||
# value of 5.0. The freefall pin and the range pin are unused
|
||||
# (-1).
|
||||
sensor = sensorObj.MMA7361(0, 1, 2, 2, 3, -1, -1, 5.0)
|
||||
|
||||
# 1.5g (true = 6g)
|
||||
sensor.setRange(False)
|
||||
|
||||
## 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()
|
||||
|
||||
# Every 10th of a second, update and print values
|
||||
while (1):
|
||||
sensor.update()
|
||||
|
||||
sensor.getAcceleration(x, y, z)
|
||||
print "Accelerometer x:", sensorObj.floatp_value(x),
|
||||
print " y:", sensorObj.floatp_value(y),
|
||||
print " z:", sensorObj.floatp_value(z)
|
||||
|
||||
sensor.getVolts(x, y, z)
|
||||
print "Volts x:", sensorObj.floatp_value(x),
|
||||
print " y:", sensorObj.floatp_value(y),
|
||||
print " z:", sensorObj.floatp_value(z)
|
||||
|
||||
print
|
||||
time.sleep(.100)
|
9
src/mma7361/CMakeLists.txt
Normal file
9
src/mma7361/CMakeLists.txt
Normal file
@ -0,0 +1,9 @@
|
||||
upm_mixed_module_init (NAME mma7361
|
||||
DESCRIPTION "upm dfrobot MMA7361 analog accelerometer"
|
||||
C_HDR mma7361.h
|
||||
C_SRC mma7361.c
|
||||
CPP_HDR mma7361.hpp
|
||||
CPP_SRC mma7361.cxx
|
||||
FTI_SRC mma7361_fti.c
|
||||
CPP_WRAPS_C
|
||||
REQUIRES upmc-utilities mraa)
|
53
src/mma7361/javaupm_mma7361.i
Normal file
53
src/mma7361/javaupm_mma7361.i
Normal file
@ -0,0 +1,53 @@
|
||||
%module javaupm_mma7361
|
||||
%include "../upm.i"
|
||||
%include "std_string.i"
|
||||
%include "cpointer.i"
|
||||
%include "typemaps.i"
|
||||
%include "arrays_java.i";
|
||||
%include "../java_buffer.i"
|
||||
|
||||
%apply int *OUTPUT { int *x, int *y, int *z };
|
||||
%apply float *OUTPUT { float *ax, float *ay, float *az };
|
||||
|
||||
%typemap(jni) float* "jfloatArray"
|
||||
%typemap(jstype) float* "float[]"
|
||||
%typemap(jtype) float* "float[]"
|
||||
|
||||
%typemap(javaout) float* {
|
||||
return $jnicall;
|
||||
}
|
||||
|
||||
%typemap(out) float *getAcceleration {
|
||||
$result = JCALL1(NewFloatArray, jenv, 3);
|
||||
JCALL4(SetFloatArrayRegion, jenv, $result, 0, 3, $1);
|
||||
}
|
||||
|
||||
%typemap(out) float *getVolts {
|
||||
$result = JCALL1(NewFloatArray, jenv, 3);
|
||||
JCALL4(SetFloatArrayRegion, jenv, $result, 0, 3, $1);
|
||||
}
|
||||
|
||||
%typemap(out) float *getNormalized {
|
||||
$result = JCALL1(NewFloatArray, jenv, 3);
|
||||
JCALL4(SetFloatArrayRegion, jenv, $result, 0, 3, $1);
|
||||
}
|
||||
|
||||
%ignore getNormalized(float *, float *, float *);
|
||||
%ignore getAcceleration(float *, float *, float *);
|
||||
%ignore getVolts(float *, float *, float *);
|
||||
|
||||
%include "mma7361.hpp"
|
||||
%{
|
||||
#include "mma7361.hpp"
|
||||
%}
|
||||
|
||||
%pragma(java) jniclasscode=%{
|
||||
static {
|
||||
try {
|
||||
System.loadLibrary("javaupm_mma7361");
|
||||
} catch (UnsatisfiedLinkError e) {
|
||||
System.err.println("Native code library failed to load. \n" + e);
|
||||
System.exit(1);
|
||||
}
|
||||
}
|
||||
%}
|
14
src/mma7361/jsupm_mma7361.i
Normal file
14
src/mma7361/jsupm_mma7361.i
Normal file
@ -0,0 +1,14 @@
|
||||
%module jsupm_mma7361
|
||||
%include "../upm.i"
|
||||
%include "std_string.i"
|
||||
%include "cpointer.i"
|
||||
|
||||
/* Send "int *" and "float *" to JavaScript as intp and floatp */
|
||||
%pointer_functions(int, intp);
|
||||
%pointer_functions(float, floatp);
|
||||
|
||||
%include "mma7361.hpp"
|
||||
%{
|
||||
#include "mma7361.hpp"
|
||||
%}
|
||||
|
394
src/mma7361/mma7361.c
Normal file
394
src/mma7361/mma7361.c
Normal file
@ -0,0 +1,394 @@
|
||||
/*
|
||||
* 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 <string.h>
|
||||
#include <assert.h>
|
||||
|
||||
#include "mma7361.h"
|
||||
|
||||
#include "upm_utilities.h"
|
||||
|
||||
// arduino map() function in macro form (Public Domain)
|
||||
#define MAP(_value, _in_min, _in_max, _out_min, _out_max) \
|
||||
( ((_value) - (_in_min)) * ((_out_max) - (_out_min)) / \
|
||||
((_in_max) - (_in_min)) + _out_min )
|
||||
|
||||
// While the DFR board can be powered at 5.0 to 3.3v, the analog
|
||||
// outputs are always going to be 3.3v - ie: the outputs are not
|
||||
// scaled to 5v, so we need to account for that.
|
||||
// We may need to make this configurable too in the future...
|
||||
#define MMA_OUTPUT_AREF 3.3
|
||||
|
||||
mma7361_context mma7361_init(int x_pin, int y_pin, int z_pin,
|
||||
int selftest_pin, int sleep_pin,
|
||||
int freefall_pin, int range_pin,
|
||||
float a_ref)
|
||||
{
|
||||
// sanity check - at least one axis needs to be enabled, or what's
|
||||
// the point?
|
||||
if (x_pin < 0 && y_pin < 0 && z_pin < 0)
|
||||
{
|
||||
printf("%s: At least one axis must be enabled.\n", __FUNCTION__);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
mma7361_context dev =
|
||||
(mma7361_context)malloc(sizeof(struct _mma7361_context));
|
||||
|
||||
if (!dev)
|
||||
return NULL;
|
||||
|
||||
// zero out context
|
||||
memset((void *)dev, 0, sizeof(struct _mma7361_context));
|
||||
|
||||
dev->aio_x = NULL;
|
||||
dev->aio_y = NULL;
|
||||
dev->aio_z = NULL;
|
||||
|
||||
dev->gpio_selftest = NULL;
|
||||
dev->gpio_sleep = NULL;
|
||||
dev->gpio_freefall = NULL;
|
||||
dev->gpio_range = NULL;
|
||||
|
||||
dev->a_res = 0;
|
||||
dev->a_ref = a_ref;
|
||||
dev->g_range = 1.5;
|
||||
|
||||
dev->offset_x = dev->offset_y = dev->offset_z = 0.0;
|
||||
dev->scale_x = dev->scale_y = dev->scale_z = 1.0;
|
||||
|
||||
dev->accel_x = 0.0;
|
||||
dev->accel_y = 0.0;
|
||||
dev->accel_z = 0.0;
|
||||
|
||||
dev->volts_x = 0.0;
|
||||
dev->volts_y = 0.0;
|
||||
dev->volts_z = 0.0;
|
||||
|
||||
dev->normalized_x = 0;
|
||||
dev->normalized_y = 0;
|
||||
dev->normalized_z = 0;
|
||||
|
||||
// initialize the MRAA contexts (only what we need)
|
||||
|
||||
// analogs
|
||||
if (x_pin >= 0)
|
||||
{
|
||||
if (!(dev->aio_x = mraa_aio_init(x_pin)))
|
||||
{
|
||||
printf("%s: mraa_aio_init(x) failed.\n", __FUNCTION__);
|
||||
mma7361_close(dev);
|
||||
return NULL;
|
||||
}
|
||||
// set our analog resolution
|
||||
dev->a_res = (float)(1 << mraa_aio_get_bit(dev->aio_x)) - 1;
|
||||
}
|
||||
|
||||
if (y_pin >= 0)
|
||||
{
|
||||
if (!(dev->aio_y = mraa_aio_init(y_pin)))
|
||||
{
|
||||
printf("%s: mraa_aio_init(y) failed.\n", __FUNCTION__);
|
||||
mma7361_close(dev);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
// set our analog resolution if not already set
|
||||
if (!dev->a_res)
|
||||
dev->a_res = (float)(1 << mraa_aio_get_bit(dev->aio_y)) - 1;
|
||||
}
|
||||
|
||||
if (z_pin >= 0)
|
||||
{
|
||||
if (!(dev->aio_z = mraa_aio_init(z_pin)))
|
||||
{
|
||||
printf("%s: mraa_aio_init(z) failed.\n", __FUNCTION__);
|
||||
mma7361_close(dev);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
// set our analog resolution if not already set
|
||||
if (!dev->a_res)
|
||||
dev->a_res = (float)(1 << mraa_aio_get_bit(dev->aio_z)) - 1;
|
||||
}
|
||||
|
||||
// now the gpios
|
||||
if (selftest_pin >= 0)
|
||||
{
|
||||
if (!(dev->gpio_selftest = mraa_gpio_init(selftest_pin)))
|
||||
{
|
||||
printf("%s: mraa_gpio_init(selftest) failed.\n", __FUNCTION__);
|
||||
mma7361_close(dev);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
mraa_gpio_dir(dev->gpio_selftest, MRAA_GPIO_OUT);
|
||||
mma7361_selftest(dev, false);
|
||||
}
|
||||
|
||||
if (sleep_pin >= 0)
|
||||
{
|
||||
if (!(dev->gpio_sleep = mraa_gpio_init(sleep_pin)))
|
||||
{
|
||||
printf("%s: mraa_gpio_init(sleep) failed.\n", __FUNCTION__);
|
||||
mma7361_close(dev);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
mraa_gpio_dir(dev->gpio_sleep, MRAA_GPIO_OUT);
|
||||
mma7361_sleep(dev, false);
|
||||
}
|
||||
|
||||
if (freefall_pin >= 0)
|
||||
{
|
||||
if (!(dev->gpio_freefall = mraa_gpio_init(freefall_pin)))
|
||||
{
|
||||
printf("%s: mraa_gpio_init(freefall) failed.\n", __FUNCTION__);
|
||||
mma7361_close(dev);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
mraa_gpio_dir(dev->gpio_freefall, MRAA_GPIO_IN);
|
||||
}
|
||||
|
||||
if (range_pin >= 0)
|
||||
{
|
||||
if (!(dev->gpio_range = mraa_gpio_init(range_pin)))
|
||||
{
|
||||
printf("%s: mraa_gpio_init(range) failed.\n", __FUNCTION__);
|
||||
mma7361_close(dev);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
mraa_gpio_dir(dev->gpio_range, MRAA_GPIO_OUT);
|
||||
mma7361_set_range(dev, false);
|
||||
}
|
||||
|
||||
return dev;
|
||||
}
|
||||
|
||||
void mma7361_close(mma7361_context dev)
|
||||
{
|
||||
assert(dev != NULL);
|
||||
|
||||
// analogs
|
||||
if (dev->aio_x)
|
||||
mraa_aio_close(dev->aio_x);
|
||||
if (dev->aio_y)
|
||||
mraa_aio_close(dev->aio_y);
|
||||
if (dev->aio_z)
|
||||
mraa_aio_close(dev->aio_z);
|
||||
|
||||
// gpios
|
||||
if (dev->gpio_selftest)
|
||||
mraa_gpio_close(dev->gpio_selftest);
|
||||
if (dev->gpio_sleep)
|
||||
mraa_gpio_close(dev->gpio_sleep);
|
||||
if (dev->gpio_freefall)
|
||||
mraa_gpio_close(dev->gpio_freefall);
|
||||
if (dev->gpio_range)
|
||||
mraa_gpio_close(dev->gpio_range);
|
||||
|
||||
free(dev);
|
||||
}
|
||||
|
||||
upm_result_t mma7361_selftest(const mma7361_context dev, bool selftest)
|
||||
{
|
||||
assert(dev != NULL);
|
||||
|
||||
if (!dev->gpio_selftest)
|
||||
return UPM_ERROR_NO_RESOURCES;
|
||||
|
||||
if (selftest)
|
||||
mraa_gpio_write(dev->gpio_selftest, 1);
|
||||
else
|
||||
mraa_gpio_write(dev->gpio_selftest, 0);
|
||||
|
||||
return UPM_SUCCESS;
|
||||
}
|
||||
|
||||
upm_result_t mma7361_sleep(const mma7361_context dev, bool sleep)
|
||||
{
|
||||
assert(dev != NULL);
|
||||
|
||||
if (!dev->gpio_sleep)
|
||||
return UPM_ERROR_NO_RESOURCES;
|
||||
|
||||
if (sleep)
|
||||
mraa_gpio_write(dev->gpio_sleep, 0);
|
||||
else
|
||||
mraa_gpio_write(dev->gpio_sleep, 1);
|
||||
|
||||
upm_delay_ms(2);
|
||||
|
||||
return UPM_SUCCESS;
|
||||
}
|
||||
|
||||
upm_result_t mma7361_freefall(const mma7361_context dev, bool *freefall)
|
||||
{
|
||||
assert(dev != NULL);
|
||||
|
||||
if (!dev->gpio_freefall)
|
||||
return UPM_ERROR_NO_RESOURCES;
|
||||
|
||||
*freefall = mraa_gpio_read(dev->gpio_freefall) ? true : false;
|
||||
|
||||
return UPM_SUCCESS;
|
||||
}
|
||||
|
||||
void mma7361_set_range(const mma7361_context dev, bool range)
|
||||
{
|
||||
assert(dev != NULL);
|
||||
|
||||
// for this one, if there is no actual GPIO available, we will not
|
||||
// error out, but still set the internal range.
|
||||
|
||||
if (range)
|
||||
dev->g_range = 6.0;
|
||||
else
|
||||
dev->g_range = 1.5;
|
||||
|
||||
if (dev->gpio_range)
|
||||
{
|
||||
if (range)
|
||||
mraa_gpio_write(dev->gpio_range, 1);
|
||||
else
|
||||
mraa_gpio_write(dev->gpio_range, 0);
|
||||
}
|
||||
}
|
||||
|
||||
void mma7361_set_offset(const mma7361_context dev, float x, float y, float z)
|
||||
{
|
||||
assert(dev != NULL);
|
||||
|
||||
dev->offset_x = x;
|
||||
dev->offset_y = y;
|
||||
dev->offset_z = z;
|
||||
}
|
||||
|
||||
void mma7361_set_scale(const mma7361_context dev, float x, float y, float z)
|
||||
{
|
||||
assert(dev != NULL);
|
||||
|
||||
dev->scale_x = x;
|
||||
dev->scale_y = y;
|
||||
dev->scale_z = z;
|
||||
}
|
||||
|
||||
upm_result_t mma7361_update(const mma7361_context dev)
|
||||
{
|
||||
assert(dev != NULL);
|
||||
|
||||
float sample;
|
||||
|
||||
if (dev->aio_x)
|
||||
{
|
||||
if ((sample = (float)mraa_aio_read(dev->aio_x)) < 0.0)
|
||||
{
|
||||
printf("%s: mraa_aio_read(x) failed.\n", __FUNCTION__);
|
||||
return UPM_ERROR_OPERATION_FAILED;
|
||||
}
|
||||
|
||||
dev->normalized_x = sample / dev->a_res;
|
||||
dev->volts_x = dev->normalized_x * dev->a_ref;
|
||||
dev->accel_x = MAP(dev->volts_x, 0.0, MMA_OUTPUT_AREF,
|
||||
-dev->g_range, dev->g_range);
|
||||
}
|
||||
|
||||
if (dev->aio_y)
|
||||
{
|
||||
if ((sample = (float)mraa_aio_read(dev->aio_y)) < 0.0)
|
||||
{
|
||||
printf("%s: mraa_aio_read(y) failed.\n", __FUNCTION__);
|
||||
return UPM_ERROR_OPERATION_FAILED;
|
||||
}
|
||||
|
||||
dev->normalized_y = sample / dev->a_res;
|
||||
dev->volts_y = dev->normalized_y * dev->a_ref;
|
||||
dev->accel_y = MAP(dev->volts_y, 0.0, MMA_OUTPUT_AREF,
|
||||
-dev->g_range, dev->g_range);
|
||||
}
|
||||
|
||||
if (dev->aio_z)
|
||||
{
|
||||
if ((sample = (float)mraa_aio_read(dev->aio_z)) < 0.0)
|
||||
{
|
||||
printf("%s: mraa_aio_read(z) failed.\n", __FUNCTION__);
|
||||
return UPM_ERROR_OPERATION_FAILED;
|
||||
}
|
||||
|
||||
dev->normalized_z = sample / dev->a_res;
|
||||
dev->volts_z = dev->normalized_z * dev->a_ref;
|
||||
dev->accel_z = MAP(dev->volts_z, 0.0, MMA_OUTPUT_AREF,
|
||||
-dev->g_range, dev->g_range);
|
||||
}
|
||||
|
||||
return UPM_SUCCESS;
|
||||
}
|
||||
|
||||
void mma7361_get_acceleration(const mma7361_context dev,
|
||||
float *x, float *y, float *z)
|
||||
{
|
||||
assert(dev != NULL);
|
||||
|
||||
if (x)
|
||||
*x = dev->accel_x * dev->scale_x + (dev->offset_x * dev->scale_x);
|
||||
|
||||
if (y)
|
||||
*y = dev->accel_y * dev->scale_y + (dev->offset_y * dev->scale_y);
|
||||
|
||||
if (z)
|
||||
*z = dev->accel_z * dev->scale_z + (dev->offset_z * dev->scale_z);
|
||||
}
|
||||
|
||||
void mma7361_get_volts(const mma7361_context dev,
|
||||
float *x, float *y, float *z)
|
||||
{
|
||||
assert(dev != NULL);
|
||||
|
||||
if (x)
|
||||
*x = dev->volts_x;
|
||||
|
||||
if (y)
|
||||
*y = dev->volts_y;
|
||||
|
||||
if (z)
|
||||
*z = dev->volts_z;
|
||||
}
|
||||
|
||||
void mma7361_get_normalized(const mma7361_context dev,
|
||||
float *x, float *y, float *z)
|
||||
{
|
||||
assert(dev != NULL);
|
||||
|
||||
if (x)
|
||||
*x = dev->normalized_x;
|
||||
|
||||
if (y)
|
||||
*y = dev->normalized_y;
|
||||
|
||||
if (z)
|
||||
*z = dev->normalized_z;
|
||||
}
|
||||
|
149
src/mma7361/mma7361.cxx
Normal file
149
src/mma7361/mma7361.cxx
Normal file
@ -0,0 +1,149 @@
|
||||
/*
|
||||
* 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 <iostream>
|
||||
#include <stdexcept>
|
||||
|
||||
#include "mma7361.hpp"
|
||||
|
||||
using namespace upm;
|
||||
using namespace std;
|
||||
|
||||
MMA7361::MMA7361(int x_pin, int y_pin, int z_pin,
|
||||
int selftest_pin, int sleep_pin,
|
||||
int freefall_pin, int range_pin,
|
||||
float a_ref) :
|
||||
m_mma7361(mma7361_init(x_pin, y_pin, z_pin, selftest_pin, sleep_pin,
|
||||
freefall_pin, range_pin, a_ref))
|
||||
{
|
||||
if (!m_mma7361)
|
||||
throw std::runtime_error(string(__FUNCTION__)
|
||||
+ ": mma7361_init() failed");
|
||||
}
|
||||
|
||||
MMA7361::~MMA7361()
|
||||
{
|
||||
mma7361_close(m_mma7361);
|
||||
}
|
||||
|
||||
void MMA7361::setRange(bool range)
|
||||
{
|
||||
mma7361_set_range(m_mma7361, range);
|
||||
}
|
||||
|
||||
void MMA7361::setSleep(bool sleep)
|
||||
{
|
||||
mma7361_sleep(m_mma7361, sleep);
|
||||
}
|
||||
|
||||
bool MMA7361::isInFreefall()
|
||||
{
|
||||
bool freefall;
|
||||
upm_result_t rv;
|
||||
|
||||
if ((rv = mma7361_freefall(m_mma7361, &freefall)))
|
||||
{
|
||||
throw std::runtime_error(string(__FUNCTION__)
|
||||
+ ": mma7361_freefall() failed with UPM error "
|
||||
+ std::to_string(int(rv)) );
|
||||
}
|
||||
|
||||
return freefall;
|
||||
}
|
||||
|
||||
void MMA7361::enableSelftest(bool enable)
|
||||
{
|
||||
upm_result_t rv;
|
||||
|
||||
if ((rv = mma7361_selftest(m_mma7361, enable)))
|
||||
{
|
||||
throw std::runtime_error(string(__FUNCTION__)
|
||||
+ ": mma7361_selftest() failed with UPM error "
|
||||
+ std::to_string(int(rv)) );
|
||||
}
|
||||
}
|
||||
|
||||
void MMA7361::update()
|
||||
{
|
||||
upm_result_t rv;
|
||||
|
||||
if ((rv = mma7361_update(m_mma7361)))
|
||||
{
|
||||
throw std::runtime_error(string(__FUNCTION__)
|
||||
+ ": mma7361_update() failed with UPM error "
|
||||
+ std::to_string(int(rv)) );
|
||||
}
|
||||
}
|
||||
|
||||
void MMA7361::setOffset(float x, float y, float z)
|
||||
{
|
||||
mma7361_set_offset(m_mma7361, x, y, z);
|
||||
}
|
||||
|
||||
void MMA7361::setScale(float x, float y, float z)
|
||||
{
|
||||
mma7361_set_scale(m_mma7361, x, y, z);
|
||||
}
|
||||
|
||||
void MMA7361::getAcceleration(float *x, float *y, float *z)
|
||||
{
|
||||
mma7361_get_acceleration(m_mma7361, x, y, z);
|
||||
}
|
||||
|
||||
float *MMA7361::getAcceleration()
|
||||
{
|
||||
static float data[3];
|
||||
|
||||
getAcceleration(&data[0], &data[1], &data[2]);
|
||||
|
||||
return data;
|
||||
}
|
||||
|
||||
void MMA7361::getVolts(float *x, float *y, float *z)
|
||||
{
|
||||
mma7361_get_volts(m_mma7361, x, y, z);
|
||||
}
|
||||
|
||||
float *MMA7361::getVolts()
|
||||
{
|
||||
static float data[3];
|
||||
|
||||
getVolts(&data[0], &data[1], &data[2]);
|
||||
|
||||
return data;
|
||||
}
|
||||
|
||||
void MMA7361::getNormalized(float *x, float *y, float *z)
|
||||
{
|
||||
mma7361_get_normalized(m_mma7361, x, y, z);
|
||||
}
|
||||
|
||||
float *MMA7361::getNormalized()
|
||||
{
|
||||
static float data[3];
|
||||
|
||||
getNormalized(&data[0], &data[1], &data[2]);
|
||||
|
||||
return data;
|
||||
}
|
250
src/mma7361/mma7361.h
Normal file
250
src/mma7361/mma7361.h
Normal file
@ -0,0 +1,250 @@
|
||||
/*
|
||||
* 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>
|
||||
#include "upm.h"
|
||||
#include "mraa/aio.h"
|
||||
#include "mraa/gpio.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @brief UPM C API for the DFRobot MMA7361 Analog Accelerometer
|
||||
*
|
||||
* The driver was tested with the DFRobot MMA7361 Analog
|
||||
* Accelerometer. It supports 3 Axes with a selectable 1.5G and 6G
|
||||
* sensitivity.
|
||||
*
|
||||
* @snippet mma7361.c Interesting
|
||||
*/
|
||||
|
||||
/**
|
||||
* Device context
|
||||
*/
|
||||
typedef struct _mma7361_context {
|
||||
// at least one of these must be intialized
|
||||
mraa_aio_context aio_x;
|
||||
mraa_aio_context aio_y;
|
||||
mraa_aio_context aio_z;
|
||||
|
||||
// optional - enable selftest
|
||||
mraa_gpio_context gpio_selftest;
|
||||
|
||||
// optional - enable sleep mode
|
||||
mraa_gpio_context gpio_sleep;
|
||||
|
||||
// optional - detect free fall (0g)
|
||||
mraa_gpio_context gpio_freefall;
|
||||
|
||||
// optional - if unconnected, range is 1.5g
|
||||
mraa_gpio_context gpio_range;
|
||||
|
||||
// selected G range
|
||||
float g_range;
|
||||
|
||||
// analog ADC resolution
|
||||
float a_res;
|
||||
|
||||
// analog reference voltage
|
||||
float a_ref;
|
||||
|
||||
// for external offset and scaling of the results
|
||||
float offset_x;
|
||||
float offset_y;
|
||||
float offset_z;
|
||||
|
||||
float scale_x;
|
||||
float scale_y;
|
||||
float scale_z;
|
||||
|
||||
// our measurements
|
||||
float accel_x;
|
||||
float accel_y;
|
||||
float accel_z;
|
||||
|
||||
// volts
|
||||
float volts_x;
|
||||
float volts_y;
|
||||
float volts_z;
|
||||
|
||||
// normalized ADC
|
||||
float normalized_x;
|
||||
float normalized_y;
|
||||
float normalized_z;
|
||||
} *mma7361_context;
|
||||
|
||||
/**
|
||||
* MMA7361 Initializer
|
||||
*
|
||||
* This sensor isn't designed for navigational purposes - rather
|
||||
* it's intended for less precise measurements such as determining
|
||||
* tilt and orientation.
|
||||
*
|
||||
* All of these pins are optional, and will depend on how your
|
||||
* device is connected. For those pins you do not need, supply -1
|
||||
* as the pin. You must supply a valid pin for at least one of the
|
||||
* axes, or what's the point?
|
||||
*
|
||||
* The DFRobot variant of this sensor uses a mechanical switch on
|
||||
* the board to determine the G-range to use, so on this board you
|
||||
* would supply -1 for the range_pin, but be sure to call
|
||||
* mma7361_set_range() with the correct parameter so that the
|
||||
* internal logic will generate correct results.
|
||||
*
|
||||
* @param x_pin Analog pin to use for X axis. -1 to disable.
|
||||
* @param y_pin Analog pin to use for Y axis. -1 to disable.
|
||||
* @param z_pin Analog pin to use for Z axis. -1 to disable.
|
||||
* @param selftest_pin GPIO pin to use for self test. -1 to disable.
|
||||
* @param sleep_pin GPIO pin to use for sleep function. -1 to disable.
|
||||
* @param freefall_pin GPIO pin to use for free fall (0g)
|
||||
* detection. -1 to disable.
|
||||
* @param range_pin GPIO pin to select range (1.5g or 6g). -1 to
|
||||
* disable.
|
||||
* @param a_ref The analog reference voltage in use
|
||||
*/
|
||||
mma7361_context mma7361_init(int x_pin, int y_pin, int z_pin,
|
||||
int selftest_pin, int sleep_pin,
|
||||
int freefall_pin, int range_pin,
|
||||
float a_ref);
|
||||
|
||||
/**
|
||||
* MMA7361 sensor close function
|
||||
*/
|
||||
void mma7361_close(mma7361_context dev);
|
||||
|
||||
/**
|
||||
* Set the range of the device. This device supports two G ranges:
|
||||
* 1.5 and 6. The default is 1.5G.
|
||||
*
|
||||
* @param dev sensor context
|
||||
* @param range true for 6G, false for 1.5G
|
||||
*/
|
||||
void mma7361_set_range(const mma7361_context dev, bool range);
|
||||
|
||||
/**
|
||||
* Set sleep mode. When in sleep mode the sensor uses minimal power.
|
||||
*
|
||||
* @param dev sensor context
|
||||
* @param sleep true to go into sleep mode, false to wake up
|
||||
* @return UPM result
|
||||
*/
|
||||
upm_result_t mma7361_sleep(const mma7361_context dev, bool sleep);
|
||||
|
||||
/**
|
||||
* Get freefall detection status.
|
||||
*
|
||||
* @param dev sensor context
|
||||
* @param freefall O pointer to a boolean value indicating whether a
|
||||
* freefall condition is being detected.
|
||||
* @return UPM result
|
||||
*/
|
||||
upm_result_t mma7361_freefall(const mma7361_context dev, bool *freefall);
|
||||
|
||||
/**
|
||||
* Enable self test mode.
|
||||
*
|
||||
* @param dev sensor context
|
||||
* @param selftest true to enable the self test mode, false otherwise.
|
||||
* @return UPM result
|
||||
*/
|
||||
upm_result_t mma7361_selftest(const mma7361_context dev, bool selftest);
|
||||
|
||||
/**
|
||||
* Read the sensor status an update internal state.
|
||||
* mma7361_update() must have been called before calling
|
||||
* mma7361_get_acceleration(), mma7361_get_normalized(), or
|
||||
* mma7361_get_volts().
|
||||
*
|
||||
* @param dev sensor context
|
||||
* @return UPM result
|
||||
*/
|
||||
upm_result_t mma7361_update(const mma7361_context dev);
|
||||
|
||||
/**
|
||||
* Set sensor offset. This offset is applied to the return values
|
||||
* before scaling. Default is 0.0.
|
||||
*
|
||||
* @param dev sensor context pointer
|
||||
* @param x Scale to apply to X value
|
||||
* @param y Scale to apply to Y value
|
||||
* @param z Scale to apply to Z value
|
||||
*/
|
||||
void mma7361_set_offset(const mma7361_context dev, float x, float y,
|
||||
float z);
|
||||
|
||||
/**
|
||||
* Set sensor scale. The acceleration return values are scaled by
|
||||
* this value before the offset is applied. Default is 1.0.
|
||||
*
|
||||
* @param dev sensor context pointer
|
||||
* @param x Offset to apply to X value
|
||||
* @param y Offset to apply to Y value
|
||||
* @param z Offset to apply to Z value
|
||||
*/
|
||||
void mma7361_set_scale(const mma7361_context dev, float x, float y,
|
||||
float z);
|
||||
|
||||
/**
|
||||
* Get computed acceleration from the sensor. mma7361_update() must
|
||||
* have been called prior to calling this function.
|
||||
*
|
||||
* @param dev sensor context pointer
|
||||
* @param x a pointer in which X acceleration data will be returned
|
||||
* @param y a pointer in which Y acceleration data will be returned
|
||||
* @param z a pointer in which Z acceleration data will be returned
|
||||
*/
|
||||
void mma7361_get_acceleration(const mma7361_context dev,
|
||||
float *x, float *y, float *z);
|
||||
|
||||
/**
|
||||
* Get the measured volts from the sensor. mma7361_update() must
|
||||
* have been called prior to calling this function.
|
||||
*
|
||||
* @param dev sensor context pointer
|
||||
* @param x a pointer in which X volt data will be returned
|
||||
* @param y a pointer in which Y volt data will be returned
|
||||
* @param z a pointer in which Z volt data will be returned
|
||||
*/
|
||||
void mma7361_get_volts(const mma7361_context dev,
|
||||
float *x, float *y, float *z);
|
||||
|
||||
/**
|
||||
* Get the normalized ADC values from the sensor. mma7361_update() must
|
||||
* have been called prior to calling this function.
|
||||
*
|
||||
* @param dev sensor context pointer
|
||||
* @param x a pointer in which X normalized ADC data will be returned
|
||||
* @param y a pointer in which Y normalized ADC data will be returned
|
||||
* @param z a pointer in which Z normalized ADC data will be returned
|
||||
*/
|
||||
void mma7361_get_normalized(const mma7361_context dev,
|
||||
float *x, float *y, float *z);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
208
src/mma7361/mma7361.hpp
Normal file
208
src/mma7361/mma7361.hpp
Normal file
@ -0,0 +1,208 @@
|
||||
/*
|
||||
* 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 <iostream>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <unistd.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "mma7361.h"
|
||||
|
||||
namespace upm {
|
||||
/**
|
||||
* @brief UPM C++ API for the DFRobot MMA7361 Analog Accelerometer
|
||||
* @defgroup mma7361 libupm-mma7361
|
||||
* @ingroup dfrobot gpio ainput accelerometer
|
||||
*/
|
||||
|
||||
/**
|
||||
* @library mma7361
|
||||
* @sensor mma7361
|
||||
* @comname DFRobot MMA7361 Analog Accelerometer
|
||||
* @type accelerometer
|
||||
* @man dfrobot
|
||||
* @con ainput gpio
|
||||
* @web http://www.dfrobot.com/index.php?route=product/product&path=36&product_id=507#.V7YEj99ytNJ
|
||||
*
|
||||
* @brief API for the DFRobot MMA7361 Analog Accelerometer
|
||||
*
|
||||
* The driver was tested with the DFRobot MMA7361 Analog
|
||||
* Accelerometer. It supports 3 Axes with a selectable 1.5G and 6G
|
||||
* sensitivity.
|
||||
*
|
||||
* @snippet mma7361.cxx Interesting
|
||||
*/
|
||||
|
||||
class MMA7361 {
|
||||
public:
|
||||
|
||||
/**
|
||||
* MMA7361 object constructor
|
||||
*
|
||||
* @param x_pin Analog pin to use for X axis. -1 to disable.
|
||||
* @param y_pin Analog pin to use for Y axis. -1 to disable.
|
||||
* @param z_pin Analog pin to use for Z axis. -1 to disable.
|
||||
* @param selftest_pin GPIO pin to use for self test. -1 to disable.
|
||||
* @param sleep_pin GPIO pin to use for sleep function. -1 to disable.
|
||||
* @param freefall_pin GPIO pin to use for free fall (0g)
|
||||
* detection. -1 to disable.
|
||||
* @param range_pin GPIO pin to select range (1.5g or 6g). -1 to
|
||||
* disable.
|
||||
* @param a_ref The analog reference voltage in use. Default 5.0.
|
||||
*/
|
||||
MMA7361(int x_pin, int y_pin, int z_pin,
|
||||
int selftest_pin, int sleep_pin,
|
||||
int freefall_pin, int range_pin,
|
||||
float a_ref=5.0);
|
||||
|
||||
/**
|
||||
* MMA7361 object destructor
|
||||
*/
|
||||
~MMA7361();
|
||||
|
||||
/**
|
||||
* Set the range of the device. This device supports two G ranges:
|
||||
* 1.5 and 6. The default is 1.5G.
|
||||
*
|
||||
* @param range true for 6G, false for 1.5G
|
||||
*/
|
||||
void setRange(bool range);
|
||||
|
||||
/**
|
||||
* Set sleep mode. When in sleep mode the sensor uses minimal power.
|
||||
*
|
||||
* @param sleep true to go into sleep mode, false to wake up
|
||||
*/
|
||||
void setSleep(bool sleep);
|
||||
|
||||
/**
|
||||
* Get freefall detection status.
|
||||
*
|
||||
* @return true if a freefall condition is detected, false otherwise.
|
||||
*/
|
||||
bool isInFreefall();
|
||||
|
||||
/**
|
||||
* Enable self test mode.
|
||||
*
|
||||
* @param enable true to enable the self test mode, false otherwise.
|
||||
*/
|
||||
void enableSelftest(bool enable);
|
||||
|
||||
/**
|
||||
* Read the sensor status an update internal state.
|
||||
* update() must have been called before calling
|
||||
* getAcceleration(), getNormalized(), or getVolts().
|
||||
*/
|
||||
void update();
|
||||
|
||||
/**
|
||||
* Set sensor offset. This offset is applied to the return values
|
||||
* before scaling. Default is 0.0.
|
||||
*
|
||||
* @param x Offset to apply to X value
|
||||
* @param y Offset to apply to Y value
|
||||
* @param z Offset to apply to Z value
|
||||
*/
|
||||
void setOffset(float x, float y, float z);
|
||||
|
||||
/**
|
||||
* Set sensor scale. The acceleration return values are scaled by
|
||||
* this value before the offset is applied. Default is 1.0.
|
||||
*
|
||||
* @param x Scale to apply to X value
|
||||
* @param y Scale to apply to Y value
|
||||
* @param z Scale to apply to Z value
|
||||
*/
|
||||
void setScale(float x, float y, float z);
|
||||
|
||||
/**
|
||||
* Get computed acceleration from the sensor. update() must have
|
||||
* been called prior to calling this function.
|
||||
*
|
||||
* @param x a pointer in which X acceleration data will be returned
|
||||
* @param y a pointer in which Y acceleration data will be returned
|
||||
* @param z a pointer in which Z acceleration data will be returned
|
||||
*/
|
||||
void getAcceleration(float *x, float *y, float *z);
|
||||
|
||||
/**
|
||||
* Get computed acceleration from the sensor. update() must have
|
||||
* been called prior to calling this function.
|
||||
*
|
||||
* @return a pointer to a statically allocated array of 3 floats
|
||||
* containing the X, Y, and Z componenets.
|
||||
*/
|
||||
float *getAcceleration();
|
||||
|
||||
/**
|
||||
* Get the measured volts from the sensor. update() must have been
|
||||
* called prior to calling this function.
|
||||
*
|
||||
* @param x a pointer in which X volt data will be returned
|
||||
* @param y a pointer in which Y volt data will be returned
|
||||
* @param z a pointer in which Z volt data will be returned
|
||||
*/
|
||||
void getVolts(float *x, float *y, float *z);
|
||||
|
||||
/**
|
||||
* Get the measured volts from the sensor. update() must have been
|
||||
* called prior to calling this function.
|
||||
*
|
||||
* @return a pointer to a statically allocated array of 3 floats
|
||||
* containing the X, Y, and Z componenets.
|
||||
*/
|
||||
float *getVolts();
|
||||
|
||||
/**
|
||||
* Get the normalized ADC values from the sensor. update() must have
|
||||
* been called prior to calling this function.
|
||||
*
|
||||
* @param x a pointer in which X normalized ADC data will be returned
|
||||
* @param y a pointer in which Y normalized ADC data will be returned
|
||||
* @param z a pointer in which Z normalized ADC data will be returned
|
||||
*/
|
||||
void getNormalized(float *x, float *y, float *z);
|
||||
|
||||
/**
|
||||
* Get the normalized ADC values from the sensor. update() must have
|
||||
* been called prior to calling this function.
|
||||
*
|
||||
* @return a pointer to a statically allocated array of 3 ints
|
||||
* containing the X, Y, and Z componenets.
|
||||
*/
|
||||
float *getNormalized();
|
||||
|
||||
protected:
|
||||
// mma7361 device context
|
||||
mma7361_context m_mma7361;
|
||||
|
||||
private:
|
||||
};
|
||||
}
|
||||
|
||||
|
122
src/mma7361/mma7361_fti.c
Normal file
122
src/mma7361/mma7361_fti.c
Normal file
@ -0,0 +1,122 @@
|
||||
/*
|
||||
* 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 "mma7361.h"
|
||||
#include "upm_fti.h"
|
||||
|
||||
/**
|
||||
* This file implements the Function Table Interface (FTI) for this sensor
|
||||
*/
|
||||
|
||||
const char upm_mma7361_name[] = "MMA7361";
|
||||
const char upm_mma7361_description[] = "Analog 3-axis Accelerometer";
|
||||
const upm_protocol_t upm_mma7361_protocol[] = {UPM_ANALOG, UPM_ANALOG,
|
||||
UPM_ANALOG, UPM_GPIO, UPM_GPIO,
|
||||
UPM_GPIO, UPM_GPIO};
|
||||
const upm_sensor_t upm_mma7361_category[] = {UPM_ACCELEROMETER};
|
||||
|
||||
// forward declarations
|
||||
const void* upm_mma7361_get_ft(upm_sensor_t sensor_type);
|
||||
void* upm_mma7361_init_name();
|
||||
void upm_mma7361_close(void *dev);
|
||||
upm_result_t upm_mma7361_get_acceleration(void *dev, float *value,
|
||||
upm_acceleration_u unit);
|
||||
upm_result_t upm_mma7361_set_scale(void *dev, float *scale);
|
||||
upm_result_t upm_mma7361_set_offset(void *dev, float *offset);
|
||||
|
||||
static const upm_sensor_ft ft =
|
||||
{
|
||||
.upm_sensor_init_name = &upm_mma7361_init_name,
|
||||
.upm_sensor_close = &upm_mma7361_close,
|
||||
};
|
||||
|
||||
static const upm_acceleration_ft aft =
|
||||
{
|
||||
.upm_acceleration_get_value = &upm_mma7361_get_acceleration
|
||||
};
|
||||
|
||||
const void* upm_mma7361_get_ft(upm_sensor_t sensor_type)
|
||||
{
|
||||
switch(sensor_type)
|
||||
{
|
||||
case UPM_SENSOR:
|
||||
return &ft;
|
||||
|
||||
case UPM_ACCELEROMETER:
|
||||
return &aft;
|
||||
|
||||
default:
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
void* upm_mma7361_init_name()
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
void upm_mma7361_close(void *dev)
|
||||
{
|
||||
mma7361_close((mma7361_context)dev);
|
||||
}
|
||||
|
||||
upm_result_t upm_mma7361_get_acceleration(void *dev, float *value,
|
||||
upm_acceleration_u unit)
|
||||
{
|
||||
upm_result_t rv;
|
||||
if ((rv = mma7361_update((mma7361_context)dev)))
|
||||
return rv;
|
||||
|
||||
// Which "value" is supposed to be returned here? Is it an array?
|
||||
// Needs docs in the FTI header file for this sensor type. We'll
|
||||
// assume it's array.
|
||||
// FIXME/CHECKME
|
||||
|
||||
// Only in G's
|
||||
mma7361_get_acceleration((mma7361_context)dev, &value[0], &value[1],
|
||||
&value[2]);
|
||||
|
||||
return UPM_SUCCESS;
|
||||
}
|
||||
|
||||
upm_result_t upm_mma7361_set_scale(void *dev, float *scale)
|
||||
{
|
||||
// FIXME/CHECKME
|
||||
// again, which scale? As it's a pointer, we'll assume it's
|
||||
// an array of 3 floats. FTI needs some docs.
|
||||
|
||||
mma7361_set_scale((mma7361_context)dev, scale[0], scale[1], scale[2]);
|
||||
return UPM_SUCCESS;
|
||||
}
|
||||
|
||||
upm_result_t upm_mma7361_set_offset(void *dev, float *offset)
|
||||
{
|
||||
// FIXME/CHECKME
|
||||
// As it's a pointer, we'll assume it's an array of 3 floats. FTI
|
||||
// needs some docs.
|
||||
|
||||
mma7361_set_offset((mma7361_context)dev, offset[0], offset[1], offset[2]);
|
||||
return UPM_SUCCESS;
|
||||
}
|
18
src/mma7361/pyupm_mma7361.i
Normal file
18
src/mma7361/pyupm_mma7361.i
Normal file
@ -0,0 +1,18 @@
|
||||
// Include doxygen-generated documentation
|
||||
%include "pyupm_doxy2swig.i"
|
||||
%module pyupm_mma7361
|
||||
%include "../upm.i"
|
||||
%include "std_string.i"
|
||||
%include "cpointer.i"
|
||||
|
||||
/* Send "int *" and "float *" to python as intp and floatp */
|
||||
%pointer_functions(int, intp);
|
||||
%pointer_functions(float, floatp);
|
||||
|
||||
%feature("autodoc", "3");
|
||||
|
||||
%include "mma7361.hpp"
|
||||
%{
|
||||
#include "mma7361.hpp"
|
||||
%}
|
||||
|
Loading…
x
Reference in New Issue
Block a user