Study of animal movement: equipment design and development

We are an interdisciplinary group whose objective is to answer questions about the basic biology of animal species in a vulnerable state.

AdvancedFull instructions provided593

Things used in this project

Story

Read more

Schematics

Arduino Nano 33 BLE + LoRa communication

Combining the Arduino Nano 33 BLE with the SEEED Grove LoRa module we will have a complete real time monitoring system.

Animal monitoring system using CC1312R1F3RGZT microcontroller

Schematic circuit of the animal monitoring system containing GPS, inertial sensors, temperature sensor and microphone using the CC1312R1F3RGZT microcontroller.

Code

Example code for transmitting IMU data

C/C++
Reads the MCU temperature (CC1312R1 has its own Temperature sensor built in)
Reads all the values of the IMU module (this includes Temperature, 3 axis of accelerometers, gyroscopes and magnetometer)
Proceed to embedded all this data inside a packet (adding header for identification and synchronization information) and send it using the RF Radio .
After a succeed transmission, proceed to the beginning of the loop
/*
 * Copyright (c) 2019-2020, Texas Instruments Incorporated
 * All rights reserved.
 *
 * 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 Texas Instruments Incorporated nor the names of
 *    its 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 THE COPYRIGHT OWNER 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.
 */

/*
 *  ======== i2copt3001_cpp.cpp ========
 */

#include <unistd.h>

/* Driver Header files */
#include <ti/drivers/GPIO.h>
#include <ti/drivers/I2C.h>
#include <ti/display/Display.h>

// to allow temperature
#include <ti/drivers/Temperature.h>

#include <stdio.h>//to allow float to conversion
/* Threading header files */
#include <pthread.h>
#include <semaphore.h>
#include <ti/sysbios/knl/Task.h> //TI RTOSto acces task sleep fro
#include <ti/sysbios/knl/Clock.h> //TI RTOSto acces task sleep fro
#include <lsm9ds1/LSM9DS1.h>
/* Driver Configuration */
#include "ti_drivers_config.h"
#define UART_MESSAGE_TX
#ifdef UART_MESSAGE_TX
#define UART_MESSAGE_TX_SIZE 52
struct uart_message{
  float t_mcu;//4 bytes
  float t_imu;//4 bytes
  float ax;//4 bytes
  float ay;//4 bytes
  float az;//4 bytes
  float gx;//4 bytes
  float gy;//4 bytes
  float gz;//4 bytes
  float mx;//4 bytes
  float my;//4 bytes
  float mz;//4 bytes
  float gps_lat;
  float gps_long;
};
union uart_message_union{
  uart_message m;
  uint8_t data[UART_MESSAGE_TX_SIZE];// total bytes=386: 2 (temp) + 2*3*(32) (accel)+2*3*(32) (gyro)
};
static uart_message_union message_to_tx;
#endif

static LSM9DS1 imu;//declares the variable
/*
 * These values narrow the limits of the sensor to
 * allow those running the example to test the interrupt feature
 */
extern Display_Handle display;
static sem_t semaphoreAlarm;
/* Thread function prototypes */
extern "C" {
void  *threadfn_imu_i2c0(void *arg0);
void rfEasyLinkradio_set_up(void);
void tx_message(uint8_t* packet_p,uint8_t packet_size);
}
/*
 *  ======== mainThread ========
 */

void *threadfn_imu_i2c0(void *arg0)
{
	int8_t temperature_mcu;
    Temperature_init();

	u_int32_t clocktick_start,clocktick_end;
	float clocktick_delta;
    display = Display_open(Display_Type_UART, NULL);//open display driver
    Display_printf(display, 0, 0, "init\n");
    if (display == NULL) {while (1);}        /* Failed to open display driver */
	rfEasyLinkradio_set_up();
    bool setup_imu=imu.begin();
	if (setup_imu ==0) // with no arguments, this uses default addresses (AG:0x6B, M:0x1E) and i2c port (Wire).
	    {Display_printf(display, 0, 0, "i2c fail to set up\n");
	    while(1);}
	if (setup_imu ==2) // with no arguments, this uses default addresses (AG:0x6B, M:0x1E) and i2c port (Wire).
	    {Display_printf(display, 0, 0, "i2c setted2, fail to communicate with imu\n");
	    while(1);}
	   // imu.write_register(IMU_GYRO_ACCCEL,1,  1);// DO NOT UNCOMMENT
	    Display_printf(display, 0, 0, "proceeding to calibrate 4\n");
	    clocktick_start=Clock_getTicks();//get the starting time of the tick
	    //imu.calibrate();//After this, each meassure will be
	    //the time to callibrate is aprox 209.560 clock ticks. With a tick=10 us,
	    //this equal to 2.095.600 us, wich rounds up 2 seconds
	    //this is important because the FIFO can store 32 outputs
	    //so the adquision time of one sample is arround
	    //2seconds/32samples=0.0625 seconds which is a Hz of 16, which is the value configured
	    clocktick_end=Clock_getTicks();//get the finishng time of the tick
	    clocktick_delta=(((float)(clocktick_end-clocktick_start))*Clock_tickPeriod)/1000;//get the finishng time of the tick
	    Display_printf(display, 0, 0, "Clock Tick Period : %1\n",Clock_tickPeriod);
	    Display_printf(display, 0, 0, "calibration succesfull, TIME: %2f  ms \n",clocktick_delta);
        Display_printf(display, 0, 0,(char *)"Callibration result:Gyro bias x: %2f y: %2f z: %2f \n",
			                                  (imu.gBias[0]),(imu.gBias[1]),(imu.gBias[2]));
        Display_printf(display, 0, 0, "------->Proceeding to meassure\n");
	    Task_sleep(200000);//1 second delay
        imu.readGyro();
	    Task_sleep(2000);//1 second delay
  	          if ( imu.tempAvailable() ) //check if there is temperature aviable
  	          {
  		      imu.readTemp();
  	          temperature_mcu = (uint8_t)Temperature_getTemperature();
	          Display_printf(display, 0, 0,(char *)"Temperature MCU: %2f,Temperature IMU: %2f",
	            		(float)temperature_mcu,imu.calcTemp(imu.temperature));
  	          }
	         if(imu.gyroAvailable() )
	    	  {
	    	    clocktick_start=Clock_getTicks();//get the starting time of the tick
	    	    imu.readGyro();
	    	    clocktick_end=Clock_getTicks();//get the finishng time of the tick
	    	    clocktick_delta=((float((clocktick_end-clocktick_start)*Clock_tickPeriod))/1000);
	    	    //time to perform read: 30 ticks of 10 us=300 us with ic=400kbps
	    	    Display_printf(display, 0, 0, "Time to read a 3 axis sample: %2f  ms\n",clocktick_delta);
	            Display_printf(display, 0, 0,(char *)"Gyro reading x: %2f y: %2f z: %2f\n",
					imu.calcGyro(imu.gx),imu.calcGyro(imu.gy),imu.calcGyro(imu.gz));
	    	  }
	    	  if ( imu.magAvailable() )
	    	  { imu.readMag();
	            Display_printf(display, 0, 0,(char *)"Mag reading x: %2f y: %2f z: %2f \n",
				imu.calcMag(imu.mx),imu.calcMag(imu.my),imu.calcMag(imu.mz));
	    	  }
	    	  if (imu.accelAvailable())
	    	  { imu.readAccel();
	            Display_printf(display, 0, 0,(char *)"Accel reading x: %2f y: %2f z: %2f \n",
				imu.calcAccel(imu.ax),imu.calcAccel(imu.ay),imu.calcAccel(imu.az));
	    	  }
             //now we start the imu in this mode
		  	  imu.enableFIFO_continous();
			 Task_sleep(200000);//1 second delay
	  	     while(1)
	  	     {
		  	  Task_sleep(1000);//0.5 second delay
	  	      imu.readAll();
		  	  #ifdef UART_MESSAGE_TX
              message_to_tx.m.t_mcu=(float)temperature_mcu;
              message_to_tx.m.t_imu=imu.calcTemp(imu.temperature);
              message_to_tx.m.ax=imu.calcAccel(imu.buffer.gyro_accel[0].ax);
              message_to_tx.m.ay=imu.calcAccel(imu.buffer.gyro_accel[0].ay);
              message_to_tx.m.az=imu.calcAccel(imu.buffer.gyro_accel[0].az);
              message_to_tx.m.gx= imu.calcGyro(imu.buffer.gyro_accel[0].gx);
              message_to_tx.m.gy= imu.calcGyro(imu.buffer.gyro_accel[0].gy);
              message_to_tx.m.gz= imu.calcGyro(imu.buffer.gyro_accel[0].gz);
              message_to_tx.m.mx= imu.calcMag(imu.mx);
              message_to_tx.m.my= imu.calcMag(imu.my);
              message_to_tx.m.mz= imu.calcMag(imu.mz);
              tx_message(message_to_tx.data,UART_MESSAGE_TX_SIZE);
              //sens message using rx
              #endif
	  	     }

}

Graphic user interface

Python
This script creates a web site using Dash & and Plotly, and show to the user the current Temperature and accelerometer values. It also computes the angle from the magnetometer measures to set the angle of a 3D figure based on the results.
#jupyter nbextension enable --py widgetsnbextension 
import platform #to get my operative system
import plotly.graph_objects as go
import serial #pip install pyserial
import struct #to unfold a C struct into other types of data
import numpy as np
import math

import threading           
import time                #to implement delays
import plotlydash as dplot

import datetime            #to get time
import webbrowser #for opening a webbroser when running scrips
import dash
from dash import dcc, html
from dash.dependencies import Input, Output

#from varname import nameof #for getting name of var #pip3 install varname
#define constants
def constant(f):
    def fset(self, value):raise TypeError
    def fget(self):return f()
    return property(fget, fset)
class _Const(object):
  @constant
  def DATA_RX_FORMAT_HEADER():   return 'f'
  @constant
  def DATA_RX_FORMAT_DATA():     return 'fffffffffffff'
  @constant
  def DATA_RX_FORMAT():          return('ffffffffffffff') #(DATA_RX_FORMAT_HEADER+DATA_RX_FORMAT_DATA)
  @constant
  def DATA_RX_SIZE():            return 56 #(DATA_RX_FORMAT_HEADER+DATA_RX_FORMAT_DATA)
  @constant
  def DATA_RX_HEADER_VALUE():    return 1.000102902456799e-37# in hex: 0x02082080 #in float: 1.000102902456799e-37
  @constant
  def SERIAL_PORT_ID_WIN():      return 'COM18'  ##in float: 1.000102902456799e-37 in hex: 0x02082080
  @constant
  def SERIAL_PORT_ID_LINUX():    return '/dev/ttyACM0'  ##in float: 1.000102902456799e-37 in hex: 0x02082080
  @constant
  def SERIAL_PORT_ID_RASPBIAN(): return '/dev/ttyS0'#serial 0:'/dev/ttyS0',serial 1:'/dev/ttyAMA0' 
  @constant
  def SERIAL_UPDATE_MS():        return 110 #150 also works
  @constant
  def WEB_TITLE():               return 'FiEstIn - Instituto Balseiro'  ##in float: 1.000102902456799e-37 in hex: 0x02082080
#create the constant class
CONST = _Const()
#declare global variables
global serial_port
# to apply an adaptative filter 
global anglex,angley,anglez 
#------------------------------------------------------------------------------
#Create the plot
#----------------------------------------------------------------------------------
# generate data
x = np.outer(np.linspace(-1.4, 1.4, 20), np.ones(20)) 
y = x.copy().T 
z = np.cos(x ** 2 + y ** 2) 
#create figure
fig = go.FigureWidget(go.Figure(data=go.Surface(x=x, y=y, z=z, showscale=False,colorscale ='viridis')))
                   #colors: blugrn, #ylgn #viridis more beautiful
camera = dict(up=dict(x=0,   y=0,   z=0),#esto controla el giro
          center=dict(x=0,   y=0,   z=0),#controls camera center
            eye=dict( x=1.2, y=1.2, z=1.2)) #control the zoom out position
fig.update_layout(scene_camera=camera,template='plotly_dark',font_size=14)
fig.update_layout(title='Awaiting for data')
#----------------------------------------------------------------------------------
#Proceed to open and init serial port
#-----------------------------------------------------------------------------------
anglex,angley,anglez=-1,-1,-1 #init as -1
opertative_system=platform.system()
if opertative_system=='Raspbian': serial_port_id=CONST.SERIAL_PORT_ID_RASPBIAN
if opertative_system=='Linux':    serial_port_id=CONST.SERIAL_PORT_ID_LINUX
if opertative_system=='Windows':  serial_port_id=CONST.SERIAL_PORT_ID_WIN
try :   serial_port.close() #will try to close port if already opened, this is a secutiry meassure
except: pass #DO NOT COMMENT if we can't close, we don't do anything
finally:serial_port = serial.Serial(serial_port_id,115200,timeout=1)#timeout must be passed in seconds
print('Serial port',serial_port) #to know the serial port used
#---------------------------------------------------------------------------------------
#Proceed to create the dash web structure
#----------------------------------------------------------------------------------
graph_plots=[]#list of dash graph plots we want to add. makes easier to have multiple plots
graph_plots.append(dcc.Graph(id='graph1',figure=fig,style={'width': '75vw', 'height': '75vh'}))  
row = html.H1(children=graph_plots)
#we add the element with the desired tittle
header = html.H1(children=CONST.WEB_TITLE,style={'color':'#7FDBFF','font_size': '130%'})
subheader = html.H2(children='\U0001F422 \U0001F422 \U0001F422 Grupo de Fsica Estadstica e Interdisciplinaria '
                    +'\U0001F422 \U0001F422 \U0001F422',style={'color':'#57F287'})                                                 
footprint = html.H3(children="\U0001F98E Andrs Oliva Trevisan, Nicols Catalano, Laila D. Kazimierski, Erika Kubisch, Karina Laneri \U0001F98E ",style={'color':'#0092CC','text-align': 'right'})                                                
#we add the element with the timer
graph_timer= dcc.Interval(id='timer_graph_update',interval=CONST.SERIAL_UPDATE_MS # in milliseconds
                                              ,n_intervals=0) #initial value of intervals
#create an object to chare ,json compatilble data between elements of the web site or external one
data_to_share=dcc.Store(id='data_to_transfer', storage_type='local')
#-----------------------------------------------------------------------------------
#we create the app layout adding all the objsects ---------------------------------
app_layout = html.Div(children=[header,subheader, row, graph_timer,data_to_share,footprint], style={
"text-align": "center", "justifyContent":"center",'backgroundColor':"#111111"})
#-----------------------------------------------------------------------------------
#Define dash callback function to update plot.
#-----Must be defined here because 'serial_port' var has to be initialized before define
#---------------------------------------------------------------------------------
app = dash.Dash(__name__)
app.layout=app_layout
#------callback function to read data from spi and store it
#---this callback is triggred by the periodic timer    
@app.callback(Output('data_to_transfer',  'data'), #must be named data, otherwise raise error
              Input('timer_graph_update', 'n_intervals')
              )
def function_rx_serial_port(n_intervals):
#print(n_intervals) #n_intervals=amounts of time the callbnack has been called since start
          rx_data=[]#init data buffer
          bytes_rx=serial_port.read(CONST.DATA_RX_SIZE)
          if len(bytes_rx)>=CONST.DATA_RX_SIZE: #Double check: crucial is serial timout=!0 
             floats=struct.unpack(CONST.DATA_RX_FORMAT, bytes_rx) #convert bytes to floats
             if floats[0]==CONST.DATA_RX_HEADER_VALUE:#verified the packet header is the correct
                rx_data=floats
          return(rx_data)      
#------callback function to read data that has been stores and then update the plot 
#-------this callback is triggred each time the 'data_to_transfer': 'data' object
         # is returned (or maybe changed, you fill have to figure it out!)         
@app.callback(Output('graph1', 'figure'),#figure MUST be an output to store the modified version
              Input('data_to_transfer', 'data'), #must be named data, otherwise raise error
              Input('graph1', 'figure') #figure MUST be an input in order to be modified
              )
def function_update_plot(rx_data,figure):
         if len(rx_data)>0:#verified the packet header is the correct
            #verified the packet header->store the variables
            temp_mcu,temp_imu=rx_data[1],rx_data[2]
            ax,ay,az=rx_data[3],rx_data[4],rx_data[5]
            gx,gy,gz=rx_data[6],rx_data[7],rx_data[8]
            mx,my,mz=rx_data[9],rx_data[10],rx_data[11]
            #anglex=0.98*(anglex+gx)+0.02*(ax)
            #angley=0.98*(angley+gy)+0.02*(ay)
            #anglez=0.98*(anglez+gz)+0.02*(az)
            mdirx=math.atan2(mz, my)#/math.pi
            mdiry=math.atan2(mx, mz)#/math.pi
            mdirz=math.atan2(my, mx)#/math.pi
            #print('angle val:',anglex,angley,anglez)
            #print('Mag val:',mx,my,mz)
            print('Mag dir :',mdirx,mdiry,mdirz)
            figure['layout']['title'] ='Temperatura Tortuga: '+str(temp_imu)+' C'+ f'<br><sup> Gravedad terrestre:{az:.3f} m/s<br> </sup>';
            figure['layout']['scene']['camera']['up']=dict(x=mdirx-0.6, y=mdiry, z=mdirz )#esto controla el giro    
         return(figure)                               #near computer (x=my, y=mz, z=-mx ) 
                            #(x=my, y=mx, z=mz )    #dict(x=mz+my, y=mx+mz, z=-mx-my)
                               #x=mx, y=my, z=mz     #dict(x=1.5+my, y=1.5+my, z=0.5+mz)
#--------------------------------------------------------------
# Clean serial port by reading, Open web browser and start dash server
#--------------------------------------------------------------
webbrowser.open_new("http://127.0.0.1:8050/")
print(serial_port.read(CONST.DATA_RX_SIZE*20))#read all it can before time out, allow us to clean the buffer
serial_port.timeout=0; #remove timeout to avoid SYNC issues
app.run_server(debug=False)
#--------------------------------------------------------------
# End of program: this point is reach when dash server is shutted down
#--------------------------------------------------------------
serial_port.close() #we close the opeened serial port top free it for other app
print('End of program: Serial port was closed')

Animal movement classifier using a NN trained with accelerometers

Arduino
This code uses a neural network trained with the real movement of specimens of the species Chelonoidis chilensis in their natural habitat and allows movement to be detected in real time. If it detects movement, it notifies the user via bluetooth.
/* Edge Impulse Arduino examples
 * Copyright (c) 2021 EdgeImpulse Inc.
 *
 * 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.
 */

/* Includes ---------------------------------------------------------------- */
//#include <Segundo_ejercicio_con_Wio_Terminal_inferencing.h>
#include <tortugas_v2_Spectrogram_inferencing.h>


// Esto fue generado para la Nano 33 Ble Sense
// necesitamos modificar esto para usar la Wio

#include"LIS3DHTR.h"
#include"TFT_eSPI.h"
LIS3DHTR<TwoWire> lis;
TFT_eSPI tft;

// tambien incluimos BLE para la Wio
#include <rpcBLEDevice.h>
#include <BLEServer.h>
#include <BLE2902.h>

/* Constant defines BLE -------------------------------------------------------- */
#define accelerometerService "19b10000-e8f2-537e-4f6c-d104768a1214"
#define firstCharacteristic  "19b10010-e8f2-537e-4f6c-d104768a1214"
#define secondCharacteristic "19b10011-e8f2-537e-4f6c-d104768a1214"
#define DESCRIPTOR_UUID      "19b10010"
#define DESCRIPTOR2_UUID     "19b10011"


/* Constant defines -------------------------------------------------------- */
#define CONVERT_G_TO_MS2    9.80665f
#define MAX_ACCEPTED_RANGE  2.0f        // starting 03/2022, models are generated setting range to +-2, but this example use Arudino library which set range to +-4g. If you are using an older model, ignore this value and use 4.0f instead


/*---------------------------------------*/
// variables y funciones usadas para la comunicacion BLE
bool deviceConnected = false;
bool oldDeviceConnected = false;
bool grabandoSD = false;

BLEServer *pServer = NULL;
BLECharacteristic * pCharacteristic;
BLECharacteristic * p2Characteristic;

class MyServerCallbacks: public BLEServerCallbacks {
    void onConnect(BLEServer* pServer) {
      Serial.println("MyServerCallbacks onConnect ");
      deviceConnected = true;
    };

    void onDisconnect(BLEServer* pServer) {
      deviceConnected = false;
    }
};

class MyCallbacks: public BLECharacteristicCallbacks {
    void onWrite(BLECharacteristic *pCharacteristic) {
      std::string rxValue = pCharacteristic->getValue();

      if (rxValue.length() > 0) {
        Serial.println("*********");
        Serial.print("Received Value: ");
        for (int i = 0; i < rxValue.length(); i++)
          Serial.print(rxValue[i]);

        Serial.println();
        Serial.println("*********");

        grabandoSD=!grabandoSD;     

        if(grabandoSD==true) pCharacteristic->setValue("grabando SD");
        else pCharacteristic->setValue("SD detenida");
        pCharacteristic->notify();
      }
    }
};
/*---------------------------------------*/

/*
 ** NOTE: If you run into TFLite arena allocation issue.
 **
 ** This may be due to may dynamic memory fragmentation.
 ** Try defining "-DEI_CLASSIFIER_ALLOCATION_STATIC" in boards.local.txt (create
 ** if it doesn't exist) and copy this file to
 ** `<ARDUINO_CORE_INSTALL_PATH>/arduino/hardware/<mbed_core>/<core_version>/`.
 **
 ** See
 ** (https://support.arduino.cc/hc/en-us/articles/360012076960-Where-are-the-installed-cores-located-)
 ** to find where Arduino installs cores on your machine.
 **
 ** If the problem persists then there's not enough memory for this model and application.
 */

/* Private variables ------------------------------------------------------- */
static bool debug_nn = false; // Set this to true to see e.g. features generated from the raw signal

int estado;
int iter;

/**
* @brief      Arduino setup function
*/
void setup()
{
    // put your setup code here, to run once:
    Serial.begin(115200);
    Serial.println("Edge Impulse Inferencing Demo");

    /* Inicializacion acelerometro */
    lis.begin(Wire1);
 
    if (!lis.available()) {
    Serial.println("Failed to initialize IMU!");
    while (1);
    }
    else {
        ei_printf("IMU initialized\r\n");
    }
    lis.setOutputDataRate(LIS3DHTR_DATARATE_100HZ); // Setting output data rage to 25Hz, can be set up tp 5kHz 
    lis.setFullScaleRange(LIS3DHTR_RANGE_16G); // Setting scale range to 2g, select from 2,4,8,16g

    /* Inicializacion TFT */
    tft.begin();
    tft.setRotation(3);
    tft.fillScreen(TFT_RED);
    tft.setFreeFont(&FreeSansBoldOblique12pt7b);
    tft.drawString("Conectacte a Tortuga Wio", 1, 80);
    tft.drawString("via BT para empezar", 1, 120);
    delay(2000);

    

    /* Inicializacion clasificador */
    if (EI_CLASSIFIER_RAW_SAMPLES_PER_FRAME != 3) {
        ei_printf("ERR: EI_CLASSIFIER_RAW_SAMPLES_PER_FRAME should be equal to 3 (the 3 sensor axes)\n");
        return;
    }

    /* Inicializacion BLE */
    Serial.println("Poniendo a funcionar BLE!");
  
    BLEDevice::init("Tortuga Wio 2");
    pServer = BLEDevice::createServer();
    pServer->setCallbacks(new MyServerCallbacks());
    
    BLEService *pService = pServer->createService(accelerometerService);

    pCharacteristic = pService->createCharacteristic(
                                           firstCharacteristic,
                                           BLECharacteristic::PROPERTY_READ |
                                           BLECharacteristic::PROPERTY_WRITE
                                         );
    pCharacteristic->setAccessPermissions(GATT_PERM_READ | GATT_PERM_WRITE);
    BLEDescriptor *pDescriptor = pCharacteristic->createDescriptor(
                                           DESCRIPTOR_UUID,
                                            ATTRIB_FLAG_VOID | ATTRIB_FLAG_ASCII_Z,
                                           GATT_PERM_READ | GATT_PERM_WRITE,
                                           2
                                           );
    pCharacteristic->setCallbacks(new MyCallbacks());
    pCharacteristic->setValue("SD detenida");

    p2Characteristic = pService->createCharacteristic(
                                           secondCharacteristic,
                                           BLECharacteristic::PROPERTY_READ |
                                           BLECharacteristic::PROPERTY_NOTIFY
                                           );
    p2Characteristic->setAccessPermissions(GATT_PERM_READ);

    // Con esto on andaban bien las notificaciones del prCharacteristisc
    /*BLEDescriptor *p2Descriptor = p2Characteristic->createDescriptor(
                                           DESCRIPTOR2_UUID,
                                           ATTRIB_FLAG_VOID | ATTRIB_FLAG_ASCII_Z,
                                           GATT_PERM_READ,
                                           2
                                           );
    */
    //pero con esto magicamente empezaron a andar...
    p2Characteristic->addDescriptor(new BLE2902());
 
    pService->start();
  
    BLEAdvertising *pAdvertising = BLEDevice::getAdvertising();
    pAdvertising->addServiceUUID(accelerometerService);
    pAdvertising->setScanResponse(true);
    pAdvertising->setMinPreferred(0x06);  // functions that help with iPhone connections issue
    pAdvertising->setMinPreferred(0x12);
    BLEDevice::startAdvertising();
    Serial.println("Characteristic defined! Now you can read it in your phone!");

    while(!deviceConnected) {
        delay(500); // give the bluetooth stack the chance to get things ready
        pServer->startAdvertising(); // restart advertising
        Serial.println("start advertising");
        oldDeviceConnected = deviceConnected;
    }
    estado=0;
    iter=0;
}

/**
 * @brief Return the sign of the number
 * 
 * @param number 
 * @return int 1 if positive (or 0) -1 if negative
 */
float ei_get_sign(float number) {
    return (number >= 0.0) ? 1.0 : -1.0;
}

/**
* @brief      Get data and run inferencing
*
* @param[in]  debug  Get debug info if true
*/

void loop()
{
    int viejoestado=estado;
    
    ei_printf("\nStarting inferencing in 2 seconds...\n");

    delay(2000);

    ei_printf("Sampling...\n");

    // Allocate a buffer here for the values we'll read from the IMU
    float buffer[EI_CLASSIFIER_DSP_INPUT_FRAME_SIZE] = { 0 };

    for (size_t ix = 0; ix < EI_CLASSIFIER_DSP_INPUT_FRAME_SIZE; ix += 3) {
        // Determine the next tick (and then sleep later)
        uint64_t next_tick = micros() + (EI_CLASSIFIER_INTERVAL_MS * 1000);

        // cambiamos esto
        // IMU.readAcceleration(buffer[ix], buffer[ix + 1], buffer[ix + 2]);
        // por esto:
        lis.getAcceleration(&buffer[ix], &buffer[ix + 1], &buffer[ix + 2]);

        for (int i = 0; i < 3; i++) {
            if (fabs(buffer[ix + i]) > MAX_ACCEPTED_RANGE) {
                buffer[ix + i] = ei_get_sign(buffer[ix + i]) * MAX_ACCEPTED_RANGE;
            }
        }

        buffer[ix + 0] *= CONVERT_G_TO_MS2*1.2;
        buffer[ix + 1] *= CONVERT_G_TO_MS2*1.2;
        buffer[ix + 2] *= CONVERT_G_TO_MS2*1.2;

        delayMicroseconds(next_tick - micros());
    }

    // Turn the raw buffer in a signal which we can the classify
    signal_t signal;
    int err = numpy::signal_from_buffer(buffer, EI_CLASSIFIER_DSP_INPUT_FRAME_SIZE, &signal);
    if (err != 0) {
        ei_printf("Failed to create signal from buffer (%d)\n", err);
        return;
    }

    // Run the classifier
    ei_impulse_result_t result = { 0 };

    err = run_classifier(&signal, &result, debug_nn);
    if (err != EI_IMPULSE_OK) {
        ei_printf("ERR: Failed to run classifier (%d)\n", err);
        return;
    }

    // print the predictions
    ei_printf("Predictions ");
    ei_printf("(DSP: %d ms., Classification: %d ms., Anomaly: %d ms.)",
        result.timing.dsp, result.timing.classification, result.timing.anomaly);
    ei_printf(": \n");
    for (size_t ix = 0; ix < EI_CLASSIFIER_LABEL_COUNT; ix++) {
        ei_printf("    %s: %.5f\n", result.classification[ix].label, result.classification[ix].value);
    }
#if EI_CLASSIFIER_HAS_ANOMALY == 1
    ei_printf("    anomaly score: %.3f\n", result.anomaly);
#endif

   // todo este bloque es para usar la TFT
   if (result.classification[0].value < result.classification[1].value) {
    tft.fillScreen(TFT_GREEN);
    tft.setFreeFont(&FreeSansBoldOblique12pt7b);
    tft.drawString("Activa", 20, 80);
    delay(2000);
    //tft.fillScreen(TFT_WHITE);
    tft.drawString("Clasificando...", 20, 80);
    estado=0;

    if(grabandoSD==true) tft.drawString("SD grabando", 20, 120);   
    else tft.drawString("SD detenida", 20, 120);   
   }
   else {
    tft.fillScreen(TFT_BLACK);
    tft.setFreeFont(&FreeSansBoldOblique12pt7b);
    tft.drawString("Inactiva", 20, 80);
    delay(2000);
    //tft.fillScreen(TFT_WHITE);
    tft.drawString("Clasificando...", 20, 80);
    estado=1;

    if(grabandoSD==true) tft.drawString("SD grabando", 20, 120);   
    else tft.drawString("SD detenida", 20, 120);   
   }
   
   // para que no se congestione el BLE solo informamos cambios de estados...
   if(viejoestado!=estado && deviceConnected){
      String accelerometerData; 
      if(estado==1) accelerometerData="INACTIVA";
      if(estado==0) accelerometerData="ACTIVA";
      Serial.println(accelerometerData);
      String value=accelerometerData;
      p2Characteristic->setValue(value.c_str());
      p2Characteristic->notify();

      delay(200);      
   }
   iter++;
}

#if !defined(EI_CLASSIFIER_SENSOR) || EI_CLASSIFIER_SENSOR != EI_CLASSIFIER_SENSOR_ACCELEROMETER
#error "Invalid model for current sensor"
#endif

Example of code for receiving IMU data

C/C++
Waits for the reception of the packet
If a reception occurs and the header is ok, proceeds to send this packet using UART. The data is then sent with a 4 byte header to avoid synchronization issues on the computer side.
Returns to the beginning of the loop
/*
 * Copyright (c) 2017-2018, Texas Instruments Incorporated
 * All rights reserved.
 *
 * 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 Texas Instruments Incorporated nor the names of
 *    its 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 THE COPYRIGHT OWNER 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.
 */

/*
 *  ======== rfEasyLinkEchoRx.c ========
 */
/* Standard C Libraries */
#include <stdlib.h>

/* XDCtools Header files */
#include <xdc/std.h>
#include <xdc/runtime/Assert.h>
#include <xdc/runtime/Error.h>
#include <xdc/runtime/System.h>

/* BIOS Header files */
#include <ti/sysbios/BIOS.h>
#include <ti/sysbios/knl/Task.h>
#include <ti/sysbios/knl/Semaphore.h>
#include <ti/sysbios/knl/Clock.h>

/* TI-RTOS Header files */
#include <ti/drivers/GPIO.h>
#include <ti/drivers/UART2.h>
/* Board Header files */
#include "ti_drivers_config.h"

/* Application Header files */
#include <ti_radio_config.h>

/* EasyLink API Header files */
#include "easylink/EasyLink.h"

/* Undefine to not use async mode */
#define RFEASYLINKECHO_ASYNC

#define RFEASYLINKECHO_TASK_STACK_SIZE    4046
#define RFEASYLINKECHO_TASK_PRIORITY      2

#define RFEASYLINKECHO_PAYLOAD_LENGTH     52

Task_Struct echoTask;    /* not static so you can see in ROV */
static Task_Params echoTaskParams;
static uint8_t echoTaskStack[RFEASYLINKECHO_TASK_STACK_SIZE];

#ifdef RFEASYLINKECHO_ASYNC
static Semaphore_Handle echoDoneSem;
#endif //RFEASYLINKECHO_ASYNC

static bool bBlockTransmit = false;
static UART2_Handle uart;
EasyLink_TxPacket txPacket = {{0}, 0, 0, {0}};
#define UART_MESSAGE_SIZE RFEASYLINKECHO_PAYLOAD_LENGTH+4
char message_to_uart[UART_MESSAGE_SIZE];//CHECKED: SAME IF ITS CHAR OR ARRAY
#ifdef RFEASYLINKECHO_ASYNC

void echoRxDoneCb(EasyLink_RxPacket * rxPacket, EasyLink_Status status)
{
    if (status == EasyLink_Status_Success)
    {
        /* Toggle RLED to indicate RX, clear GLED */
        GPIO_toggle(CONFIG_GPIO_RLED);
        GPIO_write(CONFIG_GPIO_GLED, CONFIG_GPIO_LED_OFF);
        /* Copy contents of RX packet to TX packet */
        //4 bytes to identify the first part of the package
        message_to_uart[0]=0x80;message_to_uart[1]=0x20;message_to_uart[2]=0x08;message_to_uart[3]=0x02;
        memcpy(&(message_to_uart[4]), rxPacket->payload,RFEASYLINKECHO_PAYLOAD_LENGTH);
        //UART2_write(uart, (rxPacket->payload), RFEASYLINKECHO_PAYLOAD_LENGTH, NULL);

        // UART2_write(uart, "\r\n rx:\r\n", 5, NULL);
        //copy the payload to UART
        /* Permit echo transmission */
        bBlockTransmit = false;
    }
    else
    {
        /* Set GLED and clear RLED to indicate error */
        GPIO_write(CONFIG_GPIO_GLED, CONFIG_GPIO_LED_ON);
        GPIO_write(CONFIG_GPIO_RLED, CONFIG_GPIO_LED_OFF);
        /* Block echo transmission */
        bBlockTransmit = true;
    }
    Semaphore_post(echoDoneSem);
}
#endif //RFEASYLINKECHO_ASYNC

static void rfEasyLinkEchoRxFnx(UArg arg0, UArg arg1)
{
    uint32_t absTime;
	  UART2_Params uartParams;
    /* Create a UART in CALLBACK read mode */
       UART2_Params_init(&uartParams);
       uartParams.writeMode     = UART2_Mode_BLOCKING;
       uartParams.baudRate     = 115200;
       uart = UART2_open(CONFIG_UART2_0, &uartParams);
       //
       if (uart == NULL)
       {while (1) {}} //OPEN FAILED
      UART2_write(uart, "\r\n Start task:\r\n", 10, NULL);
#ifdef RFEASYLINKECHO_ASYNC
    /* Create a semaphore for Async */
    Semaphore_Params params;
    Error_Block      eb;

    /* Init params */
    Semaphore_Params_init(&params);
    Error_init(&eb);

    /* Create semaphore instance */
    echoDoneSem = Semaphore_create(0, &params, &eb);
    if(echoDoneSem == NULL)
    {
        System_abort("Semaphore creation failed");
    }

#else
    EasyLink_RxPacket rxPacket = {{0}, 0, 0, 0, 0, {0}};
#endif //RFEASYLINKECHO_ASYNC

    // Initialize the EasyLink parameters to their default values
    EasyLink_Params easyLink_params;
    EasyLink_Params_init(&easyLink_params);

    /*
     * Initialize EasyLink with the settings found in ti_easylink_config.h
     * Modify EASYLINK_PARAM_CONFIG in ti_easylink_config.h to change the default
     * PHY
     */
    if(EasyLink_init(&easyLink_params) != EasyLink_Status_Success)
    {
        System_abort("EasyLink_init failed");
    }

    while(1) {
        // Wait to receive a packet
        //UART2_write(uart, "\r\n Wait to ress:\r\n", 15, NULL);
        EasyLink_receiveAsync(echoRxDoneCb, 0);
        //GPIO_write(CONFIG_GPIO_GLED, CONFIG_GPIO_LED_ON);
        /* Wait indefinitely for Rx */
        Semaphore_pend(echoDoneSem, BIOS_WAIT_FOREVER);
        UART2_write(uart, (message_to_uart), UART_MESSAGE_SIZE, NULL);

}
}

void echoTask_init() {

    Task_Params_init(&echoTaskParams);
    echoTaskParams.stackSize = RFEASYLINKECHO_TASK_STACK_SIZE;
    echoTaskParams.priority = RFEASYLINKECHO_TASK_PRIORITY;
    echoTaskParams.stack = &echoTaskStack;
    echoTaskParams.arg0 = (UInt)1000000;

    Task_construct(&echoTask, rfEasyLinkEchoRxFnx, &echoTaskParams, NULL);
}

/*
 *  ======== main ========
 */
int main(void)
{
	  UART2_Params uartParams;
    /* Call driver init functions. */
    Board_initGeneral();
    GPIO_init();

    GPIO_setConfig(CONFIG_GPIO_RLED, GPIO_CFG_OUT_STD | GPIO_CFG_OUT_LOW);
    GPIO_setConfig(CONFIG_GPIO_GLED, GPIO_CFG_OUT_STD | GPIO_CFG_OUT_LOW);

    GPIO_write(CONFIG_GPIO_RLED, CONFIG_GPIO_LED_OFF);
    GPIO_write(CONFIG_GPIO_GLED, CONFIG_GPIO_LED_OFF);

      echoTask_init();
    /* Start BIOS */
    BIOS_start();

    return (0);
}

Credits

Laila Kazimierski

Laila Kazimierski

1 project • 3 followers
Alejandro Kolton

Alejandro Kolton

0 projects • 1 follower
Argentinian physicist doing basic research and teaching. I started with HDW as a hobby but now I am part of a team on animal tracking.
Erika Kubisch

Erika Kubisch

0 projects • 0 followers
Karina Laneri

Karina Laneri

0 projects • 0 followers
Maru Echave

Maru Echave

0 projects • 0 followers
Im a biologist, I work with tortoises
Nicolas Catalano

Nicolas Catalano

0 projects • 0 followers
david fernando cordova mora

david fernando cordova mora

0 projects • 0 followers
Guillermo Abramson

Guillermo Abramson

0 projects • 0 followers
PhD in Physics. I work in the mathematical study of ecological systems. 100+ papers and books, supervised theses and managed projects.
Andres Oliva Trevisan

Andres Oliva Trevisan

0 projects • 0 followers
Electronic Engineer developing an ultra low power system for animal monitoring and tracking.

Comments