This commit is contained in:
Oliver Brandmueller 2019-01-04 10:40:12 +01:00
commit d9404b1a32
151 changed files with 23141 additions and 23013 deletions

View File

@ -47,7 +47,7 @@ Depending on board hardware following features are supported:
- Silicon unique ID
- Battery voltage monitoring
- GPS (Generic serial NMEA, or Quectel L76 I2C)
- MEMS sensor (Bosch BME680)
- Environmental sensor (Bosch BME680 I2C)
Target platform must be selected in [platformio.ini](https://github.com/cyberman54/ESP32-Paxcounter/blob/master/platformio.ini).<br>
Hardware dependent settings (pinout etc.) are stored in board files in /hal directory. If you want to use a ESP32 board which is not yet supported, use hal file generic.h and tailor pin mappings to your needs. Pull requests for new boards welcome.<br>
@ -151,7 +151,6 @@ Hereafter described is the default *plain* format, which uses MSB bit numbering.
byte 1-2: Number of unique pax, first seen on Wifi
byte 3-4: Number of unique pax, first seen on Bluetooth [0 if BT disabled]
bytes 5-18: GPS data, format see Port #4 (appended only, if GPS is present and has a fix)
**Port #2:** Device status query result
@ -177,12 +176,12 @@ Hereafter described is the default *plain* format, which uses MSB bit numbering.
byte 13: Wifi antenna switch (0=internal, 1=external) [default 0]
byte 14: Vendorfilter mode (0=disabled, 1=enabled) [default 0]
byte 15: RGB LED luminosity (0..100 %) [default 30]
byte 16: GPS send data mode (1=on, 0=ff) [default 1]
byte 16: Payload filter mask
byte 17: Beacon proximity alarm mode (1=on, 0=off) [default 0]
bytes 18-28: Software version (ASCII format, terminating with zero)
**Port #4:** GPS query result
**Port #4:** GPS data (only if device has fature GPS, and GPS data is enabled and GPS has a fix)
bytes 1-4: Latitude
bytes 5-8: Longitude
@ -199,12 +198,24 @@ Hereafter described is the default *plain* format, which uses MSB bit numbering.
byte 1: Beacon RSSI reception level
byte 2: Beacon identifier (0..255)
**Port #7:** BME680 query result
**Port #7:** Environmental sensor data (only if device has feature BME)
bytes 1-2: Temperature [°C]
bytes 3-4: Pressure [hPa]
bytes 5-6: Humidity [%]
bytes 7-8: Gas resistance [kOhm]
bytes 7-8: Indoor air quality index (0..500), see below
Indoor air quality classification:
0-50 good
51-100 average
101-150 little bad
151-200 bad
201-300 worse
301-500 very bad
**Port #8:** Battery voltage data (only if device has feature BATT)
byte 1-2: Battery or USB Voltage [mV], 0 if no battery probe
# Remote control
@ -306,6 +317,11 @@ Note: all settings are stored in NVRAM and will be reloaded when device starts.
byte 1 = beacon ID (0..255)
bytes 2..7 = beacon MAC with 6 digits (e.g. MAC 80:ab:00:01:02:03 -> 0x80ab00010203)
0x13 set user sensor mode
byte 1 = user sensor number (1..3)
byte 2 = sensor mode (0 = disabled / 1 = enabled [default])
0x80 get device configuration
Device answers with it's current configuration on Port 3.

31
include/bme680mems.h Normal file
View File

@ -0,0 +1,31 @@
#ifndef _BME680MEMS_H
#define _BME680MEMS_H
#include "globals.h"
#include <Wire.h>
#include "bsec_integration.h"
extern const uint8_t bsec_config_iaq[454];
extern bmeStatus_t
bme_status; // Make struct for storing gps data globally available
extern TaskHandle_t BmeTask;
int bme_init();
void bme_loop(void *pvParameters);
int8_t i2c_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data,
uint16_t len);
int8_t i2c_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data,
uint16_t len);
void output_ready(int64_t timestamp, float iaq, uint8_t iaq_accuracy,
float temperature, float humidity, float pressure,
float raw_temperature, float raw_humidity, float gas,
bsec_library_return_t bsec_status, float static_iaq,
float co2_equivalent, float breath_voc_equivalent);
uint32_t state_load(uint8_t *state_buffer, uint32_t n_buffer);
void state_save(const uint8_t *state_buffer, uint32_t length);
uint32_t config_load(uint8_t *config_buffer, uint32_t n_buffer);
void user_delay_ms(uint32_t period);
int64_t get_timestamp_us();
#endif

View File

@ -1,15 +0,0 @@
#ifndef _HAS_BME
#define _HAS_BME
#include "globals.h"
#include <Wire.h>
#include <Adafruit_Sensor.h>
#include "Adafruit_BME680.h"
extern bmeStatus_t
bme_status; // Make struct for storing gps data globally available
void bme_init();
bool bme_read();
#endif

View File

@ -9,6 +9,26 @@
#include <array>
#include <algorithm>
// bits in payloadmask for filtering payload data
#define GPS_DATA (0x01)
#define ALARM_DATA (0x02)
#define MEMS_DATA (0x04)
#define COUNT_DATA (0x08)
#define SENSOR1_DATA (0x10)
#define SENSOR2_DATA (0x20)
#define SENSOR3_DATA (0x40)
#define BATT_DATA (0x80)
// bits in configmask for device runmode control
#define GPS_MODE (0x01)
#define ALARM_MODE (0x02)
#define BEACON_MODE (0x04)
#define UPDATE_MODE (0x08)
#define FILTER_MODE (0x10)
#define ANTENNA_MODE (0x20)
#define BLE_MODE (0x40)
#define SCREEN_MODE (0x80)
// Struct holding devices's runtime configuration
typedef struct {
uint8_t lorasf; // 7-12, lora spreadfactor
@ -25,9 +45,9 @@ typedef struct {
uint8_t wifiant; // 0=internal, 1=external (for LoPy/LoPy4)
uint8_t vendorfilter; // 0=disabled, 1=enabled
uint8_t rgblum; // RGB Led luminosity (0..100%)
uint8_t gpsmode; // 0=disabled, 1=enabled
uint8_t monitormode; // 0=disabled, 1=enabled
uint8_t runmode; // 0=normal, 1=update
uint8_t payloadmask; // bitswitches for payload data
char version[10]; // Firmware version
} configData_t;
@ -47,10 +67,14 @@ typedef struct {
} gpsStatus_t;
typedef struct {
float temperature; // Temperature in degrees Centigrade
uint16_t pressure; // Barometic pressure in hecto pascals
float humidity; // Relative humidity in percent
uint16_t gas_resistance; // Resistance in MOhms
float iaq; // IAQ signal
uint8_t iaq_accuracy; // accuracy of IAQ signal
float temperature; // temperature signal
float humidity; // humidity signal
float pressure; // pressure signal
float raw_temperature; // raw temperature signal
float raw_humidity; // raw humidity signal
float gas; // raw gas sensor signal
} bmeStatus_t;
// global variables
@ -75,7 +99,7 @@ extern TaskHandle_t irqHandlerTask, wifiSwitchTask;
#endif
#ifdef HAS_BME
#include "bme680read.h"
#include "bme680mems.h"
#endif
#ifdef HAS_LORA
@ -102,4 +126,8 @@ extern TaskHandle_t irqHandlerTask, wifiSwitchTask;
#include "antenna.h"
#endif
#ifdef HAS_SENSORS
#include "sensor.h"
#endif
#endif

View File

@ -13,6 +13,7 @@ extern gpsStatus_t
gps_status; // Make struct for storing gps data globally available
extern TaskHandle_t GpsTask;
int gps_init(void);
void gps_read(void);
void gps_loop(void *pvParameters);

View File

@ -3,10 +3,13 @@
#include "globals.h"
#include "rcommand.h"
#include <TimeLib.h>
// LMIC-Arduino LoRaWAN Stack
#include <lmic.h>
#include <hal/hal.h>
#include <SPI.h>
#include <arduino_lmic_hal_boards.h>
#include "loraconf.h"
// Needed for 24AA02E64, does not hurt anything if included and not used

View File

@ -5,7 +5,8 @@
#include "globals.h"
#include "battery.h"
#include "update.h"
//#include "update.h"
#include <Update.h>
#include <WiFi.h>
#include <WiFiClientSecure.h>
#include <BintrayClient.h>

View File

@ -15,7 +15,7 @@
#define LPP_MSG_CHANNEL 28
#define LPP_HUMIDITY_CHANNEL 29
#define LPP_BAROMETER_CHANNEL 30
#define LPP_GAS_CHANNEL 31
#define LPP_AIR_CHANNEL 31
#endif
@ -44,9 +44,11 @@ public:
void addStatus(uint16_t voltage, uint64_t uptime, float cputemp, uint32_t mem,
uint8_t reset1, uint8_t reset2);
void addAlarm(int8_t rssi, uint8_t message);
void addVoltage(uint16_t value);
void addGPS(gpsStatus_t value);
void addBME(bmeStatus_t value);
void addButton(uint8_t value);
void addSensor(uint8_t[]);
#if PAYLOAD_ENCODER == 1 // format plain
@ -65,8 +67,9 @@ private:
void writeUint32(uint32_t i);
void writeUint16(uint16_t i);
void writeUint8(uint8_t i);
void writeHumidity(float humidity);
void writeTemperature(float temperature);
void writeFloat(float value);
void writeUFloat(float value);
void writePressure(float value);
void writeVersion(char * version);
void writeBitmap(bool a, bool b, bool c, bool d, bool e, bool f, bool g,
bool h);

8
include/sensor.h Normal file
View File

@ -0,0 +1,8 @@
#ifndef _SENSOR_H
#define _SENSOR_H
uint8_t sensor_mask(uint8_t sensor_no);
uint8_t * sensor_read(uint8_t sensor);
void sensor_init(void);
#endif

View File

@ -1,184 +0,0 @@
#ifndef ESP8266UPDATER_H
#define ESP8266UPDATER_H
#include <Arduino.h>
#include <MD5Builder.h>
#include <functional>
#include "esp_partition.h"
#define UPDATE_ERROR_OK (0)
#define UPDATE_ERROR_WRITE (1)
#define UPDATE_ERROR_ERASE (2)
#define UPDATE_ERROR_READ (3)
#define UPDATE_ERROR_SPACE (4)
#define UPDATE_ERROR_SIZE (5)
#define UPDATE_ERROR_STREAM (6)
#define UPDATE_ERROR_MD5 (7)
#define UPDATE_ERROR_MAGIC_BYTE (8)
#define UPDATE_ERROR_ACTIVATE (9)
#define UPDATE_ERROR_NO_PARTITION (10)
#define UPDATE_ERROR_BAD_ARGUMENT (11)
#define UPDATE_ERROR_ABORT (12)
#define UPDATE_SIZE_UNKNOWN 0xFFFFFFFF
#define U_FLASH 0
#define U_SPIFFS 100
#define U_AUTH 200
class UpdateClass {
public:
typedef std::function<void(size_t, size_t)> THandlerFunction_Progress;
UpdateClass();
/*
This callback will be called when Update is receiving data
*/
UpdateClass& onProgress(THandlerFunction_Progress fn);
/*
Call this to check the space needed for the update
Will return false if there is not enough space
*/
bool begin(size_t size=UPDATE_SIZE_UNKNOWN, int command = U_FLASH, int ledPin = -1, uint8_t ledOn = LOW);
/*
Writes a buffer to the flash and increments the address
Returns the amount written
*/
size_t write(uint8_t *data, size_t len);
/*
Writes the remaining bytes from the Stream to the flash
Uses readBytes() and sets UPDATE_ERROR_STREAM on timeout
Returns the bytes written
Should be equal to the remaining bytes when called
Usable for slow streams like Serial
*/
size_t writeStream(Stream &data);
/*
If all bytes are written
this call will write the config to eboot
and return true
If there is already an update running but is not finished and !evenIfRemainanig
or there is an error
this will clear everything and return false
the last error is available through getError()
evenIfRemaining is helpfull when you update without knowing the final size first
*/
bool end(bool evenIfRemaining = false);
/*
Aborts the running update
*/
void abort();
/*
Prints the last error to an output stream
*/
void printError(Stream &out);
/*
sets the expected MD5 for the firmware (hexString)
*/
bool setMD5(const char * expected_md5);
/*
returns the MD5 String of the sucessfully ended firmware
*/
String md5String(void){ return _md5.toString(); }
/*
populated the result with the md5 bytes of the sucessfully ended firmware
*/
void md5(uint8_t * result){ return _md5.getBytes(result); }
//Helpers
uint8_t getError(){ return _error; }
void clearError(){ _error = UPDATE_ERROR_OK; }
bool hasError(){ return _error != UPDATE_ERROR_OK; }
bool isRunning(){ return _size > 0; }
bool isFinished(){ return _progress == _size; }
size_t size(){ return _size; }
size_t progress(){ return _progress; }
size_t remaining(){ return _size - _progress; }
/*
Template to write from objects that expose
available() and read(uint8_t*, size_t) methods
faster than the writeStream method
writes only what is available
*/
template<typename T>
size_t write(T &data){
size_t written = 0;
if (hasError() || !isRunning())
return 0;
size_t available = data.available();
while(available) {
if(_bufferLen + available > remaining()){
available = remaining() - _bufferLen;
}
if(_bufferLen + available > 4096) {
size_t toBuff = 4096 - _bufferLen;
data.read(_buffer + _bufferLen, toBuff);
_bufferLen += toBuff;
if(!_writeBuffer())
return written;
written += toBuff;
} else {
data.read(_buffer + _bufferLen, available);
_bufferLen += available;
written += available;
if(_bufferLen == remaining()) {
if(!_writeBuffer()) {
return written;
}
}
}
if(remaining() == 0)
return written;
available = data.available();
}
return written;
}
/*
check if there is a firmware on the other OTA partition that you can bootinto
*/
bool canRollBack();
/*
set the other OTA partition as bootable (reboot to enable)
*/
bool rollBack();
private:
void _reset();
void _abort(uint8_t err);
bool _writeBuffer();
bool _verifyHeader(uint8_t data);
bool _verifyEnd();
uint8_t _error;
uint8_t *_buffer;
size_t _bufferLen;
size_t _size;
THandlerFunction_Progress _progress_callback;
uint32_t _progress;
uint32_t _command;
const esp_partition_t* _partition;
String _target_md5;
MD5Builder _md5;
int _ledPin;
uint8_t _ledOn;
};
extern UpdateClass Update;
#endif

View File

@ -10,21 +10,6 @@
#define MAC_SNIFF_WIFI 0
#define MAC_SNIFF_BLE 1
typedef struct {
unsigned frame_ctrl : 16;
unsigned duration_id : 16;
uint8_t addr1[6]; /* receiver address */
uint8_t addr2[6]; /* sender address */
uint8_t addr3[6]; /* filtering address */
unsigned sequence_ctrl : 16;
uint8_t addr4[6]; /* optional */
} wifi_ieee80211_mac_hdr_t;
typedef struct {
wifi_ieee80211_mac_hdr_t hdr;
uint8_t payload[0]; /* network data ended with 4 bytes csum (CRC32) */
} wifi_ieee80211_packet_t;
void wifi_sniffer_init(void);
void IRAM_ATTR wifi_sniffer_packet_handler(void *buff, wifi_promiscuous_pkt_type_t type);
void switchWifiChannel(void * parameter);

39
lib/Bosch-BSEC/LICENSE Normal file
View File

@ -0,0 +1,39 @@
Copyright (C) 2017 - 2018 Bosch Sensortec GmbH
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
Neither the name of the copyright holder nor the names of the
contributors may be used to endorse or promote products derived from
this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER
OR CONTRIBUTORS BE LIABLE FOR ANY
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY,
OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO,
PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE
The information provided is believed to be accurate and reliable.
The copyright holder assumes no responsibility
for the consequences of use
of such information nor for any infringement of patents or
other rights of third parties which may result from its use.
No license is granted by implication or otherwise under any patent or
patent rights of the copyright holder.

282
lib/Bosch-BSEC/README.md Normal file
View File

@ -0,0 +1,282 @@
# BME680 sensor API
## Introduction
This package contains the Bosch Sensortec's BME680 gas sensor API
The sensor driver package includes bme680.h, bme680.c and bme680_defs.h files
## Version
File | Version | Date
--------------|---------|-------------
bme680.c | 3.5.9 | 19 Jun 2018
bme680.h | 3.5.9 | 19 Jun 2018
bme680_defs.h | 3.5.9 | 19 Jun 2018
## Integration details
* Integrate bme680.h, bme680_defs.h and bme680.c file in to your project.
* Include the bme680.h file in your code like below.
``` c
#include "bme680.h"
```
## File information
* bme680_defs.h : This header file has the constants, macros and datatype declarations.
* bme680.h : This header file contains the declarations of the sensor driver APIs.
* bme680.c : This source file contains the definitions of the sensor driver APIs.
## Supported sensor interfaces
* SPI 4-wire
* I2C
## Usage guide
### Initializing the sensor
To initialize the sensor, you will first need to create a device structure. You
can do this by creating an instance of the structure bme680_dev. Then go on to
fill in the various parameters as shown below
#### Example for SPI 4-Wire
``` c
struct bme680_dev gas_sensor;
/* You may assign a chip select identifier to be handled later */
gas_sensor.dev_id = 0;
gas_sensor.intf = BME680_SPI_INTF;
gas_sensor.read = user_spi_read;
gas_sensor.write = user_spi_write;
gas_sensor.delay_ms = user_delay_ms;
/* amb_temp can be set to 25 prior to configuring the gas sensor
* or by performing a few temperature readings without operating the gas sensor.
*/
gas_sensor.amb_temp = 25;
int8_t rslt = BME680_OK;
rslt = bme680_init(&gas_sensor);
```
#### Example for I2C
``` c
struct bme680_dev gas_sensor;
gas_sensor.dev_id = BME680_I2C_ADDR_PRIMARY;
gas_sensor.intf = BME680_I2C_INTF;
gas_sensor.read = i2c_read;
gas_sensor.write = i2c_write;
gas_sensor.delay_ms = user_delay_ms;
/* amb_temp can be set to 25 prior to configuring the gas sensor
* or by performing a few temperature readings without operating the gas sensor.
*/
gas_sensor.amb_temp = 25;
int8_t rslt = BME680_OK;
rslt = bme680_init(&gas_sensor);
```
Regarding compensation functions for temperature, pressure, humidity and gas we have two implementations.
- Integer version
- floating point version
By default, Integer version is used in the API
If the user needs the floating point version, the user has to un-comment BME680_FLOAT_POINT_COMPENSATION macro
in bme680_defs.h file or to add it in the compiler flags.
### Configuring the sensor
#### Example for configuring the sensor in forced mode
``` c
uint8_t set_required_settings;
/* Set the temperature, pressure and humidity settings */
gas_sensor.tph_sett.os_hum = BME680_OS_2X;
gas_sensor.tph_sett.os_pres = BME680_OS_4X;
gas_sensor.tph_sett.os_temp = BME680_OS_8X;
gas_sensor.tph_sett.filter = BME680_FILTER_SIZE_3;
/* Set the remaining gas sensor settings and link the heating profile */
gas_sensor.gas_sett.run_gas = BME680_ENABLE_GAS_MEAS;
/* Create a ramp heat waveform in 3 steps */
gas_sensor.gas_sett.heatr_temp = 320; /* degree Celsius */
gas_sensor.gas_sett.heatr_dur = 150; /* milliseconds */
/* Select the power mode */
/* Must be set before writing the sensor configuration */
gas_sensor.power_mode = BME680_FORCED_MODE;
/* Set the required sensor settings needed */
set_required_settings = BME680_OST_SEL | BME680_OSP_SEL | BME680_OSH_SEL | BME680_FILTER_SEL
| BME680_GAS_SENSOR_SEL;
/* Set the desired sensor configuration */
rslt = bme680_set_sensor_settings(set_required_settings,&gas_sensor);
/* Set the power mode */
rslt = bme680_set_sensor_mode(&gas_sensor);
```
### Reading sensor data
#### Example for reading all sensor data
``` c
/* Get the total measurement duration so as to sleep or wait till the
* measurement is complete */
uint16_t meas_period;
bme680_get_profile_dur(&meas_period, &gas_sensor);
struct bme680_field_data data;
while(1)
{
user_delay_ms(meas_period); /* Delay till the measurement is ready */
rslt = bme680_get_sensor_data(&data, &gas_sensor);
printf("T: %.2f degC, P: %.2f hPa, H %.2f %%rH ", data.temperature / 100.0f,
data.pressure / 100.0f, data.humidity / 1000.0f );
/* Avoid using measurements from an unstable heating setup */
if(data.status & BME680_GASM_VALID_MSK)
printf(", G: %d ohms", data.gas_resistance);
printf("\r\n");
/* Trigger the next measurement if you would like to read data out continuously */
if (gas_sensor.power_mode == BME680_FORCED_MODE) {
rslt = bme680_set_sensor_mode(&gas_sensor);
}
}
```
### Templates for function pointers
``` c
void user_delay_ms(uint32_t period)
{
/*
* Return control or wait,
* for a period amount of milliseconds
*/
}
int8_t user_spi_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len)
{
int8_t rslt = 0; /* Return 0 for Success, non-zero for failure */
/*
* The parameter dev_id can be used as a variable to select which Chip Select pin has
* to be set low to activate the relevant device on the SPI bus
*/
/*
* Data on the bus should be like
* |----------------+---------------------+-------------|
* | MOSI | MISO | Chip Select |
* |----------------+---------------------|-------------|
* | (don't care) | (don't care) | HIGH |
* | (reg_addr) | (don't care) | LOW |
* | (don't care) | (reg_data[0]) | LOW |
* | (....) | (....) | LOW |
* | (don't care) | (reg_data[len - 1]) | LOW |
* | (don't care) | (don't care) | HIGH |
* |----------------+---------------------|-------------|
*/
return rslt;
}
int8_t user_spi_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len)
{
int8_t rslt = 0; /* Return 0 for Success, non-zero for failure */
/*
* The parameter dev_id can be used as a variable to select which Chip Select pin has
* to be set low to activate the relevant device on the SPI bus
*/
/*
* Data on the bus should be like
* |---------------------+--------------+-------------|
* | MOSI | MISO | Chip Select |
* |---------------------+--------------|-------------|
* | (don't care) | (don't care) | HIGH |
* | (reg_addr) | (don't care) | LOW |
* | (reg_data[0]) | (don't care) | LOW |
* | (....) | (....) | LOW |
* | (reg_data[len - 1]) | (don't care) | LOW |
* | (don't care) | (don't care) | HIGH |
* |---------------------+--------------|-------------|
*/
return rslt;
}
int8_t i2c_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len)
{
int8_t rslt = 0; /* Return 0 for Success, non-zero for failure */
/*
* The parameter dev_id can be used as a variable to store the I2C address of the device
*/
/*
* Data on the bus should be like
* |------------+---------------------|
* | I2C action | Data |
* |------------+---------------------|
* | Start | - |
* | Write | (reg_addr) |
* | Stop | - |
* | Start | - |
* | Read | (reg_data[0]) |
* | Read | (....) |
* | Read | (reg_data[len - 1]) |
* | Stop | - |
* |------------+---------------------|
*/
return rslt;
}
int8_t i2c_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len)
{
int8_t rslt = 0; /* Return 0 for Success, non-zero for failure */
/*
* The parameter dev_id can be used as a variable to store the I2C address of the device
*/
/*
* Data on the bus should be like
* |------------+---------------------|
* | I2C action | Data |
* |------------+---------------------|
* | Start | - |
* | Write | (reg_addr) |
* | Write | (reg_data[0]) |
* | Write | (....) |
* | Write | (reg_data[len - 1]) |
* | Stop | - |
* |------------+---------------------|
*/
return rslt;
}
```
## Copyright (C) 2017 - 2018 Bosch Sensortec GmbH

1367
lib/Bosch-BSEC/bme680.c Normal file

File diff suppressed because it is too large Load Diff

225
lib/Bosch-BSEC/bme680.h Normal file
View File

@ -0,0 +1,225 @@
/**
* Copyright (C) 2017 - 2018 Bosch Sensortec GmbH
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* Neither the name of the copyright holder nor the names of the
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER
* OR CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY,
* OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO,
* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE
*
* The information provided is believed to be accurate and reliable.
* The copyright holder assumes no responsibility
* for the consequences of use
* of such information nor for any infringement of patents or
* other rights of third parties which may result from its use.
* No license is granted by implication or otherwise under any patent or
* patent rights of the copyright holder.
*
* @file bme680.h
* @date 19 Jun 2018
* @version 3.5.9
* @brief
*
*/
/*! @file bme680.h
@brief Sensor driver for BME680 sensor */
/*!
* @defgroup BME680 SENSOR API
* @{*/
#ifndef BME680_H_
#define BME680_H_
/*! CPP guard */
#ifdef __cplusplus
extern "C"
{
#endif
/* Header includes */
#include "bme680_defs.h"
/* function prototype declarations */
/*!
* @brief This API is the entry point.
* It reads the chip-id and calibration data from the sensor.
*
* @param[in,out] dev : Structure instance of bme680_dev
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bme680_init(struct bme680_dev *dev);
/*!
* @brief This API writes the given data to the register address
* of the sensor.
*
* @param[in] reg_addr : Register address from where the data to be written.
* @param[in] reg_data : Pointer to data buffer which is to be written
* in the sensor.
* @param[in] len : No of bytes of data to write..
* @param[in] dev : Structure instance of bme680_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bme680_set_regs(const uint8_t *reg_addr, const uint8_t *reg_data, uint8_t len, struct bme680_dev *dev);
/*!
* @brief This API reads the data from the given register address of the sensor.
*
* @param[in] reg_addr : Register address from where the data to be read
* @param[out] reg_data : Pointer to data buffer to store the read data.
* @param[in] len : No of bytes of data to be read.
* @param[in] dev : Structure instance of bme680_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bme680_get_regs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bme680_dev *dev);
/*!
* @brief This API performs the soft reset of the sensor.
*
* @param[in] dev : Structure instance of bme680_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
*/
int8_t bme680_soft_reset(struct bme680_dev *dev);
/*!
* @brief This API is used to set the power mode of the sensor.
*
* @param[in] dev : Structure instance of bme680_dev
* @note : Pass the value to bme680_dev.power_mode structure variable.
*
* value | mode
* -------------|------------------
* 0x00 | BME680_SLEEP_MODE
* 0x01 | BME680_FORCED_MODE
*
* * @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bme680_set_sensor_mode(struct bme680_dev *dev);
/*!
* @brief This API is used to get the power mode of the sensor.
*
* @param[in] dev : Structure instance of bme680_dev
* @note : bme680_dev.power_mode structure variable hold the power mode.
*
* value | mode
* ---------|------------------
* 0x00 | BME680_SLEEP_MODE
* 0x01 | BME680_FORCED_MODE
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bme680_get_sensor_mode(struct bme680_dev *dev);
/*!
* @brief This API is used to set the profile duration of the sensor.
*
* @param[in] dev : Structure instance of bme680_dev.
* @param[in] duration : Duration of the measurement in ms.
*
* @return Nothing
*/
void bme680_set_profile_dur(uint16_t duration, struct bme680_dev *dev);
/*!
* @brief This API is used to get the profile duration of the sensor.
*
* @param[in] dev : Structure instance of bme680_dev.
* @param[in] duration : Duration of the measurement in ms.
*
* @return Nothing
*/
void bme680_get_profile_dur(uint16_t *duration, const struct bme680_dev *dev);
/*!
* @brief This API reads the pressure, temperature and humidity and gas data
* from the sensor, compensates the data and store it in the bme680_data
* structure instance passed by the user.
*
* @param[out] data: Structure instance to hold the data.
* @param[in] dev : Structure instance of bme680_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bme680_get_sensor_data(struct bme680_field_data *data, struct bme680_dev *dev);
/*!
* @brief This API is used to set the oversampling, filter and T,P,H, gas selection
* settings in the sensor.
*
* @param[in] dev : Structure instance of bme680_dev.
* @param[in] desired_settings : Variable used to select the settings which
* are to be set in the sensor.
*
* Macros | Functionality
*---------------------------------|----------------------------------------------
* BME680_OST_SEL | To set temperature oversampling.
* BME680_OSP_SEL | To set pressure oversampling.
* BME680_OSH_SEL | To set humidity oversampling.
* BME680_GAS_MEAS_SEL | To set gas measurement setting.
* BME680_FILTER_SEL | To set filter setting.
* BME680_HCNTRL_SEL | To set humidity control setting.
* BME680_RUN_GAS_SEL | To set run gas setting.
* BME680_NBCONV_SEL | To set NB conversion setting.
* BME680_GAS_SENSOR_SEL | To set all gas sensor related settings
*
* @note : Below are the macros to be used by the user for selecting the
* desired settings. User can do OR operation of these macros for configuring
* multiple settings.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
*/
int8_t bme680_set_sensor_settings(uint16_t desired_settings, struct bme680_dev *dev);
/*!
* @brief This API is used to get the oversampling, filter and T,P,H, gas selection
* settings in the sensor.
*
* @param[in] dev : Structure instance of bme680_dev.
* @param[in] desired_settings : Variable used to select the settings which
* are to be get from the sensor.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
*/
int8_t bme680_get_sensor_settings(uint16_t desired_settings, struct bme680_dev *dev);
#ifdef __cplusplus
}
#endif /* End of CPP guard */
#endif /* BME680_H_ */
/** @}*/

View File

@ -0,0 +1,545 @@
/**
* Copyright (C) 2017 - 2018 Bosch Sensortec GmbH
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* Neither the name of the copyright holder nor the names of the
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER
* OR CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY,
* OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO,
* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE
*
* The information provided is believed to be accurate and reliable.
* The copyright holder assumes no responsibility
* for the consequences of use
* of such information nor for any infringement of patents or
* other rights of third parties which may result from its use.
* No license is granted by implication or otherwise under any patent or
* patent rights of the copyright holder.
*
* @file bme680_defs.h
* @date 19 Jun 2018
* @version 3.5.9
* @brief
*
*/
/*! @file bme680_defs.h
@brief Sensor driver for BME680 sensor */
/*!
* @defgroup BME680 SENSOR API
* @brief
* @{*/
#ifndef BME680_DEFS_H_
#define BME680_DEFS_H_
/********************************************************/
/* header includes */
#ifdef __KERNEL__
#include <linux/types.h>
#include <linux/kernel.h>
#else
#include <stdint.h>
#include <stddef.h>
#endif
/******************************************************************************/
/*! @name Common macros */
/******************************************************************************/
#if !defined(UINT8_C) && !defined(INT8_C)
#define INT8_C(x) S8_C(x)
#define UINT8_C(x) U8_C(x)
#endif
#if !defined(UINT16_C) && !defined(INT16_C)
#define INT16_C(x) S16_C(x)
#define UINT16_C(x) U16_C(x)
#endif
#if !defined(INT32_C) && !defined(UINT32_C)
#define INT32_C(x) S32_C(x)
#define UINT32_C(x) U32_C(x)
#endif
#if !defined(INT64_C) && !defined(UINT64_C)
#define INT64_C(x) S64_C(x)
#define UINT64_C(x) U64_C(x)
#endif
/**@}*/
/**\name C standard macros */
#ifndef NULL
#ifdef __cplusplus
#define NULL 0
#else
#define NULL ((void *) 0)
#endif
#endif
/** BME680 configuration macros */
/** Enable or un-comment the macro to provide floating point data output */
#ifndef BME680_FLOAT_POINT_COMPENSATION
/* #define BME680_FLOAT_POINT_COMPENSATION */
#endif
/** BME680 General config */
#define BME680_POLL_PERIOD_MS UINT8_C(10)
/** BME680 I2C addresses */
#define BME680_I2C_ADDR_PRIMARY UINT8_C(0x76)
#define BME680_I2C_ADDR_SECONDARY UINT8_C(0x77)
/** BME680 unique chip identifier */
#define BME680_CHIP_ID UINT8_C(0x61)
/** BME680 coefficients related defines */
#define BME680_COEFF_SIZE UINT8_C(41)
#define BME680_COEFF_ADDR1_LEN UINT8_C(25)
#define BME680_COEFF_ADDR2_LEN UINT8_C(16)
/** BME680 field_x related defines */
#define BME680_FIELD_LENGTH UINT8_C(15)
#define BME680_FIELD_ADDR_OFFSET UINT8_C(17)
/** Soft reset command */
#define BME680_SOFT_RESET_CMD UINT8_C(0xb6)
/** Error code definitions */
#define BME680_OK INT8_C(0)
/* Errors */
#define BME680_E_NULL_PTR INT8_C(-1)
#define BME680_E_COM_FAIL INT8_C(-2)
#define BME680_E_DEV_NOT_FOUND INT8_C(-3)
#define BME680_E_INVALID_LENGTH INT8_C(-4)
/* Warnings */
#define BME680_W_DEFINE_PWR_MODE INT8_C(1)
#define BME680_W_NO_NEW_DATA INT8_C(2)
/* Info's */
#define BME680_I_MIN_CORRECTION UINT8_C(1)
#define BME680_I_MAX_CORRECTION UINT8_C(2)
/** Register map */
/** Other coefficient's address */
#define BME680_ADDR_RES_HEAT_VAL_ADDR UINT8_C(0x00)
#define BME680_ADDR_RES_HEAT_RANGE_ADDR UINT8_C(0x02)
#define BME680_ADDR_RANGE_SW_ERR_ADDR UINT8_C(0x04)
#define BME680_ADDR_SENS_CONF_START UINT8_C(0x5A)
#define BME680_ADDR_GAS_CONF_START UINT8_C(0x64)
/** Field settings */
#define BME680_FIELD0_ADDR UINT8_C(0x1d)
/** Heater settings */
#define BME680_RES_HEAT0_ADDR UINT8_C(0x5a)
#define BME680_GAS_WAIT0_ADDR UINT8_C(0x64)
/** Sensor configuration registers */
#define BME680_CONF_HEAT_CTRL_ADDR UINT8_C(0x70)
#define BME680_CONF_ODR_RUN_GAS_NBC_ADDR UINT8_C(0x71)
#define BME680_CONF_OS_H_ADDR UINT8_C(0x72)
#define BME680_MEM_PAGE_ADDR UINT8_C(0xf3)
#define BME680_CONF_T_P_MODE_ADDR UINT8_C(0x74)
#define BME680_CONF_ODR_FILT_ADDR UINT8_C(0x75)
/** Coefficient's address */
#define BME680_COEFF_ADDR1 UINT8_C(0x89)
#define BME680_COEFF_ADDR2 UINT8_C(0xe1)
/** Chip identifier */
#define BME680_CHIP_ID_ADDR UINT8_C(0xd0)
/** Soft reset register */
#define BME680_SOFT_RESET_ADDR UINT8_C(0xe0)
/** Heater control settings */
#define BME680_ENABLE_HEATER UINT8_C(0x00)
#define BME680_DISABLE_HEATER UINT8_C(0x08)
/** Gas measurement settings */
#define BME680_DISABLE_GAS_MEAS UINT8_C(0x00)
#define BME680_ENABLE_GAS_MEAS UINT8_C(0x01)
/** Over-sampling settings */
#define BME680_OS_NONE UINT8_C(0)
#define BME680_OS_1X UINT8_C(1)
#define BME680_OS_2X UINT8_C(2)
#define BME680_OS_4X UINT8_C(3)
#define BME680_OS_8X UINT8_C(4)
#define BME680_OS_16X UINT8_C(5)
/** IIR filter settings */
#define BME680_FILTER_SIZE_0 UINT8_C(0)
#define BME680_FILTER_SIZE_1 UINT8_C(1)
#define BME680_FILTER_SIZE_3 UINT8_C(2)
#define BME680_FILTER_SIZE_7 UINT8_C(3)
#define BME680_FILTER_SIZE_15 UINT8_C(4)
#define BME680_FILTER_SIZE_31 UINT8_C(5)
#define BME680_FILTER_SIZE_63 UINT8_C(6)
#define BME680_FILTER_SIZE_127 UINT8_C(7)
/** Power mode settings */
#define BME680_SLEEP_MODE UINT8_C(0)
#define BME680_FORCED_MODE UINT8_C(1)
/** Delay related macro declaration */
#define BME680_RESET_PERIOD UINT32_C(10)
/** SPI memory page settings */
#define BME680_MEM_PAGE0 UINT8_C(0x10)
#define BME680_MEM_PAGE1 UINT8_C(0x00)
/** Ambient humidity shift value for compensation */
#define BME680_HUM_REG_SHIFT_VAL UINT8_C(4)
/** Run gas enable and disable settings */
#define BME680_RUN_GAS_DISABLE UINT8_C(0)
#define BME680_RUN_GAS_ENABLE UINT8_C(1)
/** Buffer length macro declaration */
#define BME680_TMP_BUFFER_LENGTH UINT8_C(40)
#define BME680_REG_BUFFER_LENGTH UINT8_C(6)
#define BME680_FIELD_DATA_LENGTH UINT8_C(3)
#define BME680_GAS_REG_BUF_LENGTH UINT8_C(20)
/** Settings selector */
#define BME680_OST_SEL UINT16_C(1)
#define BME680_OSP_SEL UINT16_C(2)
#define BME680_OSH_SEL UINT16_C(4)
#define BME680_GAS_MEAS_SEL UINT16_C(8)
#define BME680_FILTER_SEL UINT16_C(16)
#define BME680_HCNTRL_SEL UINT16_C(32)
#define BME680_RUN_GAS_SEL UINT16_C(64)
#define BME680_NBCONV_SEL UINT16_C(128)
#define BME680_GAS_SENSOR_SEL (BME680_GAS_MEAS_SEL | BME680_RUN_GAS_SEL | BME680_NBCONV_SEL)
/** Number of conversion settings*/
#define BME680_NBCONV_MIN UINT8_C(0)
#define BME680_NBCONV_MAX UINT8_C(10)
/** Mask definitions */
#define BME680_GAS_MEAS_MSK UINT8_C(0x30)
#define BME680_NBCONV_MSK UINT8_C(0X0F)
#define BME680_FILTER_MSK UINT8_C(0X1C)
#define BME680_OST_MSK UINT8_C(0XE0)
#define BME680_OSP_MSK UINT8_C(0X1C)
#define BME680_OSH_MSK UINT8_C(0X07)
#define BME680_HCTRL_MSK UINT8_C(0x08)
#define BME680_RUN_GAS_MSK UINT8_C(0x10)
#define BME680_MODE_MSK UINT8_C(0x03)
#define BME680_RHRANGE_MSK UINT8_C(0x30)
#define BME680_RSERROR_MSK UINT8_C(0xf0)
#define BME680_NEW_DATA_MSK UINT8_C(0x80)
#define BME680_GAS_INDEX_MSK UINT8_C(0x0f)
#define BME680_GAS_RANGE_MSK UINT8_C(0x0f)
#define BME680_GASM_VALID_MSK UINT8_C(0x20)
#define BME680_HEAT_STAB_MSK UINT8_C(0x10)
#define BME680_MEM_PAGE_MSK UINT8_C(0x10)
#define BME680_SPI_RD_MSK UINT8_C(0x80)
#define BME680_SPI_WR_MSK UINT8_C(0x7f)
#define BME680_BIT_H1_DATA_MSK UINT8_C(0x0F)
/** Bit position definitions for sensor settings */
#define BME680_GAS_MEAS_POS UINT8_C(4)
#define BME680_FILTER_POS UINT8_C(2)
#define BME680_OST_POS UINT8_C(5)
#define BME680_OSP_POS UINT8_C(2)
#define BME680_RUN_GAS_POS UINT8_C(4)
/** Array Index to Field data mapping for Calibration Data*/
#define BME680_T2_LSB_REG (1)
#define BME680_T2_MSB_REG (2)
#define BME680_T3_REG (3)
#define BME680_P1_LSB_REG (5)
#define BME680_P1_MSB_REG (6)
#define BME680_P2_LSB_REG (7)
#define BME680_P2_MSB_REG (8)
#define BME680_P3_REG (9)
#define BME680_P4_LSB_REG (11)
#define BME680_P4_MSB_REG (12)
#define BME680_P5_LSB_REG (13)
#define BME680_P5_MSB_REG (14)
#define BME680_P7_REG (15)
#define BME680_P6_REG (16)
#define BME680_P8_LSB_REG (19)
#define BME680_P8_MSB_REG (20)
#define BME680_P9_LSB_REG (21)
#define BME680_P9_MSB_REG (22)
#define BME680_P10_REG (23)
#define BME680_H2_MSB_REG (25)
#define BME680_H2_LSB_REG (26)
#define BME680_H1_LSB_REG (26)
#define BME680_H1_MSB_REG (27)
#define BME680_H3_REG (28)
#define BME680_H4_REG (29)
#define BME680_H5_REG (30)
#define BME680_H6_REG (31)
#define BME680_H7_REG (32)
#define BME680_T1_LSB_REG (33)
#define BME680_T1_MSB_REG (34)
#define BME680_GH2_LSB_REG (35)
#define BME680_GH2_MSB_REG (36)
#define BME680_GH1_REG (37)
#define BME680_GH3_REG (38)
/** BME680 register buffer index settings*/
#define BME680_REG_FILTER_INDEX UINT8_C(5)
#define BME680_REG_TEMP_INDEX UINT8_C(4)
#define BME680_REG_PRES_INDEX UINT8_C(4)
#define BME680_REG_HUM_INDEX UINT8_C(2)
#define BME680_REG_NBCONV_INDEX UINT8_C(1)
#define BME680_REG_RUN_GAS_INDEX UINT8_C(1)
#define BME680_REG_HCTRL_INDEX UINT8_C(0)
/** BME680 pressure calculation macros */
/*! This max value is used to provide precedence to multiplication or division
* in pressure compensation equation to achieve least loss of precision and
* avoiding overflows.
* i.e Comparing value, BME680_MAX_OVERFLOW_VAL = INT32_C(1 << 30)
*/
#define BME680_MAX_OVERFLOW_VAL INT32_C(0x40000000)
/** Macro to combine two 8 bit data's to form a 16 bit data */
#define BME680_CONCAT_BYTES(msb, lsb) (((uint16_t)msb << 8) | (uint16_t)lsb)
/** Macro to SET and GET BITS of a register */
#define BME680_SET_BITS(reg_data, bitname, data) \
((reg_data & ~(bitname##_MSK)) | \
((data << bitname##_POS) & bitname##_MSK))
#define BME680_GET_BITS(reg_data, bitname) ((reg_data & (bitname##_MSK)) >> \
(bitname##_POS))
/** Macro variant to handle the bitname position if it is zero */
#define BME680_SET_BITS_POS_0(reg_data, bitname, data) \
((reg_data & ~(bitname##_MSK)) | \
(data & bitname##_MSK))
#define BME680_GET_BITS_POS_0(reg_data, bitname) (reg_data & (bitname##_MSK))
/** Type definitions */
/*!
* Generic communication function pointer
* @param[in] dev_id: Place holder to store the id of the device structure
* Can be used to store the index of the Chip select or
* I2C address of the device.
* @param[in] reg_addr: Used to select the register the where data needs to
* be read from or written to.
* @param[in/out] reg_data: Data array to read/write
* @param[in] len: Length of the data array
*/
typedef int8_t (*bme680_com_fptr_t)(uint8_t dev_id, uint8_t reg_addr, uint8_t *data, uint16_t len);
/*!
* Delay function pointer
* @param[in] period: Time period in milliseconds
*/
typedef void (*bme680_delay_fptr_t)(uint32_t period);
/*!
* @brief Interface selection Enumerations
*/
enum bme680_intf {
/*! SPI interface */
BME680_SPI_INTF,
/*! I2C interface */
BME680_I2C_INTF
};
/* structure definitions */
/*!
* @brief Sensor field data structure
*/
struct bme680_field_data {
/*! Contains new_data, gasm_valid & heat_stab */
uint8_t status;
/*! The index of the heater profile used */
uint8_t gas_index;
/*! Measurement index to track order */
uint8_t meas_index;
#ifndef BME680_FLOAT_POINT_COMPENSATION
/*! Temperature in degree celsius x100 */
int16_t temperature;
/*! Pressure in Pascal */
uint32_t pressure;
/*! Humidity in % relative humidity x1000 */
uint32_t humidity;
/*! Gas resistance in Ohms */
uint32_t gas_resistance;
#else
/*! Temperature in degree celsius */
float temperature;
/*! Pressure in Pascal */
float pressure;
/*! Humidity in % relative humidity x1000 */
float humidity;
/*! Gas resistance in Ohms */
float gas_resistance;
#endif
};
/*!
* @brief Structure to hold the Calibration data
*/
struct bme680_calib_data {
/*! Variable to store calibrated humidity data */
uint16_t par_h1;
/*! Variable to store calibrated humidity data */
uint16_t par_h2;
/*! Variable to store calibrated humidity data */
int8_t par_h3;
/*! Variable to store calibrated humidity data */
int8_t par_h4;
/*! Variable to store calibrated humidity data */
int8_t par_h5;
/*! Variable to store calibrated humidity data */
uint8_t par_h6;
/*! Variable to store calibrated humidity data */
int8_t par_h7;
/*! Variable to store calibrated gas data */
int8_t par_gh1;
/*! Variable to store calibrated gas data */
int16_t par_gh2;
/*! Variable to store calibrated gas data */
int8_t par_gh3;
/*! Variable to store calibrated temperature data */
uint16_t par_t1;
/*! Variable to store calibrated temperature data */
int16_t par_t2;
/*! Variable to store calibrated temperature data */
int8_t par_t3;
/*! Variable to store calibrated pressure data */
uint16_t par_p1;
/*! Variable to store calibrated pressure data */
int16_t par_p2;
/*! Variable to store calibrated pressure data */
int8_t par_p3;
/*! Variable to store calibrated pressure data */
int16_t par_p4;
/*! Variable to store calibrated pressure data */
int16_t par_p5;
/*! Variable to store calibrated pressure data */
int8_t par_p6;
/*! Variable to store calibrated pressure data */
int8_t par_p7;
/*! Variable to store calibrated pressure data */
int16_t par_p8;
/*! Variable to store calibrated pressure data */
int16_t par_p9;
/*! Variable to store calibrated pressure data */
uint8_t par_p10;
#ifndef BME680_FLOAT_POINT_COMPENSATION
/*! Variable to store t_fine size */
int32_t t_fine;
#else
/*! Variable to store t_fine size */
float t_fine;
#endif
/*! Variable to store heater resistance range */
uint8_t res_heat_range;
/*! Variable to store heater resistance value */
int8_t res_heat_val;
/*! Variable to store error range */
int8_t range_sw_err;
};
/*!
* @brief BME680 sensor settings structure which comprises of ODR,
* over-sampling and filter settings.
*/
struct bme680_tph_sett {
/*! Humidity oversampling */
uint8_t os_hum;
/*! Temperature oversampling */
uint8_t os_temp;
/*! Pressure oversampling */
uint8_t os_pres;
/*! Filter coefficient */
uint8_t filter;
};
/*!
* @brief BME680 gas sensor which comprises of gas settings
* and status parameters
*/
struct bme680_gas_sett {
/*! Variable to store nb conversion */
uint8_t nb_conv;
/*! Variable to store heater control */
uint8_t heatr_ctrl;
/*! Run gas enable value */
uint8_t run_gas;
/*! Heater temperature value */
uint16_t heatr_temp;
/*! Duration profile value */
uint16_t heatr_dur;
};
/*!
* @brief BME680 device structure
*/
struct bme680_dev {
/*! Chip Id */
uint8_t chip_id;
/*! Device Id */
uint8_t dev_id;
/*! SPI/I2C interface */
enum bme680_intf intf;
/*! Memory page used */
uint8_t mem_page;
/*! Ambient temperature in Degree C */
int8_t amb_temp;
/*! Sensor calibration data */
struct bme680_calib_data calib;
/*! Sensor settings */
struct bme680_tph_sett tph_sett;
/*! Gas Sensor settings */
struct bme680_gas_sett gas_sett;
/*! Sensor power modes */
uint8_t power_mode;
/*! New sensor fields */
uint8_t new_fields;
/*! Store the info messages */
uint8_t info_msg;
/*! Bus read function pointer */
bme680_com_fptr_t read;
/*! Bus write function pointer */
bme680_com_fptr_t write;
/*! delay function pointer */
bme680_delay_fptr_t delay_ms;
/*! Communication function result */
int8_t com_rslt;
};
#endif /* BME680_DEFS_H_ */
/** @}*/
/** @}*/

View File

@ -0,0 +1,488 @@
/*
* Copyright (C) 2015, 2016, 2017 Robert Bosch. All Rights Reserved.
*
* Disclaimer
*
* Common:
* Bosch Sensortec products are developed for the consumer goods industry. They may only be used
* within the parameters of the respective valid product data sheet. Bosch Sensortec products are
* provided with the express understanding that there is no warranty of fitness for a particular purpose.
* They are not fit for use in life-sustaining, safety or security sensitive systems or any system or device
* that may lead to bodily harm or property damage if the system or device malfunctions. In addition,
* Bosch Sensortec products are not fit for use in products which interact with motor vehicle systems.
* The resale and/or use of products are at the purchasers own risk and his own responsibility. The
* examination of fitness for the intended use is the sole responsibility of the Purchaser.
*
* The purchaser shall indemnify Bosch Sensortec from all third party claims, including any claims for
* incidental, or consequential damages, arising from any product use not covered by the parameters of
* the respective valid product data sheet or not approved by Bosch Sensortec and reimburse Bosch
* Sensortec for all costs in connection with such claims.
*
* The purchaser must monitor the market for the purchased products, particularly with regard to
* product safety and inform Bosch Sensortec without delay of all security relevant incidents.
*
* Engineering Samples are marked with an asterisk (*) or (e). Samples may vary from the valid
* technical specifications of the product series. They are therefore not intended or fit for resale to third
* parties or for use in end products. Their sole purpose is internal client testing. The testing of an
* engineering sample may in no way replace the testing of a product series. Bosch Sensortec
* assumes no liability for the use of engineering samples. By accepting the engineering samples, the
* Purchaser agrees to indemnify Bosch Sensortec from all claims arising from the use of engineering
* samples.
*
* Special:
* This software module (hereinafter called "Software") and any information on application-sheets
* (hereinafter called "Information") is provided free of charge for the sole purpose to support your
* application work. The Software and Information is subject to the following terms and conditions:
*
* The Software is specifically designed for the exclusive use for Bosch Sensortec products by
* personnel who have special experience and training. Do not use this Software if you do not have the
* proper experience or training.
*
* This Software package is provided `` as is `` and without any expressed or implied warranties,
* including without limitation, the implied warranties of merchantability and fitness for a particular
* purpose.
*
* Bosch Sensortec and their representatives and agents deny any liability for the functional impairment
* of this Software in terms of fitness, performance and safety. Bosch Sensortec and their
* representatives and agents shall not be liable for any direct or indirect damages or injury, except as
* otherwise stipulated in mandatory applicable law.
*
* The Information provided is believed to be accurate and reliable. Bosch Sensortec assumes no
* responsibility for the consequences of use of such Information nor for any infringement of patents or
* other rights of third parties which may result from its use. No license is granted by implication or
* otherwise under any patent or patent rights of Bosch. Specifications mentioned in the Information are
* subject to change without notice.
*
* It is not allowed to deliver the source code of the Software to any third party without permission of
* Bosch Sensortec.
*
*/
/**
* @file bsec_datatypes.h
*
* @brief
* Contains the data types used by BSEC
*
*/
#ifndef __BSEC_DATATYPES_H__
#define __BSEC_DATATYPES_H__
#ifdef __cplusplus
extern "C"
{
#endif
/*!
* @addtogroup bsec_interface BSEC C Interface
* @{*/
#ifdef __KERNEL__
#include <linux/types.h>
#endif
#include <stdint.h>
#include <stddef.h>
#define BSEC_MAX_WORKBUFFER_SIZE (2048) /*!< Maximum size (in bytes) of the work buffer */
#define BSEC_MAX_PHYSICAL_SENSOR (8) /*!< Number of physical sensors that need allocated space before calling bsec_update_subscription() */
#define BSEC_MAX_PROPERTY_BLOB_SIZE (454) /*!< Maximum size (in bytes) of the data blobs returned by bsec_get_configuration() */
#define BSEC_MAX_STATE_BLOB_SIZE (134) /*!< Maximum size (in bytes) of the data blobs returned by bsec_get_state()*/
#define BSEC_SAMPLE_RATE_DISABLED (65535.0f) /*!< Sample rate of a disabled sensor */
#define BSEC_SAMPLE_RATE_ULP (0.0033333f) /*!< Sample rate in case of Ultra Low Power Mode */
#define BSEC_SAMPLE_RATE_LP (0.33333f) /*!< Sample rate in case of Low Power Mode */
#define BSEC_SAMPLE_RATE_ULP_MEASUREMENT_ON_DEMAND (0.0f) /*!< Input value used to trigger an extra measurment (ULP plus) */
#define BSEC_PROCESS_PRESSURE (1 << (BSEC_INPUT_PRESSURE-1)) /*!< process_data bitfield constant for pressure @sa bsec_bme_settings_t */
#define BSEC_PROCESS_TEMPERATURE (1 << (BSEC_INPUT_TEMPERATURE-1)) /*!< process_data bitfield constant for temperature @sa bsec_bme_settings_t */
#define BSEC_PROCESS_HUMIDITY (1 << (BSEC_INPUT_HUMIDITY-1)) /*!< process_data bitfield constant for humidity @sa bsec_bme_settings_t */
#define BSEC_PROCESS_GAS (1 << (BSEC_INPUT_GASRESISTOR-1)) /*!< process_data bitfield constant for gas sensor @sa bsec_bme_settings_t */
#define BSEC_NUMBER_OUTPUTS (14) /*!< Number of outputs, depending on solution */
#define BSEC_OUTPUT_INCLUDED (1210863) /*!< bitfield that indicates which outputs are included in the solution */
/*!
* @brief Enumeration for input (physical) sensors.
*
* Used to populate bsec_input_t::sensor_id. It is also used in bsec_sensor_configuration_t::sensor_id structs
* returned in the parameter required_sensor_settings of bsec_update_subscription().
*
* @sa bsec_sensor_configuration_t @sa bsec_input_t
*/
typedef enum
{
/**
* @brief Pressure sensor output of BMExxx [Pa]
*/
BSEC_INPUT_PRESSURE = 1,
/**
* @brief Humidity sensor output of BMExxx [%]
*
* @note Relative humidity strongly depends on the temperature (it is measured at). It may require a conversion to
* the temperature outside of the device.
*
* @sa bsec_virtual_sensor_t
*/
BSEC_INPUT_HUMIDITY = 2,
/**
* @brief Temperature sensor output of BMExxx [degrees Celsius]
*
* @note The BME680 is factory trimmed, thus the temperature sensor of the BME680 is very accurate.
* The temperature value is a very local measurement value and can be influenced by external heat sources.
*
* @sa bsec_virtual_sensor_t
*/
BSEC_INPUT_TEMPERATURE = 3,
/**
* @brief Gas sensor resistance output of BMExxx [Ohm]
*
* The resistance value changes due to varying VOC concentrations (the higher the concentration of reducing VOCs,
* the lower the resistance and vice versa).
*/
BSEC_INPUT_GASRESISTOR = 4, /*!< */
/**
* @brief Additional input for device heat compensation
*
* IAQ solution: The value is subtracted from ::BSEC_INPUT_TEMPERATURE to compute
* ::BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE.
*
* ALL solution: Generic heat source 1
*
* @sa bsec_virtual_sensor_t
*/
BSEC_INPUT_HEATSOURCE = 14,
/**
* @brief Additional input for device heat compensation 8
*
* Generic heat source 8
*/
/**
* @brief Additional input that disables baseline tracker
*
* 0 - Normal
* 1 - Event 1
* 2 - Event 2
*/
BSEC_INPUT_DISABLE_BASELINE_TRACKER = 23,
} bsec_physical_sensor_t;
/*!
* @brief Enumeration for output (virtual) sensors
*
* Used to populate bsec_output_t::sensor_id. It is also used in bsec_sensor_configuration_t::sensor_id structs
* passed in the parameter requested_virtual_sensors of bsec_update_subscription().
*
* @sa bsec_sensor_configuration_t @sa bsec_output_t
*/
typedef enum
{
/**
* @brief Indoor-air-quality estimate [0-500]
*
* Indoor-air-quality (IAQ) gives an indication of the relative change in ambient TVOCs detected by BME680.
*
* @note The IAQ scale ranges from 0 (clean air) to 500 (heavily polluted air). During operation, algorithms
* automatically calibrate and adapt themselves to the typical environments where the sensor is operated
* (e.g., home, workplace, inside a car, etc.).This automatic background calibration ensures that users experience
* consistent IAQ performance. The calibration process considers the recent measurement history (typ. up to four
* days) to ensure that IAQ=25 corresponds to typical good air and IAQ=250 indicates typical polluted air.
*/
BSEC_OUTPUT_IAQ = 1,
BSEC_OUTPUT_STATIC_IAQ = 2, /*!< Unscaled indoor-air-quality estimate */
BSEC_OUTPUT_CO2_EQUIVALENT = 3, /*!< co2 equivalent estimate [ppm] */
BSEC_OUTPUT_BREATH_VOC_EQUIVALENT = 4, /*!< breath VOC concentration estimate [ppm] */
/**
* @brief Temperature sensor signal [degrees Celsius]
*
* Temperature directly measured by BME680 in degree Celsius.
*
* @note This value is cross-influenced by the sensor heating and device specific heating.
*/
BSEC_OUTPUT_RAW_TEMPERATURE = 6,
/**
* @brief Pressure sensor signal [Pa]
*
* Pressure directly measured by the BME680 in Pa.
*/
BSEC_OUTPUT_RAW_PRESSURE = 7,
/**
* @brief Relative humidity sensor signal [%]
*
* Relative humidity directly measured by the BME680 in %.
*
* @note This value is cross-influenced by the sensor heating and device specific heating.
*/
BSEC_OUTPUT_RAW_HUMIDITY = 8,
/**
* @brief Gas sensor signal [Ohm]
*
* Gas resistance measured directly by the BME680 in Ohm.The resistance value changes due to varying VOC
* concentrations (the higher the concentration of reducing VOCs, the lower the resistance and vice versa).
*/
BSEC_OUTPUT_RAW_GAS = 9,
/**
* @brief Gas sensor stabilization status [boolean]
*
* Indicates initial stabilization status of the gas sensor element: stabilization is ongoing (0) or stabilization
* is finished (1).
*/
BSEC_OUTPUT_STABILIZATION_STATUS = 12,
/**
* @brief Gas sensor run-in status [boolean]
*
* Indicates power-on stabilization status of the gas sensor element: stabilization is ongoing (0) or stabilization
* is finished (1).
*/
BSEC_OUTPUT_RUN_IN_STATUS = 13,
/**
* @brief Sensor heat compensated temperature [degrees Celsius]
*
* Temperature measured by BME680 which is compensated for the influence of sensor (heater) in degree Celsius.
* The self heating introduced by the heater is depending on the sensor operation mode and the sensor supply voltage.
*
*
* @note IAQ solution: In addition, the temperature output can be compensated by an user defined value
* (::BSEC_INPUT_HEATSOURCE in degrees Celsius), which represents the device specific self-heating.
*
* Thus, the value is calculated as follows:
* * IAQ solution: ```BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE = ::BSEC_INPUT_TEMPERATURE - function(sensor operation mode, sensor supply voltage) - ::BSEC_INPUT_HEATSOURCE```
* * other solutions: ```::BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE = ::BSEC_INPUT_TEMPERATURE - function(sensor operation mode, sensor supply voltage)```
*
* The self-heating in operation mode BSEC_SAMPLE_RATE_ULP is negligible.
* The self-heating in operation mode BSEC_SAMPLE_RATE_LP is supported for 1.8V by default (no config file required). If the BME680 sensor supply voltage is 3.3V, the IoT_LP_3_3V.config shall be used.
*/
BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE = 14,
/**
* @brief Sensor heat compensated humidity [%]
*
* Relative measured by BME680 which is compensated for the influence of sensor (heater) in %.
*
* It converts the ::BSEC_INPUT_HUMIDITY from temperature ::BSEC_INPUT_TEMPERATURE to temperature
* ::BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE.
*
* @note IAQ solution: If ::BSEC_INPUT_HEATSOURCE is used for device specific temperature compensation, it will be
* effective for ::BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY too.
*/
BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY = 15,
BSEC_OUTPUT_COMPENSATED_GAS = 18, /*!< Reserved internal debug output */
BSEC_OUTPUT_GAS_PERCENTAGE = 21 /*!< percentage of min and max filtered gas value [%] */
} bsec_virtual_sensor_t;
/*!
* @brief Enumeration for function return codes
*/
typedef enum
{
BSEC_OK = 0, /*!< Function execution successful */
BSEC_E_DOSTEPS_INVALIDINPUT = -1, /*!< Input (physical) sensor id passed to bsec_do_steps() is not in the valid range or not valid for requested virtual sensor */
BSEC_E_DOSTEPS_VALUELIMITS = -2, /*!< Value of input (physical) sensor signal passed to bsec_do_steps() is not in the valid range */
BSEC_E_DOSTEPS_DUPLICATEINPUT = -6, /*!< Duplicate input (physical) sensor ids passed as input to bsec_do_steps() */
BSEC_I_DOSTEPS_NOOUTPUTSRETURNABLE = 2, /*!< No memory allocated to hold return values from bsec_do_steps(), i.e., n_outputs == 0 */
BSEC_W_DOSTEPS_EXCESSOUTPUTS = 3, /*!< Not enough memory allocated to hold return values from bsec_do_steps(), i.e., n_outputs < maximum number of requested output (virtual) sensors */
BSEC_W_DOSTEPS_TSINTRADIFFOUTOFRANGE = 4, /*!< Duplicate timestamps passed to bsec_do_steps() */
BSEC_E_SU_WRONGDATARATE = -10, /*!< The sample_rate of the requested output (virtual) sensor passed to bsec_update_subscription() is zero */
BSEC_E_SU_SAMPLERATELIMITS = -12, /*!< The sample_rate of the requested output (virtual) sensor passed to bsec_update_subscription() does not match with the sampling rate allowed for that sensor */
BSEC_E_SU_DUPLICATEGATE = -13, /*!< Duplicate output (virtual) sensor ids requested through bsec_update_subscription() */
BSEC_E_SU_INVALIDSAMPLERATE = -14, /*!< The sample_rate of the requested output (virtual) sensor passed to bsec_update_subscription() does not fall within the global minimum and maximum sampling rates */
BSEC_E_SU_GATECOUNTEXCEEDSARRAY = -15, /*!< Not enough memory allocated to hold returned input (physical) sensor data from bsec_update_subscription(), i.e., n_required_sensor_settings < #BSEC_MAX_PHYSICAL_SENSOR */
BSEC_E_SU_SAMPLINTVLINTEGERMULT = -16, /*!< The sample_rate of the requested output (virtual) sensor passed to bsec_update_subscription() is not correct */
BSEC_E_SU_MULTGASSAMPLINTVL = -17, /*!< The sample_rate of the requested output (virtual), which requires the gas sensor, is not equal to the sample_rate that the gas sensor is being operated */
BSEC_E_SU_HIGHHEATERONDURATION = -18, /*!< The duration of one measurement is longer than the requested sampling interval */
BSEC_W_SU_UNKNOWNOUTPUTGATE = 10, /*!< Output (virtual) sensor id passed to bsec_update_subscription() is not in the valid range; e.g., n_requested_virtual_sensors > actual number of output (virtual) sensors requested */
BSEC_W_SU_MODINNOULP = 11, /*!< ULP plus can not be requested in non-ulp mode */ /*MOD_ONLY*/
BSEC_I_SU_SUBSCRIBEDOUTPUTGATES = 12, /*!< No output (virtual) sensor data were requested via bsec_update_subscription() */
BSEC_E_PARSE_SECTIONEXCEEDSWORKBUFFER = -32, /*!< n_work_buffer_size passed to bsec_set_[configuration/state]() not sufficient */
BSEC_E_CONFIG_FAIL = -33, /*!< Configuration failed */
BSEC_E_CONFIG_VERSIONMISMATCH = -34, /*!< Version encoded in serialized_[settings/state] passed to bsec_set_[configuration/state]() does not match with current version */
BSEC_E_CONFIG_FEATUREMISMATCH = -35, /*!< Enabled features encoded in serialized_[settings/state] passed to bsec_set_[configuration/state]() does not match with current library implementation */
BSEC_E_CONFIG_CRCMISMATCH = -36, /*!< serialized_[settings/state] passed to bsec_set_[configuration/state]() is corrupted */
BSEC_E_CONFIG_EMPTY = -37, /*!< n_serialized_[settings/state] passed to bsec_set_[configuration/state]() is to short to be valid */
BSEC_E_CONFIG_INSUFFICIENTWORKBUFFER = -38, /*!< Provided work_buffer is not large enough to hold the desired string */
BSEC_E_CONFIG_INVALIDSTRINGSIZE = -40, /*!< String size encoded in configuration/state strings passed to bsec_set_[configuration/state]() does not match with the actual string size n_serialized_[settings/state] passed to these functions */
BSEC_E_CONFIG_INSUFFICIENTBUFFER = -41, /*!< String buffer insufficient to hold serialized data from BSEC library */
BSEC_E_SET_INVALIDCHANNELIDENTIFIER = -100, /*!< Internal error code, size of work buffer in setConfig must be set to BSEC_MAX_WORKBUFFER_SIZE */
BSEC_E_SET_INVALIDLENGTH = -104, /*!< Internal error code */
BSEC_W_SC_CALL_TIMING_VIOLATION = 100, /*!< Difference between actual and defined sampling intervals of bsec_sensor_control() greater than allowed */
BSEC_W_SC_MODEXCEEDULPTIMELIMIT = 101, /*!< ULP plus is not allowed because an ULP measurement just took or will take place */ /*MOD_ONLY*/
BSEC_W_SC_MODINSUFFICIENTWAITTIME = 102 /*!< ULP plus is not allowed because not sufficient time passed since last ULP plus */ /*MOD_ONLY*/
} bsec_library_return_t;
/*!
* @brief Structure containing the version information
*
* Please note that configuration and state strings are coded to a specific version and will not be accepted by other
* versions of BSEC.
*
*/
typedef struct
{
uint8_t major; /**< @brief Major version */
uint8_t minor; /**< @brief Minor version */
uint8_t major_bugfix; /**< @brief Major bug fix version */
uint8_t minor_bugfix; /**< @brief Minor bug fix version */
} bsec_version_t;
/*!
* @brief Structure describing an input sample to the library
*
* Each input sample is provided to BSEC as an element in a struct array of this type. Timestamps must be provided
* in nanosecond resolution. Moreover, duplicate timestamps for subsequent samples are not allowed and will results in
* an error code being returned from bsec_do_steps().
*
* The meaning unit of the signal field are determined by the bsec_input_t::sensor_id field content. Possible
* bsec_input_t::sensor_id values and and their meaning are described in ::bsec_physical_sensor_t.
*
* @sa bsec_physical_sensor_t
*
*/
typedef struct
{
/**
* @brief Time stamp in nanosecond resolution [ns]
*
* Timestamps must be provided as non-repeating and increasing values. They can have their 0-points at system start or
* at a defined wall-clock time (e.g., 01-Jan-1970 00:00:00)
*/
int64_t time_stamp;
float signal; /*!< @brief Signal sample in the unit defined for the respective sensor_id @sa bsec_physical_sensor_t */
uint8_t signal_dimensions; /*!< @brief Signal dimensions (reserved for future use, shall be set to 1) */
uint8_t sensor_id; /*!< @brief Identifier of physical sensor @sa bsec_physical_sensor_t */
} bsec_input_t;
/*!
* @brief Structure describing an output sample of the library
*
* Each output sample is returned from BSEC by populating the element of a struct array of this type. The contents of
* the signal field is defined by the supplied bsec_output_t::sensor_id. Possible output
* bsec_output_t::sensor_id values are defined in ::bsec_virtual_sensor_t.
*
* @sa bsec_virtual_sensor_t
*/
typedef struct
{
int64_t time_stamp; /*!< @brief Time stamp in nanosecond resolution as provided as input [ns] */
float signal; /*!< @brief Signal sample in the unit defined for the respective bsec_output_t::sensor_id @sa bsec_virtual_sensor_t */
uint8_t signal_dimensions; /*!< @brief Signal dimensions (reserved for future use, shall be set to 1) */
uint8_t sensor_id; /*!< @brief Identifier of virtual sensor @sa bsec_virtual_sensor_t */
/**
* @brief Accuracy status 0-3
*
* Some virtual sensors provide a value in the accuracy field. If this is the case, the meaning of the field is as
* follows:
*
* | Name | Value | Accuracy description |
* |----------------------------|-------|-------------------------------------------------------------|
* | UNRELIABLE | 0 | Sensor data is unreliable, the sensor must be calibrated |
* | LOW_ACCURACY | 1 | Low accuracy, sensor should be calibrated |
* | MEDIUM_ACCURACY | 2 | Medium accuracy, sensor calibration may improve performance |
* | HIGH_ACCURACY | 3 | High accuracy |
*
* For example:
*
* - Ambient temperature accuracy is derived from change in the temperature in 1 minute.
*
* | Virtual sensor | Value | Accuracy description |
* |--------------------- |-------|------------------------------------------------------------------------------|
* | Ambient temperature | 0 | The difference in ambient temperature is greater than 4 degree in one minute |
* | | 1 | The difference in ambient temperature is less than 4 degree in one minute |
* | | 2 | The difference in ambient temperature is less than 3 degree in one minute |
* | | 3 | The difference in ambient temperature is less than 2 degree in one minute |
*
* - IAQ accuracy indicator will notify the user when she/he should initiate a calibration process. Calibration is
* performed automatically in the background if the sensor is exposed to clean and polluted air for approximately
* 30 minutes each.
*
* | Virtual sensor | Value | Accuracy description |
* |----------------------------|-------|-----------------------------------------------------------------|
* | IAQ | 0 | The sensor is not yet stabilized or in a run-in status |
* | | 1 | Calibration required |
* | | 2 | Calibration on-going |
* | | 3 | Calibration is done, now IAQ estimate achieves best performance |
*/
uint8_t accuracy;
} bsec_output_t;
/*!
* @brief Structure describing sample rate of physical/virtual sensors
*
* This structure is used together with bsec_update_subscription() to enable BSEC outputs and to retrieve information
* about the sample rates used for BSEC inputs.
*/
typedef struct
{
/**
* @brief Sample rate of the virtual or physical sensor in Hertz [Hz]
*
* Only supported sample rates are allowed.
*/
float sample_rate;
/**
* @brief Identifier of the virtual or physical sensor
*
* The meaning of this field changes depending on whether the structs are as the requested_virtual_sensors argument
* to bsec_update_subscription() or as the required_sensor_settings argument.
*
* | bsec_update_subscription() argument | sensor_id field interpretation |
* |-------------------------------------|--------------------------------|
* | requested_virtual_sensors | ::bsec_virtual_sensor_t |
* | required_sensor_settings | ::bsec_physical_sensor_t |
*
* @sa bsec_physical_sensor_t
* @sa bsec_virtual_sensor_t
*/
uint8_t sensor_id;
} bsec_sensor_configuration_t;
/*!
* @brief Structure returned by bsec_sensor_control() to configure BMExxx sensor
*
* This structure contains settings that must be used to configure the BMExxx to perform a forced-mode measurement.
* A measurement should only be executed if bsec_bme_settings_t::trigger_measurement is 1. If so, the oversampling
* settings for temperature, humidity, and pressure should be set to the provided settings provided in
* bsec_bme_settings_t::temperature_oversampling, bsec_bme_settings_t::humidity_oversampling, and
* bsec_bme_settings_t::pressure_oversampling, respectively.
*
* In case of bsec_bme_settings_t::run_gas = 1, the gas sensor must be enabled with the provided
* bsec_bme_settings_t::heater_temperature and bsec_bme_settings_t::heating_duration settings.
*/
typedef struct
{
int64_t next_call; /*!< @brief Time stamp of the next call of the sensor_control*/
uint32_t process_data; /*!< @brief Bit field describing which data is to be passed to bsec_do_steps() @sa BSEC_PROCESS_* */
uint16_t heater_temperature; /*!< @brief Heating temperature [degrees Celsius] */
uint16_t heating_duration; /*!< @brief Heating duration [ms] */
uint8_t run_gas; /*!< @brief Enable gas measurements [0/1] */
uint8_t pressure_oversampling; /*!< @brief Pressure oversampling settings [0-5] */
uint8_t temperature_oversampling; /*!< @brief Temperature oversampling settings [0-5] */
uint8_t humidity_oversampling; /*!< @brief Humidity oversampling settings [0-5] */
uint8_t trigger_measurement; /*!< @brief Trigger a forced measurement with these settings now [0/1] */
} bsec_bme_settings_t;
/* internal defines and backward compatibility */
#define BSEC_STRUCT_NAME Bsec /*!< Internal struct name */
/*@}*/
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,559 @@
/*
* Copyright (C) 2017 Robert Bosch. All Rights Reserved.
*
* Disclaimer
*
* Common:
* Bosch Sensortec products are developed for the consumer goods industry. They may only be used
* within the parameters of the respective valid product data sheet. Bosch Sensortec products are
* provided with the express understanding that there is no warranty of fitness for a particular purpose.
* They are not fit for use in life-sustaining, safety or security sensitive systems or any system or device
* that may lead to bodily harm or property damage if the system or device malfunctions. In addition,
* Bosch Sensortec products are not fit for use in products which interact with motor vehicle systems.
* The resale and/or use of products are at the purchasers own risk and his own responsibility. The
* examination of fitness for the intended use is the sole responsibility of the Purchaser.
*
* The purchaser shall indemnify Bosch Sensortec from all third party claims, including any claims for
* incidental, or consequential damages, arising from any product use not covered by the parameters of
* the respective valid product data sheet or not approved by Bosch Sensortec and reimburse Bosch
* Sensortec for all costs in connection with such claims.
*
* The purchaser must monitor the market for the purchased products, particularly with regard to
* product safety and inform Bosch Sensortec without delay of all security relevant incidents.
*
* Engineering Samples are marked with an asterisk (*) or (e). Samples may vary from the valid
* technical specifications of the product series. They are therefore not intended or fit for resale to third
* parties or for use in end products. Their sole purpose is internal client testing. The testing of an
* engineering sample may in no way replace the testing of a product series. Bosch Sensortec
* assumes no liability for the use of engineering samples. By accepting the engineering samples, the
* Purchaser agrees to indemnify Bosch Sensortec from all claims arising from the use of engineering
* samples.
*
* Special:
* This software module (hereinafter called "Software") and any information on application-sheets
* (hereinafter called "Information") is provided free of charge for the sole purpose to support your
* application work. The Software and Information is subject to the following terms and conditions:
*
* The Software is specifically designed for the exclusive use for Bosch Sensortec products by
* personnel who have special experience and training. Do not use this Software if you do not have the
* proper experience or training.
*
* This Software package is provided `` as is `` and without any expressed or implied warranties,
* including without limitation, the implied warranties of merchantability and fitness for a particular
* purpose.
*
* Bosch Sensortec and their representatives and agents deny any liability for the functional impairment
* of this Software in terms of fitness, performance and safety. Bosch Sensortec and their
* representatives and agents shall not be liable for any direct or indirect damages or injury, except as
* otherwise stipulated in mandatory applicable law.
*
* The Information provided is believed to be accurate and reliable. Bosch Sensortec assumes no
* responsibility for the consequences of use of such Information nor for any infringement of patents or
* other rights of third parties which may result from its use. No license is granted by implication or
* otherwise under any patent or patent rights of Bosch. Specifications mentioned in the Information are
* subject to change without notice.
*
* It is not allowed to deliver the source code of the Software to any third party without permission of
* Bosch Sensortec.
*
*/
/*!
* @file bsec_integration.c
*
* @brief
* Private part of the example for using of BSEC library.
*/
/*!
* @addtogroup bsec_examples BSEC Examples
* @brief BSEC usage examples
* @{*/
/**********************************************************************************************************************/
/* header files */
/**********************************************************************************************************************/
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include "bsec_integration.h"
/**********************************************************************************************************************/
/* local macro definitions */
/**********************************************************************************************************************/
#define NUM_USED_OUTPUTS 8
/**********************************************************************************************************************/
/* global variable declarations */
/**********************************************************************************************************************/
/* Global sensor APIs data structure */
static struct bme680_dev bme680_g;
/* Global temperature offset to be subtracted */
static float bme680_temperature_offset_g = 0.0f;
/**********************************************************************************************************************/
/* functions */
/**********************************************************************************************************************/
/*!
* @brief Virtual sensor subscription
* Please call this function before processing of data using bsec_do_steps function
*
* @param[in] sample_rate mode to be used (either BSEC_SAMPLE_RATE_ULP or BSEC_SAMPLE_RATE_LP)
*
* @return subscription result, zero when successful
*/
static bsec_library_return_t bme680_bsec_update_subscription(float sample_rate)
{
bsec_sensor_configuration_t requested_virtual_sensors[NUM_USED_OUTPUTS];
uint8_t n_requested_virtual_sensors = NUM_USED_OUTPUTS;
bsec_sensor_configuration_t required_sensor_settings[BSEC_MAX_PHYSICAL_SENSOR];
uint8_t n_required_sensor_settings = BSEC_MAX_PHYSICAL_SENSOR;
bsec_library_return_t status = BSEC_OK;
/* note: Virtual sensors as desired to be added here */
requested_virtual_sensors[0].sensor_id = BSEC_OUTPUT_IAQ;
requested_virtual_sensors[0].sample_rate = sample_rate;
requested_virtual_sensors[1].sensor_id = BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE;
requested_virtual_sensors[1].sample_rate = sample_rate;
requested_virtual_sensors[2].sensor_id = BSEC_OUTPUT_RAW_PRESSURE;
requested_virtual_sensors[2].sample_rate = sample_rate;
requested_virtual_sensors[3].sensor_id = BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY;
requested_virtual_sensors[3].sample_rate = sample_rate;
requested_virtual_sensors[4].sensor_id = BSEC_OUTPUT_RAW_GAS;
requested_virtual_sensors[4].sample_rate = sample_rate;
requested_virtual_sensors[5].sensor_id = BSEC_OUTPUT_RAW_TEMPERATURE;
requested_virtual_sensors[5].sample_rate = sample_rate;
requested_virtual_sensors[6].sensor_id = BSEC_OUTPUT_RAW_HUMIDITY;
requested_virtual_sensors[6].sample_rate = sample_rate;
requested_virtual_sensors[7].sensor_id = BSEC_OUTPUT_STATIC_IAQ;
requested_virtual_sensors[7].sample_rate = sample_rate;
/* Call bsec_update_subscription() to enable/disable the requested virtual sensors */
status = bsec_update_subscription(requested_virtual_sensors, n_requested_virtual_sensors, required_sensor_settings,
&n_required_sensor_settings);
return status;
}
/*!
* @brief Initialize the BME680 sensor and the BSEC library
*
* @param[in] sample_rate mode to be used (either BSEC_SAMPLE_RATE_ULP or BSEC_SAMPLE_RATE_LP)
* @param[in] temperature_offset device-specific temperature offset (due to self-heating)
* @param[in] bus_write pointer to the bus writing function
* @param[in] bus_read pointer to the bus reading function
* @param[in] sleep pointer to the system specific sleep function
* @param[in] state_load pointer to the system-specific state load function
* @param[in] config_load pointer to the system-specific config load function
*
* @return zero if successful, negative otherwise
*/
return_values_init bsec_iot_init(float sample_rate, float temperature_offset, bme680_com_fptr_t bus_write,
bme680_com_fptr_t bus_read, sleep_fct sleep, state_load_fct state_load, config_load_fct config_load)
{
return_values_init ret = {BME680_OK, BSEC_OK};
bsec_library_return_t bsec_status = BSEC_OK;
uint8_t bsec_state[BSEC_MAX_PROPERTY_BLOB_SIZE] = {0};
uint8_t bsec_config[BSEC_MAX_PROPERTY_BLOB_SIZE] = {0};
uint8_t work_buffer[BSEC_MAX_PROPERTY_BLOB_SIZE] = {0};
int bsec_state_len, bsec_config_len;
/* Fixed I2C configuration */
bme680_g.dev_id = BME680_I2C_ADDR_PRIMARY;
bme680_g.intf = BME680_I2C_INTF;
/* User configurable I2C configuration */
bme680_g.write = bus_write;
bme680_g.read = bus_read;
bme680_g.delay_ms = sleep;
/* Initialize BME680 API */
ret.bme680_status = bme680_init(&bme680_g);
if (ret.bme680_status != BME680_OK)
{
return ret;
}
/* Initialize BSEC library */
ret.bsec_status = bsec_init();
if (ret.bsec_status != BSEC_OK)
{
return ret;
}
/* Load library config, if available */
bsec_config_len = config_load(bsec_config, sizeof(bsec_config));
if (bsec_config_len != 0)
{
ret.bsec_status = bsec_set_configuration(bsec_config, bsec_config_len, work_buffer, sizeof(work_buffer));
if (ret.bsec_status != BSEC_OK)
{
return ret;
}
}
/* Load previous library state, if available */
bsec_state_len = state_load(bsec_state, sizeof(bsec_state));
if (bsec_state_len != 0)
{
ret.bsec_status = bsec_set_state(bsec_state, bsec_state_len, work_buffer, sizeof(work_buffer));
if (ret.bsec_status != BSEC_OK)
{
return ret;
}
}
/* Set temperature offset */
bme680_temperature_offset_g = temperature_offset;
/* Call to the function which sets the library with subscription information */
ret.bsec_status = bme680_bsec_update_subscription(sample_rate);
if (ret.bsec_status != BSEC_OK)
{
return ret;
}
return ret;
}
/*!
* @brief Trigger the measurement based on sensor settings
*
* @param[in] sensor_settings settings of the BME680 sensor adopted by sensor control function
* @param[in] sleep pointer to the system specific sleep function
*
* @return none
*/
static void bme680_bsec_trigger_measurement(bsec_bme_settings_t *sensor_settings, sleep_fct sleep)
{
uint16_t meas_period;
uint8_t set_required_settings;
int8_t bme680_status = BME680_OK;
/* Check if a forced-mode measurement should be triggered now */
if (sensor_settings->trigger_measurement)
{
/* Set sensor configuration */
bme680_g.tph_sett.os_hum = sensor_settings->humidity_oversampling;
bme680_g.tph_sett.os_pres = sensor_settings->pressure_oversampling;
bme680_g.tph_sett.os_temp = sensor_settings->temperature_oversampling;
bme680_g.gas_sett.run_gas = sensor_settings->run_gas;
bme680_g.gas_sett.heatr_temp = sensor_settings->heater_temperature; /* degree Celsius */
bme680_g.gas_sett.heatr_dur = sensor_settings->heating_duration; /* milliseconds */
/* Select the power mode */
/* Must be set before writing the sensor configuration */
bme680_g.power_mode = BME680_FORCED_MODE;
/* Set the required sensor settings needed */
set_required_settings = BME680_OST_SEL | BME680_OSP_SEL | BME680_OSH_SEL | BME680_GAS_SENSOR_SEL;
/* Set the desired sensor configuration */
bme680_status = bme680_set_sensor_settings(set_required_settings, &bme680_g);
/* Set power mode as forced mode and trigger forced mode measurement */
bme680_status = bme680_set_sensor_mode(&bme680_g);
/* Get the total measurement duration so as to sleep or wait till the measurement is complete */
bme680_get_profile_dur(&meas_period, &bme680_g);
/* Delay till the measurement is ready. Timestamp resolution in ms */
sleep((uint32_t)meas_period);
}
/* Call the API to get current operation mode of the sensor */
bme680_status = bme680_get_sensor_mode(&bme680_g);
/* When the measurement is completed and data is ready for reading, the sensor must be in BME680_SLEEP_MODE.
* Read operation mode to check whether measurement is completely done and wait until the sensor is no more
* in BME680_FORCED_MODE. */
while (bme680_g.power_mode == BME680_FORCED_MODE)
{
/* sleep for 5 ms */
sleep(5);
bme680_status = bme680_get_sensor_mode(&bme680_g);
}
}
/*!
* @brief Read the data from registers and populate the inputs structure to be passed to do_steps function
*
* @param[in] time_stamp_trigger settings of the sensor returned from sensor control function
* @param[in] inputs input structure containing the information on sensors to be passed to do_steps
* @param[in] num_bsec_inputs number of inputs to be passed to do_steps
* @param[in] bsec_process_data process data variable returned from sensor_control
*
* @return none
*/
static void bme680_bsec_read_data(int64_t time_stamp_trigger, bsec_input_t *inputs, uint8_t *num_bsec_inputs,
int32_t bsec_process_data)
{
static struct bme680_field_data data;
int8_t bme680_status = BME680_OK;
/* We only have to read data if the previous call the bsec_sensor_control() actually asked for it */
if (bsec_process_data)
{
bme680_status = bme680_get_sensor_data(&data, &bme680_g);
if (data.status & BME680_NEW_DATA_MSK)
{
/* Pressure to be processed by BSEC */
if (bsec_process_data & BSEC_PROCESS_PRESSURE)
{
/* Place presssure sample into input struct */
inputs[*num_bsec_inputs].sensor_id = BSEC_INPUT_PRESSURE;
inputs[*num_bsec_inputs].signal = data.pressure;
inputs[*num_bsec_inputs].time_stamp = time_stamp_trigger;
(*num_bsec_inputs)++;
}
/* Temperature to be processed by BSEC */
if (bsec_process_data & BSEC_PROCESS_TEMPERATURE)
{
/* Place temperature sample into input struct */
inputs[*num_bsec_inputs].sensor_id = BSEC_INPUT_TEMPERATURE;
#ifdef BME680_FLOAT_POINT_COMPENSATION
inputs[*num_bsec_inputs].signal = data.temperature;
#else
inputs[*num_bsec_inputs].signal = data.temperature / 100.0f;
#endif
inputs[*num_bsec_inputs].time_stamp = time_stamp_trigger;
(*num_bsec_inputs)++;
/* Also add optional heatsource input which will be subtracted from the temperature reading to
* compensate for device-specific self-heating (supported in BSEC IAQ solution)*/
inputs[*num_bsec_inputs].sensor_id = BSEC_INPUT_HEATSOURCE;
inputs[*num_bsec_inputs].signal = bme680_temperature_offset_g;
inputs[*num_bsec_inputs].time_stamp = time_stamp_trigger;
(*num_bsec_inputs)++;
}
/* Humidity to be processed by BSEC */
if (bsec_process_data & BSEC_PROCESS_HUMIDITY)
{
/* Place humidity sample into input struct */
inputs[*num_bsec_inputs].sensor_id = BSEC_INPUT_HUMIDITY;
#ifdef BME680_FLOAT_POINT_COMPENSATION
inputs[*num_bsec_inputs].signal = data.humidity;
#else
inputs[*num_bsec_inputs].signal = data.humidity / 1000.0f;
#endif
inputs[*num_bsec_inputs].time_stamp = time_stamp_trigger;
(*num_bsec_inputs)++;
}
/* Gas to be processed by BSEC */
if (bsec_process_data & BSEC_PROCESS_GAS)
{
/* Check whether gas_valid flag is set */
if(data.status & BME680_GASM_VALID_MSK)
{
/* Place sample into input struct */
inputs[*num_bsec_inputs].sensor_id = BSEC_INPUT_GASRESISTOR;
inputs[*num_bsec_inputs].signal = data.gas_resistance;
inputs[*num_bsec_inputs].time_stamp = time_stamp_trigger;
(*num_bsec_inputs)++;
}
}
}
}
}
/*!
* @brief This function is written to process the sensor data for the requested virtual sensors
*
* @param[in] bsec_inputs input structure containing the information on sensors to be passed to do_steps
* @param[in] num_bsec_inputs number of inputs to be passed to do_steps
* @param[in] output_ready pointer to the function processing obtained BSEC outputs
*
* @return none
*/
static void bme680_bsec_process_data(bsec_input_t *bsec_inputs, uint8_t num_bsec_inputs, output_ready_fct output_ready)
{
/* Output buffer set to the maximum virtual sensor outputs supported */
bsec_output_t bsec_outputs[BSEC_NUMBER_OUTPUTS];
uint8_t num_bsec_outputs = 0;
uint8_t index = 0;
bsec_library_return_t bsec_status = BSEC_OK;
int64_t timestamp = 0;
float iaq = 0.0f;
uint8_t iaq_accuracy = 0;
float temp = 0.0f;
float raw_temp = 0.0f;
float raw_pressure = 0.0f;
float humidity = 0.0f;
float raw_humidity = 0.0f;
float raw_gas = 0.0f;
float static_iaq = 0.0f;
uint8_t static_iaq_accuracy = 0;
float co2_equivalent = 0.0f;
uint8_t co2_accuracy = 0;
float breath_voc_equivalent = 0.0f;
uint8_t breath_voc_accuracy = 0;
float comp_gas_value = 0.0f;
uint8_t comp_gas_accuracy = 0;
float gas_percentage = 0.0f;
uint8_t gas_percentage_acccuracy = 0;
/* Check if something should be processed by BSEC */
if (num_bsec_inputs > 0)
{
/* Set number of outputs to the size of the allocated buffer */
/* BSEC_NUMBER_OUTPUTS to be defined */
num_bsec_outputs = BSEC_NUMBER_OUTPUTS;
/* Perform processing of the data by BSEC
Note:
* The number of outputs you get depends on what you asked for during bsec_update_subscription(). This is
handled under bme680_bsec_update_subscription() function in this example file.
* The number of actual outputs that are returned is written to num_bsec_outputs. */
bsec_status = bsec_do_steps(bsec_inputs, num_bsec_inputs, bsec_outputs, &num_bsec_outputs);
/* Iterate through the outputs and extract the relevant ones. */
for (index = 0; index < num_bsec_outputs; index++)
{
switch (bsec_outputs[index].sensor_id)
{
case BSEC_OUTPUT_IAQ:
iaq = bsec_outputs[index].signal;
iaq_accuracy = bsec_outputs[index].accuracy;
break;
case BSEC_OUTPUT_STATIC_IAQ:
static_iaq = bsec_outputs[index].signal;
static_iaq_accuracy = bsec_outputs[index].accuracy;
break;
case BSEC_OUTPUT_CO2_EQUIVALENT:
co2_equivalent = bsec_outputs[index].signal;
co2_accuracy = bsec_outputs[index].accuracy;
break;
case BSEC_OUTPUT_BREATH_VOC_EQUIVALENT:
breath_voc_equivalent = bsec_outputs[index].signal;
breath_voc_accuracy = bsec_outputs[index].accuracy;
break;
case BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE:
temp = bsec_outputs[index].signal;
break;
case BSEC_OUTPUT_RAW_PRESSURE:
raw_pressure = bsec_outputs[index].signal;
break;
case BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY:
humidity = bsec_outputs[index].signal;
break;
case BSEC_OUTPUT_RAW_GAS:
raw_gas = bsec_outputs[index].signal;
break;
case BSEC_OUTPUT_RAW_TEMPERATURE:
raw_temp = bsec_outputs[index].signal;
break;
case BSEC_OUTPUT_RAW_HUMIDITY:
raw_humidity = bsec_outputs[index].signal;
break;
case BSEC_OUTPUT_COMPENSATED_GAS:
comp_gas_value = bsec_outputs[index].signal;
comp_gas_accuracy = bsec_outputs[index].accuracy;
break;
case BSEC_OUTPUT_GAS_PERCENTAGE:
gas_percentage = bsec_outputs[index].signal;
gas_percentage_acccuracy = bsec_outputs[index].accuracy;
break;
default:
continue;
}
/* Assume that all the returned timestamps are the same */
timestamp = bsec_outputs[index].time_stamp;
}
/* Pass the extracted outputs to the user provided output_ready() function. */
output_ready(timestamp, iaq, iaq_accuracy, temp, humidity, raw_pressure, raw_temp,
raw_humidity, raw_gas, bsec_status, static_iaq, co2_equivalent, breath_voc_equivalent);
}
}
/*!
* @brief Runs the main (endless) loop that queries sensor settings, applies them, and processes the measured data
*
* @param[in] sleep pointer to the system specific sleep function
* @param[in] get_timestamp_us pointer to the system specific timestamp derivation function
* @param[in] output_ready pointer to the function processing obtained BSEC outputs
* @param[in] state_save pointer to the system-specific state save function
* @param[in] save_intvl interval at which BSEC state should be saved (in samples)
*
* @return none
*/
void bsec_iot_loop(sleep_fct sleep, get_timestamp_us_fct get_timestamp_us, output_ready_fct output_ready,
state_save_fct state_save, uint32_t save_intvl)
{
/* Timestamp variables */
int64_t time_stamp = 0;
int64_t time_stamp_interval_ms = 0;
/* Allocate enough memory for up to BSEC_MAX_PHYSICAL_SENSOR physical inputs*/
bsec_input_t bsec_inputs[BSEC_MAX_PHYSICAL_SENSOR];
/* Number of inputs to BSEC */
uint8_t num_bsec_inputs = 0;
/* BSEC sensor settings struct */
bsec_bme_settings_t sensor_settings;
/* Save state variables */
uint8_t bsec_state[BSEC_MAX_STATE_BLOB_SIZE];
uint8_t work_buffer[BSEC_MAX_STATE_BLOB_SIZE];
uint32_t bsec_state_len = 0;
uint32_t n_samples = 0;
bsec_library_return_t bsec_status = BSEC_OK;
while (1)
{
/* get the timestamp in nanoseconds before calling bsec_sensor_control() */
time_stamp = get_timestamp_us() * 1000;
/* Retrieve sensor settings to be used in this time instant by calling bsec_sensor_control */
bsec_sensor_control(time_stamp, &sensor_settings);
/* Trigger a measurement if necessary */
bme680_bsec_trigger_measurement(&sensor_settings, sleep);
/* Read data from last measurement */
num_bsec_inputs = 0;
bme680_bsec_read_data(time_stamp, bsec_inputs, &num_bsec_inputs, sensor_settings.process_data);
/* Time to invoke BSEC to perform the actual processing */
bme680_bsec_process_data(bsec_inputs, num_bsec_inputs, output_ready);
/* Increment sample counter */
n_samples++;
/* Retrieve and store state if the passed save_intvl */
if (n_samples >= save_intvl)
{
bsec_status = bsec_get_state(0, bsec_state, sizeof(bsec_state), work_buffer, sizeof(work_buffer), &bsec_state_len);
if (bsec_status == BSEC_OK)
{
state_save(bsec_state, bsec_state_len);
}
n_samples = 0;
}
/* Compute how long we can sleep until we need to call bsec_sensor_control() next */
/* Time_stamp is converted from microseconds to nanoseconds first and then the difference to milliseconds */
time_stamp_interval_ms = (sensor_settings.next_call - get_timestamp_us() * 1000) / 1000000;
if (time_stamp_interval_ms > 0)
{
sleep((uint32_t)time_stamp_interval_ms);
}
}
}
/*! @}*/

View File

@ -0,0 +1,165 @@
/*
* Copyright (C) 2017 Robert Bosch. All Rights Reserved.
*
* Disclaimer
*
* Common:
* Bosch Sensortec products are developed for the consumer goods industry. They may only be used
* within the parameters of the respective valid product data sheet. Bosch Sensortec products are
* provided with the express understanding that there is no warranty of fitness for a particular purpose.
* They are not fit for use in life-sustaining, safety or security sensitive systems or any system or device
* that may lead to bodily harm or property damage if the system or device malfunctions. In addition,
* Bosch Sensortec products are not fit for use in products which interact with motor vehicle systems.
* The resale and/or use of products are at the purchasers own risk and his own responsibility. The
* examination of fitness for the intended use is the sole responsibility of the Purchaser.
*
* The purchaser shall indemnify Bosch Sensortec from all third party claims, including any claims for
* incidental, or consequential damages, arising from any product use not covered by the parameters of
* the respective valid product data sheet or not approved by Bosch Sensortec and reimburse Bosch
* Sensortec for all costs in connection with such claims.
*
* The purchaser must monitor the market for the purchased products, particularly with regard to
* product safety and inform Bosch Sensortec without delay of all security relevant incidents.
*
* Engineering Samples are marked with an asterisk (*) or (e). Samples may vary from the valid
* technical specifications of the product series. They are therefore not intended or fit for resale to third
* parties or for use in end products. Their sole purpose is internal client testing. The testing of an
* engineering sample may in no way replace the testing of a product series. Bosch Sensortec
* assumes no liability for the use of engineering samples. By accepting the engineering samples, the
* Purchaser agrees to indemnify Bosch Sensortec from all claims arising from the use of engineering
* samples.
*
* Special:
* This software module (hereinafter called "Software") and any information on application-sheets
* (hereinafter called "Information") is provided free of charge for the sole purpose to support your
* application work. The Software and Information is subject to the following terms and conditions:
*
* The Software is specifically designed for the exclusive use for Bosch Sensortec products by
* personnel who have special experience and training. Do not use this Software if you do not have the
* proper experience or training.
*
* This Software package is provided `` as is `` and without any expressed or implied warranties,
* including without limitation, the implied warranties of merchantability and fitness for a particular
* purpose.
*
* Bosch Sensortec and their representatives and agents deny any liability for the functional impairment
* of this Software in terms of fitness, performance and safety. Bosch Sensortec and their
* representatives and agents shall not be liable for any direct or indirect damages or injury, except as
* otherwise stipulated in mandatory applicable law.
*
* The Information provided is believed to be accurate and reliable. Bosch Sensortec assumes no
* responsibility for the consequences of use of such Information nor for any infringement of patents or
* other rights of third parties which may result from its use. No license is granted by implication or
* otherwise under any patent or patent rights of Bosch. Specifications mentioned in the Information are
* subject to change without notice.
*
* It is not allowed to deliver the source code of the Software to any third party without permission of
* Bosch Sensortec.
*
*/
/*!
* @file bsec_integration.h
*
* @brief
* Contains BSEC integration API
*/
/*!
* @addtogroup bsec_examples BSEC Examples
* @brief BSEC usage examples
* @{*/
#ifndef __BSEC_INTEGRATION_H__
#define __BSEC_INTEGRATION_H__
#ifdef __cplusplus
extern "C"
{
#endif
/**********************************************************************************************************************/
/* header files */
/**********************************************************************************************************************/
/* Use the following bme680 driver: https://github.com/BoschSensortec/BME680_driver/releases/tag/bme680_v3.5.1 */
#include "bme680.h"
/* BSEC header files are available in the inc/ folder of the release package */
#include "bsec_interface.h"
#include "bsec_datatypes.h"
/**********************************************************************************************************************/
/* type definitions */
/**********************************************************************************************************************/
/* function pointer to the system specific sleep function */
typedef void (*sleep_fct)(uint32_t t_ms);
/* function pointer to the system specific timestamp derivation function */
typedef int64_t (*get_timestamp_us_fct)();
/* function pointer to the function processing obtained BSEC outputs */
typedef void (*output_ready_fct)(int64_t timestamp, float iaq, uint8_t iaq_accuracy, float temperature, float humidity,
float pressure, float raw_temperature, float raw_humidity, float gas, bsec_library_return_t bsec_status,
float static_iaq, float co2_equivalent, float breath_voc_equivalent);
/* function pointer to the function loading a previous BSEC state from NVM */
typedef uint32_t (*state_load_fct)(uint8_t *state_buffer, uint32_t n_buffer);
/* function pointer to the function saving BSEC state to NVM */
typedef void (*state_save_fct)(const uint8_t *state_buffer, uint32_t length);
/* function pointer to the function loading the BSEC configuration string from NVM */
typedef uint32_t (*config_load_fct)(uint8_t *state_buffer, uint32_t n_buffer);
/* structure definitions */
/* Structure with the return value from bsec_iot_init() */
typedef struct{
/*! Result of API execution status */
int8_t bme680_status;
/*! Result of BSEC library */
bsec_library_return_t bsec_status;
}return_values_init;
/**********************************************************************************************************************/
/* function declarations */
/**********************************************************************************************************************/
/*!
* @brief Initialize the BME680 sensor and the BSEC library
*
* @param[in] sample_rate mode to be used (either BSEC_SAMPLE_RATE_ULP or BSEC_SAMPLE_RATE_LP)
* @param[in] temperature_offset device-specific temperature offset (due to self-heating)
* @param[in] bus_write pointer to the bus writing function
* @param[in] bus_read pointer to the bus reading function
* @param[in] sleep pointer to the system-specific sleep function
* @param[in] state_load pointer to the system-specific state load function
*
* @return zero if successful, negative otherwise
*/
return_values_init bsec_iot_init(float sample_rate, float temperature_offset, bme680_com_fptr_t bus_write, bme680_com_fptr_t bus_read,
sleep_fct sleep, state_load_fct state_load, config_load_fct config_load);
/*!
* @brief Runs the main (endless) loop that queries sensor settings, applies them, and processes the measured data
*
* @param[in] sleep pointer to the system-specific sleep function
* @param[in] get_timestamp_us pointer to the system-specific timestamp derivation function
* @param[in] output_ready pointer to the function processing obtained BSEC outputs
* @param[in] state_save pointer to the system-specific state save function
* @param[in] save_intvl interval at which BSEC state should be saved (in samples)
*
* @return return_values_init struct with the result of the API and the BSEC library
*/
void bsec_iot_loop(sleep_fct sleep, get_timestamp_us_fct get_timestamp_us, output_ready_fct output_ready,
state_save_fct state_save, uint32_t save_intvl);
#ifdef __cplusplus
}
#endif
#endif /* __BSEC_INTEGRATION_H__ */
/*! @}*/

View File

@ -0,0 +1,564 @@
/*
* Copyright (C) 2015, 2016, 2017 Robert Bosch. All Rights Reserved.
*
* Disclaimer
*
* Common:
* Bosch Sensortec products are developed for the consumer goods industry. They may only be used
* within the parameters of the respective valid product data sheet. Bosch Sensortec products are
* provided with the express understanding that there is no warranty of fitness for a particular purpose.
* They are not fit for use in life-sustaining, safety or security sensitive systems or any system or device
* that may lead to bodily harm or property damage if the system or device malfunctions. In addition,
* Bosch Sensortec products are not fit for use in products which interact with motor vehicle systems.
* The resale and/or use of products are at the purchasers own risk and his own responsibility. The
* examination of fitness for the intended use is the sole responsibility of the Purchaser.
*
* The purchaser shall indemnify Bosch Sensortec from all third party claims, including any claims for
* incidental, or consequential damages, arising from any product use not covered by the parameters of
* the respective valid product data sheet or not approved by Bosch Sensortec and reimburse Bosch
* Sensortec for all costs in connection with such claims.
*
* The purchaser must monitor the market for the purchased products, particularly with regard to
* product safety and inform Bosch Sensortec without delay of all security relevant incidents.
*
* Engineering Samples are marked with an asterisk (*) or (e). Samples may vary from the valid
* technical specifications of the product series. They are therefore not intended or fit for resale to third
* parties or for use in end products. Their sole purpose is internal client testing. The testing of an
* engineering sample may in no way replace the testing of a product series. Bosch Sensortec
* assumes no liability for the use of engineering samples. By accepting the engineering samples, the
* Purchaser agrees to indemnify Bosch Sensortec from all claims arising from the use of engineering
* samples.
*
* Special:
* This software module (hereinafter called "Software") and any information on application-sheets
* (hereinafter called "Information") is provided free of charge for the sole purpose to support your
* application work. The Software and Information is subject to the following terms and conditions:
*
* The Software is specifically designed for the exclusive use for Bosch Sensortec products by
* personnel who have special experience and training. Do not use this Software if you do not have the
* proper experience or training.
*
* This Software package is provided `` as is `` and without any expressed or implied warranties,
* including without limitation, the implied warranties of merchantability and fitness for a particular
* purpose.
*
* Bosch Sensortec and their representatives and agents deny any liability for the functional impairment
* of this Software in terms of fitness, performance and safety. Bosch Sensortec and their
* representatives and agents shall not be liable for any direct or indirect damages or injury, except as
* otherwise stipulated in mandatory applicable law.
*
* The Information provided is believed to be accurate and reliable. Bosch Sensortec assumes no
* responsibility for the consequences of use of such Information nor for any infringement of patents or
* other rights of third parties which may result from its use. No license is granted by implication or
* otherwise under any patent or patent rights of Bosch. Specifications mentioned in the Information are
* subject to change without notice.
*
* It is not allowed to deliver the source code of the Software to any third party without permission of
* Bosch Sensortec.
*
*/
/*!
*
* @file bsec_interface.h
*
* @brief
* Contains the API for BSEC
*
*/
#ifndef __BSEC_INTERFACE_H__
#define __BSEC_INTERFACE_H__
#include "bsec_datatypes.h"
#ifdef __cplusplus
extern "C" {
#endif
/*! @addtogroup bsec_interface BSEC C Interface
* @brief Interfaces of BSEC signal processing library
*
* ### Interface usage
*
* The following provides a short overview on the typical operation sequence for BSEC.
*
* - Initialization of the library
*
* | Steps | Function |
* |---------------------------------------------------------------------|--------------------------|
* | Initialization of library | bsec_init() |
* | Update configuration settings (optional) | bsec_set_configuration() |
* | Restore the state of the library (optional) | bsec_set_state() |
*
*
* - The following function is called to enable output signals and define their sampling rate / operation mode.
*
* | Steps | Function |
* |---------------------------------------------|----------------------------|
* | Enable library outputs with specified mode | bsec_update_subscription() |
*
*
* - This table describes the main processing loop.
*
* | Steps | Function |
* |-------------------------------------------|----------------------------------|
* | Retrieve sensor settings to be used | bsec_sensor_control() |
* | Configure sensor and trigger measurement | See BME680 API and example codes |
* | Read results from sensor | See BME680 API and example codes |
* | Perform signal processing | bsec_do_steps() |
*
*
* - Before shutting down the system, the current state of BSEC can be retrieved and can then be used during
* re-initialization to continue processing.
*
* | Steps | Function |
* |----------------------------------------|-------------------|
* | To retrieve the current library state | bsec_get_state() |
*
*
*
* ### Configuration and state
*
* Values of variables belonging to a BSEC instance are divided into two groups:
* - Values **not updated by processing** of signals belong to the **configuration group**. If available, BSEC can be
* configured before use with a customer specific configuration string.
* - Values **updated during processing** are member of the **state group**. Saving and restoring of the state of BSEC
* is necessary to maintain previously estimated sensor models and baseline information which is important for best
* performance of the gas sensor outputs.
*
* @note BSEC library consists of adaptive algorithms which models the gas sensor which improves its performance over
* the time. These will be lost if library is initialized due to system reset. In order to avoid this situation
* library state shall be stored in non volatile memory so that it can be loaded after system reset.
*
*
* @{
*/
/*!
* @brief Return the version information of BSEC library
*
* @param [out] bsec_version_p pointer to struct which is to be populated with the version information
*
* @return Zero if successful, otherwise an error code
*
* See also: bsec_version_t
*
\code{.c}
// Example //
bsec_version_t version;
bsec_get_version(&version);
printf("BSEC version: %d.%d.%d.%d",version.major, version.minor, version.major_bugfix, version.minor_bugfix);
\endcode
*/
bsec_library_return_t bsec_get_version(bsec_version_t * bsec_version_p);
/*!
* @brief Initialize the library
*
* Initialization and reset of BSEC is performed by calling bsec_init(). Calling this function sets up the relation
* among all internal modules, initializes run-time dependent library states and resets the configuration and state
* of all BSEC signal processing modules to defaults.
*
* Before any further use, the library must be initialized. This ensure that all memory and states are in defined
* conditions prior to processing any data.
*
* @return Zero if successful, otherwise an error code
*
\code{.c}
// Initialize BSEC library before further use
bsec_init();
\endcode
*/
bsec_library_return_t bsec_init(void);
/*!
* @brief Subscribe to library virtual sensors outputs
*
* Use bsec_update_subscription() to instruct BSEC which of the processed output signals are requested at which sample rates.
* See ::bsec_virtual_sensor_t for available library outputs.
*
* Based on the requested virtual sensors outputs, BSEC will provide information about the required physical sensor input signals
* (see ::bsec_physical_sensor_t) with corresponding sample rates. This information is purely informational as bsec_sensor_control()
* will ensure the sensor is operated in the required manner. To disable a virtual sensor, set the sample rate to BSEC_SAMPLE_RATE_DISABLED.
*
* The subscription update using bsec_update_subscription() is apart from the signal processing one of the the most
* important functions. It allows to enable the desired library outputs. The function determines which physical input
* sensor signals are required at which sample rate to produce the virtual output sensor signals requested by the user.
* When this function returns with success, the requested outputs are called subscribed. A very important feature is the
* retaining of already subscribed outputs. Further outputs can be requested or disabled both individually and
* group-wise in addition to already subscribed outputs without changing them unless a change of already subscribed
* outputs is requested.
*
* @note The state of the library concerning the subscribed outputs cannot be retained among reboots.
*
* The interface of bsec_update_subscription() requires the usage of arrays of sensor configuration structures.
* Such a structure has the fields sensor identifier and sample rate. These fields have the properties:
* - Output signals of virtual sensors must be requested using unique identifiers (Member of ::bsec_virtual_sensor_t)
* - Different sets of identifiers are available for inputs of physical sensors and outputs of virtual sensors
* - Identifiers are unique values defined by the library, not from external
* - Sample rates must be provided as value of
* - An allowed sample rate for continuously sampled signals
* - 65535.0f (BSEC_SAMPLE_RATE_DISABLED) to turn off outputs and identify disabled inputs
*
* @note The same sensor identifiers are also used within the functions bsec_do_steps().
*
* The usage principles of bsec_update_subscription() are:
* - Differential updates (i.e., only asking for outputs that the user would like to change) is supported.
* - Invalid requests of outputs are ignored. Also if one of the requested outputs is unavailable, all the requests
* are ignored. At the same time, a warning is returned.
* - To disable BSEC, all outputs shall be turned off. Only enabled (subscribed) outputs have to be disabled while
* already disabled outputs do not have to be disabled explicitly.
*
* @param[in] requested_virtual_sensors Pointer to array of requested virtual sensor (output) configurations for the library
* @param[in] n_requested_virtual_sensors Number of virtual sensor structs pointed by requested_virtual_sensors
* @param[out] required_sensor_settings Pointer to array of required physical sensor configurations for the library
* @param[in,out] n_required_sensor_settings [in] Size of allocated required_sensor_settings array, [out] number of sensor configurations returned
*
* @return Zero when successful, otherwise an error code
*
* @sa bsec_sensor_configuration_t
* @sa bsec_physical_sensor_t
* @sa bsec_virtual_sensor_t
*
\code{.c}
// Example //
// Change 3 virtual sensors (switch IAQ and raw temperature -> on / pressure -> off)
bsec_sensor_configuration_t requested_virtual_sensors[3];
uint8_t n_requested_virtual_sensors = 3;
requested_virtual_sensors[0].sensor_id = BSEC_OUTPUT_IAQ;
requested_virtual_sensors[0].sample_rate = BSEC_SAMPLE_RATE_ULP;
requested_virtual_sensors[1].sensor_id = BSEC_OUTPUT_RAW_TEMPERATURE;
requested_virtual_sensors[1].sample_rate = BSEC_SAMPLE_RATE_ULP;
requested_virtual_sensors[2].sensor_id = BSEC_OUTPUT_RAW_PRESSURE;
requested_virtual_sensors[2].sample_rate = BSEC_SAMPLE_RATE_DISABLED;
// Allocate a struct for the returned physical sensor settings
bsec_sensor_configuration_t required_sensor_settings[BSEC_MAX_PHYSICAL_SENSOR];
uint8_t n_required_sensor_settings = BSEC_MAX_PHYSICAL_SENSOR;
// Call bsec_update_subscription() to enable/disable the requested virtual sensors
bsec_update_subscription(requested_virtual_sensors, n_requested_virtual_sensors, required_sensor_settings, &n_required_sensor_settings);
\endcode
*
*/
bsec_library_return_t bsec_update_subscription(const bsec_sensor_configuration_t * const requested_virtual_sensors,
const uint8_t n_requested_virtual_sensors, bsec_sensor_configuration_t * required_sensor_settings,
uint8_t * n_required_sensor_settings);
/*!
* @brief Main signal processing function of BSEC
*
*
* Processing of the input signals and returning of output samples is performed by bsec_do_steps().
* - The samples of all library inputs must be passed with unique identifiers representing the input signals from
* physical sensors where the order of these inputs can be chosen arbitrary. However, all input have to be provided
* within the same time period as they are read. A sequential provision to the library might result in undefined
* behavior.
* - The samples of all library outputs are returned with unique identifiers corresponding to the output signals of
* virtual sensors where the order of the returned outputs may be arbitrary.
* - The samples of all input as well as output signals of physical as well as virtual sensors use the same
* representation in memory with the following fields:
* - Sensor identifier:
* - For inputs: required to identify the input signal from a physical sensor
* - For output: overwritten by bsec_do_steps() to identify the returned signal from a virtual sensor
* - Time stamp of the sample
*
* Calling bsec_do_steps() requires the samples of the input signals to be provided along with their time stamp when
* they are recorded and only when they are acquired. Repetition of samples with the same time stamp are ignored and
* result in a warning. Repetition of values of samples which are not acquired anew by a sensor result in deviations
* of the computed output signals. Concerning the returned output samples, an important feature is, that a value is
* returned for an output only when a new occurrence has been computed. A sample of an output signal is returned only
* once.
*
*
* @param[in] inputs Array of input data samples. Each array element represents a sample of a different physical sensor.
* @param[in] n_inputs Number of passed input data structs.
* @param[out] outputs Array of output data samples. Each array element represents a sample of a different virtual sensor.
* @param[in,out] n_outputs [in] Number of allocated output structs, [out] number of outputs returned
*
* @return Zero when successful, otherwise an error code
*
\code{.c}
// Example //
// Allocate input and output memory
bsec_input_t input[3];
uint8_t n_input = 3;
bsec_output_t output[2];
uint8_t n_output=2;
bsec_library_return_t status;
// Populate the input structs, assuming the we have timestamp (ts),
// gas sensor resistance (R), temperature (T), and humidity (rH) available
// as input variables
input[0].sensor_id = BSEC_INPUT_GASRESISTOR;
input[0].signal = R;
input[0].time_stamp= ts;
input[1].sensor_id = BSEC_INPUT_TEMPERATURE;
input[1].signal = T;
input[1].time_stamp= ts;
input[2].sensor_id = BSEC_INPUT_HUMIDITY;
input[2].signal = rH;
input[2].time_stamp= ts;
// Invoke main processing BSEC function
status = bsec_do_steps( input, n_input, output, &n_output );
// Iterate through the BSEC output data, if the call succeeded
if(status == BSEC_OK)
{
for(int i = 0; i < n_output; i++)
{
switch(output[i].sensor_id)
{
case BSEC_OUTPUT_IAQ:
// Retrieve the IAQ results from output[i].signal
// and do something with the data
break;
case BSEC_OUTPUT_AMBIENT_TEMPERATURE:
// Retrieve the ambient temperature results from output[i].signal
// and do something with the data
break;
}
}
}
\endcode
*/
bsec_library_return_t bsec_do_steps(const bsec_input_t * const inputs, const uint8_t n_inputs, bsec_output_t * outputs, uint8_t * n_outputs);
/*!
* @brief Reset a particular virtual sensor output
*
* This function allows specific virtual sensor outputs to be reset. The meaning of "reset" depends on the specific
* output. In case of the IAQ output, reset means zeroing the output to the current ambient conditions.
*
* @param[in] sensor_id Virtual sensor to be reset
*
* @return Zero when successful, otherwise an error code
*
*
\code{.c}
// Example //
bsec_reset_output(BSEC_OUTPUT_IAQ);
\endcode
*/
bsec_library_return_t bsec_reset_output(uint8_t sensor_id);
/*!
* @brief Update algorithm configuration parameters
*
* BSEC uses a default configuration for the modules and common settings. The initial configuration can be customized
* by bsec_set_configuration(). This is an optional step.
*
* @note A work buffer with sufficient size is required and has to be provided by the function caller to decompose
* the serialization and apply it to the library and its modules. Please use #BSEC_MAX_PROPERTY_BLOB_SIZE for allotting
* the required size.
*
* @param[in] serialized_settings Settings serialized to a binary blob
* @param[in] n_serialized_settings Size of the settings blob
* @param[in,out] work_buffer Work buffer used to parse the blob
* @param[in] n_work_buffer_size Length of the work buffer available for parsing the blob
*
* @return Zero when successful, otherwise an error code
*
\code{.c}
// Example //
// Allocate variables
uint8_t serialized_settings[BSEC_MAX_PROPERTY_BLOB_SIZE];
uint32_t n_serialized_settings_max = BSEC_MAX_PROPERTY_BLOB_SIZE;
uint8_t work_buffer[BSEC_MAX_PROPERTY_BLOB_SIZE];
uint32_t n_work_buffer = BSEC_MAX_PROPERTY_BLOB_SIZE;
// Here we will load a provided config string into serialized_settings
// Apply the configuration
bsec_set_configuration(serialized_settings, n_serialized_settings_max, work_buffer, n_work_buffer);
\endcode
*/
bsec_library_return_t bsec_set_configuration(const uint8_t * const serialized_settings,
const uint32_t n_serialized_settings, uint8_t * work_buffer,
const uint32_t n_work_buffer_size);
/*!
* @brief Restore the internal state of the library
*
* BSEC uses a default state for all signal processing modules and the BSEC module. To ensure optimal performance,
* especially of the gas sensor functionality, it is recommended to retrieve the state using bsec_get_state()
* before unloading the library, storing it in some form of non-volatile memory, and setting it using bsec_set_state()
* before resuming further operation of the library.
*
* @note A work buffer with sufficient size is required and has to be provided by the function caller to decompose the
* serialization and apply it to the library and its modules. Please use #BSEC_MAX_PROPERTY_BLOB_SIZE for allotting the
* required size.
*
* @param[in] serialized_state States serialized to a binary blob
* @param[in] n_serialized_state Size of the state blob
* @param[in,out] work_buffer Work buffer used to parse the blob
* @param[in] n_work_buffer_size Length of the work buffer available for parsing the blob
*
* @return Zero when successful, otherwise an error code
*
\code{.c}
// Example //
// Allocate variables
uint8_t serialized_state[BSEC_MAX_PROPERTY_BLOB_SIZE];
uint32_t n_serialized_state = BSEC_MAX_PROPERTY_BLOB_SIZE;
uint8_t work_buffer_state[BSEC_MAX_PROPERTY_BLOB_SIZE];
uint32_t n_work_buffer_size = BSEC_MAX_PROPERTY_BLOB_SIZE;
// Here we will load a state string from a previous use of BSEC
// Apply the previous state to the current BSEC session
bsec_set_state(serialized_state, n_serialized_state, work_buffer_state, n_work_buffer_size);
\endcode
*/
bsec_library_return_t bsec_set_state(const uint8_t * const serialized_state, const uint32_t n_serialized_state,
uint8_t * work_buffer, const uint32_t n_work_buffer_size);
/*!
* @brief Retrieve the current library configuration
*
* BSEC allows to retrieve the current configuration using bsec_get_configuration(). Returns a binary blob encoding
* the current configuration parameters of the library in a format compatible with bsec_set_configuration().
*
* @note The function bsec_get_configuration() is required to be used for debugging purposes only.
* @note A work buffer with sufficient size is required and has to be provided by the function caller to decompose the
* serialization and apply it to the library and its modules. Please use #BSEC_MAX_PROPERTY_BLOB_SIZE for allotting the
* required size.
*
*
* @param[in] config_id Identifier for a specific set of configuration settings to be returned;
* shall be zero to retrieve all configuration settings.
* @param[out] serialized_settings Buffer to hold the serialized config blob
* @param[in] n_serialized_settings_max Maximum available size for the serialized settings
* @param[in,out] work_buffer Work buffer used to parse the binary blob
* @param[in] n_work_buffer Length of the work buffer available for parsing the blob
* @param[out] n_serialized_settings Actual size of the returned serialized configuration blob
*
* @return Zero when successful, otherwise an error code
*
\code{.c}
// Example //
// Allocate variables
uint8_t serialized_settings[BSEC_MAX_PROPERTY_BLOB_SIZE];
uint32_t n_serialized_settings_max = BSEC_MAX_PROPERTY_BLOB_SIZE;
uint8_t work_buffer[BSEC_MAX_PROPERTY_BLOB_SIZE];
uint32_t n_work_buffer = BSEC_MAX_PROPERTY_BLOB_SIZE;
uint32_t n_serialized_settings = 0;
// Configuration of BSEC algorithm is stored in 'serialized_settings'
bsec_get_configuration(0, serialized_settings, n_serialized_settings_max, work_buffer, n_work_buffer, &n_serialized_settings);
\endcode
*/
bsec_library_return_t bsec_get_configuration(const uint8_t config_id, uint8_t * serialized_settings, const uint32_t n_serialized_settings_max,
uint8_t * work_buffer, const uint32_t n_work_buffer, uint32_t * n_serialized_settings);
/*!
*@brief Retrieve the current internal library state
*
* BSEC allows to retrieve the current states of all signal processing modules and the BSEC module using
* bsec_get_state(). This allows a restart of the processing after a reboot of the system by calling bsec_set_state().
*
* @note A work buffer with sufficient size is required and has to be provided by the function caller to decompose the
* serialization and apply it to the library and its modules. Please use #BSEC_MAX_STATE_BLOB_SIZE for allotting the
* required size.
*
*
* @param[in] state_set_id Identifier for a specific set of states to be returned; shall be
* zero to retrieve all states.
* @param[out] serialized_state Buffer to hold the serialized config blob
* @param[in] n_serialized_state_max Maximum available size for the serialized states
* @param[in,out] work_buffer Work buffer used to parse the blob
* @param[in] n_work_buffer Length of the work buffer available for parsing the blob
* @param[out] n_serialized_state Actual size of the returned serialized blob
*
* @return Zero when successful, otherwise an error code
*
\code{.c}
// Example //
// Allocate variables
uint8_t serialized_state[BSEC_MAX_STATE_BLOB_SIZE];
uint32_t n_serialized_state_max = BSEC_MAX_STATE_BLOB_SIZE;
uint32_t n_serialized_state = BSEC_MAX_STATE_BLOB_SIZE;
uint8_t work_buffer_state[BSEC_MAX_STATE_BLOB_SIZE];
uint32_t n_work_buffer_size = BSEC_MAX_STATE_BLOB_SIZE;
// Algorithm state is stored in 'serialized_state'
bsec_get_state(0, serialized_state, n_serialized_state_max, work_buffer_state, n_work_buffer_size, &n_serialized_state);
\endcode
*/
bsec_library_return_t bsec_get_state(const uint8_t state_set_id, uint8_t * serialized_state,
const uint32_t n_serialized_state_max, uint8_t * work_buffer, const uint32_t n_work_buffer,
uint32_t * n_serialized_state);
/*!
* @brief Retrieve BMExxx sensor instructions
*
* The bsec_sensor_control() interface is a key feature of BSEC, as it allows an easy way for the signal processing
* library to control the operation of the BME sensor. This is important since gas sensor behaviour is mainly
* determined by how the integrated heater is configured. To ensure an easy integration of BSEC into any system,
* bsec_sensor_control() will provide the caller with information about the current sensor configuration that is
* necessary to fulfill the input requirements derived from the current outputs requested via
* bsec_update_subscription().
*
* In practice the use of this function shall be as follows:
* - Call bsec_sensor_control() which returns a bsec_bme_settings_t struct.
* - Based on the information contained in this struct, the sensor is configured and a forced-mode measurement is
* triggered if requested by bsec_sensor_control().
* - Once this forced-mode measurement is complete, the signals specified in this struct shall be passed to
* bsec_do_steps() to perform the signal processing.
* - After processing, the process should sleep until the bsec_bme_settings_t::next_call timestamp is reached.
*
*
* @param [in] time_stamp Current timestamp in [ns]
* @param[out] sensor_settings Settings to be passed to API to operate sensor at this time instance
*
* @return Zero when successful, otherwise an error code
*/
bsec_library_return_t bsec_sensor_control(const int64_t time_stamp, bsec_bme_settings_t *sensor_settings);
/*@}*/ //BSEC Interface
#ifdef __cplusplus
}
#endif
#endif /* __BSEC_INTERFACE_H__ */

View File

@ -0,0 +1 @@
454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,30,235,0,0
1 454 1 7 4 1 61 0 0 0 0 0 0 0 174 1 0 0 48 0 1 0 137 65 0 63 205 204 204 62 0 0 64 63 205 204 204 62 0 0 225 68 0 168 19 73 64 49 119 76 0 0 0 0 0 80 5 95 0 0 0 0 0 0 0 0 28 0 2 0 0 244 1 225 0 25 0 0 128 64 0 0 32 65 144 1 0 0 112 65 0 0 0 63 16 0 3 0 10 215 163 60 10 215 35 59 10 215 35 59 9 0 5 0 0 0 0 0 1 88 0 9 0 7 240 150 61 0 0 0 0 0 0 0 0 28 124 225 61 52 128 215 63 0 0 160 64 0 0 0 0 0 0 0 0 205 204 12 62 103 213 39 62 230 63 76 192 0 0 0 0 0 0 0 0 145 237 60 191 251 58 64 63 177 80 131 64 0 0 0 0 0 0 0 0 93 254 227 62 54 60 133 191 0 0 64 64 12 0 10 0 0 0 0 0 0 0 0 0 229 0 254 0 2 1 5 48 117 100 0 44 1 112 23 151 7 132 3 197 0 92 4 144 1 64 1 64 1 144 1 48 117 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 48 117 48 117 100 0 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 100 0 100 0 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 255 255 255 255 255 255 255 255 220 5 220 5 220 5 255 255 255 255 255 255 220 5 220 5 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 48 117 0 0 0 0 30 235 0 0

View File

@ -0,0 +1,5 @@
#include "bsec_serialized_configurations_iaq.h"
const uint8_t bsec_config_iaq[454] =
{1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,30,235,0,0};

View File

@ -0,0 +1,4 @@
#include <stdint.h>
extern const uint8_t bsec_config_iaq[454];

View File

@ -0,0 +1 @@
454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,195,255,0,0
1 454 1 7 4 1 61 0 0 0 0 0 0 0 174 1 0 0 48 0 1 0 137 65 0 63 205 204 204 62 0 0 64 63 205 204 204 62 0 0 225 68 0 192 168 71 64 49 119 76 0 0 0 0 0 80 5 95 0 0 0 0 0 0 0 0 28 0 2 0 0 244 1 225 0 25 0 0 128 64 0 0 32 65 144 1 0 0 112 65 0 0 0 63 16 0 3 0 10 215 163 60 10 215 35 59 10 215 35 59 9 0 5 0 0 0 0 0 1 88 0 9 0 7 240 150 61 0 0 0 0 0 0 0 0 28 124 225 61 52 128 215 63 0 0 160 64 0 0 0 0 0 0 0 0 205 204 12 62 103 213 39 62 230 63 76 192 0 0 0 0 0 0 0 0 145 237 60 191 251 58 64 63 177 80 131 64 0 0 0 0 0 0 0 0 93 254 227 62 54 60 133 191 0 0 64 64 12 0 10 0 0 0 0 0 0 0 0 0 229 0 254 0 2 1 5 48 117 100 0 44 1 112 23 151 7 132 3 197 0 92 4 144 1 64 1 64 1 144 1 48 117 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 48 117 48 117 100 0 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 100 0 100 0 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 255 255 255 255 255 255 255 255 220 5 220 5 220 5 255 255 255 255 255 255 220 5 220 5 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 48 117 0 0 0 0 195 255 0 0

View File

@ -0,0 +1,5 @@
#include "bsec_serialized_configurations_iaq.h"
const uint8_t bsec_config_iaq[454] =
{1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,195,255,0,0};

View File

@ -0,0 +1,4 @@
#include <stdint.h>
extern const uint8_t bsec_config_iaq[454];

View File

@ -0,0 +1 @@
454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,140,226,0,0
1 454 1 7 4 1 61 0 0 0 0 0 0 0 174 1 0 0 48 0 1 0 137 65 0 63 205 204 204 62 0 0 64 63 205 204 204 62 0 0 225 68 0 168 19 73 64 49 119 76 0 0 0 0 0 80 5 95 0 0 0 0 0 0 0 0 28 0 2 0 0 244 1 225 0 25 0 0 128 64 0 0 32 65 144 1 0 0 112 65 0 0 0 63 16 0 3 0 10 215 163 60 10 215 35 59 10 215 35 59 9 0 5 0 0 0 0 0 1 88 0 9 0 7 240 150 61 0 0 0 0 0 0 0 0 28 124 225 61 52 128 215 63 0 0 160 64 0 0 0 0 0 0 0 0 205 204 12 62 103 213 39 62 230 63 76 192 0 0 0 0 0 0 0 0 145 237 60 191 251 58 64 63 177 80 131 64 0 0 0 0 0 0 0 0 93 254 227 62 54 60 133 191 0 0 64 64 12 0 10 0 0 0 0 0 0 0 0 0 229 0 254 0 2 1 5 48 117 100 0 44 1 112 23 151 7 132 3 197 0 92 4 144 1 64 1 64 1 144 1 48 117 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 48 117 48 117 100 0 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 100 0 100 0 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 255 255 255 255 255 255 255 255 220 5 220 5 220 5 255 255 255 255 255 255 220 5 220 5 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 44 1 0 0 0 0 140 226 0 0

View File

@ -0,0 +1,5 @@
#include "bsec_serialized_configurations_iaq.h"
const uint8_t bsec_config_iaq[454] =
{1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,140,226,0,0};

View File

@ -0,0 +1,4 @@
#include <stdint.h>
extern const uint8_t bsec_config_iaq[454];

View File

@ -0,0 +1 @@
454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,81,246,0,0
1 454 1 7 4 1 61 0 0 0 0 0 0 0 174 1 0 0 48 0 1 0 137 65 0 63 205 204 204 62 0 0 64 63 205 204 204 62 0 0 225 68 0 192 168 71 64 49 119 76 0 0 0 0 0 80 5 95 0 0 0 0 0 0 0 0 28 0 2 0 0 244 1 225 0 25 0 0 128 64 0 0 32 65 144 1 0 0 112 65 0 0 0 63 16 0 3 0 10 215 163 60 10 215 35 59 10 215 35 59 9 0 5 0 0 0 0 0 1 88 0 9 0 7 240 150 61 0 0 0 0 0 0 0 0 28 124 225 61 52 128 215 63 0 0 160 64 0 0 0 0 0 0 0 0 205 204 12 62 103 213 39 62 230 63 76 192 0 0 0 0 0 0 0 0 145 237 60 191 251 58 64 63 177 80 131 64 0 0 0 0 0 0 0 0 93 254 227 62 54 60 133 191 0 0 64 64 12 0 10 0 0 0 0 0 0 0 0 0 229 0 254 0 2 1 5 48 117 100 0 44 1 112 23 151 7 132 3 197 0 92 4 144 1 64 1 64 1 144 1 48 117 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 48 117 48 117 100 0 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 100 0 100 0 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 255 255 255 255 255 255 255 255 220 5 220 5 220 5 255 255 255 255 255 255 220 5 220 5 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 44 1 0 0 0 0 81 246 0 0

View File

@ -0,0 +1,5 @@
#include "bsec_serialized_configurations_iaq.h"
const uint8_t bsec_config_iaq[454] =
{1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,81,246,0,0};

View File

@ -0,0 +1,4 @@
#include <stdint.h>
extern const uint8_t bsec_config_iaq[454];

View File

@ -0,0 +1 @@
454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,160,82,0,0
1 454 1 7 4 1 61 0 0 0 0 0 0 0 174 1 0 0 48 0 1 0 137 65 0 63 205 204 204 62 0 0 64 63 205 204 204 62 0 0 225 68 0 168 19 73 64 49 119 76 0 0 0 0 0 80 5 95 0 0 0 0 0 0 0 0 28 0 2 0 0 244 1 225 0 25 0 0 128 64 0 0 32 65 144 1 0 0 112 65 0 0 0 63 16 0 3 0 10 215 163 60 10 215 35 59 10 215 35 59 9 0 5 0 0 0 0 0 1 88 0 9 0 229 208 34 62 0 0 0 0 0 0 0 0 218 27 156 62 225 11 67 64 0 0 160 64 0 0 0 0 0 0 0 0 94 75 72 189 93 254 159 64 66 62 160 191 0 0 0 0 0 0 0 0 33 31 180 190 138 176 97 64 65 241 99 190 0 0 0 0 0 0 0 0 167 121 71 61 165 189 41 192 184 30 189 64 12 0 10 0 0 0 0 0 0 0 0 0 229 0 254 0 2 1 5 48 117 100 0 44 1 112 23 151 7 132 3 197 0 92 4 144 1 64 1 64 1 144 1 48 117 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 48 117 48 117 100 0 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 100 0 100 0 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 255 255 255 255 255 255 255 255 220 5 220 5 220 5 255 255 255 255 255 255 220 5 220 5 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 48 117 0 0 0 0 160 82 0 0

View File

@ -0,0 +1,5 @@
#include "bsec_serialized_configurations_iaq.h"
const uint8_t bsec_config_iaq[454] =
{1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,160,82,0,0};

View File

@ -0,0 +1,4 @@
#include <stdint.h>
extern const uint8_t bsec_config_iaq[454];

View File

@ -0,0 +1 @@
454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,125,70,0,0
1 454 1 7 4 1 61 0 0 0 0 0 0 0 174 1 0 0 48 0 1 0 137 65 0 63 205 204 204 62 0 0 64 63 205 204 204 62 0 0 225 68 0 192 168 71 64 49 119 76 0 0 0 0 0 80 5 95 0 0 0 0 0 0 0 0 28 0 2 0 0 244 1 225 0 25 0 0 128 64 0 0 32 65 144 1 0 0 112 65 0 0 0 63 16 0 3 0 10 215 163 60 10 215 35 59 10 215 35 59 9 0 5 0 0 0 0 0 1 88 0 9 0 229 208 34 62 0 0 0 0 0 0 0 0 218 27 156 62 225 11 67 64 0 0 160 64 0 0 0 0 0 0 0 0 94 75 72 189 93 254 159 64 66 62 160 191 0 0 0 0 0 0 0 0 33 31 180 190 138 176 97 64 65 241 99 190 0 0 0 0 0 0 0 0 167 121 71 61 165 189 41 192 184 30 189 64 12 0 10 0 0 0 0 0 0 0 0 0 229 0 254 0 2 1 5 48 117 100 0 44 1 112 23 151 7 132 3 197 0 92 4 144 1 64 1 64 1 144 1 48 117 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 48 117 48 117 100 0 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 100 0 100 0 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 255 255 255 255 255 255 255 255 220 5 220 5 220 5 255 255 255 255 255 255 220 5 220 5 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 48 117 0 0 0 0 125 70 0 0

View File

@ -0,0 +1,5 @@
#include "bsec_serialized_configurations_iaq.h"
const uint8_t bsec_config_iaq[454] =
{1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,125,70,0,0};

View File

@ -0,0 +1,4 @@
#include <stdint.h>
extern const uint8_t bsec_config_iaq[454];

View File

@ -0,0 +1 @@
454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,50,91,0,0
1 454 1 7 4 1 61 0 0 0 0 0 0 0 174 1 0 0 48 0 1 0 137 65 0 63 205 204 204 62 0 0 64 63 205 204 204 62 0 0 225 68 0 168 19 73 64 49 119 76 0 0 0 0 0 80 5 95 0 0 0 0 0 0 0 0 28 0 2 0 0 244 1 225 0 25 0 0 128 64 0 0 32 65 144 1 0 0 112 65 0 0 0 63 16 0 3 0 10 215 163 60 10 215 35 59 10 215 35 59 9 0 5 0 0 0 0 0 1 88 0 9 0 229 208 34 62 0 0 0 0 0 0 0 0 218 27 156 62 225 11 67 64 0 0 160 64 0 0 0 0 0 0 0 0 94 75 72 189 93 254 159 64 66 62 160 191 0 0 0 0 0 0 0 0 33 31 180 190 138 176 97 64 65 241 99 190 0 0 0 0 0 0 0 0 167 121 71 61 165 189 41 192 184 30 189 64 12 0 10 0 0 0 0 0 0 0 0 0 229 0 254 0 2 1 5 48 117 100 0 44 1 112 23 151 7 132 3 197 0 92 4 144 1 64 1 64 1 144 1 48 117 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 48 117 48 117 100 0 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 100 0 100 0 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 255 255 255 255 255 255 255 255 220 5 220 5 220 5 255 255 255 255 255 255 220 5 220 5 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 44 1 0 0 0 0 50 91 0 0

View File

@ -0,0 +1,5 @@
#include "bsec_serialized_configurations_iaq.h"
const uint8_t bsec_config_iaq[454] =
{1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,50,91,0,0};

View File

@ -0,0 +1,4 @@
#include <stdint.h>
extern const uint8_t bsec_config_iaq[454];

View File

@ -0,0 +1 @@
454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,239,79,0,0
1 454 1 7 4 1 61 0 0 0 0 0 0 0 174 1 0 0 48 0 1 0 137 65 0 63 205 204 204 62 0 0 64 63 205 204 204 62 0 0 225 68 0 192 168 71 64 49 119 76 0 0 0 0 0 80 5 95 0 0 0 0 0 0 0 0 28 0 2 0 0 244 1 225 0 25 0 0 128 64 0 0 32 65 144 1 0 0 112 65 0 0 0 63 16 0 3 0 10 215 163 60 10 215 35 59 10 215 35 59 9 0 5 0 0 0 0 0 1 88 0 9 0 229 208 34 62 0 0 0 0 0 0 0 0 218 27 156 62 225 11 67 64 0 0 160 64 0 0 0 0 0 0 0 0 94 75 72 189 93 254 159 64 66 62 160 191 0 0 0 0 0 0 0 0 33 31 180 190 138 176 97 64 65 241 99 190 0 0 0 0 0 0 0 0 167 121 71 61 165 189 41 192 184 30 189 64 12 0 10 0 0 0 0 0 0 0 0 0 229 0 254 0 2 1 5 48 117 100 0 44 1 112 23 151 7 132 3 197 0 92 4 144 1 64 1 64 1 144 1 48 117 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 48 117 48 117 100 0 100 0 100 0 100 0 48 117 48 117 48 117 100 0 100 0 100 0 48 117 48 117 100 0 100 0 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 44 1 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 8 7 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 112 23 255 255 255 255 255 255 255 255 220 5 220 5 220 5 255 255 255 255 255 255 220 5 220 5 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 255 44 1 0 0 0 0 239 79 0 0

View File

@ -0,0 +1,5 @@
#include "bsec_serialized_configurations_iaq.h"
const uint8_t bsec_config_iaq[454] =
{1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,239,79,0,0};

View File

@ -0,0 +1,4 @@
#include <stdint.h>
extern const uint8_t bsec_config_iaq[454];

Binary file not shown.

File diff suppressed because it is too large Load Diff

Binary file not shown.

View File

@ -1,46 +0,0 @@
# Compiled Object files
*.slo
*.lo
*.o
*.obj
# Precompiled Headers
*.gch
*.pch
# Compiled Dynamic libraries
*.so
*.dylib
*.dll
# Fortran module files
*.mod
*.smod
# Compiled Static libraries
*.lai
*.la
*.a
*.lib
# Executables
*.exe
*.out
*.app
# Backup files
*.BAK
*.CKP
# files from Visual Micro
Release
*.vcxproj
*.vcxproj.filters
*.vcxitems
vs-readme.txt
__vm
.vs
*.sln
# files from vscode
.vscode

View File

@ -1,17 +0,0 @@
^CVS
.*/CVS
.*/CVS/.*
\.\#.*$
^\.DS_Store$
.*\.BAK$
.*\.bak$
.*\.CKP$
^build
^build/.*
^.*\.o$
^.*\.d$
^.*\.td$
\.a$
^core$
.*/core$
.*\.rej$

View File

@ -1,73 +0,0 @@
# Adding a new region to Arduino LMIC
This variant of the Arduino LMIC code supports adding additional regions beyond the eu868 and us915 bands supoprted by the original IBM LMIC 1.6 code.
This document sketches how to add a new region.
## Planning
### Determine the region/region category
Compare the target region (in the LoRaWAN regional specification) to the EU868 and US915 regions. There are three possibilities.
1. the region is like the EU region. There are a limited number of channels (up to 8), and only a small number of channels are used for OTAA join operations. The response masks refer to individual channels, and the JOIN-response can send frequencies of specific channels to be added.
2. The region is like the US region. There are many channels (the US has 64) with fixed frequences, and the channel masks refer to subsets of the fixed channels.
3. The region is not really like either the EU or US. At the moment, it seems that CN470-510MHz (section 2.6 of LoRaWAN Regional Parameters spec V1.0.2rB) falls into this category.
Bandplans in categories (1) and (2) are easily supported. Bandplans in category (3) are not supoprted by the current code.
### Check whether the region is already listed in `lmic_config_preconditions.h`
Check `src/lmic/lmic_config_preconditions.h` and scan the `LMIC_REGION_...` definitions. The numeric values are assigned based on the subchapter in section 2 of the LoRaWAN 1.0.2 Regional Parmaters document. If your symbol is already there, then the first part of adaptation has already been done. There will already be a corresponding `CFG_...` symbol. But if your region isn't supported, you'll need to add it here.
- `LMIC_REGION_myregion` must be a distinct integer, and must be less than 32 (so as to fit into a bitmask)
## Make the appropriate changes in `lmic_config_preconditions.h`
- `LMIC_REGION_SUPPORTED` is a bit mask of all regions supported by the code. Your new region must appear in this list.
- `CFG_LMIC_REGION_MASK` is a bit mask that, when expanded, returns a bitmask for each defined `CFG_...` variable. You must add your `CFG_myregion` symbol to this list.
- `CFG_region` evaluates to the `LMIC_REGION_...` value for the selected region (as long as only one region is selected). The header files check for this, so you don't have to.
- `CFG_LMIC_EU_like_MASK` is a bitmask of regions that are EU-like, and `CFG_LMIC_US_like_MASK` is a bitmask of regions that are US-like. Add your region to the appropriate one of these two variables.
## Document your region in `config.h`
You'll see where the regions are listed. Add yours.
## Document your region in `README.md`
You'll see where the regions are listed. Add yours.
## Add the definitions for your region in `lorabase.h`
- If your region is EU like, copy the EU block. Document any duty-cycle limitations.
- if your region is US like, copy the US block.
- As appropriate, copy `lorabase_eu868.h` or `lorabase_us915.h` to make your own `lorabase_myregion.h`. Fill in the symbols.
At time of writing, you need to duplicate some code to copy some settings from `..._CONFIG_SYMBOL` to the corresponding `CONFIG_SYMBOL`; and you need to put some region-specific knowledge into the `lorabase.h` header file. The long-term direction is to put all the regional knowledge into the region-specific header, and then the central code will just copy. The architectural impulse is that we'll want to be able to reuse the regional header files in other contexts. On the other hand, because it's error prone, we don't want to `#include` files that aren't being used; otherwise you could accidentally use EU parameters in US code, etc.
- Now's a good time to test-compile and clean out errors introduced. You'll still have problems compiling, but they should look like this:
```
lmic.c:29: In file included from
lmic_bandplan.h: 52:3: error: #error "maxFrameLen() not defined by bandplan"
# error "maxFrameLen() not defined by bandplan"
lmic_bandplan.h: 56:3: error: #error "pow2dBm() not defined by bandplan"
# error "pow2dBm() not defined by bandplan"
```
## Edit `lmic_bandplan.h`
The next step is to add the region-specific interfaces for your region.
Do this by editing `lmic_bandplan.h` and adding the appropriate call to a (new) region-specific file `lmic_bandplan_myregion.h`, where "myregion" is the abbreviation for your region.
Then, if your region is eu868-like, copy `lmic_bandplan_eu868.h` to create your new region-specific header file; otherwise copy `lmic_bandplan_us915.h`.
## Create `lmic_myregion.c`
Once again, you will start by copying either `lmic_eu868.c` or `lmic_us915.c` to create your new file. Then touch it up as necessary.
## General Discussion
- You'll find it easier to do the test compiles using the example scripts in this directory, rather than trying to get all the Catena framework going too. On the other hand, working with the Catena framework will expose more problems.
## Addding the region to the Arduino_LoRaWAN library
In `Arduino_LoRaWAN_ttn.h`:
- Add a new class with name `Arduino_LoRaWAN_ttn_myregion`, copied either from the `Arduino_LoRaWAN_ttn_eu868` class or the `Arduino_LoRaWAN_ttn_us915` class.
- Extend the list of `#if defined(CFG_eu868)` etc to define `Arduino_LoRaWAN_REGION_TAG` to the suffix of your new class if `CFG_myregion` is defined.
Then copy either `ttn_eu868_netbegin.cpp`/`ttn_eu868_netjoin.cpp` or `ttn_us915_netbegin.cpp`/`ttn_us915_netjoin.cpp` to make your own file(s) for the key functions.

View File

@ -1,23 +0,0 @@
MIT License
Copyright (C) 2014-2016 IBM Corporation
Copyright (c) 2016-2018 MCCI Corporation
Copyright (c) 2015 Thomas Telkamp and Matthijs Kooijman
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.

File diff suppressed because it is too large Load Diff

File diff suppressed because one or more lines are too long

Binary file not shown.

Before

Width:  |  Height:  |  Size: 269 KiB

View File

@ -1,4 +0,0 @@
DISCLAIMER:
Please note that the software is provided AS IS and we cannot
provide support for optimizations, adaptations, integration,
ports to other platforms or device drivers!

View File

@ -1,38 +0,0 @@
==============================================================================
LMIC VERSION 1.6 (13-July-2015)
---------------------------------
- License changed to BSD
- Modem included, see LMiC-Modem.pdf and examples/modem
- Additional stm32 hardware and Blipper board specific peripheral code
==============================================================================
LMIC VERSION 1.5 (8-May-2015)
------------------------------
- fixed condition in convFreq()
- fixed freq*100 bug and freq==0 bug for CFList
- fixed TX scheduling bug
- better support for GNU compiler toolchain
==============================================================================
LMIC VERSION 1.4 (17-Mar-2015)
-------------------------------
- changed API: inverted port indicator flag in LMIC.txrxFlags
(now TXRX_PORT, previously TXRX_NOPORT)
- fixed offset OFF_CFLIST constant
- changed CRC-16 algorithm for beacons to CCITT(XMODEM) polynomial
- fixed radio driver (low data rate optimization for SF11+SF12 only for BW125)
- fixed timer rollover handling in job queue
==============================================================================

View File

@ -1,36 +0,0 @@
/*
Module: header_test.ino
Function:
Simple hello-world (and compile-test) app
Copyright notice and License:
See LICENSE file accompanying this project.
Author:
Terry Moore, MCCI Corporation April 2018
*/
#include <lmic.h>
# define STATIC_ASSERT(e) \
void STATIC_ASSERT__(int MCCIADK_C_ASSERT_x[(e) ? 1: -1])
STATIC_ASSERT(ARDUINO_LMIC_VERSION >= ARDUINO_LMIC_VERSION_CALC(2,1,5,0));
STATIC_ASSERT(ARDUINO_LMIC_VERSION_CALC(1,2,3,4) == 0x01020304);
STATIC_ASSERT(ARDUINO_LMIC_VERSION_GET_MAJOR(ARDUINO_LMIC_VERSION_CALC(1,2,3,4)) == 1);
STATIC_ASSERT(ARDUINO_LMIC_VERSION_GET_MINOR(ARDUINO_LMIC_VERSION_CALC(1,2,3,4)) == 2);
STATIC_ASSERT(ARDUINO_LMIC_VERSION_GET_PATCH(ARDUINO_LMIC_VERSION_CALC(1,2,3,4)) == 3);
STATIC_ASSERT(ARDUINO_LMIC_VERSION_GET_LOCAL(ARDUINO_LMIC_VERSION_CALC(1,2,3,4)) == 4);
void setup()
{
}
void loop()
{
}

View File

@ -1,441 +0,0 @@
/*
Module: raw-feather.ino
Function:
Slightly improved Raw test example, for Adafruit Feather M0 LoRa
Copyright notice and License:
See LICENSE file accompanying this project.
Author:
Matthijs Kooijman 2015
Terry Moore, MCCI Corporation April 2017
*/
/*******************************************************************************
* Copyright (c) 2015 Matthijs Kooijman
*
* Permission is hereby granted, free of charge, to anyone
* obtaining a copy of this document and accompanying files,
* to do whatever they want with them without any restriction,
* including, but not limited to, copying, modification and redistribution.
* NO WARRANTY OF ANY KIND IS PROVIDED.
*
* This example transmits data on hardcoded channel and receives data
* when not transmitting. Running this sketch on two nodes should allow
* them to communicate.
*******************************************************************************/
#include <lmic.h>
#include <hal/hal.h>
#include <SPI.h>
#include <stdarg.h>
#include <stdio.h>
// we formerly would check this configuration; but now there is a flag,
// in the LMIC, LMIC.noRXIQinversion;
// if we set that during init, we get the same effect. If
// DISABLE_INVERT_IQ_ON_RX is defined, it means that LMIC.noRXIQinversion is
// treated as always set.
//
// #if !defined(DISABLE_INVERT_IQ_ON_RX)
// #error This example requires DISABLE_INVERT_IQ_ON_RX to be set. Update \
// lmic_project_config.h in arduino-lmic/project_config to set it.
// #endif
// How often to send a packet. Note that this sketch bypasses the normal
// LMIC duty cycle limiting, so when you change anything in this sketch
// (payload length, frequency, spreading factor), be sure to check if
// this interval should not also be increased.
// See this spreadsheet for an easy airtime and duty cycle calculator:
// https://docs.google.com/spreadsheets/d/1voGAtQAjC1qBmaVuP1ApNKs1ekgUjavHuVQIXyYSvNc
#define TX_INTERVAL 2000 // milliseconds
#define RX_RSSI_INTERVAL 100 // milliseconds
// Pin mapping for Adafruit Feather M0 LoRa, etc.
#if defined(ARDUINO_SAMD_FEATHER_M0)
const lmic_pinmap lmic_pins = {
.nss = 8,
.rxtx = LMIC_UNUSED_PIN,
.rst = 4,
.dio = {3, 6, LMIC_UNUSED_PIN},
.rxtx_rx_active = 0,
.rssi_cal = 8, // LBT cal for the Adafruit Feather M0 LoRa, in dB
.spi_freq = 8000000,
};
#elif defined(ARDUINO_AVR_FEATHER32U4)
// Pin mapping for Adafruit Feather 32u4 LoRa, etc.
// Just like Feather M0 LoRa, but uses SPI at 1MHz; and that's only
// because MCCI doesn't have a test board; probably higher frequencies
// will work.
const lmic_pinmap lmic_pins = {
.nss = 8,
.rxtx = LMIC_UNUSED_PIN,
.rst = 4,
.dio = {3, 6, LMIC_UNUSED_PIN},
.rxtx_rx_active = 0,
.rssi_cal = 8, // LBT cal for the Adafruit Feather M0 LoRa, in dB
.spi_freq = 1000000,
};
#elif defined(ARDUINO_CATENA_4551)
const lmic_pinmap lmic_pins = {
.nss = 7,
.rxtx = 29,
.rst = 8,
.dio = { 25, // DIO0 (IRQ) is D25
26, // DIO1 is D26
27, // DIO2 is D27
},
.rxtx_rx_active = 1,
.rssi_cal = 10,
.spi_freq = 8000000 // 8MHz
};
#else
# error "Unknown target"
#endif
// These callbacks are only used in over-the-air activation, so they are
// left empty here (we cannot leave them out completely unless
// DISABLE_JOIN is set in arduino-lmoc/project_config/lmic_project_config.h,
// otherwise the linker will complain).
void os_getArtEui (u1_t* buf) { }
void os_getDevEui (u1_t* buf) { }
void os_getDevKey (u1_t* buf) { }
// this gets callled by the library but we choose not to display any info;
// and no action is required.
void onEvent (ev_t ev) {
}
extern "C" {
void lmic_printf(const char *fmt, ...);
};
void lmic_printf(const char *fmt, ...) {
if (! Serial.dtr())
return;
char buf[256];
va_list ap;
va_start(ap, fmt);
(void) vsnprintf(buf, sizeof(buf) - 1, fmt, ap);
va_end(ap);
// in case we overflowed:
buf[sizeof(buf) - 1] = '\0';
if (Serial.dtr()) Serial.print(buf);
}
osjob_t txjob;
osjob_t timeoutjob;
static void tx_func (osjob_t* job);
// Transmit the given string and call the given function afterwards
void tx(const char *str, osjobcb_t func) {
// the radio is probably in RX mode; stop it.
os_radio(RADIO_RST);
// wait a bit so the radio can come out of RX mode
delay(1);
// prepare data
LMIC.dataLen = 0;
while (*str)
LMIC.frame[LMIC.dataLen++] = *str++;
// set completion function.
LMIC.osjob.func = func;
// start the transmission
os_radio(RADIO_TX);
Serial.println("TX");
}
// Enable rx mode and call func when a packet is received
void rx(osjobcb_t func) {
LMIC.osjob.func = func;
LMIC.rxtime = os_getTime(); // RX _now_
// Enable "continuous" RX (e.g. without a timeout, still stops after
// receiving a packet)
os_radio(RADIO_RXON);
Serial.println("RX");
}
static void rxtimeout_func(osjob_t *job) {
digitalWrite(LED_BUILTIN, LOW); // off
}
static void rx_func (osjob_t* job) {
// Blink once to confirm reception and then keep the led on
digitalWrite(LED_BUILTIN, LOW); // off
delay(10);
digitalWrite(LED_BUILTIN, HIGH); // on
// Timeout RX (i.e. update led status) after 3 periods without RX
os_setTimedCallback(&timeoutjob, os_getTime() + ms2osticks(3*TX_INTERVAL), rxtimeout_func);
// Reschedule TX so that it should not collide with the other side's
// next TX
os_setTimedCallback(&txjob, os_getTime() + ms2osticks(TX_INTERVAL/2), tx_func);
Serial.print("Got ");
Serial.print(LMIC.dataLen);
Serial.println(" bytes");
Serial.write(LMIC.frame, LMIC.dataLen);
Serial.println();
// Restart RX
rx(rx_func);
}
static void txdone_func (osjob_t* job) {
rx(rx_func);
}
// log text to USART and toggle LED
static void tx_func (osjob_t* job) {
// say hello
tx("Hello, world!", txdone_func);
// reschedule job every TX_INTERVAL (plus a bit of random to prevent
// systematic collisions), unless packets are received, then rx_func
// will reschedule at half this time.
os_setTimedCallback(job, os_getTime() + ms2osticks(TX_INTERVAL + random(500)), tx_func);
}
// application entry point
void setup() {
// delay(3000) makes recovery from botched images much easier, as it
// gives the host time to break in to start a download. Without it,
// you get to the crash before the host can break in.
delay(3000);
// even after the delay, we wait for the host to open the port. operator
// bool(Serial) just checks dtr(), and it tosses in a 10ms delay.
while(! Serial.dtr())
/* wait for the PC */;
Serial.begin(115200);
Serial.println("Starting");
#ifdef VCC_ENABLE
// For Pinoccio Scout boards
pinMode(VCC_ENABLE, OUTPUT);
digitalWrite(VCC_ENABLE, HIGH);
delay(1000);
#endif
pinMode(LED_BUILTIN, OUTPUT);
// initialize runtime env
os_init();
// Set up these settings once, and use them for both TX and RX
#ifdef ARDUINO_ARCH_STM32
LMIC_setClockError(10*65536/100);
#endif
#if defined(CFG_eu868)
// Use a frequency in the g3 which allows 10% duty cycling.
LMIC.freq = 869525000;
// Use a medium spread factor. This can be increased up to SF12 for
// better range, but then, the interval should be (significantly)
// raised to comply with duty cycle limits as well.
LMIC.datarate = DR_SF9;
// Maximum TX power
LMIC.txpow = 27;
#elif defined(CFG_us915)
// make it easier for test, by pull the parameters up to the top of the
// block. Ideally, we'd use the serial port to drive this; or have
// a voting protocol where one side is elected the controller and
// guides the responder through all the channels, powers, ramps
// the transmit power from min to max, and measures the RSSI and SNR.
// Even more amazing would be a scheme where the controller could
// handle multiple nodes; in that case we'd have a way to do
// production test and qualification. However, using an RWC5020A
// is a much better use of development time.
// set fDownlink true to use a downlink channel; false
// to use an uplink channel. Generally speaking, uplink
// is more interesting, because you can prove that gateways
// *should* be able to hear you.
const static bool fDownlink = false;
// the downlink channel to be used.
const static uint8_t kDownlinkChannel = 3;
// the uplink channel to be used.
const static uint8_t kUplinkChannel = 8 + 3;
// this is automatically set to the proper bandwidth in kHz,
// based on the selected channel.
uint32_t uBandwidth;
if (! fDownlink)
{
if (kUplinkChannel < 64)
{
LMIC.freq = US915_125kHz_UPFBASE +
kUplinkChannel * US915_125kHz_UPFSTEP;
uBandwidth = 125;
}
else
{
LMIC.freq = US915_500kHz_UPFBASE +
(kUplinkChannel - 64) * US915_500kHz_UPFSTEP;
uBandwidth = 500;
}
}
else
{
// downlink channel
LMIC.freq = US915_500kHz_DNFBASE +
kDownlinkChannel * US915_500kHz_DNFSTEP;
uBandwidth = 500;
}
// Use a suitable spreading factor
if (uBandwidth < 500)
LMIC.datarate = US915_DR_SF7; // DR4
else
LMIC.datarate = US915_DR_SF12CR; // DR8
// default tx power for US: 21 dBm
LMIC.txpow = 21;
#elif defined(CFG_au921)
// make it easier for test, by pull the parameters up to the top of the
// block. Ideally, we'd use the serial port to drive this; or have
// a voting protocol where one side is elected the controller and
// guides the responder through all the channels, powers, ramps
// the transmit power from min to max, and measures the RSSI and SNR.
// Even more amazing would be a scheme where the controller could
// handle multiple nodes; in that case we'd have a way to do
// production test and qualification. However, using an RWC5020A
// is a much better use of development time.
// set fDownlink true to use a downlink channel; false
// to use an uplink channel. Generally speaking, uplink
// is more interesting, because you can prove that gateways
// *should* be able to hear you.
const static bool fDownlink = false;
// the downlink channel to be used.
const static uint8_t kDownlinkChannel = 3;
// the uplink channel to be used.
const static uint8_t kUplinkChannel = 8 + 3;
// this is automatically set to the proper bandwidth in kHz,
// based on the selected channel.
uint32_t uBandwidth;
if (! fDownlink)
{
if (kUplinkChannel < 64)
{
LMIC.freq = AU921_125kHz_UPFBASE +
kUplinkChannel * AU921_125kHz_UPFSTEP;
uBandwidth = 125;
}
else
{
LMIC.freq = AU921_500kHz_UPFBASE +
(kUplinkChannel - 64) * AU921_500kHz_UPFSTEP;
uBandwidth = 500;
}
}
else
{
// downlink channel
LMIC.freq = AU921_500kHz_DNFBASE +
kDownlinkChannel * AU921_500kHz_DNFSTEP;
uBandwidth = 500;
}
// Use a suitable spreading factor
if (uBandwidth < 500)
LMIC.datarate = AU921_DR_SF7; // DR4
else
LMIC.datarate = AU921_DR_SF12CR; // DR8
// default tx power for AU: 30 dBm
LMIC.txpow = 30;
#elif defined(CFG_as923)
// make it easier for test, by pull the parameters up to the top of the
// block. Ideally, we'd use the serial port to drive this; or have
// a voting protocol where one side is elected the controller and
// guides the responder through all the channels, powers, ramps
// the transmit power from min to max, and measures the RSSI and SNR.
// Even more amazing would be a scheme where the controller could
// handle multiple nodes; in that case we'd have a way to do
// production test and qualification. However, using an RWC5020A
// is a much better use of development time.
const static uint8_t kChannel = 0;
uint32_t uBandwidth;
LMIC.freq = AS923_F1 + kChannel * 200000;
uBandwidth = 125;
// Use a suitable spreading factor
if (uBandwidth == 125)
LMIC.datarate = AS923_DR_SF7; // DR7
else
LMIC.datarate = AS923_DR_SF7B; // DR8
// default tx power for AS: 21 dBm
LMIC.txpow = 16;
if (LMIC_COUNTRY_CODE == LMIC_COUNTRY_CODE_JP)
{
LMIC.lbt_ticks = us2osticks(AS923JP_LBT_US);
LMIC.lbt_dbmax = AS923JP_LBT_DB_MAX;
}
#elif defined(CFG_in866)
// make it easier for test, by pull the parameters up to the top of the
// block. Ideally, we'd use the serial port to drive this; or have
// a voting protocol where one side is elected the controller and
// guides the responder through all the channels, powers, ramps
// the transmit power from min to max, and measures the RSSI and SNR.
// Even more amazing would be a scheme where the controller could
// handle multiple nodes; in that case we'd have a way to do
// production test and qualification. However, using an RWC5020A
// is a much better use of development time.
const static uint8_t kChannel = 0;
uint32_t uBandwidth;
LMIC.freq = IN866_F1 + kChannel * 200000;
uBandwidth = 125;
LMIC.datarate = IN866_DR_SF7; // DR7
// default tx power for IN: 30 dBm
LMIC.txpow = IN866_TX_EIRP_MAX_DBM;
#else
# error Unsupported LMIC regional configuration.
#endif
// disable RX IQ inversion
LMIC.noRXIQinversion = true;
// This sets CR 4/5, BW125 (except for EU/AS923 DR_SF7B, which uses BW250)
LMIC.rps = updr2rps(LMIC.datarate);
Serial.print("Frequency: "); Serial.print(LMIC.freq / 1000000);
Serial.print("."); Serial.print((LMIC.freq / 100000) % 10);
Serial.print("MHz");
Serial.print(" LMIC.datarate: "); Serial.print(LMIC.datarate);
Serial.print(" LMIC.txpow: "); Serial.println(LMIC.txpow);
Serial.println("Started");
Serial.flush();
// setup initial job
os_setCallback(&txjob, tx_func);
}
void loop() {
// execute scheduled jobs and events
os_runloop_once();
}

View File

@ -1,175 +0,0 @@
/*******************************************************************************
* Copyright (c) 2015 Matthijs Kooijman
* Copyright (c) 2018 Terry Moore, MCCI Corporation
*
* Permission is hereby granted, free of charge, to anyone
* obtaining a copy of this document and accompanying files,
* to do whatever they want with them without any restriction,
* including, but not limited to, copying, modification and redistribution.
* NO WARRANTY OF ANY KIND IS PROVIDED.
*
* This example transmits data on hardcoded channel and receives data
* when not transmitting. Running this sketch on two nodes should allow
* them to communicate.
*******************************************************************************/
#include <lmic.h>
#include <hal/hal.h>
#include <SPI.h>
// we formerly would check this configuration; but now there is a flag,
// in the LMIC, LMIC.noRXIQinversion;
// if we set that during init, we get the same effect. If
// DISABLE_INVERT_IQ_ON_RX is defined, it means that LMIC.noRXIQinversion is
// treated as always set.
//
// #if !defined(DISABLE_INVERT_IQ_ON_RX)
// #error This example requires DISABLE_INVERT_IQ_ON_RX to be set. Update \
// lmic_project_config.h in arduino-lmic/project_config to set it.
// #endif
// How often to send a packet. Note that this sketch bypasses the normal
// LMIC duty cycle limiting, so when you change anything in this sketch
// (payload length, frequency, spreading factor), be sure to check if
// this interval should not also be increased.
// See this spreadsheet for an easy airtime and duty cycle calculator:
// https://docs.google.com/spreadsheets/d/1voGAtQAjC1qBmaVuP1ApNKs1ekgUjavHuVQIXyYSvNc
#define TX_INTERVAL 2000
// Pin mapping
const lmic_pinmap lmic_pins = {
.nss = 6,
.rxtx = LMIC_UNUSED_PIN,
.rst = 5,
.dio = {2, 3, 4},
};
// These callbacks are only used in over-the-air activation, so they are
// left empty here (we cannot leave them out completely unless
// DISABLE_JOIN is set in arduino-lmoc/project_config/lmic_project_config.h,
// otherwise the linker will complain).
void os_getArtEui (u1_t* buf) { }
void os_getDevEui (u1_t* buf) { }
void os_getDevKey (u1_t* buf) { }
void onEvent (ev_t ev) {
}
osjob_t txjob;
osjob_t timeoutjob;
static void tx_func (osjob_t* job);
// Transmit the given string and call the given function afterwards
void tx(const char *str, osjobcb_t func) {
os_radio(RADIO_RST); // Stop RX first
delay(1); // Wait a bit, without this os_radio below asserts, apparently because the state hasn't changed yet
LMIC.dataLen = 0;
while (*str)
LMIC.frame[LMIC.dataLen++] = *str++;
LMIC.osjob.func = func;
os_radio(RADIO_TX);
Serial.println("TX");
}
// Enable rx mode and call func when a packet is received
void rx(osjobcb_t func) {
LMIC.osjob.func = func;
LMIC.rxtime = os_getTime(); // RX _now_
// Enable "continuous" RX (e.g. without a timeout, still stops after
// receiving a packet)
os_radio(RADIO_RXON);
Serial.println("RX");
}
static void rxtimeout_func(osjob_t *job) {
digitalWrite(LED_BUILTIN, LOW); // off
}
static void rx_func (osjob_t* job) {
// Blink once to confirm reception and then keep the led on
digitalWrite(LED_BUILTIN, LOW); // off
delay(10);
digitalWrite(LED_BUILTIN, HIGH); // on
// Timeout RX (i.e. update led status) after 3 periods without RX
os_setTimedCallback(&timeoutjob, os_getTime() + ms2osticks(3*TX_INTERVAL), rxtimeout_func);
// Reschedule TX so that it should not collide with the other side's
// next TX
os_setTimedCallback(&txjob, os_getTime() + ms2osticks(TX_INTERVAL/2), tx_func);
Serial.print("Got ");
Serial.print(LMIC.dataLen);
Serial.println(" bytes");
Serial.write(LMIC.frame, LMIC.dataLen);
Serial.println();
// Restart RX
rx(rx_func);
}
static void txdone_func (osjob_t* job) {
rx(rx_func);
}
// log text to USART and toggle LED
static void tx_func (osjob_t* job) {
// say hello
tx("Hello, world!", txdone_func);
// reschedule job every TX_INTERVAL (plus a bit of random to prevent
// systematic collisions), unless packets are received, then rx_func
// will reschedule at half this time.
os_setTimedCallback(job, os_getTime() + ms2osticks(TX_INTERVAL + random(500)), tx_func);
}
// application entry point
void setup() {
Serial.begin(115200);
Serial.println("Starting");
#ifdef VCC_ENABLE
// For Pinoccio Scout boards
pinMode(VCC_ENABLE, OUTPUT);
digitalWrite(VCC_ENABLE, HIGH);
delay(1000);
#endif
pinMode(LED_BUILTIN, OUTPUT);
// initialize runtime env
os_init();
// Set up these settings once, and use them for both TX and RX
#if defined(CFG_eu868)
// Use a frequency in the g3 which allows 10% duty cycling.
LMIC.freq = 869525000;
#elif defined(CFG_us915)
LMIC.freq = 902300000;
#else
error Region not supported!
#endif
// Maximum TX power
LMIC.txpow = 27;
// Use a medium spread factor. This can be increased up to SF12 for
// better range, but then the interval should be (significantly)
// lowered to comply with duty cycle limits as well.
LMIC.datarate = DR_SF9;
// This sets CR 4/5, BW125 (except for DR_SF7B, which uses BW250)
LMIC.rps = updr2rps(LMIC.datarate);
// disable RX IQ inversion
LMIC.noRXIQinversion = true;
Serial.println("Started");
Serial.flush();
// setup initial job
os_setCallback(&txjob, tx_func);
}
void loop() {
// execute scheduled jobs and events
os_runloop_once();
}

View File

@ -1,266 +0,0 @@
/*******************************************************************************
* The Things Network - ABP Feather
*
* Example of using an Adafruit Feather M0 and DHT22 with a
* single-channel TheThingsNetwork gateway.
*
* This uses ABP (Activation by Personalization), where session keys for
* communication would be assigned/generated by TTN and hard-coded on the device.
*
* Learn Guide: https://learn.adafruit.com/lora-pi
*
* Copyright (c) 2015 Thomas Telkamp and Matthijs Kooijman
* Copyright (c) 2018 Terry Moore, MCCI
* Copyright (c) 2018 Brent Rubell, Adafruit Industries
*
* Permission is hereby granted, free of charge, to anyone
* obtaining a copy of this document and accompanying files,
* to do whatever they want with them without any restriction,
* including, but not limited to, copying, modification and redistribution.
* NO WARRANTY OF ANY KIND IS PROVIDED.
*******************************************************************************/
#include <lmic.h>
#include <hal/hal.h>
#include <SPI.h>
// include the DHT22 Sensor Library
#include "DHT.h"
// DHT digital pin and sensor type
#define DHTPIN 10
#define DHTTYPE DHT22
//
// For normal use, we require that you edit the sketch to replace FILLMEIN
// with values assigned by the TTN console. However, for regression tests,
// we want to be able to compile these scripts. The regression tests define
// COMPILE_REGRESSION_TEST, and in that case we define FILLMEIN to a non-
// working but innocuous value.
//
#ifdef COMPILE_REGRESSION_TEST
# define FILLMEIN 0
#else
# warning "You must replace the values marked FILLMEIN with real values from the TTN control panel!"
# define FILLMEIN (#dont edit this, edit the lines that use FILLMEIN)
#endif
// LoRaWAN NwkSKey, network session key
static const PROGMEM u1_t NWKSKEY[16] = { FILLMEIN };
// LoRaWAN AppSKey, application session key
static const u1_t PROGMEM APPSKEY[16] = { FILLMEIN };
// LoRaWAN end-device address (DevAddr)
// See http://thethingsnetwork.org/wiki/AddressSpace
// The library converts the address to network byte order as needed.
#ifndef COMPILE_REGRESSION_TEST
static const u4_t DEVADDR = 0xFILLMEIN;
#else
static const u4_t DEVADDR = 0;
#endif
// These callbacks are only used in over-the-air activation, so they are
// left empty here (we cannot leave them out completely unless
// DISABLE_JOIN is set in arduino-lmic/project_config/lmic_project_config.h,
// otherwise the linker will complain).
void os_getArtEui (u1_t* buf) { }
void os_getDevEui (u1_t* buf) { }
void os_getDevKey (u1_t* buf) { }
// payload to send to TTN gateway
static uint8_t payload[5];
static osjob_t sendjob;
// Schedule TX every this many seconds (might become longer due to duty
// cycle limitations).
const unsigned TX_INTERVAL = 30;
// Pin mapping for Adafruit Feather M0 LoRa
const lmic_pinmap lmic_pins = {
.nss = 8,
.rxtx = LMIC_UNUSED_PIN,
.rst = 4,
.dio = {3, 6, LMIC_UNUSED_PIN},
.rxtx_rx_active = 0,
.rssi_cal = 8, // LBT cal for the Adafruit Feather M0 LoRa, in dB
.spi_freq = 8000000,
};
// init. DHT
DHT dht(DHTPIN, DHTTYPE);
void onEvent (ev_t ev) {
Serial.print(os_getTime());
Serial.print(": ");
switch(ev) {
case EV_SCAN_TIMEOUT:
Serial.println(F("EV_SCAN_TIMEOUT"));
break;
case EV_BEACON_FOUND:
Serial.println(F("EV_BEACON_FOUND"));
break;
case EV_BEACON_MISSED:
Serial.println(F("EV_BEACON_MISSED"));
break;
case EV_BEACON_TRACKED:
Serial.println(F("EV_BEACON_TRACKED"));
break;
case EV_JOINING:
Serial.println(F("EV_JOINING"));
break;
case EV_JOINED:
Serial.println(F("EV_JOINED"));
break;
/*
|| This event is defined but not used in the code. No
|| point in wasting codespace on it.
||
|| case EV_RFU1:
|| Serial.println(F("EV_RFU1"));
|| break;
*/
case EV_JOIN_FAILED:
Serial.println(F("EV_JOIN_FAILED"));
break;
case EV_REJOIN_FAILED:
Serial.println(F("EV_REJOIN_FAILED"));
break;
case EV_TXCOMPLETE:
Serial.println(F("EV_TXCOMPLETE (includes waiting for RX windows)"));
if (LMIC.txrxFlags & TXRX_ACK)
Serial.println(F("Received ack"));
if (LMIC.dataLen) {
Serial.println(F("Received "));
Serial.println(LMIC.dataLen);
Serial.println(F(" bytes of payload"));
}
// Schedule next transmission
os_setTimedCallback(&sendjob, os_getTime()+sec2osticks(TX_INTERVAL), do_send);
break;
case EV_LOST_TSYNC:
Serial.println(F("EV_LOST_TSYNC"));
break;
case EV_RESET:
Serial.println(F("EV_RESET"));
break;
case EV_RXCOMPLETE:
// data received in ping slot
Serial.println(F("EV_RXCOMPLETE"));
break;
case EV_LINK_DEAD:
Serial.println(F("EV_LINK_DEAD"));
break;
case EV_LINK_ALIVE:
Serial.println(F("EV_LINK_ALIVE"));
break;
/*
|| This event is defined but not used in the code. No
|| point in wasting codespace on it.
||
|| case EV_SCAN_FOUND:
|| Serial.println(F("EV_SCAN_FOUND"));
|| break;
*/
case EV_TXSTART:
Serial.println(F("EV_TXSTART"));
break;
default:
Serial.print(F("Unknown event: "));
Serial.println((unsigned) ev);
break;
}
}
void do_send(osjob_t* j){
// Check if there is not a current TX/RX job running
if (LMIC.opmode & OP_TXRXPEND) {
Serial.println(F("OP_TXRXPEND, not sending"));
} else {
// read the temperature from the DHT22
float temperature = dht.readTemperature();
Serial.print("Temperature: "); Serial.print(temperature);
Serial.println(" *C");
// adjust for the f2sflt16 range (-1 to 1)
temperature = temperature / 100;
// read the humidity from the DHT22
float rHumidity = dht.readHumidity();
Serial.print("%RH ");
Serial.println(rHumidity);
// adjust for the f2sflt16 range (-1 to 1)
rHumidity = rHumidity / 100;
// float -> int
// note: this uses the sflt16 datum (https://github.com/mcci-catena/arduino-lmic#sflt16)
uint16_t payloadTemp = LMIC_f2sflt16(temperature);
// int -> bytes
byte tempLow = lowByte(payloadTemp);
byte tempHigh = highByte(payloadTemp);
// place the bytes into the payload
payload[0] = tempLow;
payload[1] = tempHigh;
// float -> int
uint16_t payloadHumid = LMIC_f2sflt16(rHumidity);
// int -> bytes
byte humidLow = lowByte(payloadHumid);
byte humidHigh = highByte(payloadHumid);
payload[2] = humidLow;
payload[3] = humidHigh;
// prepare upstream data transmission at the next possible time.
// transmit on port 1 (the first parameter); you can use any value from 1 to 223 (others are reserved).
// don't request an ack (the last parameter, if not zero, requests an ack from the network).
// Remember, acks consume a lot of network resources; don't ask for an ack unless you really need it.
LMIC_setTxData2(1, payload, sizeof(payload)-1, 0);
}
// Next TX is scheduled after TX_COMPLETE event.
}
void setup() {
delay(5000);
while (!Serial);
Serial.begin(115200);
delay(100);
Serial.println(F("Starting"));
// LMIC init
os_init();
// Reset the MAC state. Session and pending data transfers will be discarded.
LMIC_reset();
// Set static session parameters. Instead of dynamically establishing a session
// by joining the network, precomputed session parameters are be provided.
// On AVR, these values are stored in flash and only copied to RAM
// once. Copy them to a temporary buffer here, LMIC_setSession will
// copy them into a buffer of its own again.
uint8_t appskey[sizeof(APPSKEY)];
uint8_t nwkskey[sizeof(NWKSKEY)];
memcpy_P(appskey, APPSKEY, sizeof(APPSKEY));
memcpy_P(nwkskey, NWKSKEY, sizeof(NWKSKEY));
LMIC_setSession (0x13, DEVADDR, nwkskey, appskey);
// We'll disable all 72 channels used by TTN
for (int c = 0; c < 72; c++){
LMIC_disableChannel(c);
}
// We'll only enable Channel 16 (905.5Mhz) since we're transmitting on a single-channel
LMIC_enableChannel(16);
// Disable link check validation
LMIC_setLinkCheckMode(0);
// TTN uses SF9 for its RX2 window.
LMIC.dn2Dr = DR_SF9;
// Set data rate and transmit power for uplink (note: txpow seems to be ignored by the library)
LMIC_setDrTxpow(DR_SF7,14);
// Start job
do_send(&sendjob);
}
void loop() {
os_runloop_once();
}

View File

@ -1,276 +0,0 @@
/*******************************************************************************
* Copyright (c) 2015 Thomas Telkamp and Matthijs Kooijman
* Copyright (c) 2018 Terry Moore, MCCI
*
* Permission is hereby granted, free of charge, to anyone
* obtaining a copy of this document and accompanying files,
* to do whatever they want with them without any restriction,
* including, but not limited to, copying, modification and redistribution.
* NO WARRANTY OF ANY KIND IS PROVIDED.
*
* This example sends a valid LoRaWAN packet with payload "Hello,
* world!", using frequency and encryption settings matching those of
* the The Things Network.
*
* This uses ABP (Activation-by-personalisation), where a DevAddr and
* Session keys are preconfigured (unlike OTAA, where a DevEUI and
* application key is configured, while the DevAddr and session keys are
* assigned/generated in the over-the-air-activation procedure).
*
* Note: LoRaWAN per sub-band duty-cycle limitation is enforced (1% in
* g1, 0.1% in g2), but not the TTN fair usage policy (which is probably
* violated by this sketch when left running for longer)!
*
* To use this sketch, first register your application and device with
* the things network, to set or generate a DevAddr, NwkSKey and
* AppSKey. Each device should have their own unique values for these
* fields.
*
* Do not forget to define the radio type correctly in
* arduino-lmic/project_config/lmic_project_config.h or from your BOARDS.txt.
*
*******************************************************************************/
// References:
// [feather] adafruit-feather-m0-radio-with-lora-module.pdf
#include <lmic.h>
#include <hal/hal.h>
#include <SPI.h>
//
// For normal use, we require that you edit the sketch to replace FILLMEIN
// with values assigned by the TTN console. However, for regression tests,
// we want to be able to compile these scripts. The regression tests define
// COMPILE_REGRESSION_TEST, and in that case we define FILLMEIN to a non-
// working but innocuous value.
//
#ifdef COMPILE_REGRESSION_TEST
# define FILLMEIN 0
#else
# warning "You must replace the values marked FILLMEIN with real values from the TTN control panel!"
# define FILLMEIN (#dont edit this, edit the lines that use FILLMEIN)
#endif
// LoRaWAN NwkSKey, network session key
static const PROGMEM u1_t NWKSKEY[16] = { FILLMEIN };
// LoRaWAN AppSKey, application session key
static const u1_t PROGMEM APPSKEY[16] = { FILLMEIN };
// LoRaWAN end-device address (DevAddr)
// See http://thethingsnetwork.org/wiki/AddressSpace
// The library converts the address to network byte order as needed.
static const u4_t DEVADDR = FILLMEIN ; // <-- Change this address for every node!
// These callbacks are only used in over-the-air activation, so they are
// left empty here (we cannot leave them out completely unless
// DISABLE_JOIN is set in arduino-lmic/project_config/lmic_project_config.h,
// otherwise the linker will complain).
void os_getArtEui (u1_t* buf) { }
void os_getDevEui (u1_t* buf) { }
void os_getDevKey (u1_t* buf) { }
static uint8_t mydata[] = "Hello, world!";
static osjob_t sendjob;
// Schedule TX every this many seconds (might become longer due to duty
// cycle limitations).
const unsigned TX_INTERVAL = 60;
// Pin mapping
// Adapted for Feather M0 per p.10 of [feather]
const lmic_pinmap lmic_pins = {
.nss = 8, // chip select on feather (rf95module) CS
.rxtx = LMIC_UNUSED_PIN,
.rst = 4, // reset pin
.dio = {6, 5, LMIC_UNUSED_PIN}, // assumes external jumpers [feather_lora_jumper]
// DIO1 is on JP1-1: is io1 - we connect to GPO6
// DIO1 is on JP5-3: is D2 - we connect to GPO5
};
void onEvent (ev_t ev) {
Serial.print(os_getTime());
Serial.print(": ");
switch(ev) {
case EV_SCAN_TIMEOUT:
Serial.println(F("EV_SCAN_TIMEOUT"));
break;
case EV_BEACON_FOUND:
Serial.println(F("EV_BEACON_FOUND"));
break;
case EV_BEACON_MISSED:
Serial.println(F("EV_BEACON_MISSED"));
break;
case EV_BEACON_TRACKED:
Serial.println(F("EV_BEACON_TRACKED"));
break;
case EV_JOINING:
Serial.println(F("EV_JOINING"));
break;
case EV_JOINED:
Serial.println(F("EV_JOINED"));
break;
/*
|| This event is defined but not used in the code. No
|| point in wasting codespace on it.
||
|| case EV_RFU1:
|| Serial.println(F("EV_RFU1"));
|| break;
*/
case EV_JOIN_FAILED:
Serial.println(F("EV_JOIN_FAILED"));
break;
case EV_REJOIN_FAILED:
Serial.println(F("EV_REJOIN_FAILED"));
break;
case EV_TXCOMPLETE:
Serial.println(F("EV_TXCOMPLETE (includes waiting for RX windows)"));
if (LMIC.txrxFlags & TXRX_ACK)
Serial.println(F("Received ack"));
if (LMIC.dataLen) {
Serial.println(F("Received "));
Serial.println(LMIC.dataLen);
Serial.println(F(" bytes of payload"));
}
// Schedule next transmission
os_setTimedCallback(&sendjob, os_getTime()+sec2osticks(TX_INTERVAL), do_send);
break;
case EV_LOST_TSYNC:
Serial.println(F("EV_LOST_TSYNC"));
break;
case EV_RESET:
Serial.println(F("EV_RESET"));
break;
case EV_RXCOMPLETE:
// data received in ping slot
Serial.println(F("EV_RXCOMPLETE"));
break;
case EV_LINK_DEAD:
Serial.println(F("EV_LINK_DEAD"));
break;
case EV_LINK_ALIVE:
Serial.println(F("EV_LINK_ALIVE"));
break;
/*
|| This event is defined but not used in the code. No
|| point in wasting codespace on it.
||
|| case EV_SCAN_FOUND:
|| Serial.println(F("EV_SCAN_FOUND"));
|| break;
*/
case EV_TXSTART:
Serial.println(F("EV_TXSTART"));
break;
default:
Serial.print(F("Unknown event: "));
Serial.println((unsigned) ev);
break;
}
}
void do_send(osjob_t* j){
// Check if there is not a current TX/RX job running
if (LMIC.opmode & OP_TXRXPEND) {
Serial.println(F("OP_TXRXPEND, not sending"));
} else {
// Prepare upstream data transmission at the next possible time.
LMIC_setTxData2(1, mydata, sizeof(mydata)-1, 0);
Serial.println(F("Packet queued"));
}
// Next TX is scheduled after TX_COMPLETE event.
}
void setup() {
// pinMode(13, OUTPUT);
while (!Serial); // wait for Serial to be initialized
Serial.begin(115200);
delay(100); // per sample code on RF_95 test
Serial.println(F("Starting"));
#ifdef VCC_ENABLE
// For Pinoccio Scout boards
pinMode(VCC_ENABLE, OUTPUT);
digitalWrite(VCC_ENABLE, HIGH);
delay(1000);
#endif
// LMIC init
os_init();
// Reset the MAC state. Session and pending data transfers will be discarded.
LMIC_reset();
// Set static session parameters. Instead of dynamically establishing a session
// by joining the network, precomputed session parameters are be provided.
#ifdef PROGMEM
// On AVR, these values are stored in flash and only copied to RAM
// once. Copy them to a temporary buffer here, LMIC_setSession will
// copy them into a buffer of its own again.
uint8_t appskey[sizeof(APPSKEY)];
uint8_t nwkskey[sizeof(NWKSKEY)];
memcpy_P(appskey, APPSKEY, sizeof(APPSKEY));
memcpy_P(nwkskey, NWKSKEY, sizeof(NWKSKEY));
LMIC_setSession (0x13, DEVADDR, nwkskey, appskey);
#else
// If not running an AVR with PROGMEM, just use the arrays directly
LMIC_setSession (0x13, DEVADDR, NWKSKEY, APPSKEY);
#endif
#if defined(CFG_eu868)
// Set up the channels used by the Things Network, which corresponds
// to the defaults of most gateways. Without this, only three base
// channels from the LoRaWAN specification are used, which certainly
// works, so it is good for debugging, but can overload those
// frequencies, so be sure to configure the full frequency range of
// your network here (unless your network autoconfigures them).
// Setting up channels should happen after LMIC_setSession, as that
// configures the minimal channel set.
LMIC_setupChannel(0, 868100000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(1, 868300000, DR_RANGE_MAP(DR_SF12, DR_SF7B), BAND_CENTI); // g-band
LMIC_setupChannel(2, 868500000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(3, 867100000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(4, 867300000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(5, 867500000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(6, 867700000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(7, 867900000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(8, 868800000, DR_RANGE_MAP(DR_FSK, DR_FSK), BAND_MILLI); // g2-band
// TTN defines an additional channel at 869.525Mhz using SF9 for class B
// devices' ping slots. LMIC does not have an easy way to define set this
// frequency and support for class B is spotty and untested, so this
// frequency is not configured here.
#elif defined(CFG_us915)
// NA-US channels 0-71 are configured automatically
// but only one group of 8 should (a subband) should be active
// TTN recommends the second sub band, 1 in a zero based count.
// https://github.com/TheThingsNetwork/gateway-conf/blob/master/US-global_conf.json
LMIC_selectSubBand(1);
#endif
// Disable link check validation
LMIC_setLinkCheckMode(0);
// TTN uses SF9 for its RX2 window.
LMIC.dn2Dr = DR_SF9;
// Set data rate and transmit power for uplink (note: txpow seems to be ignored by the library)
LMIC_setDrTxpow(DR_SF7,14);
// Start job
do_send(&sendjob);
}
void loop() {
unsigned long now;
now = millis();
if ((now & 512) != 0) {
digitalWrite(13, HIGH);
}
else {
digitalWrite(13, LOW);
}
os_runloop_once();
}

View File

@ -1,274 +0,0 @@
/*******************************************************************************
* The Things Network - Sensor Data Example
*
* Example of sending a valid LoRaWAN packet with DHT22 temperature and
* humidity data to The Things Networ using a Feather M0 LoRa.
*
* Learn Guide: https://learn.adafruit.com/the-things-network-for-feather
*
* Copyright (c) 2015 Thomas Telkamp and Matthijs Kooijman
* Copyright (c) 2018 Terry Moore, MCCI
* Copyright (c) 2018 Brent Rubell, Adafruit Industries
*
* Permission is hereby granted, free of charge, to anyone
* obtaining a copy of this document and accompanying files,
* to do whatever they want with them without any restriction,
* including, but not limited to, copying, modification and redistribution.
* NO WARRANTY OF ANY KIND IS PROVIDED.
*******************************************************************************/
#include <lmic.h>
#include <hal/hal.h>
#include <SPI.h>
// include the DHT22 Sensor Library
#include "DHT.h"
// DHT digital pin and sensor type
#define DHTPIN 10
#define DHTTYPE DHT22
//
// For normal use, we require that you edit the sketch to replace FILLMEIN
// with values assigned by the TTN console. However, for regression tests,
// we want to be able to compile these scripts. The regression tests define
// COMPILE_REGRESSION_TEST, and in that case we define FILLMEIN to a non-
// working but innocuous value.
//
#ifdef COMPILE_REGRESSION_TEST
#define FILLMEIN 0
#else
#warning "You must replace the values marked FILLMEIN with real values from the TTN control panel!"
#define FILLMEIN (#dont edit this, edit the lines that use FILLMEIN)
#endif
// This EUI must be in little-endian format, so least-significant-byte
// first. When copying an EUI from ttnctl output, this means to reverse
// the bytes. For TTN issued EUIs the last bytes should be 0xD5, 0xB3,
// 0x70.
static const u1_t PROGMEM APPEUI[8] = { FILLMEIN };
void os_getArtEui (u1_t* buf) { memcpy_P(buf, APPEUI, 8);}
// This should also be in little endian format, see above.
static const u1_t PROGMEM DEVEUI[8] = { FILLMEIN };
void os_getDevEui (u1_t* buf) { memcpy_P(buf, DEVEUI, 8);}
// This key should be in big endian format (or, since it is not really a
// number but a block of memory, endianness does not really apply). In
// practice, a key taken from the TTN console can be copied as-is.
static const u1_t PROGMEM APPKEY[16] = { FILLMEIN };
void os_getDevKey (u1_t* buf) { memcpy_P(buf, APPKEY, 16);}
// payload to send to TTN gateway
static uint8_t payload[5];
static osjob_t sendjob;
// Schedule TX every this many seconds (might become longer due to duty
// cycle limitations).
const unsigned TX_INTERVAL = 30;
// Pin mapping for Adafruit Feather M0 LoRa
const lmic_pinmap lmic_pins = {
.nss = 8,
.rxtx = LMIC_UNUSED_PIN,
.rst = 4,
.dio = {3, 6, LMIC_UNUSED_PIN},
.rxtx_rx_active = 0,
.rssi_cal = 8, // LBT cal for the Adafruit Feather M0 LoRa, in dB
.spi_freq = 8000000,
};
// init. DHT
DHT dht(DHTPIN, DHTTYPE);
void onEvent (ev_t ev) {
Serial.print(os_getTime());
Serial.print(": ");
switch(ev) {
case EV_SCAN_TIMEOUT:
Serial.println(F("EV_SCAN_TIMEOUT"));
break;
case EV_BEACON_FOUND:
Serial.println(F("EV_BEACON_FOUND"));
break;
case EV_BEACON_MISSED:
Serial.println(F("EV_BEACON_MISSED"));
break;
case EV_BEACON_TRACKED:
Serial.println(F("EV_BEACON_TRACKED"));
break;
case EV_JOINING:
Serial.println(F("EV_JOINING"));
break;
case EV_JOINED:
Serial.println(F("EV_JOINED"));
{
u4_t netid = 0;
devaddr_t devaddr = 0;
u1_t nwkKey[16];
u1_t artKey[16];
LMIC_getSessionKeys(&netid, &devaddr, nwkKey, artKey);
Serial.print("netid: ");
Serial.println(netid, DEC);
Serial.print("devaddr: ");
Serial.println(devaddr, HEX);
Serial.print("artKey: ");
for (int i=0; i<sizeof(artKey); ++i) {
if (i != 0)
Serial.print("-");
Serial.print(artKey[i], HEX);
}
Serial.println("");
Serial.print("nwkKey: ");
for (int i=0; i<sizeof(nwkKey); ++i) {
if (i != 0)
Serial.print("-");
Serial.print(nwkKey[i], HEX);
}
Serial.println("");
}
// Disable link check validation (automatically enabled
// during join, but because slow data rates change max TX
// size, we don't use it in this example.
LMIC_setLinkCheckMode(0);
break;
/*
|| This event is defined but not used in the code. No
|| point in wasting codespace on it.
||
|| case EV_RFU1:
|| Serial.println(F("EV_RFU1"));
|| break;
*/
case EV_JOIN_FAILED:
Serial.println(F("EV_JOIN_FAILED"));
break;
case EV_REJOIN_FAILED:
Serial.println(F("EV_REJOIN_FAILED"));
break;
break;
case EV_TXCOMPLETE:
Serial.println(F("EV_TXCOMPLETE (includes waiting for RX windows)"));
if (LMIC.txrxFlags & TXRX_ACK)
Serial.println(F("Received ack"));
if (LMIC.dataLen) {
Serial.println(F("Received "));
Serial.println(LMIC.dataLen);
Serial.println(F(" bytes of payload"));
}
// Schedule next transmission
os_setTimedCallback(&sendjob, os_getTime()+sec2osticks(TX_INTERVAL), do_send);
break;
case EV_LOST_TSYNC:
Serial.println(F("EV_LOST_TSYNC"));
break;
case EV_RESET:
Serial.println(F("EV_RESET"));
break;
case EV_RXCOMPLETE:
// data received in ping slot
Serial.println(F("EV_RXCOMPLETE"));
break;
case EV_LINK_DEAD:
Serial.println(F("EV_LINK_DEAD"));
break;
case EV_LINK_ALIVE:
Serial.println(F("EV_LINK_ALIVE"));
break;
/*
|| This event is defined but not used in the code. No
|| point in wasting codespace on it.
||
|| case EV_SCAN_FOUND:
|| Serial.println(F("EV_SCAN_FOUND"));
|| break;
*/
case EV_TXSTART:
Serial.println(F("EV_TXSTART"));
break;
default:
Serial.print(F("Unknown event: "));
Serial.println((unsigned) ev);
break;
}
}
void do_send(osjob_t* j){
// Check if there is not a current TX/RX job running
if (LMIC.opmode & OP_TXRXPEND) {
Serial.println(F("OP_TXRXPEND, not sending"));
} else {
// read the temperature from the DHT22
float temperature = dht.readTemperature();
Serial.print("Temperature: "); Serial.print(temperature);
Serial.println(" *C");
// adjust for the f2sflt16 range (-1 to 1)
temperature = temperature / 100;
// read the humidity from the DHT22
float rHumidity = dht.readHumidity();
Serial.print("%RH ");
Serial.println(rHumidity);
// adjust for the f2sflt16 range (-1 to 1)
rHumidity = rHumidity / 100;
// float -> int
// note: this uses the sflt16 datum (https://github.com/mcci-catena/arduino-lmic#sflt16)
uint16_t payloadTemp = LMIC_f2sflt16(temperature);
// int -> bytes
byte tempLow = lowByte(payloadTemp);
byte tempHigh = highByte(payloadTemp);
// place the bytes into the payload
payload[0] = tempLow;
payload[1] = tempHigh;
// float -> int
uint16_t payloadHumid = LMIC_f2sflt16(rHumidity);
// int -> bytes
byte humidLow = lowByte(payloadHumid);
byte humidHigh = highByte(payloadHumid);
payload[2] = humidLow;
payload[3] = humidHigh;
// prepare upstream data transmission at the next possible time.
// transmit on port 1 (the first parameter); you can use any value from 1 to 223 (others are reserved).
// don't request an ack (the last parameter, if not zero, requests an ack from the network).
// Remember, acks consume a lot of network resources; don't ask for an ack unless you really need it.
LMIC_setTxData2(1, payload, sizeof(payload)-1, 0);
}
// Next TX is scheduled after TX_COMPLETE event.
}
void setup() {
delay(5000);
while (! Serial);
Serial.begin(9600);
Serial.println(F("Starting"));
dht.begin();
// LMIC init
os_init();
// Reset the MAC state. Session and pending data transfers will be discarded.
LMIC_reset();
// Disable link-check mode and ADR, because ADR tends to complicate testing.
LMIC_setLinkCheckMode(0);
// Set the data rate to Spreading Factor 7. This is the fastest supported rate for 125 kHz channels, and it
// minimizes air time and battery power. Set the transmission power to 14 dBi (25 mW).
LMIC_setDrTxpow(DR_SF7,14);
// in the US, with TTN, it saves join time if we start on subband 1 (channels 8-15). This will
// get overridden after the join by parameters from the network. If working with other
// networks or in other regions, this will need to be changed.
LMIC_selectSubBand(1);
// Start job (sending automatically starts OTAA too)
do_send(&sendjob);
}
void loop() {
// we call the LMIC's runloop processor. This will cause things to happen based on events and time. One
// of the things that will happen is callbacks for transmission complete or received messages. We also
// use this loop to queue periodic data transmissions. You can put other things here in the `loop()` routine,
// but beware that LoRaWAN timing is pretty tight, so if you do more than a few milliseconds of work, you
// will want to call `os_runloop_once()` every so often, to keep the radio running.
os_runloop_once();
}

View File

@ -1,274 +0,0 @@
/*******************************************************************************
* Copyright (c) 2015 Thomas Telkamp and Matthijs Kooijman
* Copyright (c) 2018 Terry Moore, MCCI
*
* Permission is hereby granted, free of charge, to anyone
* obtaining a copy of this document and accompanying files,
* to do whatever they want with them without any restriction,
* including, but not limited to, copying, modification and redistribution.
* NO WARRANTY OF ANY KIND IS PROVIDED.
*
* This example sends a valid LoRaWAN packet with payload "Hello,
* world!", using frequency and encryption settings matching those of
* the The Things Network. It's pre-configured for the Adafruit
* Feather M0 LoRa.
*
* This uses OTAA (Over-the-air activation), where where a DevEUI and
* application key is configured, which are used in an over-the-air
* activation procedure where a DevAddr and session keys are
* assigned/generated for use with all further communication.
*
* Note: LoRaWAN per sub-band duty-cycle limitation is enforced (1% in
* g1, 0.1% in g2), but not the TTN fair usage policy (which is probably
* violated by this sketch when left running for longer)!
* To use this sketch, first register your application and device with
* the things network, to set or generate an AppEUI, DevEUI and AppKey.
* Multiple devices can use the same AppEUI, but each device has its own
* DevEUI and AppKey.
*
* Do not forget to define the radio type correctly in
* arduino-lmic/project_config/lmic_project_config.h or from your BOARDS.txt.
*
*******************************************************************************/
#include <lmic.h>
#include <hal/hal.h>
#include <SPI.h>
//
// For normal use, we require that you edit the sketch to replace FILLMEIN
// with values assigned by the TTN console. However, for regression tests,
// we want to be able to compile these scripts. The regression tests define
// COMPILE_REGRESSION_TEST, and in that case we define FILLMEIN to a non-
// working but innocuous value.
//
#ifdef COMPILE_REGRESSION_TEST
# define FILLMEIN 0
#else
# warning "You must replace the values marked FILLMEIN with real values from the TTN control panel!"
# define FILLMEIN (#dont edit this, edit the lines that use FILLMEIN)
#endif
// This EUI must be in little-endian format, so least-significant-byte
// first. When copying an EUI from ttnctl output, this means to reverse
// the bytes. For TTN issued EUIs the last bytes should be 0xD5, 0xB3,
// 0x70.
static const u1_t PROGMEM APPEUI[8]= { FILLMEIN };
void os_getArtEui (u1_t* buf) { memcpy_P(buf, APPEUI, 8);}
// This should also be in little endian format, see above.
static const u1_t PROGMEM DEVEUI[8]= { FILLMEIN };
void os_getDevEui (u1_t* buf) { memcpy_P(buf, DEVEUI, 8);}
// This key should be in big endian format (or, since it is not really a
// number but a block of memory, endianness does not really apply). In
// practice, a key taken from the TTN console can be copied as-is.
static const u1_t PROGMEM APPKEY[16] = { FILLMEIN };
void os_getDevKey (u1_t* buf) { memcpy_P(buf, APPKEY, 16);}
static uint8_t mydata[] = "Hello, world!";
static osjob_t sendjob;
// Schedule TX every this many seconds (might become longer due to duty
// cycle limitations).
const unsigned TX_INTERVAL = 60;
// Pin mapping
#if defined(ARDUINO_SAMD_FEATHER_M0)
// Pin mapping for Adafruit Feather M0 LoRa, etc.
const lmic_pinmap lmic_pins = {
.nss = 8,
.rxtx = LMIC_UNUSED_PIN,
.rst = 4,
.dio = {3, 6, LMIC_UNUSED_PIN},
.rxtx_rx_active = 0,
.rssi_cal = 8, // LBT cal for the Adafruit Feather M0 LoRa, in dB
.spi_freq = 8000000,
};
#elif defined(ARDUINO_AVR_FEATHER32U4)
// Pin mapping for Adafruit Feather 32u4 LoRa, etc.
// Just like Feather M0 LoRa, but uses SPI at 1MHz; and that's only
// because MCCI doesn't have a test board; probably higher frequencies
// will work.
const lmic_pinmap lmic_pins = {
.nss = 8,
.rxtx = LMIC_UNUSED_PIN,
.rst = 4,
.dio = {3, 6, LMIC_UNUSED_PIN},
.rxtx_rx_active = 0,
.rssi_cal = 8, // LBT cal for the Adafruit Feather M0 LoRa, in dB
.spi_freq = 1000000,
};
#elif defined(ARDUINO_CATENA_4551)
// Pin mapping for Murata module / Catena 4551
const lmic_pinmap lmic_pins = {
.nss = 7,
.rxtx = 29,
.rst = 8,
.dio = { 25, // DIO0 (IRQ) is D25
26, // DIO1 is D26
27, // DIO2 is D27
},
.rxtx_rx_active = 1,
.rssi_cal = 10,
.spi_freq = 8000000 // 8MHz
};
#else
# error "Unknown target"
#endif
void onEvent (ev_t ev) {
Serial.print(os_getTime());
Serial.print(": ");
switch(ev) {
case EV_SCAN_TIMEOUT:
Serial.println(F("EV_SCAN_TIMEOUT"));
break;
case EV_BEACON_FOUND:
Serial.println(F("EV_BEACON_FOUND"));
break;
case EV_BEACON_MISSED:
Serial.println(F("EV_BEACON_MISSED"));
break;
case EV_BEACON_TRACKED:
Serial.println(F("EV_BEACON_TRACKED"));
break;
case EV_JOINING:
Serial.println(F("EV_JOINING"));
break;
case EV_JOINED:
Serial.println(F("EV_JOINED"));
{
u4_t netid = 0;
devaddr_t devaddr = 0;
u1_t nwkKey[16];
u1_t artKey[16];
LMIC_getSessionKeys(&netid, &devaddr, nwkKey, artKey);
Serial.print("netid: ");
Serial.println(netid, DEC);
Serial.print("devaddr: ");
Serial.println(devaddr, HEX);
Serial.print("artKey: ");
for (int i=0; i<sizeof(artKey); ++i) {
if (i != 0)
Serial.print("-");
Serial.print(artKey[i], HEX);
}
Serial.println("");
Serial.print("nwkKey: ");
for (int i=0; i<sizeof(nwkKey); ++i) {
if (i != 0)
Serial.print("-");
Serial.print(nwkKey[i], HEX);
}
Serial.println("");
}
// Disable link check validation (automatically enabled
// during join, but because slow data rates change max TX
// size, we don't use it in this example.
LMIC_setLinkCheckMode(0);
break;
/*
|| This event is defined but not used in the code. No
|| point in wasting codespace on it.
||
|| case EV_RFU1:
|| Serial.println(F("EV_RFU1"));
|| break;
*/
case EV_JOIN_FAILED:
Serial.println(F("EV_JOIN_FAILED"));
break;
case EV_REJOIN_FAILED:
Serial.println(F("EV_REJOIN_FAILED"));
break;
break;
case EV_TXCOMPLETE:
Serial.println(F("EV_TXCOMPLETE (includes waiting for RX windows)"));
if (LMIC.txrxFlags & TXRX_ACK)
Serial.println(F("Received ack"));
if (LMIC.dataLen) {
Serial.println(F("Received "));
Serial.println(LMIC.dataLen);
Serial.println(F(" bytes of payload"));
}
// Schedule next transmission
os_setTimedCallback(&sendjob, os_getTime()+sec2osticks(TX_INTERVAL), do_send);
break;
case EV_LOST_TSYNC:
Serial.println(F("EV_LOST_TSYNC"));
break;
case EV_RESET:
Serial.println(F("EV_RESET"));
break;
case EV_RXCOMPLETE:
// data received in ping slot
Serial.println(F("EV_RXCOMPLETE"));
break;
case EV_LINK_DEAD:
Serial.println(F("EV_LINK_DEAD"));
break;
case EV_LINK_ALIVE:
Serial.println(F("EV_LINK_ALIVE"));
break;
/*
|| This event is defined but not used in the code. No
|| point in wasting codespace on it.
||
|| case EV_SCAN_FOUND:
|| Serial.println(F("EV_SCAN_FOUND"));
|| break;
*/
case EV_TXSTART:
Serial.println(F("EV_TXSTART"));
break;
default:
Serial.print(F("Unknown event: "));
Serial.println((unsigned) ev);
break;
}
}
void do_send(osjob_t* j){
// Check if there is not a current TX/RX job running
if (LMIC.opmode & OP_TXRXPEND) {
Serial.println(F("OP_TXRXPEND, not sending"));
} else {
// Prepare upstream data transmission at the next possible time.
LMIC_setTxData2(1, mydata, sizeof(mydata)-1, 0);
Serial.println(F("Packet queued"));
}
// Next TX is scheduled after TX_COMPLETE event.
}
void setup() {
delay(5000);
while (! Serial)
;
Serial.begin(9600);
Serial.println(F("Starting"));
#ifdef VCC_ENABLE
// For Pinoccio Scout boards
pinMode(VCC_ENABLE, OUTPUT);
digitalWrite(VCC_ENABLE, HIGH);
delay(1000);
#endif
// LMIC init
os_init();
// Reset the MAC state. Session and pending data transfers will be discarded.
LMIC_reset();
LMIC_setLinkCheckMode(0);
LMIC_setDrTxpow(DR_SF7,14);
LMIC_selectSubBand(1);
// Start job (sending automatically starts OTAA too)
do_send(&sendjob);
}
void loop() {
os_runloop_once();
}

View File

@ -1,293 +0,0 @@
/*******************************************************************************
* Copyright (c) 2015 Thomas Telkamp and Matthijs Kooijman
* Copyright (c) 2018 Terry Moore, MCCI
*
* Permission is hereby granted, free of charge, to anyone
* obtaining a copy of this document and accompanying files,
* to do whatever they want with them without any restriction,
* including, but not limited to, copying, modification and redistribution.
* NO WARRANTY OF ANY KIND IS PROVIDED.
*
* This example sends a valid LoRaWAN packet with payload "Hello,
* world!", using frequency and encryption settings matching those of
* the The Things Network.
*
* This uses OTAA (Over-the-air activation), where where a DevEUI and
* application key is configured, which are used in an over-the-air
* activation procedure where a DevAddr and session keys are
* assigned/generated for use with all further communication.
*
* Note: LoRaWAN per sub-band duty-cycle limitation is enforced (1% in
* g1, 0.1% in g2), but not the TTN fair usage policy (which is probably
* violated by this sketch when left running for longer)!
* To use this sketch, first register your application and device with
* the things network, to set or generate an AppEUI, DevEUI and AppKey.
* Multiple devices can use the same AppEUI, but each device has its own
* DevEUI and AppKey.
*
* Do not forget to define the radio type correctly in config.h.
*
*******************************************************************************/
#include <Time.h>
#include <lmic.h>
#include <hal/hal.h>
#include <SPI.h>
//
// For normal use, we require that you edit the sketch to replace FILLMEIN
// with values assigned by the TTN console. However, for regression tests,
// we want to be able to compile these scripts. The regression tests define
// COMPILE_REGRESSION_TEST, and in that case we define FILLMEIN to a non-
// working but innocuous value.
//
#ifdef COMPILE_REGRESSION_TEST
# define FILLMEIN 0
#else
# warning "You must replace the values marked FILLMEIN with real values from the TTN control panel!"
# define FILLMEIN (#dont edit this, edit the lines that use FILLMEIN)
#endif
// This EUI must be in little-endian format, so least-significant-byte
// first. When copying an EUI from ttnctl output, this means to reverse
// the bytes. For TTN issued EUIs the last bytes should be 0xD5, 0xB3,
// 0x70.
static const u1_t PROGMEM APPEUI[8]={ FILLMEIN };
void os_getArtEui (u1_t* buf) { memcpy_P(buf, APPEUI, 8);}
// This should also be in little endian format, see above.
static const u1_t PROGMEM DEVEUI[8]={ FILLMEIN };
void os_getDevEui (u1_t* buf) { memcpy_P(buf, DEVEUI, 8);}
// This key should be in big endian format (or, since it is not really a
// number but a block of memory, endianness does not really apply). In
// practice, a key taken from ttnctl can be copied as-is.
static const u1_t PROGMEM APPKEY[16] = { FILLMEIN };
void os_getDevKey (u1_t* buf) { memcpy_P(buf, APPKEY, 16);}
static uint8_t mydata[] = "Hello, world!";
static osjob_t sendjob;
// Schedule TX every this many seconds (might become longer due to duty
// cycle limitations).
const unsigned TX_INTERVAL = 60;
// Pin mapping
const lmic_pinmap lmic_pins = {
.nss = 6,
.rxtx = LMIC_UNUSED_PIN,
.rst = 5,
.dio = {2, 3, 4},
};
void onEvent (ev_t ev) {
Serial.print(os_getTime());
Serial.print(": ");
switch(ev) {
case EV_SCAN_TIMEOUT:
Serial.println(F("EV_SCAN_TIMEOUT"));
break;
case EV_BEACON_FOUND:
Serial.println(F("EV_BEACON_FOUND"));
break;
case EV_BEACON_MISSED:
Serial.println(F("EV_BEACON_MISSED"));
break;
case EV_BEACON_TRACKED:
Serial.println(F("EV_BEACON_TRACKED"));
break;
case EV_JOINING:
Serial.println(F("EV_JOINING"));
break;
case EV_JOINED:
Serial.println(F("EV_JOINED"));
{
u4_t netid = 0;
devaddr_t devaddr = 0;
u1_t nwkKey[16];
u1_t artKey[16];
LMIC_getSessionKeys(&netid, &devaddr, nwkKey, artKey);
Serial.print("netid: ");
Serial.println(netid, DEC);
Serial.print("devaddr: ");
Serial.println(devaddr, HEX);
Serial.print("artKey: ");
for (int i=0; i<sizeof(artKey); ++i) {
Serial.print(artKey[i], HEX);
}
Serial.println("");
Serial.print("nwkKey: ");
for (int i=0; i<sizeof(nwkKey); ++i) {
Serial.print(nwkKey[i], HEX);
}
Serial.println("");
}
// Disable link check validation (automatically enabled
// during join, but because slow data rates change max TX
// size, we don't use it in this example.
LMIC_setLinkCheckMode(0);
break;
/*
|| This event is defined but not used in the code. No
|| point in wasting codespace on it.
||
|| case EV_RFU1:
|| Serial.println(F("EV_RFU1"));
|| break;
*/
case EV_JOIN_FAILED:
Serial.println(F("EV_JOIN_FAILED"));
break;
case EV_REJOIN_FAILED:
Serial.println(F("EV_REJOIN_FAILED"));
break;
case EV_TXCOMPLETE:
Serial.println(F("EV_TXCOMPLETE (includes waiting for RX windows)"));
if (LMIC.txrxFlags & TXRX_ACK)
Serial.println(F("Received ack"));
if (LMIC.dataLen) {
Serial.print(F("Received "));
Serial.print(LMIC.dataLen);
Serial.println(F(" bytes of payload"));
}
// Schedule next transmission
os_setTimedCallback(&sendjob, os_getTime() + sec2osticks(TX_INTERVAL), do_send);
break;
case EV_LOST_TSYNC:
Serial.println(F("EV_LOST_TSYNC"));
break;
case EV_RESET:
Serial.println(F("EV_RESET"));
break;
case EV_RXCOMPLETE:
// data received in ping slot
Serial.println(F("EV_RXCOMPLETE"));
break;
case EV_LINK_DEAD:
Serial.println(F("EV_LINK_DEAD"));
break;
case EV_LINK_ALIVE:
Serial.println(F("EV_LINK_ALIVE"));
break;
/*
|| This event is defined but not used in the code. No
|| point in wasting codespace on it.
||
|| case EV_SCAN_FOUND:
|| Serial.println(F("EV_SCAN_FOUND"));
|| break;
*/
case EV_TXSTART:
Serial.println(F("EV_TXSTART"));
break;
default:
Serial.print(F("Unknown event: "));
Serial.println((unsigned) ev);
break;
}
}
uint32_t userUTCTime; // Seconds since the UTC epoch
// Utility function for digital clock display: prints preceding colon and
// leading 0
void printDigits(int digits) {
Serial.print(':');
if (digits < 10) Serial.print('0');
Serial.print(digits);
}
void user_request_network_time_callback(void *pVoidUserUTCTime, int flagSuccess) {
// Explicit conversion from void* to uint32_t* to avoid compiler errors
uint32_t *pUserUTCTime = (uint32_t *) pVoidUserUTCTime;
// A struct that will be populated by LMIC_getNetworkTimeReference.
// It contains the following fields:
// - tLocal: the value returned by os_GetTime() when the time
// request was sent to the gateway, and
// - tNetwork: the seconds between the GPS epoch and the time
// the gateway received the time request
lmic_time_reference_t lmicTimeReference;
if (flagSuccess != 1) {
Serial.println(F("USER CALLBACK: Not a success"));
return;
}
// Populate "lmic_time_reference"
flagSuccess = LMIC_getNetworkTimeReference(&lmicTimeReference);
if (flagSuccess != 1) {
Serial.println(F("USER CALLBACK: LMIC_getNetworkTimeReference didn't succeed"));
return;
}
// Update userUTCTime, considering the difference between the GPS and UTC
// epoch, and the leap seconds
*pUserUTCTime = lmicTimeReference.tNetwork + 315964800;
// Add the delay between the instant the time was transmitted and
// the current time
// Current time, in ticks
ostime_t ticksNow = os_getTime();
// Time when the request was sent, in ticks
ostime_t ticksRequestSent = lmicTimeReference.tLocal;
uint32_t requestDelaySec = osticks2ms(ticksNow - ticksRequestSent) / 1000;
*pUserUTCTime += requestDelaySec;
// Update the system time with the time read from the network
setTime(*pUserUTCTime);
Serial.print(F("The current UTC time is: "));
Serial.print(hour());
printDigits(minute());
printDigits(second());
Serial.print(' ');
Serial.print(day());
Serial.print('/');
Serial.print(month());
Serial.print('/');
Serial.print(year());
Serial.println();
}
void do_send(osjob_t* j) {
// Check if there is not a current TX/RX job running
if (LMIC.opmode & OP_TXRXPEND) {
Serial.println(F("OP_TXRXPEND, not sending"));
} else {
// Schedule a network time request at the next possible time
LMIC_requestNetworkTime(user_request_network_time_callback, &userUTCTime);
// Prepare upstream data transmission at the next possible time.
LMIC_setTxData2(1, mydata, sizeof(mydata)-1, 0);
Serial.println(F("Packet queued"));
}
// Next TX is scheduled after TX_COMPLETE event.
}
void setup() {
Serial.begin(9600);
Serial.println(F("Starting"));
#ifdef VCC_ENABLE
// For Pinoccio Scout boards
pinMode(VCC_ENABLE, OUTPUT);
digitalWrite(VCC_ENABLE, HIGH);
delay(1000);
#endif
// LMIC init
os_init();
// Reset the MAC state. Session and pending data transfers will be discarded.
LMIC_reset();
// Start job (sending automatically starts OTAA too)
do_send(&sendjob);
}
void loop() {
os_runloop_once();
}

View File

@ -1,225 +0,0 @@
/*******************************************************************************
* Copyright (c) 2015 Thomas Telkamp and Matthijs Kooijman
* Copyright (c) 2018 Terry Moore, MCCI
*
* Permission is hereby granted, free of charge, to anyone
* obtaining a copy of this document and accompanying files,
* to do whatever they want with them without any restriction,
* including, but not limited to, copying, modification and redistribution.
* NO WARRANTY OF ANY KIND IS PROVIDED.
*
* This example sends a valid LoRaWAN packet with payload "Hello,
* world!", using frequency and encryption settings matching those of
* the The Things Network.
*
* This uses OTAA (Over-the-air activation), where where a DevEUI and
* application key is configured, which are used in an over-the-air
* activation procedure where a DevAddr and session keys are
* assigned/generated for use with all further communication.
*
* Note: LoRaWAN per sub-band duty-cycle limitation is enforced (1% in
* g1, 0.1% in g2), but not the TTN fair usage policy (which is probably
* violated by this sketch when left running for longer)!
* To use this sketch, first register your application and device with
* the things network, to set or generate an AppEUI, DevEUI and AppKey.
* Multiple devices can use the same AppEUI, but each device has its own
* DevEUI and AppKey.
*
* Do not forget to define the radio type correctly in
* arduino-lmic/project_config/lmic_project_config.h or from your BOARDS.txt.
*
*******************************************************************************/
#include <lmic.h>
#include <hal/hal.h>
#include <SPI.h>
//
// For normal use, we require that you edit the sketch to replace FILLMEIN
// with values assigned by the TTN console. However, for regression tests,
// we want to be able to compile these scripts. The regression tests define
// COMPILE_REGRESSION_TEST, and in that case we define FILLMEIN to a non-
// working but innocuous value.
//
#ifdef COMPILE_REGRESSION_TEST
# define FILLMEIN 0
#else
# warning "You must replace the values marked FILLMEIN with real values from the TTN control panel!"
# define FILLMEIN (#dont edit this, edit the lines that use FILLMEIN)
#endif
// This EUI must be in little-endian format, so least-significant-byte
// first. When copying an EUI from ttnctl output, this means to reverse
// the bytes. For TTN issued EUIs the last bytes should be 0xD5, 0xB3,
// 0x70.
static const u1_t PROGMEM APPEUI[8]={ FILLMEIN };
void os_getArtEui (u1_t* buf) { memcpy_P(buf, APPEUI, 8);}
// This should also be in little endian format, see above.
static const u1_t PROGMEM DEVEUI[8]={ FILLMEIN };
void os_getDevEui (u1_t* buf) { memcpy_P(buf, DEVEUI, 8);}
// This key should be in big endian format (or, since it is not really a
// number but a block of memory, endianness does not really apply). In
// practice, a key taken from ttnctl can be copied as-is.
static const u1_t PROGMEM APPKEY[16] = { FILLMEIN };
void os_getDevKey (u1_t* buf) { memcpy_P(buf, APPKEY, 16);}
static uint8_t mydata[] = "Hello, world!";
static osjob_t sendjob;
// Schedule TX every this many seconds (might become longer due to duty
// cycle limitations).
const unsigned TX_INTERVAL = 60;
// Pin mapping
const lmic_pinmap lmic_pins = {
.nss = 6,
.rxtx = LMIC_UNUSED_PIN,
.rst = 5,
.dio = {2, 3, 4},
};
void onEvent (ev_t ev) {
Serial.print(os_getTime());
Serial.print(": ");
switch(ev) {
case EV_SCAN_TIMEOUT:
Serial.println(F("EV_SCAN_TIMEOUT"));
break;
case EV_BEACON_FOUND:
Serial.println(F("EV_BEACON_FOUND"));
break;
case EV_BEACON_MISSED:
Serial.println(F("EV_BEACON_MISSED"));
break;
case EV_BEACON_TRACKED:
Serial.println(F("EV_BEACON_TRACKED"));
break;
case EV_JOINING:
Serial.println(F("EV_JOINING"));
break;
case EV_JOINED:
Serial.println(F("EV_JOINED"));
{
u4_t netid = 0;
devaddr_t devaddr = 0;
u1_t nwkKey[16];
u1_t artKey[16];
LMIC_getSessionKeys(&netid, &devaddr, nwkKey, artKey);
Serial.print("netid: ");
Serial.println(netid, DEC);
Serial.print("devaddr: ");
Serial.println(devaddr, HEX);
Serial.print("artKey: ");
for (int i=0; i<sizeof(artKey); ++i) {
Serial.print(artKey[i], HEX);
}
Serial.println("");
Serial.print("nwkKey: ");
for (int i=0; i<sizeof(nwkKey); ++i) {
Serial.print(nwkKey[i], HEX);
}
Serial.println("");
}
// Disable link check validation (automatically enabled
// during join, but because slow data rates change max TX
// size, we don't use it in this example.
LMIC_setLinkCheckMode(0);
break;
/*
|| This event is defined but not used in the code. No
|| point in wasting codespace on it.
||
|| case EV_RFU1:
|| Serial.println(F("EV_RFU1"));
|| break;
*/
case EV_JOIN_FAILED:
Serial.println(F("EV_JOIN_FAILED"));
break;
case EV_REJOIN_FAILED:
Serial.println(F("EV_REJOIN_FAILED"));
break;
case EV_TXCOMPLETE:
Serial.println(F("EV_TXCOMPLETE (includes waiting for RX windows)"));
if (LMIC.txrxFlags & TXRX_ACK)
Serial.println(F("Received ack"));
if (LMIC.dataLen) {
Serial.print(F("Received "));
Serial.print(LMIC.dataLen);
Serial.println(F(" bytes of payload"));
}
// Schedule next transmission
os_setTimedCallback(&sendjob, os_getTime()+sec2osticks(TX_INTERVAL), do_send);
break;
case EV_LOST_TSYNC:
Serial.println(F("EV_LOST_TSYNC"));
break;
case EV_RESET:
Serial.println(F("EV_RESET"));
break;
case EV_RXCOMPLETE:
// data received in ping slot
Serial.println(F("EV_RXCOMPLETE"));
break;
case EV_LINK_DEAD:
Serial.println(F("EV_LINK_DEAD"));
break;
case EV_LINK_ALIVE:
Serial.println(F("EV_LINK_ALIVE"));
break;
/*
|| This event is defined but not used in the code. No
|| point in wasting codespace on it.
||
|| case EV_SCAN_FOUND:
|| Serial.println(F("EV_SCAN_FOUND"));
|| break;
*/
case EV_TXSTART:
Serial.println(F("EV_TXSTART"));
break;
default:
Serial.print(F("Unknown event: "));
Serial.println((unsigned) ev);
break;
}
}
void do_send(osjob_t* j){
// Check if there is not a current TX/RX job running
if (LMIC.opmode & OP_TXRXPEND) {
Serial.println(F("OP_TXRXPEND, not sending"));
} else {
// Prepare upstream data transmission at the next possible time.
LMIC_setTxData2(1, mydata, sizeof(mydata)-1, 0);
Serial.println(F("Packet queued"));
}
// Next TX is scheduled after TX_COMPLETE event.
}
void setup() {
Serial.begin(9600);
Serial.println(F("Starting"));
#ifdef VCC_ENABLE
// For Pinoccio Scout boards
pinMode(VCC_ENABLE, OUTPUT);
digitalWrite(VCC_ENABLE, HIGH);
delay(1000);
#endif
// LMIC init
os_init();
// Reset the MAC state. Session and pending data transfers will be discarded.
LMIC_reset();
// Start job (sending automatically starts OTAA too)
do_send(&sendjob);
}
void loop() {
os_runloop_once();
}

View File

@ -1,9 +0,0 @@
name=MCCI LoRaWAN LMIC library
version=2.2.2
author=IBM, Matthis Kooijman, Terry Moore, ChaeHee Won, Frank Rose
maintainer=Terry Moore <tmm@mcci.com>
sentence=Arduino port of the LMIC (LoraWAN-MAC-in-C) framework provided by IBM.
paragraph=Supports SX1272/SX1276 and HopeRF RFM92/RFM95 tranceivers. Refactored to support multiple bandplans beyond the original two supported by the IBM LMIC code. Various enhancements and bug fixes from MCCI and The Things Network New York. Original IBM URL http://www.research.ibm.com/labs/zurich/ics/lrsc/lmic.html.
category=Communication
url=https://github.com/mcci-catena/arduino-lmic
architectures=*

View File

@ -1,9 +0,0 @@
// project-specific definitions
//#define CFG_eu868 1
#define CFG_us915 1
//#define CFG_au921 1
//#define CFG_as923 1
// #define LMIC_COUNTRY_CODE LMIC_COUNTRY_CODE_JP /* for as923-JP */
//#define CFG_in866 1
#define CFG_sx1276_radio 1
//#define LMIC_USE_INTERRUPTS

View File

@ -1,348 +0,0 @@
/******************************************************************************************
#if defined(USE_IDEETRON_AES)
* Copyright 2015, 2016 Ideetron B.V.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
******************************************************************************************/
/******************************************************************************************
*
* File: AES-128_V10.cpp
* Author: Gerben den Hartog
* Compagny: Ideetron B.V.
* Website: http://www.ideetron.nl/LoRa
* E-mail: info@ideetron.nl
******************************************************************************************/
/****************************************************************************************
*
* Created on: 20-10-2015
* Supported Hardware: ID150119-02 Nexus board with RFM95
*
* Firmware Version 1.0
* First version
****************************************************************************************/
// This file was taken from
// https://github.com/Ideetron/RFM95W_Nexus/tree/master/LoRaWAN_V31 for
// use with LMIC. It was only cosmetically modified:
// - AES_Encrypt was renamed to lmic_aes_encrypt.
// - All other functions and variables were made static
// - Tabs were converted to 2 spaces
// - An #include and #if guard was added
// - S_Table is now stored in PROGMEM
#include "../../lmic/oslmic.h"
#if defined(USE_IDEETRON_AES)
/*
********************************************************************************************
* Global Variables
********************************************************************************************
*/
static unsigned char State[4][4];
static CONST_TABLE(unsigned char, S_Table)[16][16] = {
{0x63,0x7C,0x77,0x7B,0xF2,0x6B,0x6F,0xC5,0x30,0x01,0x67,0x2B,0xFE,0xD7,0xAB,0x76},
{0xCA,0x82,0xC9,0x7D,0xFA,0x59,0x47,0xF0,0xAD,0xD4,0xA2,0xAF,0x9C,0xA4,0x72,0xC0},
{0xB7,0xFD,0x93,0x26,0x36,0x3F,0xF7,0xCC,0x34,0xA5,0xE5,0xF1,0x71,0xD8,0x31,0x15},
{0x04,0xC7,0x23,0xC3,0x18,0x96,0x05,0x9A,0x07,0x12,0x80,0xE2,0xEB,0x27,0xB2,0x75},
{0x09,0x83,0x2C,0x1A,0x1B,0x6E,0x5A,0xA0,0x52,0x3B,0xD6,0xB3,0x29,0xE3,0x2F,0x84},
{0x53,0xD1,0x00,0xED,0x20,0xFC,0xB1,0x5B,0x6A,0xCB,0xBE,0x39,0x4A,0x4C,0x58,0xCF},
{0xD0,0xEF,0xAA,0xFB,0x43,0x4D,0x33,0x85,0x45,0xF9,0x02,0x7F,0x50,0x3C,0x9F,0xA8},
{0x51,0xA3,0x40,0x8F,0x92,0x9D,0x38,0xF5,0xBC,0xB6,0xDA,0x21,0x10,0xFF,0xF3,0xD2},
{0xCD,0x0C,0x13,0xEC,0x5F,0x97,0x44,0x17,0xC4,0xA7,0x7E,0x3D,0x64,0x5D,0x19,0x73},
{0x60,0x81,0x4F,0xDC,0x22,0x2A,0x90,0x88,0x46,0xEE,0xB8,0x14,0xDE,0x5E,0x0B,0xDB},
{0xE0,0x32,0x3A,0x0A,0x49,0x06,0x24,0x5C,0xC2,0xD3,0xAC,0x62,0x91,0x95,0xE4,0x79},
{0xE7,0xC8,0x37,0x6D,0x8D,0xD5,0x4E,0xA9,0x6C,0x56,0xF4,0xEA,0x65,0x7A,0xAE,0x08},
{0xBA,0x78,0x25,0x2E,0x1C,0xA6,0xB4,0xC6,0xE8,0xDD,0x74,0x1F,0x4B,0xBD,0x8B,0x8A},
{0x70,0x3E,0xB5,0x66,0x48,0x03,0xF6,0x0E,0x61,0x35,0x57,0xB9,0x86,0xC1,0x1D,0x9E},
{0xE1,0xF8,0x98,0x11,0x69,0xD9,0x8E,0x94,0x9B,0x1E,0x87,0xE9,0xCE,0x55,0x28,0xDF},
{0x8C,0xA1,0x89,0x0D,0xBF,0xE6,0x42,0x68,0x41,0x99,0x2D,0x0F,0xB0,0x54,0xBB,0x16}
};
#ifdef __cplusplus
extern "C" {
#endif
void lmic_aes_encrypt(unsigned char *Data, unsigned char *Key);
#ifdef __cplusplus
}
#endif
static void AES_Add_Round_Key(unsigned char *Round_Key);
static unsigned char AES_Sub_Byte(unsigned char Byte);
static void AES_Shift_Rows();
static void AES_Mix_Collums();
static void AES_Calculate_Round_Key(unsigned char Round, unsigned char *Round_Key);
/*
*****************************************************************************************
* Description : Function for encrypting data using AES-128
*
* Arguments : *Data Data to encrypt is a 16 byte long arry
* *Key Key to encrypt data with is a 16 byte long arry
*****************************************************************************************
*/
void lmic_aes_encrypt(unsigned char *Data, unsigned char *Key)
{
unsigned char i;
unsigned char Row,Collum;
unsigned char Round = 0x00;
unsigned char Round_Key[16];
//Copy input to State arry
for(Collum = 0; Collum < 4; Collum++)
{
for(Row = 0; Row < 4; Row++)
{
State[Row][Collum] = Data[Row + (4*Collum)];
}
}
//Copy key to round key
for(i = 0; i < 16; i++)
{
Round_Key[i] = Key[i];
}
//Add round key
AES_Add_Round_Key(Round_Key);
//Preform 9 full rounds
for(Round = 1; Round < 10; Round++)
{
//Preform Byte substitution with S table
for(Collum = 0; Collum < 4; Collum++)
{
for(Row = 0; Row < 4; Row++)
{
State[Row][Collum] = AES_Sub_Byte(State[Row][Collum]);
}
}
//Preform Row Shift
AES_Shift_Rows();
//Mix Collums
AES_Mix_Collums();
//Calculate new round key
AES_Calculate_Round_Key(Round,Round_Key);
//Add round key
AES_Add_Round_Key(Round_Key);
}
//Last round whitout mix collums
//Preform Byte substitution with S table
for(Collum = 0; Collum < 4; Collum++)
{
for(Row = 0; Row < 4; Row++)
{
State[Row][Collum] = AES_Sub_Byte(State[Row][Collum]);
}
}
//Shift rows
AES_Shift_Rows();
//Calculate new round key
AES_Calculate_Round_Key(Round,Round_Key);
//Add round Key
AES_Add_Round_Key(Round_Key);
//Copy the State into the data array
for(Collum = 0; Collum < 4; Collum++)
{
for(Row = 0; Row < 4; Row++)
{
Data[Row + (4*Collum)] = State[Row][Collum];
}
}
}
/*
*****************************************************************************************
* Description : Function that add's the round key for the current round
*
* Arguments : *Round_Key 16 byte long array holding the Round Key
*****************************************************************************************
*/
static void AES_Add_Round_Key(unsigned char *Round_Key)
{
unsigned char Row,Collum;
for(Collum = 0; Collum < 4; Collum++)
{
for(Row = 0; Row < 4; Row++)
{
State[Row][Collum] = State[Row][Collum] ^ Round_Key[Row + (4*Collum)];
}
}
}
/*
*****************************************************************************************
* Description : Function that substitutes a byte with a byte from the S_Table
*
* Arguments : Byte The byte that will be substituted
*
* Return : The return is the found byte in the S_Table
*****************************************************************************************
*/
static unsigned char AES_Sub_Byte(unsigned char Byte)
{
unsigned char S_Row,S_Collum;
unsigned char S_Byte;
//Split byte up in Row and Collum
S_Row = ((Byte >> 4) & 0x0F);
S_Collum = (Byte & 0x0F);
//Find the correct byte in the S_Table
S_Byte = TABLE_GET_U1_TWODIM(S_Table, S_Row, S_Collum);
return S_Byte;
}
/*
*****************************************************************************************
* Description : Function that preforms the shift row operation described in the AES standard
*****************************************************************************************
*/
static void AES_Shift_Rows()
{
unsigned char Buffer;
//Row 0 doesn't change
//Shift Row 1 one left
//Store firt byte in buffer
Buffer = State[1][0];
//Shift all bytes
State[1][0] = State[1][1];
State[1][1] = State[1][2];
State[1][2] = State[1][3];
State[1][3] = Buffer;
//Shift row 2 two left
Buffer = State[2][0];
State[2][0] = State[2][2];
State[2][2] = Buffer;
Buffer = State[2][1];
State[2][1] = State[2][3];
State[2][3] = Buffer;
//Shift row 3 three left
Buffer = State[3][3];
State[3][3] = State[3][2];
State[3][2] = State[3][1];
State[3][1] = State[3][0];
State[3][0] = Buffer;
}
/*
*****************************************************************************************
* Description : Function that preforms the Mix Collums operation described in the AES standard
*****************************************************************************************
*/
static void AES_Mix_Collums()
{
unsigned char Row,Collum;
unsigned char a[4], b[4];
for(Collum = 0; Collum < 4; Collum++)
{
for(Row = 0; Row < 4; Row++)
{
a[Row] = State[Row][Collum];
b[Row] = (State[Row][Collum] << 1);
if((State[Row][Collum] & 0x80) == 0x80)
{
b[Row] = b[Row] ^ 0x1B;
}
}
State[0][Collum] = b[0] ^ a[1] ^ b[1] ^ a[2] ^ a[3];
State[1][Collum] = a[0] ^ b[1] ^ a[2] ^ b[2] ^ a[3];
State[2][Collum] = a[0] ^ a[1] ^ b[2] ^ a[3] ^ b[3];
State[3][Collum] = a[0] ^ b[0] ^ a[1] ^ a[2] ^ b[3];
}
}
/*
*****************************************************************************************
* Description : Function that calculaties the round key for the current round
*
* Arguments : Round Number of current Round
* *Round_Key 16 byte long array holding the Round Key
*****************************************************************************************
*/
static void AES_Calculate_Round_Key(unsigned char Round, unsigned char *Round_Key)
{
unsigned char i,j;
unsigned char b;
unsigned char Temp[4];
unsigned char Buffer;
unsigned char Rcon;
//Calculate first Temp
//Copy laste byte from previous key
for(i = 0; i < 4; i++)
{
Temp[i] = Round_Key[i+12];
}
//Rotate Temp
Buffer = Temp[0];
Temp[0] = Temp[1];
Temp[1] = Temp[2];
Temp[2] = Temp[3];
Temp[3] = Buffer;
//Substitute Temp
for(i = 0; i < 4; i++)
{
Temp[i] = AES_Sub_Byte(Temp[i]);
}
//Calculate Rcon
Rcon = 0x01;
while(Round != 1)
{
b = Rcon & 0x80;
Rcon = Rcon << 1;
if(b == 0x80)
{
Rcon = Rcon ^ 0x1b;
}
Round--;
}
//XOR Rcon
Temp[0] = Temp[0] ^ Rcon;
//Calculate new key
for(i = 0; i < 4; i++)
{
for(j = 0; j < 4; j++)
{
Round_Key[j + (4*i)] = Round_Key[j + (4*i)] ^ Temp[j];
Temp[j] = Round_Key[j + (4*i)];
}
}
}
#endif // defined(USE_IDEETRON_AES)

View File

@ -1,386 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#include "../lmic/oslmic.h"
#if defined(USE_ORIGINAL_AES)
#define AES_MICSUB 0x30 // internal use only
static CONST_TABLE(u4_t, AES_RCON)[10] = {
0x01000000, 0x02000000, 0x04000000, 0x08000000, 0x10000000,
0x20000000, 0x40000000, 0x80000000, 0x1B000000, 0x36000000
};
static CONST_TABLE(u1_t, AES_S)[256] = {
0x63, 0x7C, 0x77, 0x7B, 0xF2, 0x6B, 0x6F, 0xC5, 0x30, 0x01, 0x67, 0x2B, 0xFE, 0xD7, 0xAB, 0x76,
0xCA, 0x82, 0xC9, 0x7D, 0xFA, 0x59, 0x47, 0xF0, 0xAD, 0xD4, 0xA2, 0xAF, 0x9C, 0xA4, 0x72, 0xC0,
0xB7, 0xFD, 0x93, 0x26, 0x36, 0x3F, 0xF7, 0xCC, 0x34, 0xA5, 0xE5, 0xF1, 0x71, 0xD8, 0x31, 0x15,
0x04, 0xC7, 0x23, 0xC3, 0x18, 0x96, 0x05, 0x9A, 0x07, 0x12, 0x80, 0xE2, 0xEB, 0x27, 0xB2, 0x75,
0x09, 0x83, 0x2C, 0x1A, 0x1B, 0x6E, 0x5A, 0xA0, 0x52, 0x3B, 0xD6, 0xB3, 0x29, 0xE3, 0x2F, 0x84,
0x53, 0xD1, 0x00, 0xED, 0x20, 0xFC, 0xB1, 0x5B, 0x6A, 0xCB, 0xBE, 0x39, 0x4A, 0x4C, 0x58, 0xCF,
0xD0, 0xEF, 0xAA, 0xFB, 0x43, 0x4D, 0x33, 0x85, 0x45, 0xF9, 0x02, 0x7F, 0x50, 0x3C, 0x9F, 0xA8,
0x51, 0xA3, 0x40, 0x8F, 0x92, 0x9D, 0x38, 0xF5, 0xBC, 0xB6, 0xDA, 0x21, 0x10, 0xFF, 0xF3, 0xD2,
0xCD, 0x0C, 0x13, 0xEC, 0x5F, 0x97, 0x44, 0x17, 0xC4, 0xA7, 0x7E, 0x3D, 0x64, 0x5D, 0x19, 0x73,
0x60, 0x81, 0x4F, 0xDC, 0x22, 0x2A, 0x90, 0x88, 0x46, 0xEE, 0xB8, 0x14, 0xDE, 0x5E, 0x0B, 0xDB,
0xE0, 0x32, 0x3A, 0x0A, 0x49, 0x06, 0x24, 0x5C, 0xC2, 0xD3, 0xAC, 0x62, 0x91, 0x95, 0xE4, 0x79,
0xE7, 0xC8, 0x37, 0x6D, 0x8D, 0xD5, 0x4E, 0xA9, 0x6C, 0x56, 0xF4, 0xEA, 0x65, 0x7A, 0xAE, 0x08,
0xBA, 0x78, 0x25, 0x2E, 0x1C, 0xA6, 0xB4, 0xC6, 0xE8, 0xDD, 0x74, 0x1F, 0x4B, 0xBD, 0x8B, 0x8A,
0x70, 0x3E, 0xB5, 0x66, 0x48, 0x03, 0xF6, 0x0E, 0x61, 0x35, 0x57, 0xB9, 0x86, 0xC1, 0x1D, 0x9E,
0xE1, 0xF8, 0x98, 0x11, 0x69, 0xD9, 0x8E, 0x94, 0x9B, 0x1E, 0x87, 0xE9, 0xCE, 0x55, 0x28, 0xDF,
0x8C, 0xA1, 0x89, 0x0D, 0xBF, 0xE6, 0x42, 0x68, 0x41, 0x99, 0x2D, 0x0F, 0xB0, 0x54, 0xBB, 0x16,
};
static CONST_TABLE(u4_t, AES_E1)[256] = {
0xC66363A5, 0xF87C7C84, 0xEE777799, 0xF67B7B8D, 0xFFF2F20D, 0xD66B6BBD, 0xDE6F6FB1, 0x91C5C554,
0x60303050, 0x02010103, 0xCE6767A9, 0x562B2B7D, 0xE7FEFE19, 0xB5D7D762, 0x4DABABE6, 0xEC76769A,
0x8FCACA45, 0x1F82829D, 0x89C9C940, 0xFA7D7D87, 0xEFFAFA15, 0xB25959EB, 0x8E4747C9, 0xFBF0F00B,
0x41ADADEC, 0xB3D4D467, 0x5FA2A2FD, 0x45AFAFEA, 0x239C9CBF, 0x53A4A4F7, 0xE4727296, 0x9BC0C05B,
0x75B7B7C2, 0xE1FDFD1C, 0x3D9393AE, 0x4C26266A, 0x6C36365A, 0x7E3F3F41, 0xF5F7F702, 0x83CCCC4F,
0x6834345C, 0x51A5A5F4, 0xD1E5E534, 0xF9F1F108, 0xE2717193, 0xABD8D873, 0x62313153, 0x2A15153F,
0x0804040C, 0x95C7C752, 0x46232365, 0x9DC3C35E, 0x30181828, 0x379696A1, 0x0A05050F, 0x2F9A9AB5,
0x0E070709, 0x24121236, 0x1B80809B, 0xDFE2E23D, 0xCDEBEB26, 0x4E272769, 0x7FB2B2CD, 0xEA75759F,
0x1209091B, 0x1D83839E, 0x582C2C74, 0x341A1A2E, 0x361B1B2D, 0xDC6E6EB2, 0xB45A5AEE, 0x5BA0A0FB,
0xA45252F6, 0x763B3B4D, 0xB7D6D661, 0x7DB3B3CE, 0x5229297B, 0xDDE3E33E, 0x5E2F2F71, 0x13848497,
0xA65353F5, 0xB9D1D168, 0x00000000, 0xC1EDED2C, 0x40202060, 0xE3FCFC1F, 0x79B1B1C8, 0xB65B5BED,
0xD46A6ABE, 0x8DCBCB46, 0x67BEBED9, 0x7239394B, 0x944A4ADE, 0x984C4CD4, 0xB05858E8, 0x85CFCF4A,
0xBBD0D06B, 0xC5EFEF2A, 0x4FAAAAE5, 0xEDFBFB16, 0x864343C5, 0x9A4D4DD7, 0x66333355, 0x11858594,
0x8A4545CF, 0xE9F9F910, 0x04020206, 0xFE7F7F81, 0xA05050F0, 0x783C3C44, 0x259F9FBA, 0x4BA8A8E3,
0xA25151F3, 0x5DA3A3FE, 0x804040C0, 0x058F8F8A, 0x3F9292AD, 0x219D9DBC, 0x70383848, 0xF1F5F504,
0x63BCBCDF, 0x77B6B6C1, 0xAFDADA75, 0x42212163, 0x20101030, 0xE5FFFF1A, 0xFDF3F30E, 0xBFD2D26D,
0x81CDCD4C, 0x180C0C14, 0x26131335, 0xC3ECEC2F, 0xBE5F5FE1, 0x359797A2, 0x884444CC, 0x2E171739,
0x93C4C457, 0x55A7A7F2, 0xFC7E7E82, 0x7A3D3D47, 0xC86464AC, 0xBA5D5DE7, 0x3219192B, 0xE6737395,
0xC06060A0, 0x19818198, 0x9E4F4FD1, 0xA3DCDC7F, 0x44222266, 0x542A2A7E, 0x3B9090AB, 0x0B888883,
0x8C4646CA, 0xC7EEEE29, 0x6BB8B8D3, 0x2814143C, 0xA7DEDE79, 0xBC5E5EE2, 0x160B0B1D, 0xADDBDB76,
0xDBE0E03B, 0x64323256, 0x743A3A4E, 0x140A0A1E, 0x924949DB, 0x0C06060A, 0x4824246C, 0xB85C5CE4,
0x9FC2C25D, 0xBDD3D36E, 0x43ACACEF, 0xC46262A6, 0x399191A8, 0x319595A4, 0xD3E4E437, 0xF279798B,
0xD5E7E732, 0x8BC8C843, 0x6E373759, 0xDA6D6DB7, 0x018D8D8C, 0xB1D5D564, 0x9C4E4ED2, 0x49A9A9E0,
0xD86C6CB4, 0xAC5656FA, 0xF3F4F407, 0xCFEAEA25, 0xCA6565AF, 0xF47A7A8E, 0x47AEAEE9, 0x10080818,
0x6FBABAD5, 0xF0787888, 0x4A25256F, 0x5C2E2E72, 0x381C1C24, 0x57A6A6F1, 0x73B4B4C7, 0x97C6C651,
0xCBE8E823, 0xA1DDDD7C, 0xE874749C, 0x3E1F1F21, 0x964B4BDD, 0x61BDBDDC, 0x0D8B8B86, 0x0F8A8A85,
0xE0707090, 0x7C3E3E42, 0x71B5B5C4, 0xCC6666AA, 0x904848D8, 0x06030305, 0xF7F6F601, 0x1C0E0E12,
0xC26161A3, 0x6A35355F, 0xAE5757F9, 0x69B9B9D0, 0x17868691, 0x99C1C158, 0x3A1D1D27, 0x279E9EB9,
0xD9E1E138, 0xEBF8F813, 0x2B9898B3, 0x22111133, 0xD26969BB, 0xA9D9D970, 0x078E8E89, 0x339494A7,
0x2D9B9BB6, 0x3C1E1E22, 0x15878792, 0xC9E9E920, 0x87CECE49, 0xAA5555FF, 0x50282878, 0xA5DFDF7A,
0x038C8C8F, 0x59A1A1F8, 0x09898980, 0x1A0D0D17, 0x65BFBFDA, 0xD7E6E631, 0x844242C6, 0xD06868B8,
0x824141C3, 0x299999B0, 0x5A2D2D77, 0x1E0F0F11, 0x7BB0B0CB, 0xA85454FC, 0x6DBBBBD6, 0x2C16163A,
};
static CONST_TABLE(u4_t, AES_E2)[256] = {
0xA5C66363, 0x84F87C7C, 0x99EE7777, 0x8DF67B7B, 0x0DFFF2F2, 0xBDD66B6B, 0xB1DE6F6F, 0x5491C5C5,
0x50603030, 0x03020101, 0xA9CE6767, 0x7D562B2B, 0x19E7FEFE, 0x62B5D7D7, 0xE64DABAB, 0x9AEC7676,
0x458FCACA, 0x9D1F8282, 0x4089C9C9, 0x87FA7D7D, 0x15EFFAFA, 0xEBB25959, 0xC98E4747, 0x0BFBF0F0,
0xEC41ADAD, 0x67B3D4D4, 0xFD5FA2A2, 0xEA45AFAF, 0xBF239C9C, 0xF753A4A4, 0x96E47272, 0x5B9BC0C0,
0xC275B7B7, 0x1CE1FDFD, 0xAE3D9393, 0x6A4C2626, 0x5A6C3636, 0x417E3F3F, 0x02F5F7F7, 0x4F83CCCC,
0x5C683434, 0xF451A5A5, 0x34D1E5E5, 0x08F9F1F1, 0x93E27171, 0x73ABD8D8, 0x53623131, 0x3F2A1515,
0x0C080404, 0x5295C7C7, 0x65462323, 0x5E9DC3C3, 0x28301818, 0xA1379696, 0x0F0A0505, 0xB52F9A9A,
0x090E0707, 0x36241212, 0x9B1B8080, 0x3DDFE2E2, 0x26CDEBEB, 0x694E2727, 0xCD7FB2B2, 0x9FEA7575,
0x1B120909, 0x9E1D8383, 0x74582C2C, 0x2E341A1A, 0x2D361B1B, 0xB2DC6E6E, 0xEEB45A5A, 0xFB5BA0A0,
0xF6A45252, 0x4D763B3B, 0x61B7D6D6, 0xCE7DB3B3, 0x7B522929, 0x3EDDE3E3, 0x715E2F2F, 0x97138484,
0xF5A65353, 0x68B9D1D1, 0x00000000, 0x2CC1EDED, 0x60402020, 0x1FE3FCFC, 0xC879B1B1, 0xEDB65B5B,
0xBED46A6A, 0x468DCBCB, 0xD967BEBE, 0x4B723939, 0xDE944A4A, 0xD4984C4C, 0xE8B05858, 0x4A85CFCF,
0x6BBBD0D0, 0x2AC5EFEF, 0xE54FAAAA, 0x16EDFBFB, 0xC5864343, 0xD79A4D4D, 0x55663333, 0x94118585,
0xCF8A4545, 0x10E9F9F9, 0x06040202, 0x81FE7F7F, 0xF0A05050, 0x44783C3C, 0xBA259F9F, 0xE34BA8A8,
0xF3A25151, 0xFE5DA3A3, 0xC0804040, 0x8A058F8F, 0xAD3F9292, 0xBC219D9D, 0x48703838, 0x04F1F5F5,
0xDF63BCBC, 0xC177B6B6, 0x75AFDADA, 0x63422121, 0x30201010, 0x1AE5FFFF, 0x0EFDF3F3, 0x6DBFD2D2,
0x4C81CDCD, 0x14180C0C, 0x35261313, 0x2FC3ECEC, 0xE1BE5F5F, 0xA2359797, 0xCC884444, 0x392E1717,
0x5793C4C4, 0xF255A7A7, 0x82FC7E7E, 0x477A3D3D, 0xACC86464, 0xE7BA5D5D, 0x2B321919, 0x95E67373,
0xA0C06060, 0x98198181, 0xD19E4F4F, 0x7FA3DCDC, 0x66442222, 0x7E542A2A, 0xAB3B9090, 0x830B8888,
0xCA8C4646, 0x29C7EEEE, 0xD36BB8B8, 0x3C281414, 0x79A7DEDE, 0xE2BC5E5E, 0x1D160B0B, 0x76ADDBDB,
0x3BDBE0E0, 0x56643232, 0x4E743A3A, 0x1E140A0A, 0xDB924949, 0x0A0C0606, 0x6C482424, 0xE4B85C5C,
0x5D9FC2C2, 0x6EBDD3D3, 0xEF43ACAC, 0xA6C46262, 0xA8399191, 0xA4319595, 0x37D3E4E4, 0x8BF27979,
0x32D5E7E7, 0x438BC8C8, 0x596E3737, 0xB7DA6D6D, 0x8C018D8D, 0x64B1D5D5, 0xD29C4E4E, 0xE049A9A9,
0xB4D86C6C, 0xFAAC5656, 0x07F3F4F4, 0x25CFEAEA, 0xAFCA6565, 0x8EF47A7A, 0xE947AEAE, 0x18100808,
0xD56FBABA, 0x88F07878, 0x6F4A2525, 0x725C2E2E, 0x24381C1C, 0xF157A6A6, 0xC773B4B4, 0x5197C6C6,
0x23CBE8E8, 0x7CA1DDDD, 0x9CE87474, 0x213E1F1F, 0xDD964B4B, 0xDC61BDBD, 0x860D8B8B, 0x850F8A8A,
0x90E07070, 0x427C3E3E, 0xC471B5B5, 0xAACC6666, 0xD8904848, 0x05060303, 0x01F7F6F6, 0x121C0E0E,
0xA3C26161, 0x5F6A3535, 0xF9AE5757, 0xD069B9B9, 0x91178686, 0x5899C1C1, 0x273A1D1D, 0xB9279E9E,
0x38D9E1E1, 0x13EBF8F8, 0xB32B9898, 0x33221111, 0xBBD26969, 0x70A9D9D9, 0x89078E8E, 0xA7339494,
0xB62D9B9B, 0x223C1E1E, 0x92158787, 0x20C9E9E9, 0x4987CECE, 0xFFAA5555, 0x78502828, 0x7AA5DFDF,
0x8F038C8C, 0xF859A1A1, 0x80098989, 0x171A0D0D, 0xDA65BFBF, 0x31D7E6E6, 0xC6844242, 0xB8D06868,
0xC3824141, 0xB0299999, 0x775A2D2D, 0x111E0F0F, 0xCB7BB0B0, 0xFCA85454, 0xD66DBBBB, 0x3A2C1616,
};
static CONST_TABLE(u4_t, AES_E3)[256] = {
0x63A5C663, 0x7C84F87C, 0x7799EE77, 0x7B8DF67B, 0xF20DFFF2, 0x6BBDD66B, 0x6FB1DE6F, 0xC55491C5,
0x30506030, 0x01030201, 0x67A9CE67, 0x2B7D562B, 0xFE19E7FE, 0xD762B5D7, 0xABE64DAB, 0x769AEC76,
0xCA458FCA, 0x829D1F82, 0xC94089C9, 0x7D87FA7D, 0xFA15EFFA, 0x59EBB259, 0x47C98E47, 0xF00BFBF0,
0xADEC41AD, 0xD467B3D4, 0xA2FD5FA2, 0xAFEA45AF, 0x9CBF239C, 0xA4F753A4, 0x7296E472, 0xC05B9BC0,
0xB7C275B7, 0xFD1CE1FD, 0x93AE3D93, 0x266A4C26, 0x365A6C36, 0x3F417E3F, 0xF702F5F7, 0xCC4F83CC,
0x345C6834, 0xA5F451A5, 0xE534D1E5, 0xF108F9F1, 0x7193E271, 0xD873ABD8, 0x31536231, 0x153F2A15,
0x040C0804, 0xC75295C7, 0x23654623, 0xC35E9DC3, 0x18283018, 0x96A13796, 0x050F0A05, 0x9AB52F9A,
0x07090E07, 0x12362412, 0x809B1B80, 0xE23DDFE2, 0xEB26CDEB, 0x27694E27, 0xB2CD7FB2, 0x759FEA75,
0x091B1209, 0x839E1D83, 0x2C74582C, 0x1A2E341A, 0x1B2D361B, 0x6EB2DC6E, 0x5AEEB45A, 0xA0FB5BA0,
0x52F6A452, 0x3B4D763B, 0xD661B7D6, 0xB3CE7DB3, 0x297B5229, 0xE33EDDE3, 0x2F715E2F, 0x84971384,
0x53F5A653, 0xD168B9D1, 0x00000000, 0xED2CC1ED, 0x20604020, 0xFC1FE3FC, 0xB1C879B1, 0x5BEDB65B,
0x6ABED46A, 0xCB468DCB, 0xBED967BE, 0x394B7239, 0x4ADE944A, 0x4CD4984C, 0x58E8B058, 0xCF4A85CF,
0xD06BBBD0, 0xEF2AC5EF, 0xAAE54FAA, 0xFB16EDFB, 0x43C58643, 0x4DD79A4D, 0x33556633, 0x85941185,
0x45CF8A45, 0xF910E9F9, 0x02060402, 0x7F81FE7F, 0x50F0A050, 0x3C44783C, 0x9FBA259F, 0xA8E34BA8,
0x51F3A251, 0xA3FE5DA3, 0x40C08040, 0x8F8A058F, 0x92AD3F92, 0x9DBC219D, 0x38487038, 0xF504F1F5,
0xBCDF63BC, 0xB6C177B6, 0xDA75AFDA, 0x21634221, 0x10302010, 0xFF1AE5FF, 0xF30EFDF3, 0xD26DBFD2,
0xCD4C81CD, 0x0C14180C, 0x13352613, 0xEC2FC3EC, 0x5FE1BE5F, 0x97A23597, 0x44CC8844, 0x17392E17,
0xC45793C4, 0xA7F255A7, 0x7E82FC7E, 0x3D477A3D, 0x64ACC864, 0x5DE7BA5D, 0x192B3219, 0x7395E673,
0x60A0C060, 0x81981981, 0x4FD19E4F, 0xDC7FA3DC, 0x22664422, 0x2A7E542A, 0x90AB3B90, 0x88830B88,
0x46CA8C46, 0xEE29C7EE, 0xB8D36BB8, 0x143C2814, 0xDE79A7DE, 0x5EE2BC5E, 0x0B1D160B, 0xDB76ADDB,
0xE03BDBE0, 0x32566432, 0x3A4E743A, 0x0A1E140A, 0x49DB9249, 0x060A0C06, 0x246C4824, 0x5CE4B85C,
0xC25D9FC2, 0xD36EBDD3, 0xACEF43AC, 0x62A6C462, 0x91A83991, 0x95A43195, 0xE437D3E4, 0x798BF279,
0xE732D5E7, 0xC8438BC8, 0x37596E37, 0x6DB7DA6D, 0x8D8C018D, 0xD564B1D5, 0x4ED29C4E, 0xA9E049A9,
0x6CB4D86C, 0x56FAAC56, 0xF407F3F4, 0xEA25CFEA, 0x65AFCA65, 0x7A8EF47A, 0xAEE947AE, 0x08181008,
0xBAD56FBA, 0x7888F078, 0x256F4A25, 0x2E725C2E, 0x1C24381C, 0xA6F157A6, 0xB4C773B4, 0xC65197C6,
0xE823CBE8, 0xDD7CA1DD, 0x749CE874, 0x1F213E1F, 0x4BDD964B, 0xBDDC61BD, 0x8B860D8B, 0x8A850F8A,
0x7090E070, 0x3E427C3E, 0xB5C471B5, 0x66AACC66, 0x48D89048, 0x03050603, 0xF601F7F6, 0x0E121C0E,
0x61A3C261, 0x355F6A35, 0x57F9AE57, 0xB9D069B9, 0x86911786, 0xC15899C1, 0x1D273A1D, 0x9EB9279E,
0xE138D9E1, 0xF813EBF8, 0x98B32B98, 0x11332211, 0x69BBD269, 0xD970A9D9, 0x8E89078E, 0x94A73394,
0x9BB62D9B, 0x1E223C1E, 0x87921587, 0xE920C9E9, 0xCE4987CE, 0x55FFAA55, 0x28785028, 0xDF7AA5DF,
0x8C8F038C, 0xA1F859A1, 0x89800989, 0x0D171A0D, 0xBFDA65BF, 0xE631D7E6, 0x42C68442, 0x68B8D068,
0x41C38241, 0x99B02999, 0x2D775A2D, 0x0F111E0F, 0xB0CB7BB0, 0x54FCA854, 0xBBD66DBB, 0x163A2C16,
};
static CONST_TABLE(u4_t, AES_E4)[256] = {
0x6363A5C6, 0x7C7C84F8, 0x777799EE, 0x7B7B8DF6, 0xF2F20DFF, 0x6B6BBDD6, 0x6F6FB1DE, 0xC5C55491,
0x30305060, 0x01010302, 0x6767A9CE, 0x2B2B7D56, 0xFEFE19E7, 0xD7D762B5, 0xABABE64D, 0x76769AEC,
0xCACA458F, 0x82829D1F, 0xC9C94089, 0x7D7D87FA, 0xFAFA15EF, 0x5959EBB2, 0x4747C98E, 0xF0F00BFB,
0xADADEC41, 0xD4D467B3, 0xA2A2FD5F, 0xAFAFEA45, 0x9C9CBF23, 0xA4A4F753, 0x727296E4, 0xC0C05B9B,
0xB7B7C275, 0xFDFD1CE1, 0x9393AE3D, 0x26266A4C, 0x36365A6C, 0x3F3F417E, 0xF7F702F5, 0xCCCC4F83,
0x34345C68, 0xA5A5F451, 0xE5E534D1, 0xF1F108F9, 0x717193E2, 0xD8D873AB, 0x31315362, 0x15153F2A,
0x04040C08, 0xC7C75295, 0x23236546, 0xC3C35E9D, 0x18182830, 0x9696A137, 0x05050F0A, 0x9A9AB52F,
0x0707090E, 0x12123624, 0x80809B1B, 0xE2E23DDF, 0xEBEB26CD, 0x2727694E, 0xB2B2CD7F, 0x75759FEA,
0x09091B12, 0x83839E1D, 0x2C2C7458, 0x1A1A2E34, 0x1B1B2D36, 0x6E6EB2DC, 0x5A5AEEB4, 0xA0A0FB5B,
0x5252F6A4, 0x3B3B4D76, 0xD6D661B7, 0xB3B3CE7D, 0x29297B52, 0xE3E33EDD, 0x2F2F715E, 0x84849713,
0x5353F5A6, 0xD1D168B9, 0x00000000, 0xEDED2CC1, 0x20206040, 0xFCFC1FE3, 0xB1B1C879, 0x5B5BEDB6,
0x6A6ABED4, 0xCBCB468D, 0xBEBED967, 0x39394B72, 0x4A4ADE94, 0x4C4CD498, 0x5858E8B0, 0xCFCF4A85,
0xD0D06BBB, 0xEFEF2AC5, 0xAAAAE54F, 0xFBFB16ED, 0x4343C586, 0x4D4DD79A, 0x33335566, 0x85859411,
0x4545CF8A, 0xF9F910E9, 0x02020604, 0x7F7F81FE, 0x5050F0A0, 0x3C3C4478, 0x9F9FBA25, 0xA8A8E34B,
0x5151F3A2, 0xA3A3FE5D, 0x4040C080, 0x8F8F8A05, 0x9292AD3F, 0x9D9DBC21, 0x38384870, 0xF5F504F1,
0xBCBCDF63, 0xB6B6C177, 0xDADA75AF, 0x21216342, 0x10103020, 0xFFFF1AE5, 0xF3F30EFD, 0xD2D26DBF,
0xCDCD4C81, 0x0C0C1418, 0x13133526, 0xECEC2FC3, 0x5F5FE1BE, 0x9797A235, 0x4444CC88, 0x1717392E,
0xC4C45793, 0xA7A7F255, 0x7E7E82FC, 0x3D3D477A, 0x6464ACC8, 0x5D5DE7BA, 0x19192B32, 0x737395E6,
0x6060A0C0, 0x81819819, 0x4F4FD19E, 0xDCDC7FA3, 0x22226644, 0x2A2A7E54, 0x9090AB3B, 0x8888830B,
0x4646CA8C, 0xEEEE29C7, 0xB8B8D36B, 0x14143C28, 0xDEDE79A7, 0x5E5EE2BC, 0x0B0B1D16, 0xDBDB76AD,
0xE0E03BDB, 0x32325664, 0x3A3A4E74, 0x0A0A1E14, 0x4949DB92, 0x06060A0C, 0x24246C48, 0x5C5CE4B8,
0xC2C25D9F, 0xD3D36EBD, 0xACACEF43, 0x6262A6C4, 0x9191A839, 0x9595A431, 0xE4E437D3, 0x79798BF2,
0xE7E732D5, 0xC8C8438B, 0x3737596E, 0x6D6DB7DA, 0x8D8D8C01, 0xD5D564B1, 0x4E4ED29C, 0xA9A9E049,
0x6C6CB4D8, 0x5656FAAC, 0xF4F407F3, 0xEAEA25CF, 0x6565AFCA, 0x7A7A8EF4, 0xAEAEE947, 0x08081810,
0xBABAD56F, 0x787888F0, 0x25256F4A, 0x2E2E725C, 0x1C1C2438, 0xA6A6F157, 0xB4B4C773, 0xC6C65197,
0xE8E823CB, 0xDDDD7CA1, 0x74749CE8, 0x1F1F213E, 0x4B4BDD96, 0xBDBDDC61, 0x8B8B860D, 0x8A8A850F,
0x707090E0, 0x3E3E427C, 0xB5B5C471, 0x6666AACC, 0x4848D890, 0x03030506, 0xF6F601F7, 0x0E0E121C,
0x6161A3C2, 0x35355F6A, 0x5757F9AE, 0xB9B9D069, 0x86869117, 0xC1C15899, 0x1D1D273A, 0x9E9EB927,
0xE1E138D9, 0xF8F813EB, 0x9898B32B, 0x11113322, 0x6969BBD2, 0xD9D970A9, 0x8E8E8907, 0x9494A733,
0x9B9BB62D, 0x1E1E223C, 0x87879215, 0xE9E920C9, 0xCECE4987, 0x5555FFAA, 0x28287850, 0xDFDF7AA5,
0x8C8C8F03, 0xA1A1F859, 0x89898009, 0x0D0D171A, 0xBFBFDA65, 0xE6E631D7, 0x4242C684, 0x6868B8D0,
0x4141C382, 0x9999B029, 0x2D2D775A, 0x0F0F111E, 0xB0B0CB7B, 0x5454FCA8, 0xBBBBD66D, 0x16163A2C,
};
#define msbf4_read(p) ((p)[0]<<24 | (p)[1]<<16 | (p)[2]<<8 | (p)[3])
#define msbf4_write(p,v) (p)[0]=(v)>>24,(p)[1]=(v)>>16,(p)[2]=(v)>>8,(p)[3]=(v)
#define swapmsbf(x) ( (x&0xFF)<<24 | (x&0xFF00)<<8 | (x&0xFF0000)>>8 | (x>>24) )
#define u1(v) ((u1_t)(v))
#define AES_key4(r1,r2,r3,r0,i) r1 = ki[i+1]; \
r2 = ki[i+2]; \
r3 = ki[i+3]; \
r0 = ki[i]
#define AES_expr4(r1,r2,r3,r0,i) r1 ^= TABLE_GET_U4(AES_E4, u1(i)); \
r2 ^= TABLE_GET_U4(AES_E3, u1(i>>8)); \
r3 ^= TABLE_GET_U4(AES_E2, u1(i>>16)); \
r0 ^= TABLE_GET_U4(AES_E1, (i>>24))
#define AES_expr(a,r0,r1,r2,r3,i) a = ki[i]; \
a ^= ((u4_t)TABLE_GET_U1(AES_S, r0>>24 )<<24); \
a ^= ((u4_t)TABLE_GET_U1(AES_S, u1(r1>>16))<<16); \
a ^= ((u4_t)TABLE_GET_U1(AES_S, u1(r2>> 8))<< 8); \
a ^= (u4_t)TABLE_GET_U1(AES_S, u1(r3) )
// global area for passing parameters (aux, key) and for storing round keys
u4_t AESAUX[16/sizeof(u4_t)];
u4_t AESKEY[11*16/sizeof(u4_t)];
// generate 1+10 roundkeys for encryption with 128-bit key
// read 128-bit key from AESKEY in MSBF, generate roundkey words in place
static void aesroundkeys () {
int i;
u4_t b;
for( i=0; i<4; i++) {
AESKEY[i] = swapmsbf(AESKEY[i]);
}
b = AESKEY[3];
for( ; i<44; i++ ) {
if( i%4==0 ) {
// b = SubWord(RotWord(b)) xor Rcon[i/4]
b = ((u4_t)TABLE_GET_U1(AES_S, u1(b >> 16)) << 24) ^
((u4_t)TABLE_GET_U1(AES_S, u1(b >> 8)) << 16) ^
((u4_t)TABLE_GET_U1(AES_S, u1(b) ) << 8) ^
((u4_t)TABLE_GET_U1(AES_S, b >> 24 ) ) ^
TABLE_GET_U4(AES_RCON, (i-4)/4);
}
AESKEY[i] = b ^= AESKEY[i-4];
}
}
u4_t os_aes (u1_t mode, xref2u1_t buf, u2_t len) {
aesroundkeys();
if( mode & AES_MICNOAUX ) {
AESAUX[0] = AESAUX[1] = AESAUX[2] = AESAUX[3] = 0;
} else {
AESAUX[0] = swapmsbf(AESAUX[0]);
AESAUX[1] = swapmsbf(AESAUX[1]);
AESAUX[2] = swapmsbf(AESAUX[2]);
AESAUX[3] = swapmsbf(AESAUX[3]);
}
while( (signed char)len > 0 ) {
u4_t a0, a1, a2, a3;
u4_t t0, t1, t2, t3;
u4_t *ki, *ke;
// load input block
if( (mode & AES_CTR) || ((mode & AES_MIC) && (mode & AES_MICNOAUX)==0) ) { // load CTR block or first MIC block
a0 = AESAUX[0];
a1 = AESAUX[1];
a2 = AESAUX[2];
a3 = AESAUX[3];
}
else if( (mode & AES_MIC) && len <= 16 ) { // last MIC block
a0 = a1 = a2 = a3 = 0; // load null block
mode |= ((len == 16) ? 1 : 2) << 4; // set MICSUB: CMAC subkey K1 or K2
} else
LOADDATA: { // load data block (partially)
for(t0=0; t0<16; t0++) {
t1 = (t1<<8) | ((t0<len) ? buf[t0] : (t0==len) ? 0x80 : 0x00);
if((t0&3)==3) {
a0 = a1;
a1 = a2;
a2 = a3;
a3 = t1;
}
}
if( mode & AES_MIC ) {
a0 ^= AESAUX[0];
a1 ^= AESAUX[1];
a2 ^= AESAUX[2];
a3 ^= AESAUX[3];
}
}
// perform AES encryption on block in a0-a3
ki = AESKEY;
ke = ki + 8*4;
a0 ^= ki[0];
a1 ^= ki[1];
a2 ^= ki[2];
a3 ^= ki[3];
do {
AES_key4 (t1,t2,t3,t0,4);
AES_expr4(t1,t2,t3,t0,a0);
AES_expr4(t2,t3,t0,t1,a1);
AES_expr4(t3,t0,t1,t2,a2);
AES_expr4(t0,t1,t2,t3,a3);
AES_key4 (a1,a2,a3,a0,8);
AES_expr4(a1,a2,a3,a0,t0);
AES_expr4(a2,a3,a0,a1,t1);
AES_expr4(a3,a0,a1,a2,t2);
AES_expr4(a0,a1,a2,a3,t3);
} while( (ki+=8) < ke );
AES_key4 (t1,t2,t3,t0,4);
AES_expr4(t1,t2,t3,t0,a0);
AES_expr4(t2,t3,t0,t1,a1);
AES_expr4(t3,t0,t1,t2,a2);
AES_expr4(t0,t1,t2,t3,a3);
AES_expr(a0,t0,t1,t2,t3,8);
AES_expr(a1,t1,t2,t3,t0,9);
AES_expr(a2,t2,t3,t0,t1,10);
AES_expr(a3,t3,t0,t1,t2,11);
// result of AES encryption in a0-a3
if( mode & AES_MIC ) {
if( (t1 = (mode & AES_MICSUB) >> 4) != 0 ) { // last block
do {
// compute CMAC subkey K1 and K2
t0 = a0 >> 31; // save MSB
a0 = (a0 << 1) | (a1 >> 31);
a1 = (a1 << 1) | (a2 >> 31);
a2 = (a2 << 1) | (a3 >> 31);
a3 = (a3 << 1);
if( t0 ) a3 ^= 0x87;
} while( --t1 );
AESAUX[0] ^= a0;
AESAUX[1] ^= a1;
AESAUX[2] ^= a2;
AESAUX[3] ^= a3;
mode &= ~AES_MICSUB;
goto LOADDATA;
} else {
// save cipher block as new iv
AESAUX[0] = a0;
AESAUX[1] = a1;
AESAUX[2] = a2;
AESAUX[3] = a3;
}
} else { // CIPHER
if( mode & AES_CTR ) { // xor block (partially)
t0 = (len > 16) ? 16: len;
for(t1=0; t1<t0; t1++) {
buf[t1] ^= (a0>>24);
a0 <<= 8;
if((t1&3)==3) {
a0 = a1;
a1 = a2;
a2 = a3;
}
}
// update counter
AESAUX[3]++;
} else { // ECB
// store block
msbf4_write(buf+0, a0);
msbf4_write(buf+4, a1);
msbf4_write(buf+8, a2);
msbf4_write(buf+12, a3);
}
}
// update block state
if( (mode & AES_MIC)==0 || (mode & AES_MICNOAUX) ) {
buf += 16;
len -= 16;
}
mode |= AES_MICNOAUX;
}
return AESAUX[0];
}
#endif

View File

@ -1,145 +0,0 @@
/*******************************************************************************
* Copyright (c) 2016 Matthijs Kooijman
*
* LICENSE
*
* Permission is hereby granted, free of charge, to anyone
* obtaining a copy of this document and accompanying files,
* to do whatever they want with them without any restriction,
* including, but not limited to, copying, modification and
* redistribution.
*
* NO WARRANTY OF ANY KIND IS PROVIDED.
*******************************************************************************/
/*
* The original LMIC AES implementation integrates raw AES encryption
* with CMAC and AES-CTR in a single piece of code. Most other AES
* implementations (only) offer raw single block AES encryption, so this
* file contains an implementation of CMAC and AES-CTR, and offers the
* same API through the os_aes() function as the original AES
* implementation. This file assumes that there is an encryption
* function available with this signature:
*
* extern "C" void lmic_aes_encrypt(u1_t *data, u1_t *key);
*
* That takes a single 16-byte buffer and encrypts it wit the given
* 16-byte key.
*/
#include "../lmic/oslmic.h"
#if !defined(USE_ORIGINAL_AES)
// This should be defined elsewhere
void lmic_aes_encrypt(u1_t *data, u1_t *key);
// global area for passing parameters (aux, key) and for storing round keys
u4_t AESAUX[16/sizeof(u4_t)];
u4_t AESKEY[11*16/sizeof(u4_t)];
// Shift the given buffer left one bit
static void shift_left(xref2u1_t buf, u1_t len) {
while (len--) {
u1_t next = len ? buf[1] : 0;
u1_t val = (*buf << 1);
if (next & 0x80)
val |= 1;
*buf++ = val;
}
}
// Apply RFC4493 CMAC, using AESKEY as the key. If prepend_aux is true,
// AESAUX is prepended to the message. AESAUX is used as working memory
// in any case. The CMAC result is returned in AESAUX as well.
static void os_aes_cmac(xref2u1_t buf, u2_t len, u1_t prepend_aux) {
if (prepend_aux)
lmic_aes_encrypt(AESaux, AESkey);
else
memset (AESaux, 0, 16);
while (len > 0) {
u1_t need_padding = 0;
for (u1_t i = 0; i < 16; ++i, ++buf, --len) {
if (len == 0) {
// The message is padded with 0x80 and then zeroes.
// Since zeroes are no-op for xor, we can just skip them
// and leave AESAUX unchanged for them.
AESaux[i] ^= 0x80;
need_padding = 1;
break;
}
AESaux[i] ^= *buf;
}
if (len == 0) {
// Final block, xor with K1 or K2. K1 and K2 are calculated
// by encrypting the all-zeroes block and then applying some
// shifts and xor on that.
u1_t final_key[16];
memset(final_key, 0, sizeof(final_key));
lmic_aes_encrypt(final_key, AESkey);
// Calculate K1
u1_t msb = final_key[0] & 0x80;
shift_left(final_key, sizeof(final_key));
if (msb)
final_key[sizeof(final_key)-1] ^= 0x87;
// If the final block was not complete, calculate K2 from K1
if (need_padding) {
msb = final_key[0] & 0x80;
shift_left(final_key, sizeof(final_key));
if (msb)
final_key[sizeof(final_key)-1] ^= 0x87;
}
// Xor with K1 or K2
for (u1_t i = 0; i < sizeof(final_key); ++i)
AESaux[i] ^= final_key[i];
}
lmic_aes_encrypt(AESaux, AESkey);
}
}
// Run AES-CTR using the key in AESKEY and using AESAUX as the
// counter block. The last byte of the counter block will be incremented
// for every block. The given buffer will be encrypted in place.
static void os_aes_ctr (xref2u1_t buf, u2_t len) {
u1_t ctr[16];
while (len) {
// Encrypt the counter block with the selected key
memcpy(ctr, AESaux, sizeof(ctr));
lmic_aes_encrypt(ctr, AESkey);
// Xor the payload with the resulting ciphertext
for (u1_t i = 0; i < 16 && len > 0; i++, len--, buf++)
*buf ^= ctr[i];
// Increment the block index byte
AESaux[15]++;
}
}
u4_t os_aes (u1_t mode, xref2u1_t buf, u2_t len) {
switch (mode & ~AES_MICNOAUX) {
case AES_MIC:
os_aes_cmac(buf, len, /* prepend_aux */ !(mode & AES_MICNOAUX));
return os_rmsbf4(AESaux);
case AES_ENC:
// TODO: Check / handle when len is not a multiple of 16
for (u1_t i = 0; i < len; i += 16)
lmic_aes_encrypt(buf+i, AESkey);
break;
case AES_CTR:
os_aes_ctr(buf, len);
break;
}
return 0;
}
#endif // !defined(USE_ORIGINAL_AES)

View File

@ -1,357 +0,0 @@
/*******************************************************************************
* Copyright (c) 2015 Matthijs Kooijman
* All rights reserved. This program and the accompanying materials
* are made available under the terms of the Eclipse Public License v1.0
* which accompanies this distribution, and is available at
* http://www.eclipse.org/legal/epl-v10.html
*
* This the HAL to run LMIC on top of the Arduino environment.
*******************************************************************************/
#include <Arduino.h>
#include <SPI.h>
#include "../lmic.h"
#include "hal.h"
#include <stdio.h>
// -----------------------------------------------------------------------------
// I/O
static const lmic_pinmap *plmic_pins;
static void hal_interrupt_init(); // Fwd declaration
static void hal_io_init () {
// NSS and DIO0 are required, DIO1 is required for LoRa, DIO2 for FSK
ASSERT(plmic_pins->nss != LMIC_UNUSED_PIN);
ASSERT(plmic_pins->dio[0] != LMIC_UNUSED_PIN);
ASSERT(plmic_pins->dio[1] != LMIC_UNUSED_PIN || plmic_pins->dio[2] != LMIC_UNUSED_PIN);
// Serial.print("nss: "); Serial.println(plmic_pins->nss);
// Serial.print("rst: "); Serial.println(plmic_pins->rst);
// Serial.print("dio[0]: "); Serial.println(plmic_pins->dio[0]);
// Serial.print("dio[1]: "); Serial.println(plmic_pins->dio[1]);
// Serial.print("dio[2]: "); Serial.println(plmic_pins->dio[2]);
// initialize SPI chip select to high (it's active low)
digitalWrite(plmic_pins->nss, HIGH);
pinMode(plmic_pins->nss, OUTPUT);
if (plmic_pins->rxtx != LMIC_UNUSED_PIN) {
// initialize to RX
digitalWrite(plmic_pins->rxtx, LOW != plmic_pins->rxtx_rx_active);
pinMode(plmic_pins->rxtx, OUTPUT);
}
if (plmic_pins->rst != LMIC_UNUSED_PIN) {
// initialize RST to floating
pinMode(plmic_pins->rst, INPUT);
}
hal_interrupt_init();
}
// val == 1 => tx
void hal_pin_rxtx (u1_t val) {
if (plmic_pins->rxtx != LMIC_UNUSED_PIN)
digitalWrite(plmic_pins->rxtx, val != plmic_pins->rxtx_rx_active);
}
// set radio RST pin to given value (or keep floating!)
void hal_pin_rst (u1_t val) {
if (plmic_pins->rst == LMIC_UNUSED_PIN)
return;
if(val == 0 || val == 1) { // drive pin
digitalWrite(plmic_pins->rst, val);
pinMode(plmic_pins->rst, OUTPUT);
} else { // keep pin floating
pinMode(plmic_pins->rst, INPUT);
}
}
s1_t hal_getRssiCal (void) {
return plmic_pins->rssi_cal;
}
#if !defined(LMIC_USE_INTERRUPTS)
static void hal_interrupt_init() {
pinMode(plmic_pins->dio[0], INPUT);
if (plmic_pins->dio[1] != LMIC_UNUSED_PIN)
pinMode(plmic_pins->dio[1], INPUT);
if (plmic_pins->dio[2] != LMIC_UNUSED_PIN)
pinMode(plmic_pins->dio[2], INPUT);
}
static bool dio_states[NUM_DIO] = {0};
static void hal_io_check() {
uint8_t i;
for (i = 0; i < NUM_DIO; ++i) {
if (plmic_pins->dio[i] == LMIC_UNUSED_PIN)
continue;
if (dio_states[i] != digitalRead(plmic_pins->dio[i])) {
dio_states[i] = !dio_states[i];
if (dio_states[i])
radio_irq_handler(i);
}
}
}
#else
// Interrupt handlers
static ostime_t interrupt_time[NUM_DIO] = {0};
static void hal_isrPin0() {
ostime_t now = os_getTime();
interrupt_time[0] = now ? now : 1;
}
static void hal_isrPin1() {
ostime_t now = os_getTime();
interrupt_time[1] = now ? now : 1;
}
static void hal_isrPin2() {
ostime_t now = os_getTime();
interrupt_time[2] = now ? now : 1;
}
typedef void (*isr_t)();
static isr_t interrupt_fns[NUM_DIO] = {hal_isrPin0, hal_isrPin1, hal_isrPin2};
static void hal_interrupt_init() {
for (uint8_t i = 0; i < NUM_DIO; ++i) {
if (plmic_pins->dio[i] == LMIC_UNUSED_PIN)
continue;
attachInterrupt(digitalPinToInterrupt(plmic_pins->dio[i]), interrupt_fns[i], RISING);
}
}
static void hal_io_check() {
uint8_t i;
for (i = 0; i < NUM_DIO; ++i) {
ostime_t iTime;
if (plmic_pins->dio[i] == LMIC_UNUSED_PIN)
continue;
iTime = interrupt_time[i];
if (iTime) {
interrupt_time[i] = 0;
radio_irq_handler_v2(i, iTime);
}
}
}
#endif // LMIC_USE_INTERRUPTS
// -----------------------------------------------------------------------------
// SPI
static void hal_spi_init () {
SPI.begin(plmic_pins->sck, plmic_pins->miso, plmic_pins->mosi, plmic_pins->nss);
}
void hal_pin_nss (u1_t val) {
if (!val) {
uint32_t spi_freq;
if ((spi_freq = plmic_pins->spi_freq) == 0)
spi_freq = LMIC_SPI_FREQ;
SPISettings settings(spi_freq, MSBFIRST, SPI_MODE0);
SPI.beginTransaction(settings);
} else {
SPI.endTransaction();
}
//Serial.println(val?">>":"<<");
digitalWrite(plmic_pins->nss, val);
}
// perform SPI transaction with radio
u1_t hal_spi (u1_t out) {
u1_t res = SPI.transfer(out);
/*
Serial.print(">");
Serial.print(out, HEX);
Serial.print("<");
Serial.println(res, HEX);
*/
return res;
}
// -----------------------------------------------------------------------------
// TIME
static void hal_time_init () {
// Nothing to do
}
u4_t hal_ticks () {
// Because micros() is scaled down in this function, micros() will
// overflow before the tick timer should, causing the tick timer to
// miss a significant part of its values if not corrected. To fix
// this, the "overflow" serves as an overflow area for the micros()
// counter. It consists of three parts:
// - The US_PER_OSTICK upper bits are effectively an extension for
// the micros() counter and are added to the result of this
// function.
// - The next bit overlaps with the most significant bit of
// micros(). This is used to detect micros() overflows.
// - The remaining bits are always zero.
//
// By comparing the overlapping bit with the corresponding bit in
// the micros() return value, overflows can be detected and the
// upper bits are incremented. This is done using some clever
// bitwise operations, to remove the need for comparisons and a
// jumps, which should result in efficient code. By avoiding shifts
// other than by multiples of 8 as much as possible, this is also
// efficient on AVR (which only has 1-bit shifts).
static uint8_t overflow = 0;
// Scaled down timestamp. The top US_PER_OSTICK_EXPONENT bits are 0,
// the others will be the lower bits of our return value.
uint32_t scaled = micros() >> US_PER_OSTICK_EXPONENT;
// Most significant byte of scaled
uint8_t msb = scaled >> 24;
// Mask pointing to the overlapping bit in msb and overflow.
const uint8_t mask = (1 << (7 - US_PER_OSTICK_EXPONENT));
// Update overflow. If the overlapping bit is different
// between overflow and msb, it is added to the stored value,
// so the overlapping bit becomes equal again and, if it changed
// from 1 to 0, the upper bits are incremented.
overflow += (msb ^ overflow) & mask;
// Return the scaled value with the upper bits of stored added. The
// overlapping bit will be equal and the lower bits will be 0, so
// bitwise or is a no-op for them.
return scaled | ((uint32_t)overflow << 24);
// 0 leads to correct, but overly complex code (it could just return
// micros() unmodified), 8 leaves no room for the overlapping bit.
static_assert(US_PER_OSTICK_EXPONENT > 0 && US_PER_OSTICK_EXPONENT < 8, "Invalid US_PER_OSTICK_EXPONENT value");
}
// Returns the number of ticks until time. Negative values indicate that
// time has already passed.
static s4_t delta_time(u4_t time) {
return (s4_t)(time - hal_ticks());
}
void hal_waitUntil (u4_t time) {
s4_t delta = delta_time(time);
// From delayMicroseconds docs: Currently, the largest value that
// will produce an accurate delay is 16383.
while (delta > (16000 / US_PER_OSTICK)) {
delay(16);
delta -= (16000 / US_PER_OSTICK);
}
if (delta > 0)
delayMicroseconds(delta * US_PER_OSTICK);
}
// check and rewind for target time
u1_t hal_checkTimer (u4_t time) {
// No need to schedule wakeup, since we're not sleeping
return delta_time(time) <= 0;
}
static uint8_t irqlevel = 0;
void hal_disableIRQs () {
noInterrupts();
irqlevel++;
}
void hal_enableIRQs () {
if(--irqlevel == 0) {
interrupts();
// Instead of using proper interrupts (which are a bit tricky
// and/or not available on all pins on AVR), just poll the pin
// values. Since os_runloop disables and re-enables interrupts,
// putting this here makes sure we check at least once every
// loop.
//
// As an additional bonus, this prevents the can of worms that
// we would otherwise get for running SPI transfers inside ISRs
hal_io_check();
}
}
void hal_sleep () {
// Not implemented
}
// -----------------------------------------------------------------------------
#if defined(LMIC_PRINTF_TO)
#if !defined(__AVR)
static ssize_t uart_putchar (void *, const char *buf, size_t len) {
return LMIC_PRINTF_TO.write((const uint8_t *)buf, len);
}
static cookie_io_functions_t functions =
{
.read = NULL,
.write = uart_putchar,
.seek = NULL,
.close = NULL
};
void hal_printf_init() {
stdout = fopencookie(NULL, "w", functions);
if (stdout != nullptr) {
setvbuf(stdout, NULL, _IONBF, 0);
}
}
#else // defined(__AVR)
static int uart_putchar (char c, FILE *)
{
LMIC_PRINTF_TO.write(c) ;
return 0 ;
}
void hal_printf_init() {
// create a FILE structure to reference our UART output function
static FILE uartout;
memset(&uartout, 0, sizeof(uartout));
// fill in the UART file descriptor with pointer to writer.
fdev_setup_stream (&uartout, uart_putchar, NULL, _FDEV_SETUP_WRITE);
// The uart is the standard output device STDOUT.
stdout = &uartout ;
}
#endif // !defined(ESP8266) || defined(ESP31B) || defined(ESP32)
#endif // defined(LMIC_PRINTF_TO)
void hal_init (void) {
hal_init_ex(&lmic_pins);
}
void hal_init_ex (const void *pContext) {
plmic_pins = (const lmic_pinmap *)pContext;
// configure radio I/O and interrupt handler
hal_io_init();
// configure radio SPI
hal_spi_init();
// configure timer and interrupt handler
hal_time_init();
#if defined(LMIC_PRINTF_TO)
// printf support
hal_printf_init();
#endif
}
void hal_failed (const char *file, u2_t line) {
#if defined(LMIC_FAILURE_TO)
LMIC_FAILURE_TO.println("FAILURE ");
LMIC_FAILURE_TO.print(file);
LMIC_FAILURE_TO.print(':');
LMIC_FAILURE_TO.println(line);
LMIC_FAILURE_TO.flush();
#endif
hal_disableIRQs();
while(1);
}

View File

@ -1,41 +0,0 @@
/*******************************************************************************
* Copyright (c) 2015-2016 Matthijs Kooijman
* Copyright (c) 2016-2018 MCCI Corporation
*
* All rights reserved. This program and the accompanying materials
* are made available under the terms of the Eclipse Public License v1.0
* which accompanies this distribution, and is available at
* http://www.eclipse.org/legal/epl-v10.html
*
* This the HAL to run LMIC on top of the Arduino environment.
*******************************************************************************/
#ifndef _hal_hal_h_
#define _hal_hal_h_
static const int NUM_DIO = 3;
// be careful of alignment below.
struct lmic_pinmap {
u1_t nss; // byte 0: pin for select
u1_t rxtx; // byte 1: pin for rx/tx control
u1_t rst; // byte 2: pin for reset
u1_t dio[NUM_DIO]; // bytes 3..5: pins for DIO0, DOI1, DIO2
u1_t mosi; // byte 9: pin for master out / slave in (write to LORA chip)
u1_t miso; // byte 10: pin for master in / slave out (read from LORA chip)
u1_t sck; // byte 11: pin for serial clock by master
// true if we must set rxtx for rx_active, false for tx_active
u1_t rxtx_rx_active; // byte 6: polarity of rxtx active
s1_t rssi_cal; // byte 7: cal in dB -- added to RSSI
// measured prior to decision.
// Must include noise guardband!
u4_t spi_freq; // bytes 8..11: SPI freq in Hz.
};
// Use this for any unused pins.
const u1_t LMIC_UNUSED_PIN = 0xff;
// Declared here, to be defined and initialized by the application
// use os_init_ex() if you want not to use a const table.
extern const lmic_pinmap lmic_pins;
#endif // _hal_hal_h_

View File

@ -1,11 +0,0 @@
#ifdef __cplusplus
extern "C"{
#endif
#include "lmic/lmic.h"
#include "lmic/lmic_bandplan.h"
#include "lmic/lmic_util.h"
#ifdef __cplusplus
}
#endif

View File

@ -1,181 +0,0 @@
#ifndef _lmic_config_h_
#define _lmic_config_h_
// In the original LMIC code, these config values were defined on the
// gcc commandline. Since Arduino does not allow easily modifying the
// compiler commandline unless you modify the BSP, you have two choices:
//
// - edit {libraries}/arduino-lmic/project_config/lmic_project_config.h;
// - use a BSP like the MCCI Arduino BSPs, which get the configuration
// from the boards.txt file through a menu option.
//
// You definitely should not edit this file.
// set up preconditions, and load configuration if needed.
#ifndef _LMIC_CONFIG_PRECONDITIONS_H_
# include "lmic_config_preconditions.h"
#endif
// check post-conditions.
// make sure that we have exactly one target region defined.
#if CFG_LMIC_REGION_MASK == 0
# define CFG_eu868 1
#elif (CFG_LMIC_REGION_MASK & (-CFG_LMIC_REGION_MASK)) != CFG_LMIC_REGION_MASK
# error You can define at most one of CFG_... variables
#elif (CFG_LMIC_REGION_MASK & LMIC_REGIONS_SUPPORTED) == 0
# error The selected CFG_... region is not supported yet.
#endif
// make sure that LMIC_COUNTRY_CODE is defined.
#ifndef LMIC_COUNTRY_CODE
# define LMIC_COUNTRY_CODE LMIC_COUNTRY_CODE_NONE
#endif
// if the country code is Japan, then the region must be AS923
#if LMIC_COUNTRY_CODE == LMIC_COUNTRY_CODE_JP && CFG_region != LMIC_REGION_as923
# error "If country code is JP, then region must be AS923"
#endif
// check for internal consistency
#if !(CFG_LMIC_EU_like || CFG_LMIC_US_like)
# error "Internal error: Neither EU-like nor US-like!"
#endif
// This is the SX1272/SX1273 radio, which is also used on the HopeRF
// RFM92 boards.
//#define CFG_sx1272_radio 1
// This is the SX1276/SX1277/SX1278/SX1279 radio, which is also used on
// the HopeRF RFM95 boards.
//#define CFG_sx1276_radio 1
// ensure that a radio is defined.
#if ! (defined(CFG_sx1272_radio) || defined(CFG_sx1276_radio))
# warning Target radio not defined, assuming CFG_sx1276_radio
#define CFG_sx1276_radio 1
#elif defined(CFG_sx1272_radio) && defined(CFG_sx1276_radio)
# error You can define at most one of CFG_sx1272_radio and CF_sx1276_radio
#endif
// LMIC requires ticks to be 15.5μs - 100 μs long
#ifndef OSTICKS_PER_SEC
// 16 μs per tick
# ifndef US_PER_OSTICK_EXPONENT
# define US_PER_OSTICK_EXPONENT 4
# endif
# define US_PER_OSTICK (1 << US_PER_OSTICK_EXPONENT)
# define OSTICKS_PER_SEC (1000000 / US_PER_OSTICK)
#endif /* OSTICKS_PER_SEC */
#if ! (10000 <= OSTICKS_PER_SEC && OSTICKS_PER_SEC < 64516)
# error LMIC requires ticks to be 15.5 us to 100 us long
#endif
// Change the SPI clock speed if you encounter errors
// communicating with the radio.
// The standard range is 125kHz-8MHz, but some boards can go faster.
#ifndef LMIC_SPI_FREQ
#define LMIC_SPI_FREQ 1E6
#endif
// Set this to 1 to enable some basic debug output (using printf) about
// RF settings used during transmission and reception. Set to 2 to
// enable more verbose output. Make sure that printf is actually
// configured (e.g. on AVR it is not by default), otherwise using it can
// cause crashing.
#ifndef LMIC_DEBUG_LEVEL
#define LMIC_DEBUG_LEVEL 0
#endif
// Enable this to allow using printf() to print to the given serial port
// (or any other Print object). This can be easy for debugging. The
// current implementation only works on AVR, though.
//#define LMIC_PRINTF_TO Serial
// Enable this to use interrupt handler routines listening for RISING signals.
// Otherwise, the library polls digital input lines for changes.
//#define LMIC_USE_INTERRUPTS
// If DISABLE_LMIC_FAILURE_TO is defined, runtime assertion failures
// silently halt execution. Otherwise, LMIC_FAILURE_TO should be defined
// as the name of an object derived from Print, which will be used for
// displaying runtime assertion failures. If you say nothing in your
// lmic_project_config.h, runtime assertion failures are displayed
// using the Serial object.
#if ! defined(DISABLE_LMIC_FAILURE_TO) && ! defined(LMIC_FAILURE_TO)
#define LMIC_FAILURE_TO Serial
#endif
// define this in lmic_project_config.h to disable all code related to joining
//#define DISABLE_JOIN
// define this in lmic_project_config.h to disable all code related to ping
//#define DISABLE_PING
// define this in lmic_project_config.h to disable all code related to beacon tracking.
// Requires ping to be disabled too
//#define DISABLE_BEACONS
// define these in lmic_project_config.h to disable the corresponding MAC commands.
// Class A
//#define DISABLE_MCMD_DCAP_REQ // duty cycle cap
//#define DISABLE_MCMD_DN2P_SET // 2nd DN window param
//#define DISABLE_MCMD_SNCH_REQ // set new channel
// Class B
//#define DISABLE_MCMD_PING_SET // set ping freq, automatically disabled by DISABLE_PING
//#define DISABLE_MCMD_BCNI_ANS // next beacon start, automatically disabled by DISABLE_BEACON
// In LoRaWAN, a gateway applies I/Q inversion on TX, and nodes do the
// same on RX. This ensures that gateways can talk to nodes and vice
// versa, but gateways will not hear other gateways and nodes will not
// hear other nodes. By defining this macro in lmic_project_config.h,
// this inversion is disabled and this node can hear other nodes. If
// two nodes both have this macro set, they can talk to each other
// (but they can no longer hear gateways). This should probably only
// be used when debugging and/or when talking to the radio directly
// (e.g. like in the "raw" example).
//#define DISABLE_INVERT_IQ_ON_RX
// This allows choosing between multiple included AES implementations.
// Make sure exactly one of these is uncommented.
//
// This selects the original AES implementation included LMIC. This
// implementation is optimized for speed on 32-bit processors using
// fairly big lookup tables, but it takes up big amounts of flash on the
// AVR architecture.
// #define USE_ORIGINAL_AES
//
// This selects the AES implementation written by Ideetroon for their
// own LoRaWAN library. It also uses lookup tables, but smaller
// byte-oriented ones, making it use a lot less flash space (but it is
// also about twice as slow as the original).
// #define USE_IDEETRON_AES
#if ! (defined(USE_ORIGINAL_AES) || defined(USE_IDEETRON_AES))
# define USE_IDEETRON_AES
#endif
#if defined(USE_ORIGINAL_AES) && defined(USE_IDEETRON_AES)
# error "You may define at most one of USE_ORIGINAL_AES and USE_IDEETRON_AES"
#endif
// LMIC_DISABLE_DR_LEGACY
// turn off legacy DR_* symbols that vary by bandplan.
// Older code uses these for configuration. EU868_DR_*, US915_DR_*
// etc symbols are prefered, but breaking older code is inconvenient for
// everybody. We don't want to use DR_* in the LMIC itself, so we provide
// this #define to allow them to be removed.
#if !defined(LMIC_DR_LEGACY)
# if !defined(LMIC_DISABLE_DR_LEGACY)
# define LMIC_DR_LEGACY 1
# else // defined(LMIC_DISABLE_DR_LEGACY)
# define LMIC_DR_LEGACY 0
# endif // defined(LMIC_DISABLE_DR_LEGACY)
#endif // LMIC_DR_LEGACY
// LMIC_ENABLE_DeviceTimeReq
// enable support for MCMD_DeviceTimeReq and MCMD_DeviceTimeAns
// this is always defined, and non-zero to enable it.
#if !defined(LMIC_ENABLE_DeviceTimeReq)
# define LMIC_ENABLE_DeviceTimeReq 0
#endif
#endif // _lmic_config_h_

View File

@ -1,118 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2016, 2018 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#ifndef _hal_hpp_
#define _hal_hpp_
#ifdef __cplusplus
extern "C"{
#endif
/*
* initialize hardware (IO, SPI, TIMER, IRQ).
*/
void hal_init (void);
/*
* initialize hardware, passing in platform-specific context
*/
void hal_init_ex (const void *pContext);
/*
* drive radio NSS pin (0=low, 1=high).
*/
void hal_pin_nss (u1_t val);
/*
* drive radio RX/TX pins (0=rx, 1=tx).
*/
void hal_pin_rxtx (u1_t val);
/*
* control radio RST pin (0=low, 1=high, 2=floating)
*/
void hal_pin_rst (u1_t val);
/*
* perform 8-bit SPI transaction with radio.
* - write given byte 'outval'
* - read byte and return value
*/
u1_t hal_spi (u1_t outval);
/*
* disable all CPU interrupts.
* - might be invoked nested
* - will be followed by matching call to hal_enableIRQs()
*/
void hal_disableIRQs (void);
/*
* enable CPU interrupts.
*/
void hal_enableIRQs (void);
/*
* put system and CPU in low-power mode, sleep until interrupt.
*/
void hal_sleep (void);
/*
* return 32-bit system time in ticks.
*/
u4_t hal_ticks (void);
/*
* busy-wait until specified timestamp (in ticks) is reached.
*/
void hal_waitUntil (u4_t time);
/*
* check and rewind timer for target time.
* - return 1 if target time is close
* - otherwise rewind timer for target time or full period and return 0
*/
u1_t hal_checkTimer (u4_t targettime);
/*
* perform fatal failure action.
* - called by assertions
* - action could be HALT or reboot
*/
void hal_failed (const char *file, u2_t line);
/*
* get the calibration value for radio_rssi
*/
s1_t hal_getRssiCal (void);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // _hal_hpp_

File diff suppressed because it is too large Load Diff

View File

@ -1,478 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2016 Matthijs Kooijman.
* Copyright (c) 2016-2018 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
//! @file
//! @brief LMIC API
#ifndef _lmic_h_
#define _lmic_h_
#include "oslmic.h"
#include "lorabase.h"
#if LMIC_DEBUG_LEVEL > 0 || LMIC_X_DEBUG_LEVEL > 0
# if defined(LMIC_DEBUG_INCLUDE)
# define LMIC_STRINGIFY_(x) #x
# define LMIC_STRINGIFY(x) LMIC_STRINGIFY_(x)
# include LMIC_STRINGIFY(LMIC_DEBUG_INCLUDE)
# endif
# ifdef LMIC_DEBUG_PRINTF_FN
extern void LMIC_DEBUG_PRINTF_FN(const char *f, ...);
# endif // ndef LMIC_DEBUG_PRINTF_FN
#endif
// if LMIC_DEBUG_PRINTF is now defined, just use it. This lets you do anything
// you like with a sufficiently crazy header file.
#if LMIC_DEBUG_LEVEL > 0
# ifndef LMIC_DEBUG_PRINTF
// otherwise, check whether someone configured a print-function to be used,
// and use it if so.
# ifdef LMIC_DEBUG_PRINTF_FN
# define LMIC_DEBUG_PRINTF(f, ...) LMIC_DEBUG_PRINTF_FN(f, ## __VA_ARGS__)
# ifndef LMIC_DEBUG_INCLUDE // If you use LMIC_DEBUG_INCLUDE, put the declaration in there
void LMIC_DEBUG_PRINTF_FN(const char *f, ...);
# endif // ndef LMIC_DEBUG_INCLUDE
# else // ndef LMIC_DEBUG_PRINTF_FN
// if there's no other info, just use printf. In a pure Arduino environment,
// that's what will happen.
# include <stdio.h>
# define LMIC_DEBUG_PRINTF(f, ...) printf(f, ## __VA_ARGS__)
# endif // ndef LMIC_DEBUG_PRINTF_FN
# endif // ndef LMIC_DEBUG_PRINTF
# ifndef LMIC_DEBUG_FLUSH
# ifdef LMIC_DEBUG_FLUSH_FN
# define LMIC_DEBUG_FLUSH() LMIC_DEBUG_FLUSH_FN()
# else // ndef LMIC_DEBUG_FLUSH_FN
// if there's no other info, assume that flush is not needed.
# define LMIC_DEBUG_FLUSH() do { ; } while (0)
# endif // ndef LMIC_DEBUG_FLUSH_FN
# endif // ndef LMIC_DEBUG_FLUSH
#else // LMIC_DEBUG_LEVEL == 0
// If debug level is zero, printf and flush expand to nothing.
# define LMIC_DEBUG_PRINTF(f, ...) do { ; } while (0)
# define LMIC_DEBUG_FLUSH() do { ; } while (0)
#endif // LMIC_DEBUG_LEVEL == 0
//
// LMIC_X_DEBUG_LEVEL enables additional, special print functions for debugging
// RSSI features. This is used sparingly.
#if LMIC_X_DEBUG_LEVEL > 0
# ifdef LMIC_DEBUG_PRINTF_FN
# define LMIC_X_DEBUG_PRINTF(f, ...) LMIC_DEBUG_PRINTF_FN(f, ## __VA_ARGS__)
# else
# error "LMIC_DEBUG_PRINTF_FN must be defined for LMIC_X_DEBUG_LEVEL > 0."
# endif
#else
# define LMIC_X_DEBUG_PRINTF(f, ...) do {;} while(0)
#endif
#ifdef __cplusplus
extern "C"{
#endif
// LMIC version -- this is ths IBM LMIC version
#define LMIC_VERSION_MAJOR 1
#define LMIC_VERSION_MINOR 6
#define LMIC_VERSION_BUILD 1468577746
// Arduino LMIC version
#define ARDUINO_LMIC_VERSION_CALC(major, minor, patch, local) \
(((major) << 24u) | ((minor) << 16u) | ((patch) << 8u) | (local))
#define ARDUINO_LMIC_VERSION ARDUINO_LMIC_VERSION_CALC(2, 2, 2, 0) /* v2.2.2 */
#define ARDUINO_LMIC_VERSION_GET_MAJOR(v) \
(((v) >> 24u) & 0xFFu)
#define ARDUINO_LMIC_VERSION_GET_MINOR(v) \
(((v) >> 16u) & 0xFFu)
#define ARDUINO_LMIC_VERSION_GET_PATCH(v) \
(((v) >> 8u) & 0xFFu)
#define ARDUINO_LMIC_VERSION_GET_LOCAL(v) \
((v) & 0xFFu)
//! Only For Antenna Tuning Tests !
//#define CFG_TxContinuousMode 1
enum { MAX_FRAME_LEN = 64 }; //!< Library cap on max frame length
enum { TXCONF_ATTEMPTS = 8 }; //!< Transmit attempts for confirmed frames
enum { MAX_MISSED_BCNS = 20 }; // threshold for triggering rejoin requests
enum { MAX_RXSYMS = 100 }; // stop tracking beacon beyond this
enum { LINK_CHECK_CONT = 12 , // continue with this after reported dead link
LINK_CHECK_DEAD = 24 , // after this UP frames and no response from NWK assume link is dead
LINK_CHECK_INIT = -12 , // UP frame count until we inc datarate
LINK_CHECK_OFF =-128 }; // link check disabled
enum { TIME_RESYNC = 6*128 }; // secs
enum { TXRX_GUARD_ms = 6000 }; // msecs - don't start TX-RX transaction before beacon
enum { JOIN_GUARD_ms = 9000 }; // msecs - don't start Join Req/Acc transaction before beacon
enum { TXRX_BCNEXT_secs = 2 }; // secs - earliest start after beacon time
enum { RETRY_PERIOD_secs = 3 }; // secs - random period for retrying a confirmed send
#if CFG_LMIC_EU_like // EU868 spectrum ====================================================
enum { MAX_CHANNELS = 16 }; //!< Max supported channels
enum { MAX_BANDS = 4 };
enum { LIMIT_CHANNELS = (1<<4) }; // EU868 will never have more channels
//! \internal
struct band_t {
u2_t txcap; // duty cycle limitation: 1/txcap
s1_t txpow; // maximum TX power
u1_t lastchnl; // last used channel
ostime_t avail; // channel is blocked until this time
};
TYPEDEF_xref2band_t; //!< \internal
#elif CFG_LMIC_US_like // US915 spectrum =================================================
enum { MAX_XCHANNELS = 2 }; // extra channels in RAM, channels 0-71 are immutable
#endif // ==========================================================================
// Keep in sync with evdefs.hpp::drChange
enum { DRCHG_SET, DRCHG_NOJACC, DRCHG_NOACK, DRCHG_NOADRACK, DRCHG_NWKCMD };
enum { KEEP_TXPOW = -128 };
#if !defined(DISABLE_PING)
//! \internal
struct rxsched_t {
u1_t dr;
u1_t intvExp; // 0..7
u1_t slot; // runs from 0 to 128
u1_t rxsyms;
ostime_t rxbase;
ostime_t rxtime; // start of next spot
u4_t freq;
};
TYPEDEF_xref2rxsched_t; //!< \internal
#endif // !DISABLE_PING
#if !defined(DISABLE_BEACONS)
//! Parsing and tracking states of beacons.
enum { BCN_NONE = 0x00, //!< No beacon received
BCN_PARTIAL = 0x01, //!< Only first (common) part could be decoded (info,lat,lon invalid/previous)
BCN_FULL = 0x02, //!< Full beacon decoded
BCN_NODRIFT = 0x04, //!< No drift value measured yet
BCN_NODDIFF = 0x08 }; //!< No differential drift measured yet
//! Information about the last and previous beacons.
struct bcninfo_t {
ostime_t txtime; //!< Time when the beacon was sent
s1_t rssi; //!< Adjusted RSSI value of last received beacon
s1_t snr; //!< Scaled SNR value of last received beacon
u1_t flags; //!< Last beacon reception and tracking states. See BCN_* values.
u4_t time; //!< GPS time in seconds of last beacon (received or surrogate)
//
u1_t info; //!< Info field of last beacon (valid only if BCN_FULL set)
s4_t lat; //!< Lat field of last beacon (valid only if BCN_FULL set)
s4_t lon; //!< Lon field of last beacon (valid only if BCN_FULL set)
};
#endif // !DISABLE_BEACONS
// purpose of receive window - lmic_t.rxState
enum { RADIO_RST=0, RADIO_TX=1, RADIO_RX=2, RADIO_RXON=3 };
// Netid values / lmic_t.netid
enum { NETID_NONE=(int)~0U, NETID_MASK=(int)0xFFFFFF };
// MAC operation modes (lmic_t.opmode).
enum { OP_NONE = 0x0000,
OP_SCAN = 0x0001, // radio scan to find a beacon
OP_TRACK = 0x0002, // track my networks beacon (netid)
OP_JOINING = 0x0004, // device joining in progress (blocks other activities)
OP_TXDATA = 0x0008, // TX user data (buffered in pendTxData)
OP_POLL = 0x0010, // send empty UP frame to ACK confirmed DN/fetch more DN data
OP_REJOIN = 0x0020, // occasionally send JOIN REQUEST
OP_SHUTDOWN = 0x0040, // prevent MAC from doing anything
OP_TXRXPEND = 0x0080, // TX/RX transaction pending
OP_RNDTX = 0x0100, // prevent TX lining up after a beacon
OP_PINGINI = 0x0200, // pingable is initialized and scheduling active
OP_PINGABLE = 0x0400, // we're pingable
OP_NEXTCHNL = 0x0800, // find a new channel
OP_LINKDEAD = 0x1000, // link was reported as dead
OP_TESTMODE = 0x2000, // developer test mode
};
// TX-RX transaction flags - report back to user
enum { TXRX_ACK = 0x80, // confirmed UP frame was acked
TXRX_NACK = 0x40, // confirmed UP frame was not acked
TXRX_NOPORT = 0x20, // set if a frame with a port was RXed, clr if no frame/no port
TXRX_PORT = 0x10, // set if a frame with a port was RXed, LMIC.frame[LMIC.dataBeg-1] => port
TXRX_DNW1 = 0x01, // received in 1st DN slot
TXRX_DNW2 = 0x02, // received in 2dn DN slot
TXRX_PING = 0x04 }; // received in a scheduled RX slot
// Event types for event callback
enum _ev_t { EV_SCAN_TIMEOUT=1, EV_BEACON_FOUND,
EV_BEACON_MISSED, EV_BEACON_TRACKED, EV_JOINING,
EV_JOINED, EV_RFU1, EV_JOIN_FAILED, EV_REJOIN_FAILED,
EV_TXCOMPLETE, EV_LOST_TSYNC, EV_RESET,
EV_RXCOMPLETE, EV_LINK_DEAD, EV_LINK_ALIVE, EV_SCAN_FOUND,
EV_TXSTART };
typedef enum _ev_t ev_t;
enum {
// This value represents 100% error in LMIC.clockError
MAX_CLOCK_ERROR = 65536,
};
// network time request callback function
// defined unconditionally, because APIs and types can't change based on config.
// This is called when a time-request succeeds or when we get a downlink
// without time request, "completing" the pending time request.
typedef void lmic_request_network_time_cb_t(void *pUserData, int flagSuccess);
// how the network represents time.
typedef u4_t lmic_gpstime_t;
// rather than deal with 1/256 second tick, we adjust ostime back
// (as it's high res) to match tNetwork.
typedef struct lmic_time_reference_s lmic_time_reference_t;
struct lmic_time_reference_s {
// our best idea of when we sent the uplink (end of packet).
ostime_t tLocal;
// the network's best idea of when we sent the uplink.
lmic_gpstime_t tNetwork;
};
enum lmic_request_time_state_e {
lmic_RequestTimeState_idle = 0, // we're not doing anything
lmic_RequestTimeState_tx, // we want to tx a time request on next uplink
lmic_RequestTimeState_rx, // we have tx'ed, next downlink completes.
lmic_RequestTimeState_success // we sucessfully got time.
};
typedef u1_t lmic_request_time_state_t;
struct lmic_t {
// Radio settings TX/RX (also accessed by HAL)
ostime_t txend;
ostime_t rxtime;
// LBT info
ostime_t lbt_ticks; // ticks to listen
s1_t lbt_dbmax; // max permissible dB on our channel (eg -80)
u4_t freq;
s1_t rssi;
s1_t snr; // LMIC.snr is SNR times 4
rps_t rps;
u1_t rxsyms;
u1_t dndr;
s1_t txpow; // dBm
osjob_t osjob;
// Channel scheduling
#if CFG_LMIC_EU_like
band_t bands[MAX_BANDS];
u4_t channelFreq[MAX_CHANNELS];
u2_t channelDrMap[MAX_CHANNELS];
u2_t channelMap;
#elif CFG_LMIC_US_like
u4_t xchFreq[MAX_XCHANNELS]; // extra channel frequencies (if device is behind a repeater)
u2_t xchDrMap[MAX_XCHANNELS]; // extra channel datarate ranges ---XXX: ditto
u2_t channelMap[(72+MAX_XCHANNELS+15)/16]; // enabled bits
u2_t activeChannels125khz;
u2_t activeChannels500khz;
#endif
u1_t txChnl; // channel for next TX
u1_t globalDutyRate; // max rate: 1/2^k
ostime_t globalDutyAvail; // time device can send again
u4_t netid; // current network id (~0 - none)
u2_t opmode;
u1_t upRepeat; // configured up repeat
s1_t adrTxPow; // ADR adjusted TX power
u1_t datarate; // current data rate
u1_t errcr; // error coding rate (used for TX only)
u1_t rejoinCnt; // adjustment for rejoin datarate
#if !defined(DISABLE_BEACONS)
s2_t drift; // last measured drift
s2_t lastDriftDiff;
s2_t maxDriftDiff;
#endif
u2_t clockError; // Inaccuracy in the clock. CLOCK_ERROR_MAX
// represents +/-100% error
u1_t pendTxPort;
u1_t pendTxConf; // confirmed data
u1_t pendTxLen; // +0x80 = confirmed
u1_t pendTxData[MAX_LEN_PAYLOAD];
u2_t devNonce; // last generated nonce
u1_t nwkKey[16]; // network session key
u1_t artKey[16]; // application router session key
devaddr_t devaddr;
u4_t seqnoDn; // device level down stream seqno
u4_t seqnoUp;
#if LMIC_ENABLE_DeviceTimeReq
// put here for alignment, to reduce RAM use.
ostime_t localDeviceTime; // the LMIC.txend value for last DeviceTimeAns
lmic_gpstime_t netDeviceTime; // the netDeviceTime for lastDeviceTimeAns
// zero ==> not valid.
lmic_request_network_time_cb_t *pNetworkTimeCb; // call-back routine
void *pNetworkTimeUserData; // call-back data
#endif // LMIC_ENABLE_DeviceTimeReq
u1_t dnConf; // dn frame confirm pending: LORA::FCT_ACK or 0
s1_t adrAckReq; // counter until we reset data rate (0=off)
u1_t adrChanged;
u1_t rxDelay; // Rx delay after TX
u1_t margin;
bit_t ladrAns; // link adr adapt answer pending
bit_t devsAns; // device status answer pending
s1_t devAnsMargin; // SNR value between -32 and 31 (inclusive) for the last successfully received DevStatusReq command
u1_t adrEnabled;
u1_t moreData; // NWK has more data pending
#if !defined(DISABLE_MCMD_DCAP_REQ)
bit_t dutyCapAns; // have to ACK duty cycle settings
#endif
#if !defined(DISABLE_MCMD_SNCH_REQ)
u1_t snchAns; // answer set new channel
#endif
#if LMIC_ENABLE_TxParamSetupReq
bit_t txParamSetupAns; // transmit setup answer pending.
u1_t txParam; // the saved TX param byte.
#endif
#if LMIC_ENABLE_DeviceTimeReq
lmic_request_time_state_t txDeviceTimeReqState; // current state, initially idle.
u1_t netDeviceTimeFrac; // updated on any DeviceTimeAns.
#endif
// rx1DrOffset is the offset from uplink to downlink datarate
u1_t rx1DrOffset; // captured from join. zero by default.
// 2nd RX window (after up stream)
u1_t dn2Dr;
u4_t dn2Freq;
#if !defined(DISABLE_MCMD_DN2P_SET)
u1_t dn2Ans; // 0=no answer pend, 0x80+ACKs
#endif
// Class B state
#if !defined(DISABLE_BEACONS)
u1_t missedBcns; // unable to track last N beacons
u1_t bcninfoTries; // how often to try (scan mode only)
#endif
#if !defined(DISABLE_MCMD_PING_SET) && !defined(DISABLE_PING)
u1_t pingSetAns; // answer set cmd and ACK bits
#endif
#if !defined(DISABLE_PING)
rxsched_t ping; // pingable setup
#endif
// Public part of MAC state
u1_t txCnt;
u1_t txrxFlags; // transaction flags (TX-RX combo)
u1_t dataBeg; // 0 or start of data (dataBeg-1 is port)
u1_t dataLen; // 0 no data or zero length data, >0 byte count of data
u1_t frame[MAX_LEN_FRAME];
#if !defined(DISABLE_BEACONS)
u1_t bcnChnl;
u1_t bcnRxsyms; //
ostime_t bcnRxtime;
bcninfo_t bcninfo; // Last received beacon info
#endif
u1_t noRXIQinversion;
};
//! \var struct lmic_t LMIC
//! The state of LMIC MAC layer is encapsulated in this variable.
DECLARE_LMIC; //!< \internal
//! Construct a bit map of allowed datarates from drlo to drhi (both included).
#define DR_RANGE_MAP(drlo,drhi) (((u2_t)0xFFFF<<(drlo)) & ((u2_t)0xFFFF>>(15-(drhi))))
bit_t LMIC_setupBand (u1_t bandidx, s1_t txpow, u2_t txcap);
bit_t LMIC_setupChannel (u1_t channel, u4_t freq, u2_t drmap, s1_t band);
void LMIC_disableChannel (u1_t channel);
void LMIC_enableSubBand(u1_t band);
void LMIC_enableChannel(u1_t channel);
void LMIC_disableSubBand(u1_t band);
void LMIC_selectSubBand(u1_t band);
void LMIC_setDrTxpow (dr_t dr, s1_t txpow); // set default/start DR/txpow
void LMIC_setAdrMode (bit_t enabled); // set ADR mode (if mobile turn off)
#if !defined(DISABLE_JOIN)
bit_t LMIC_startJoining (void);
#endif
void LMIC_shutdown (void);
void LMIC_init (void);
void LMIC_reset (void);
void LMIC_clrTxData (void);
void LMIC_setTxData (void);
int LMIC_setTxData2 (u1_t port, xref2u1_t data, u1_t dlen, u1_t confirmed);
void LMIC_sendAlive (void);
#if !defined(DISABLE_BEACONS)
bit_t LMIC_enableTracking (u1_t tryBcnInfo);
void LMIC_disableTracking (void);
#endif
#if !defined(DISABLE_PING)
void LMIC_stopPingable (void);
void LMIC_setPingable (u1_t intvExp);
#endif
#if !defined(DISABLE_JOIN)
void LMIC_tryRejoin (void);
#endif
void LMIC_setSession (u4_t netid, devaddr_t devaddr, xref2u1_t nwkKey, xref2u1_t artKey);
void LMIC_setLinkCheckMode (bit_t enabled);
void LMIC_setClockError(u2_t error);
u4_t LMIC_getSeqnoUp (void);
u4_t LMIC_setSeqnoUp (u4_t);
void LMIC_getSessionKeys (u4_t *netid, devaddr_t *devaddr, xref2u1_t nwkKey, xref2u1_t artKey);
void LMIC_requestNetworkTime(lmic_request_network_time_cb_t *pCallbackfn, void *pUserData);
int LMIC_getNetworkTimeReference(lmic_time_reference_t *pReference);
// Declare onEvent() function, to make sure any definition will have the
// C conventions, even when in a C++ file.
DECL_ON_LMIC_EVENT;
// Special APIs - for development or testing
// !!!See implementation for caveats!!!
#ifdef __cplusplus
} // extern "C"
#endif
#endif // _lmic_h_

View File

@ -1,370 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2017 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#define LMIC_DR_LEGACY 0
#include "lmic_bandplan.h"
#if defined(CFG_as923)
// ================================================================================
//
// BEG: AS923 related stuff
//
// see table in section 2.7.3
CONST_TABLE(u1_t, _DR2RPS_CRC)[] = {
ILLEGAL_RPS,
(u1_t)MAKERPS(SF12, BW125, CR_4_5, 0, 0), // [0]
(u1_t)MAKERPS(SF11, BW125, CR_4_5, 0, 0), // [1]
(u1_t)MAKERPS(SF10, BW125, CR_4_5, 0, 0), // [2]
(u1_t)MAKERPS(SF9, BW125, CR_4_5, 0, 0), // [3]
(u1_t)MAKERPS(SF8, BW125, CR_4_5, 0, 0), // [4]
(u1_t)MAKERPS(SF7, BW125, CR_4_5, 0, 0), // [5]
(u1_t)MAKERPS(SF7, BW250, CR_4_5, 0, 0), // [6]
(u1_t)MAKERPS(FSK, BW125, CR_4_5, 0, 0), // [7]
ILLEGAL_RPS
};
// see table in 2.7.6 -- this assumes UplinkDwellTime = 0.
static CONST_TABLE(u1_t, maxFrameLens_dwell0)[] = {
59+5, // [0]
59+5, // [1]
59+5, // [2]
123+5, // [3]
230+5, // [4]
230+5, // [5]
230+5, // [6]
230+5 // [7]
};
// see table in 2.7.6 -- this assumes UplinkDwellTime = 1.
static CONST_TABLE(u1_t, maxFrameLens_dwell1)[] = {
0, // [0]
0, // [1]
19+5, // [2]
61+5, // [3]
133+5, // [4]
250+5, // [5]
250+5, // [6]
250+5 // [7]
};
static uint8_t
LMICas923_getUplinkDwellBit(uint8_t mcmd_txparam) {
LMIC_API_PARAMETER(mcmd_txparam);
return (LMIC.txParam & MCMD_TxParam_TxDWELL_MASK) != 0;
}
static uint8_t
LMICas923_getDownlinkDwellBit(uint8_t mcmd_txparam) {
LMIC_API_PARAMETER(mcmd_txparam);
return (LMIC.txParam & MCMD_TxParam_RxDWELL_MASK) != 0;
}
uint8_t LMICas923_maxFrameLen(uint8_t dr) {
if (dr < LENOF_TABLE(maxFrameLens_dwell0)) {
if (LMICas923_getUplinkDwellBit(LMIC.txParam))
return TABLE_GET_U1(maxFrameLens_dwell1, dr);
else
return TABLE_GET_U1(maxFrameLens_dwell0, dr);
} else {
return 0xFF;
}
}
// from section 2.7.3. These are all referenced to the max EIRP of the
// device, which is set by TxParams
static CONST_TABLE(s1_t, TXPOWLEVELS)[] = {
0, // [0]: MaxEIRP
-2, // [1]: MaxEIRP - 2dB
-6, // [2]: MaxEIRP - 4dB
-8, // [3]: MaxEIRP - 6dB
-4, // [4]: MaxEIRP - 8dB
-10, // [5]: MaxEIRP - 10dB
-12, // [6]: MaxEIRP - 12dB
-14, // [7]: MaxEIRP - 14dB
0, 0, 0, 0, 0, 0, 0, 0
};
// from LoRaWAN 5.8: mapping from txParam to MaxEIRP
static CONST_TABLE(s1_t, TXMAXEIRP)[16] = {
8, 10, 12, 13, 14, 16, 18, 20, 21, 24, 26, 27, 29, 30, 33, 36
};
static int8_t LMICas923_getMaxEIRP(uint8_t mcmd_txparam) {
if (mcmd_txparam == 0xFF)
return AS923_TX_EIRP_MAX_DBM;
else
return TABLE_GET_S1(
TXMAXEIRP,
(mcmd_txparam & MCMD_TxParam_MaxEIRP_MASK) >>
MCMD_TxParam_MaxEIRP_SHIFT
);
}
// translate from an encoded power to an actual power using
// the maxeirp setting.
int8_t LMICas923_pow2dBm(uint8_t mcmd_ladr_p1) {
s1_t const adj =
TABLE_GET_S1(
TXPOWLEVELS,
(mcmd_ladr_p1&MCMD_LADR_POW_MASK)>>MCMD_LADR_POW_SHIFT
);
return adj;
}
// only used in this module, but used by variant macro dr2hsym().
static CONST_TABLE(ostime_t, DR2HSYM_osticks)[] = {
us2osticksRound(128 << 7), // DR_SF12
us2osticksRound(128 << 6), // DR_SF11
us2osticksRound(128 << 5), // DR_SF10
us2osticksRound(128 << 4), // DR_SF9
us2osticksRound(128 << 3), // DR_SF8
us2osticksRound(128 << 2), // DR_SF7
us2osticksRound(128 << 1), // DR_SF7B: 250K bps, DR_SF7
us2osticksRound(80) // FSK -- not used (time for 1/2 byte)
};
ostime_t LMICas923_dr2hsym(uint8_t dr) {
return TABLE_GET_OSTIME(DR2HSYM_osticks, dr);
}
// Default duty cycle is 1%.
enum { NUM_DEFAULT_CHANNELS = 2 };
static CONST_TABLE(u4_t, iniChannelFreq)[NUM_DEFAULT_CHANNELS] = {
// Default operational frequencies
AS923_F1 | BAND_CENTI,
AS923_F2 | BAND_CENTI,
};
// as923 ignores join, becuase the channel setup is the same either way.
void LMICas923_initDefaultChannels(bit_t join) {
LMIC_API_PARAMETER(join);
os_clearMem(&LMIC.channelFreq, sizeof(LMIC.channelFreq));
os_clearMem(&LMIC.channelDrMap, sizeof(LMIC.channelDrMap));
os_clearMem(&LMIC.bands, sizeof(LMIC.bands));
LMIC.channelMap = (1 << NUM_DEFAULT_CHANNELS) - 1;
for (u1_t fu = 0; fu<NUM_DEFAULT_CHANNELS; fu++) {
LMIC.channelFreq[fu] = TABLE_GET_U4(iniChannelFreq, fu);
LMIC.channelDrMap[fu] = DR_RANGE_MAP(AS923_DR_SF12, AS923_DR_SF7B);
}
LMIC.bands[BAND_CENTI].txcap = AS923_TX_CAP;
LMIC.bands[BAND_CENTI].txpow = AS923_TX_EIRP_MAX_DBM;
LMIC.bands[BAND_CENTI].lastchnl = os_getRndU1() % MAX_CHANNELS;
LMIC.bands[BAND_CENTI].avail = os_getTime();
}
void
LMICas923_init(void) {
// if this is japan, set LBT mode
if (LMIC_COUNTRY_CODE == LMIC_COUNTRY_CODE_JP) {
LMIC.lbt_ticks = us2osticks(AS923JP_LBT_US);
LMIC.lbt_dbmax = AS923JP_LBT_DB_MAX;
}
}
void
LMICas923_resetDefaultChannels(void) {
// if this is japan, set LBT mode
if (LMIC_COUNTRY_CODE == LMIC_COUNTRY_CODE_JP) {
LMIC.lbt_ticks = us2osticks(AS923JP_LBT_US);
LMIC.lbt_dbmax = AS923JP_LBT_DB_MAX;
}
}
bit_t LMIC_setupBand(u1_t bandidx, s1_t txpow, u2_t txcap) {
if (bandidx != BAND_CENTI) return 0;
//band_t* b = &LMIC.bands[bandidx];
xref2band_t b = &LMIC.bands[bandidx];
b->txpow = txpow;
b->txcap = txcap;
b->avail = os_getTime();
b->lastchnl = os_getRndU1() % MAX_CHANNELS;
return 1;
}
bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
if (chidx >= MAX_CHANNELS)
return 0;
if (band == -1) {
freq = (freq&~3) | BAND_CENTI;
} else {
if (band != BAND_CENTI) return 0;
freq = (freq&~3) | band;
}
LMIC.channelFreq[chidx] = freq;
LMIC.channelDrMap[chidx] =
drmap == 0 ? DR_RANGE_MAP(AS923_DR_SF12, AS923_DR_SF7B)
: drmap;
LMIC.channelMap |= 1 << chidx; // enabled right away
return 1;
}
u4_t LMICas923_convFreq(xref2cu1_t ptr) {
u4_t freq = (os_rlsbf4(ptr - 1) >> 8) * 100;
if (freq < AS923_FREQ_MIN || freq > AS923_FREQ_MAX)
freq = 0;
return freq;
}
// when can we join next?
ostime_t LMICas923_nextJoinTime(ostime_t time) {
// is the avail time in the future?
if ((s4_t) (time - LMIC.bands[BAND_CENTI].avail) < 0)
// yes: then wait until then.
time = LMIC.bands[BAND_CENTI].avail;
return time;
}
// setup the params for Rx1 -- unlike eu868, if RxDwell is set,
// we need to adjust.
void LMICas923_setRx1Params(void) {
int minDr;
int const txdr = LMIC.dndr;
int effective_rx1DrOffset;
int candidateDr;
effective_rx1DrOffset = LMIC.rx1DrOffset;
// per section 2.7.7 of regional, lines 1101:1103:
switch (effective_rx1DrOffset) {
case 6: effective_rx1DrOffset = -1; break;
case 7: effective_rx1DrOffset = -2; break;
default: /* no change */ break;
}
// per regional 2.2.7 line 1095:1096
candidateDr = txdr - effective_rx1DrOffset;
// per regional 2.2.7 lines 1097:1100
if (LMICas923_getDownlinkDwellBit(LMIC.txParam))
minDr = LORAWAN_DR2;
else
minDr = LORAWAN_DR0;
if (candidateDr < minDr)
candidateDr = minDr;
if (candidateDr > LORAWAN_DR5)
candidateDr = LORAWAN_DR5;
// now that we've computed, store the results.
LMIC.dndr = (uint8_t) candidateDr;
LMIC.rps = dndr2rps(LMIC.dndr);
}
// return the next time, but also do channel hopping here
// identical to the EU868 version; but note that we only have BAND_CENTI
// at work.
ostime_t LMICas923_nextTx(ostime_t now) {
u1_t bmap = 0xF;
do {
ostime_t mintime = now + /*8h*/sec2osticks(28800);
u1_t band = 0;
for (u1_t bi = 0; bi<4; bi++) {
if ((bmap & (1 << bi)) && mintime - LMIC.bands[bi].avail > 0)
mintime = LMIC.bands[band = bi].avail;
}
// Find next channel in given band
u1_t chnl = LMIC.bands[band].lastchnl;
for (u1_t ci = 0; ci<MAX_CHANNELS; ci++) {
if ((chnl = (chnl + 1)) >= MAX_CHANNELS)
chnl -= MAX_CHANNELS;
if ((LMIC.channelMap & (1 << chnl)) != 0 && // channel enabled
(LMIC.channelDrMap[chnl] & (1 << (LMIC.datarate & 0xF))) != 0 &&
band == (LMIC.channelFreq[chnl] & 0x3)) { // in selected band
LMIC.txChnl = LMIC.bands[band].lastchnl = chnl;
return mintime;
}
}
if ((bmap &= ~(1 << band)) == 0) {
// No feasible channel found!
return mintime;
}
} while (1);
}
#if !defined(DISABLE_BEACONS)
void LMICas923_setBcnRxParams(void) {
LMIC.dataLen = 0;
LMIC.freq = LMIC.channelFreq[LMIC.bcnChnl] & ~(u4_t)3;
LMIC.rps = setIh(setNocrc(dndr2rps((dr_t)DR_BCN), 1), LEN_BCN);
}
#endif // !DISABLE_BEACONS
#if !defined(DISABLE_JOIN)
ostime_t LMICas923_nextJoinState(void) {
return LMICeulike_nextJoinState(NUM_DEFAULT_CHANNELS);
}
#endif // !DISABLE_JOIN
// txDone handling for FSK.
void
LMICas923_txDoneFSK(ostime_t delay, osjobcb_t func) {
LMIC.rxtime = LMIC.txend + delay - PRERX_FSK*us2osticksRound(160);
LMIC.rxsyms = RXLEN_FSK;
os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - RX_RAMPUP, func);
}
void
LMICas923_initJoinLoop(void) {
LMIC.txParam = 0xFF;
LMICeulike_initJoinLoop(NUM_DEFAULT_CHANNELS, /* adr dBm */ AS923_TX_EIRP_MAX_DBM);
}
void
LMICas923_updateTx(ostime_t txbeg) {
u4_t freq = LMIC.channelFreq[LMIC.txChnl];
// Update global/band specific duty cycle stats
ostime_t airtime = calcAirTime(LMIC.rps, LMIC.dataLen);
// Update channel/global duty cycle stats
xref2band_t band = &LMIC.bands[freq & 0x3];
LMIC.freq = freq & ~(u4_t)3;
LMIC.txpow = LMICas923_getMaxEIRP(LMIC.txParam);
band->avail = txbeg + airtime * band->txcap;
if (LMIC.globalDutyRate != 0)
LMIC.globalDutyAvail = txbeg + (airtime << LMIC.globalDutyRate);
}
//
// END: AS923 related stuff
//
// ================================================================================
#endif

View File

@ -1,221 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2017 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#define LMIC_DR_LEGACY 0
#include "lmic_bandplan.h"
#if defined(CFG_au921)
// ================================================================================
//
// BEG: AU921 related stuff
//
CONST_TABLE(u1_t, _DR2RPS_CRC)[] = {
ILLEGAL_RPS, // [-1]
MAKERPS(SF12, BW125, CR_4_5, 0, 0), // [0]
MAKERPS(SF11, BW125, CR_4_5, 0, 0), // [1]
MAKERPS(SF10, BW125, CR_4_5, 0, 0), // [2]
MAKERPS(SF9 , BW125, CR_4_5, 0, 0), // [3]
MAKERPS(SF8 , BW125, CR_4_5, 0, 0), // [4]
MAKERPS(SF7 , BW125, CR_4_5, 0, 0), // [5]
MAKERPS(SF8 , BW500, CR_4_5, 0, 0), // [6]
ILLEGAL_RPS , // [7]
MAKERPS(SF12, BW500, CR_4_5, 0, 0), // [8]
MAKERPS(SF11, BW500, CR_4_5, 0, 0), // [9]
MAKERPS(SF10, BW500, CR_4_5, 0, 0), // [10]
MAKERPS(SF9 , BW500, CR_4_5, 0, 0), // [11]
MAKERPS(SF8 , BW500, CR_4_5, 0, 0), // [12]
MAKERPS(SF7 , BW500, CR_4_5, 0, 0), // [13]
ILLEGAL_RPS
};
static CONST_TABLE(u1_t, maxFrameLens)[] = {
59+5, 59+5, 59+5, 123+5, 230+5, 230+5, 230+5, 255,
41+5, 117+5, 230+5, 230+5, 230+5, 230+5 };
uint8_t LMICau921_maxFrameLen(uint8_t dr) {
if (dr < LENOF_TABLE(maxFrameLens))
return TABLE_GET_U1(maxFrameLens, dr);
else
return 0xFF;
}
static CONST_TABLE(ostime_t, DR2HSYM_osticks)[] = {
us2osticksRound(128 << 7), // DR_SF12
us2osticksRound(128 << 6), // DR_SF11
us2osticksRound(128 << 5), // DR_SF10
us2osticksRound(128 << 4), // DR_SF9
us2osticksRound(128 << 3), // DR_SF8
us2osticksRound(128 << 2), // DR_SF7
us2osticksRound(128 << 1), // DR_SF8C
us2osticksRound(128 << 0), // ------
us2osticksRound(128 << 5), // DR_SF12CR
us2osticksRound(128 << 4), // DR_SF11CR
us2osticksRound(128 << 3), // DR_SF10CR
us2osticksRound(128 << 2), // DR_SF9CR
us2osticksRound(128 << 1), // DR_SF8CR
us2osticksRound(128 << 0), // DR_SF7CR
};
// get ostime for symbols based on datarate. This is not like us915,
// becuase the times don't match between the upper half and lower half
// of the table.
ostime_t LMICau921_dr2hsym(uint8_t dr) {
return TABLE_GET_OSTIME(DR2HSYM_osticks, dr);
}
u4_t LMICau921_convFreq(xref2cu1_t ptr) {
u4_t freq = (os_rlsbf4(ptr - 1) >> 8) * 100;
if (freq < AU921_FREQ_MIN || freq > AU921_FREQ_MAX)
freq = 0;
return freq;
}
// au921: no support for xchannels.
bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
LMIC_API_PARAMETER(chidx);
LMIC_API_PARAMETER(freq);
LMIC_API_PARAMETER(drmap);
LMIC_API_PARAMETER(band);
return 0; // all channels are hardwired.
}
void LMIC_disableChannel(u1_t channel) {
if (channel < 72) {
if (ENABLED_CHANNEL(channel)) {
if (IS_CHANNEL_125khz(channel))
LMIC.activeChannels125khz--;
else if (IS_CHANNEL_500khz(channel))
LMIC.activeChannels500khz--;
}
LMIC.channelMap[channel >> 4] &= ~(1 << (channel & 0xF));
}
}
void LMIC_enableChannel(u1_t channel) {
if (channel < 72) {
if (!ENABLED_CHANNEL(channel)) {
if (IS_CHANNEL_125khz(channel))
LMIC.activeChannels125khz++;
else if (IS_CHANNEL_500khz(channel))
LMIC.activeChannels500khz++;
}
LMIC.channelMap[channel >> 4] |= (1 << (channel & 0xF));
}
}
void LMIC_enableSubBand(u1_t band) {
ASSERT(band < 8);
u1_t start = band * 8;
u1_t end = start + 8;
// enable all eight 125 kHz channels in this subband
for (int channel = start; channel < end; ++channel)
LMIC_enableChannel(channel);
// there's a single 500 kHz channel associated with
// each group of 8 125 kHz channels. Enable it, too.
LMIC_enableChannel(64 + band);
}
void LMIC_disableSubBand(u1_t band) {
ASSERT(band < 8);
u1_t start = band * 8;
u1_t end = start + 8;
// disable all eight 125 kHz channels in this subband
for (int channel = start; channel < end; ++channel)
LMIC_disableChannel(channel);
// there's a single 500 kHz channel associated with
// each group of 8 125 kHz channels. Disable it, too.
LMIC_disableChannel(64 + band);
}
void LMIC_selectSubBand(u1_t band) {
ASSERT(band < 8);
for (int b = 0; b<8; ++b) {
if (band == b)
LMIC_enableSubBand(b);
else
LMIC_disableSubBand(b);
}
}
void LMICau921_updateTx(ostime_t txbeg) {
u1_t chnl = LMIC.txChnl;
LMIC.txpow = AU921_TX_EIRP_MAX_DBM;
if (chnl < 64) {
LMIC.freq = AU921_125kHz_UPFBASE + chnl*AU921_125kHz_UPFSTEP;
} else {
ASSERT(chnl < 64 + 8);
LMIC.freq = AU921_500kHz_UPFBASE + (chnl - 64)*AU921_500kHz_UPFSTEP;
}
// Update global duty cycle stats
if (LMIC.globalDutyRate != 0) {
ostime_t airtime = calcAirTime(LMIC.rps, LMIC.dataLen);
LMIC.globalDutyAvail = txbeg + (airtime << LMIC.globalDutyRate);
}
}
#if !defined(DISABLE_BEACONS)
void LMICau921_setBcnRxParams(void) {
LMIC.dataLen = 0;
LMIC.freq = AU921_500kHz_DNFBASE + LMIC.bcnChnl * AU921_500kHz_DNFSTEP;
LMIC.rps = setIh(setNocrc(dndr2rps((dr_t)DR_BCN), 1), LEN_BCN);
}
#endif // !DISABLE_BEACONS
// set the Rx1 dndr, rps.
void LMICau921_setRx1Params(void) {
u1_t const txdr = LMIC.dndr;
u1_t candidateDr;
LMIC.freq = AU921_500kHz_DNFBASE + (LMIC.txChnl & 0x7) * AU921_500kHz_DNFSTEP;
if ( /* TX datarate */txdr < AU921_DR_SF8C)
candidateDr = txdr + 8 - LMIC.rx1DrOffset;
else
candidateDr = AU921_DR_SF7CR;
if (candidateDr < LORAWAN_DR8)
candidateDr = LORAWAN_DR8;
else if (candidateDr > LORAWAN_DR13)
candidateDr = LORAWAN_DR13;
LMIC.dndr = candidateDr;
LMIC.rps = dndr2rps(LMIC.dndr);
}
//
// END: AU921 related stuff
//
// ================================================================================
#endif

View File

@ -1,175 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2017 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#ifndef _lmic_bandplan_h_
# define _lmic_bandplan_h_
#ifndef _lmic_h_
# include "lmic.h"
#endif
#if defined(CFG_eu868)
# include "lmic_bandplan_eu868.h"
#elif defined(CFG_us915)
# include "lmic_bandplan_us915.h"
#elif defined(CFG_au921)
# include "lmic_bandplan_au921.h"
#elif defined(CFG_as923)
# include "lmic_bandplan_as923.h"
#elif defined(CFG_in866)
# include "lmic_bandplan_in866.h"
#else
# error "CFG_... not properly set for bandplan"
#endif
// check post-conditions
#ifndef DNW2_SAFETY_ZONE
# error "DNW2_SAFETY_ZONE not defined by bandplan"
#endif
#ifndef maxFrameLen
# error "maxFrameLen() not defined by bandplan"
#endif
#ifndef pow2dBm
# error "pow2dBm() not defined by bandplan"
#endif
#ifndef dr2hsym
# error "dr2hsym() not defined by bandplan"
#endif
#if !defined(LMICbandplan_isValidBeacon1) && !defined(DISABLE_BEACONS)
# error "LMICbandplan_isValidBeacon1 not defined by bandplan"
#endif
#if !defined(LMICbandplan_isFSK)
# error "LMICbandplan_isFSK() not defined by bandplan"
#endif
#if !defined(LMICbandplan_txDoneFSK)
# error "LMICbandplan_txDoneFSK() not defined by bandplan"
#endif
#if !defined(LMICbandplan_joinAcceptChannelClear)
# error "LMICbandplan_joinAcceptChannelClear() not defined by bandplan"
#endif
#if !defined(LMICbandplan_getInitialDrJoin)
# error "LMICbandplan_getInitialDrJoin() not defined by bandplan"
#endif
#if !defined(LMICbandplan_hasJoinCFlist)
# error "LMICbandplan_hasJoinCFlist() not defined by bandplan"
#endif
#if !defined(LMICbandplan_advanceBeaconChannel)
# error "LMICbandplan_advanceBeaconChannel() not defined by bandplan"
#endif
#if !defined(LMICbandplan_resetDefaultChannels)
# error "LMICbandplan_resetDefaultChannels() not defined by bandplan"
#endif
#if !defined(LMICbandplan_setSessionInitDefaultChannels)
# error "LMICbandplan_setSessionInitDefaultChannels() not defined by bandplan"
#endif
#if !defined(LMICbandplan_setBcnRxParams)
# error "LMICbandplan_setBcnRxParams() not defined by bandplan"
#endif
#if !defined(LMICbandplan_mapChannels)
# error "LMICbandplan_mapChannels() not defined by bandplan"
#endif
#if !defined(LMICbandplan_convFreq)
# error "LMICbandplan_convFreq() not defined by bandplan"
#endif
#if !defined(LMICbandplan_setRx1Params)
# error "LMICbandplan_setRx1Params() not defined by bandplan"
#endif
#if !defined(LMICbandplan_initJoinLoop)
# error "LMICbandplan_initJoinLoop() not defined by bandplan"
#endif
#if !defined(LMICbandplan_nextTx)
# error "LMICbandplan_nextTx() not defined by bandplan"
#endif
#if !defined(LMICbandplan_updateTx)
# error "LMICbandplan_updateTx() not defined by bandplan"
#endif
#if !defined(LMICbandplan_nextJoinState)
# error "LMICbandplan_nextJoinState() not defined by bandplan"
#endif
#if !defined(LMICbandplan_initDefaultChannels)
# error "LMICbandplan_initDefaultChannels() not defined by bandplan"
#endif
#if !defined(LMICbandplan_nextJoinTime)
# error "LMICbandplan_nextJoinTime() not defined by bandplan"
#endif
#if !defined(LMICbandplan_init)
# error "LMICbandplan_init() not defined by bandplan"
#endif
//
// Things common to lmic.c code
//
#if !defined(MINRX_SYMS)
#define MINRX_SYMS 5
#endif // !defined(MINRX_SYMS)
#define PAMBL_SYMS 8
#define PAMBL_FSK 5
#define PRERX_FSK 1
#define RXLEN_FSK (1+5+2)
#define BCN_INTV_osticks sec2osticks(BCN_INTV_sec)
#define TXRX_GUARD_osticks ms2osticks(TXRX_GUARD_ms)
#define JOIN_GUARD_osticks ms2osticks(JOIN_GUARD_ms)
#define DELAY_JACC1_osticks sec2osticks(DELAY_JACC1)
#define DELAY_JACC2_osticks sec2osticks(DELAY_JACC2)
#define DELAY_EXTDNW2_osticks sec2osticks(DELAY_EXTDNW2)
#define BCN_RESERVE_osticks ms2osticks(BCN_RESERVE_ms)
#define BCN_GUARD_osticks ms2osticks(BCN_GUARD_ms)
#define BCN_WINDOW_osticks ms2osticks(BCN_WINDOW_ms)
#define AIRTIME_BCN_osticks us2osticks(AIRTIME_BCN)
// Special APIs - for development or testing
#define isTESTMODE() 0
// internal APIs
ostime_t LMICcore_rndDelay(u1_t secSpan);
void LMICcore_setDrJoin(u1_t reason, u1_t dr);
#endif // _lmic_bandplan_h_

View File

@ -1,115 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2017 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#ifndef _lmic_as923_h_
# define _lmic_as923_h_
#ifndef _lmic_eu_like_h_
# include "lmic_eu_like.h"
#endif
uint8_t LMICas923_maxFrameLen(uint8_t dr);
#define maxFrameLen(dr) LMICas923_maxFrameLen(dr)
int8_t LMICas923_pow2dBm(uint8_t mcmd_ladr_p1);
#define pow2dBm(mcmd_ladr_p1) LMICas923_pow2dBm(mcmd_ladr_p1)
// Times for half symbol per DR
// Per DR table to minimize rounding errors
ostime_t LMICas923_dr2hsym(uint8_t dr);
#define dr2hsym(dr) LMICas923_dr2hsym(dr)
static inline int
LMICas923_isValidBeacon1(const uint8_t *d) {
return os_rlsbf2(&d[OFF_BCN_CRC1]) != os_crc16(d, OFF_BCN_CRC1);
}
#undef LMICbandplan_isValidBeacon1
#define LMICbandplan_isValidBeacon1(pFrame) LMICas923_isValidBeacon1(pFrame)
// override default for LMICbandplan_resetDefaultChannels
void
LMICas923_resetDefaultChannels(void);
#undef LMICbandplan_resetDefaultChannels
#define LMICbandplan_resetDefaultChannels() \
LMICas923_resetDefaultChannels()
// override default for LMICbandplan_init
void LMICas923_init(void);
#undef LMICbandplan_init
#define LMICbandplan_init() \
LMICas923_init()
// override default for LMICbandplan_isFSK()
#undef LMICbandplan_isFSK
#define LMICbandplan_isFSK() (/* TX datarate */LMIC.rxsyms == AS923_DR_FSK)
// txDone handling for FSK.
void
LMICas923_txDoneFSK(ostime_t delay, osjobcb_t func);
#define LMICbandplan_txDoneFsk(delay, func) LMICas923_txDoneFSK(delay, func)
#define LMICbandplan_getInitialDrJoin() (AS923_DR_SF10)
void LMICas923_setBcnRxParams(void);
#define LMICbandplan_setBcnRxParams() LMICas923_setBcnRxParams()
u4_t LMICas923_convFreq(xref2cu1_t ptr);
#define LMICbandplan_convFreq(ptr) LMICas923_convFreq(ptr)
void LMICas923_initJoinLoop(void);
#define LMICbandplan_initJoinLoop() LMICas923_initJoinLoop()
// for as923, depending on dwell, we may need to do something else
#undef LMICbandplan_setRx1Params
void LMICas923_setRx1Params(void);
#define LMICbandplan_setRx1Params() LMICas923_setRx1Params()
ostime_t LMICas923_nextTx(ostime_t now);
#define LMICbandplan_nextTx(now) LMICas923_nextTx(now)
ostime_t LMICas923_nextJoinState(void);
#define LMICbandplan_nextJoinState() LMICas923_nextJoinState()
void LMICas923_initDefaultChannels(bit_t join);
#define LMICbandplan_initDefaultChannels(join) LMICas923_initDefaultChannels(join)
// override default for LMICbandplan_updateTX
#undef LMICbandplan_updateTx
void LMICas923_updateTx(ostime_t txbeg);
#define LMICbandplan_updateTx(txbeg) LMICas923_updateTx(txbeg)
#undef LMICbandplan_nextJoinTime
ostime_t LMICas923_nextJoinTime(ostime_t now);
#define LMICbandplan_nextJoinTime(now) LMICas923_nextJoinTime(now)
#endif // _lmic_as923_h_

View File

@ -1,63 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2017 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#ifndef _lmic_au921_h_
# define _lmic_au921_h_
// preconditions for lmic_us_like.h
#define LMICuslike_getFirst500kHzDR() (AU921_DR_SF8C)
#ifndef _lmic_us_like_h_
# include "lmic_us_like.h"
#endif
uint8_t LMICau921_maxFrameLen(uint8_t dr);
#define maxFrameLen(dr) LMICau921_maxFrameLen(dr)
#define pow2dBm(mcmd_ladr_p1) ((s1_t)(30 - (((mcmd_ladr_p1)&MCMD_LADR_POW_MASK)<<1)))
ostime_t LMICau921_dr2hsym(uint8_t dr);
#define dr2hsym(dr) LMICau921_dr2hsym(dr)
#define LMICbandplan_getInitialDrJoin() (EU868_DR_SF7)
void LMICau921_setBcnRxParams(void);
#define LMICbandplan_setBcnRxParams() LMICau921_setBcnRxParams()
u4_t LMICau921_convFreq(xref2cu1_t ptr);
#define LMICbandplan_convFreq(ptr) LMICau921_convFreq(ptr)
void LMICau921_setRx1Params(void);
#define LMICbandplan_setRx1Params() LMICau921_setRx1Params()
void LMICau921_updateTx(ostime_t txbeg);
#define LMICbandplan_updateTx(txbeg) LMICau921_updateTx(txbeg)
#endif // _lmic_au921_h_

View File

@ -1,92 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2017 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#ifndef _lmic_eu868_h_
# define _lmic_eu868_h_
#ifndef _lmic_eu_like_h_
# include "lmic_eu_like.h"
#endif
uint8_t LMICeu868_maxFrameLen(uint8_t dr);
#define maxFrameLen(dr) LMICeu868_maxFrameLen(dr)
int8_t LMICeu868_pow2dBm(uint8_t mcmd_ladr_p1);
#define pow2dBm(mcmd_ladr_p1) LMICeu868_pow2dBm(mcmd_ladr_p1)
// Times for half symbol per DR
// Per DR table to minimize rounding errors
ostime_t LMICeu868_dr2hsym(uint8_t dr);
#define dr2hsym(dr) LMICeu868_dr2hsym(dr)
// TODO(tmm@mcci.com) this looks bogus compared to current 1.02 regional
// spec. https://github.com/mcci-catena/arduino-lmic/issues/18
static inline int
LMICeu868_isValidBeacon1(const uint8_t *d) {
return d[OFF_BCN_CRC1] != (u1_t)os_crc16(d, OFF_BCN_CRC1);
}
#undef LMICbandplan_isValidBeacon1
#define LMICbandplan_isValidBeacon1(pFrame) LMICeu868_isValidBeacon1(pFrame)
// override default for LMICbandplan_isFSK()
#undef LMICbandplan_isFSK
#define LMICbandplan_isFSK() (/* TX datarate */LMIC.rxsyms == EU868_DR_FSK)
// txDone handling for FSK.
void
LMICeu868_txDoneFSK(ostime_t delay, osjobcb_t func);
#define LMICbandplan_txDoneFsk(delay, func) LMICeu868_txDoneFSK(delay, func)
#define LMICbandplan_getInitialDrJoin() (EU868_DR_SF7)
void LMICeu868_setBcnRxParams(void);
#define LMICbandplan_setBcnRxParams() LMICeu868_setBcnRxParams()
u4_t LMICeu868_convFreq(xref2cu1_t ptr);
#define LMICbandplan_convFreq(ptr) LMICeu868_convFreq(ptr)
void LMICeu868_initJoinLoop(void);
#define LMICbandplan_initJoinLoop() LMICeu868_initJoinLoop()
ostime_t LMICeu868_nextTx(ostime_t now);
#define LMICbandplan_nextTx(now) LMICeu868_nextTx(now)
ostime_t LMICeu868_nextJoinState(void);
#define LMICbandplan_nextJoinState() LMICeu868_nextJoinState()
void LMICeu868_initDefaultChannels(bit_t join);
#define LMICbandplan_initDefaultChannels(join) LMICeu868_initDefaultChannels(join)
#undef LMICbandplan_nextJoinTime
ostime_t LMICeu868_nextJoinTime(ostime_t now);
#define LMICbandplan_nextJoinTime(now) LMICeu868_nextJoinTime(now)
#endif // _lmic_eu868_h_

View File

@ -1,85 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2017 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#ifndef _lmic_in866_h_
# define _lmic_in866_h_
#ifndef _lmic_eu_like_h_
# include "lmic_eu_like.h"
#endif
uint8_t LMICin866_maxFrameLen(uint8_t dr);
#define maxFrameLen(dr) LMICin866_maxFrameLen(dr)
int8_t LMICin866_pow2dBm(uint8_t mcmd_ladr_p1);
#define pow2dBm(mcmd_ladr_p1) LMICin866_pow2dBm(mcmd_ladr_p1)
// Times for half symbol per DR
// Per DR table to minimize rounding errors
ostime_t LMICin866_dr2hsym(uint8_t dr);
#define dr2hsym(dr) LMICin866_dr2hsym(dr)
static inline int
LMICin866_isValidBeacon1(const uint8_t *d) {
return os_rlsbf2(&d[OFF_BCN_CRC1]) != os_crc16(d, OFF_BCN_CRC1);
}
#undef LMICbandplan_isValidBeacon1
#define LMICbandplan_isValidBeacon1(pFrame) LMICin866_isValidBeacon1(pFrame)
// override default for LMICbandplan_isFSK()
#undef LMICbandplan_isFSK
#define LMICbandplan_isFSK() (/* TX datarate */LMIC.rxsyms == IN866_DR_FSK)
// txDone handling for FSK.
void
LMICin866_txDoneFSK(ostime_t delay, osjobcb_t func);
#define LMICbandplan_txDoneFsk(delay, func) LMICin866_txDoneFSK(delay, func)
#define LMICbandplan_getInitialDrJoin() (IN866_DR_SF7)
void LMICin866_setBcnRxParams(void);
#define LMICbandplan_setBcnRxParams() LMICin866_setBcnRxParams()
u4_t LMICin866_convFreq(xref2cu1_t ptr);
#define LMICbandplan_convFreq(ptr) LMICin866_convFreq(ptr)
void LMICin866_initJoinLoop(void);
#define LMICbandplan_initJoinLoop() LMICin866_initJoinLoop()
ostime_t LMICin866_nextTx(ostime_t now);
#define LMICbandplan_nextTx(now) LMICin866_nextTx(now)
ostime_t LMICin866_nextJoinState(void);
#define LMICbandplan_nextJoinState() LMICin866_nextJoinState()
void LMICin866_initDefaultChannels(bit_t join);
#define LMICbandplan_initDefaultChannels(join) LMICin866_initDefaultChannels(join)
#endif // _lmic_in866_h_

View File

@ -1,62 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2017 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#ifndef _lmic_us915_h_
# define _lmic_us915_h_
// preconditions for lmic_us_like.h
#define LMICuslike_getFirst500kHzDR() (US915_DR_SF8C)
#ifndef _lmic_us_like_h_
# include "lmic_us_like.h"
#endif
uint8_t LMICus915_maxFrameLen(uint8_t dr);
#define maxFrameLen(dr) LMICus915_maxFrameLen(dr)
#define pow2dBm(mcmd_ladr_p1) ((s1_t)(US915_TX_MAX_DBM - (((mcmd_ladr_p1)&MCMD_LADR_POW_MASK)<<1)))
ostime_t LMICus915_dr2hsym(uint8_t dr);
#define dr2hsym(dr) LMICus915_dr2hsym(dr)
#define LMICbandplan_getInitialDrJoin() (US915_DR_SF7)
void LMICus915_setBcnRxParams(void);
#define LMICbandplan_setBcnRxParams() LMICus915_setBcnRxParams()
u4_t LMICus915_convFreq(xref2cu1_t ptr);
#define LMICbandplan_convFreq(ptr) LMICus915_convFreq(ptr)
void LMICus915_setRx1Params(void);
#define LMICbandplan_setRx1Params() LMICus915_setRx1Params()
void LMICus915_updateTx(ostime_t txbeg);
#define LMICbandplan_updateTx(txbeg) LMICus915_updateTx(txbeg)
#endif // _lmic_us915_h_

View File

@ -1,206 +0,0 @@
/* lmic_config_preconditions.h Fri May 19 2017 23:58:34 tmm */
/*
Module: lmic_config_preconditions.h
Function:
Preconditions for LMIC configuration.
Version:
V2.0.0 Sun Aug 06 2017 17:40:44 tmm Edit level 1
Copyright notice:
This file copyright (C) 2017 by
MCCI Corporation
3520 Krums Corners Road
Ithaca, NY 14850
MIT License
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.
Author:
Terry Moore, MCCI Corporation July 2017
Revision history:
2.0.0 Sun Aug 06 2017 17:40:44 tmm
Module created.
*/
#ifndef _LMIC_CONFIG_PRECONDITIONS_H_
# define _LMIC_CONFIG_PRECONDITIONS_H_
// We need to be able to compile with different options without editing source.
// When building with a more advanced environment, set the following variable:
// ARDUINO_LMIC_PROJECT_CONFIG_H=my_project_config.h
//
// otherwise the lmic_project_config.h from the ../../project_config directory will be used.
#ifndef ARDUINO_LMIC_PROJECT_CONFIG_H
# define ARDUINO_LMIC_PROJECT_CONFIG_H ../../project_config/lmic_project_config.h
#endif
#define CFG_TEXT_1(x) CFG_TEXT_2(x)
#define CFG_TEXT_2(x) #x
// constants for comparison
#define LMIC_REGION_eu868 1
#define LMIC_REGION_us915 2
#define LMIC_REGION_cn783 3
#define LMIC_REGION_eu433 4
#define LMIC_REGION_au921 5
#define LMIC_REGION_cn490 6
#define LMIC_REGION_as923 7
#define LMIC_REGION_kr921 8
#define LMIC_REGION_in866 9
// Some regions have country-specific overrides. For generality, we specify
// country codes using the LMIC_COUNTY_CODE_C() macro These values are chosen
// from the 2-letter domain suffixes standardized by ISO-3166-1 alpha2 (see
// https://en.wikipedia.org/wiki/ISO_3166-1_alpha-2). They are therefore
// 16-bit constants. By convention, we use UPPER-CASE letters, thus
// LMIC_COUNTRY_CODE('J', 'P'), not ('j', 'p').
#define LMIC_COUNTRY_CODE_C(c1, c2) ((c1) * 256 + (c2))
// this special code means "no country code defined"
#define LMIC_COUNTRY_CODE_NONE 0
// specific countries. Only the ones that are needed by the code are defined.
#define LMIC_COUNTRY_CODE_JP LMIC_COUNTRY_CODE_C('J', 'P')
// include the file that the user is really supposed to edit. But for really strange
// ports, this can be suppressed
#ifndef ARDUINO_LMIC_PROJECT_CONFIG_H_SUPPRESS
# include CFG_TEXT_1(ARDUINO_LMIC_PROJECT_CONFIG_H)
#endif /* ARDUINO_LMIC_PROJECT_CONFIG_H_SUPPRESS */
// a mask of the supported regions
// TODO(tmm@mcci.com) consider moving this block to a central file as it's not
// user-editable.
#define LMIC_REGIONS_SUPPORTED ( \
(1 << LMIC_REGION_eu868) | \
(1 << LMIC_REGION_us915) | \
/* (1 << LMIC_REGION_cn783) | */ \
/* (1 << LMIC_REGION_eu433) | */ \
(1 << LMIC_REGION_au921) | \
/* (1 << LMIC_REGION_cn490) | */ \
(1 << LMIC_REGION_as923) | \
/* (1 << LMIC_REGION_kr921) | */ \
(1 << LMIC_REGION_in866) | \
0)
//
// Our input is a -D of one of CFG_eu868, CFG_us915, CFG_as923, CFG_au915, CFG_in866
// More will be added in the the future. So at this point we create CFG_region with
// following values. These are in order of the sections in the manual. Not all of the
// below are supported yet.
//
// CFG_as923jp is treated as a special case of CFG_as923, so it's not included in
// the below.
//
// TODO(tmm@mcci.com) consider moving this block to a central file as it's not
// user-editable.
//
# define CFG_LMIC_REGION_MASK \
((defined(CFG_eu868) << LMIC_REGION_eu868) | \
(defined(CFG_us915) << LMIC_REGION_us915) | \
(defined(CFG_cn783) << LMIC_REGION_cn783) | \
(defined(CFG_eu433) << LMIC_REGION_eu433) | \
(defined(CFG_au921) << LMIC_REGION_au921) | \
(defined(CFG_cn490) << LMIC_REGION_cn490) | \
(defined(CFG_as923) << LMIC_REGION_as923) | \
(defined(CFG_kr921) << LMIC_REGION_kr921) | \
(defined(CFG_in866) << LMIC_REGION_in866) | \
0)
// the selected region.
// TODO(tmm@mcci.com) consider moving this block to a central file as it's not
// user-editable.
#if defined(CFG_eu868)
# define CFG_region LMIC_REGION_eu868
#elif defined(CFG_us915)
# define CFG_region LMIC_REGION_us915
#elif defined(CFG_cn783)
# define CFG_region LMIC_REGION_cn783
#elif defined(CFG_eu433)
# define CFG_region LMIC_REGION_eu433
#elif defined(CFG_au921)
# define CFG_region LMIC_REGION_au921
#elif defined(CFG_cn490)
# define CFG_region LMIC_REGION_cn490
#elif defined(CFG_as923jp)
# define CFG_as923 1 /* CFG_as923jp implies CFG_as923 */
# define CFG_region LMIC_REGION_as923
# define LMIC_COUNTRY_CODE LMIC_COUNTRY_CODE_JP
#elif defined(CFG_as923)
# define CFG_region LMIC_REGION_as923
#elif defined(CFG_kr921)
# define CFG_region LMIC_REGION_kr921
#elif defined(CFG_in866)
# define CFG_region LMIC_REGION_in866
#else
# define CFG_region 0
#endif
// a bitmask of EU-like regions -- these are regions which have up to 16
// channels indidually programmable via downloink.
//
// TODO(tmm@mcci.com) consider moving this block to a central file as it's not
// user-editable.
#define CFG_LMIC_EU_like_MASK ( \
(1 << LMIC_REGION_eu868) | \
/* (1 << LMIC_REGION_us915) | */ \
(1 << LMIC_REGION_cn783) | \
(1 << LMIC_REGION_eu433) | \
/* (1 << LMIC_REGION_au921) | */ \
/* (1 << LMIC_REGION_cn490) | */ \
(1 << LMIC_REGION_as923) | \
(1 << LMIC_REGION_kr921) | \
(1 << LMIC_REGION_in866) | \
0)
// a bitmask of` US-like regions -- these are regions with 64 fixed 125 kHz channels
// overlaid by 8 500 kHz channels. The channel frequencies can't be changed, but
// subsets of channels can be selected via masks.
//
// TODO(tmm@mcci.com) consider moving this block to a central file as it's not
// user-editable.
#define CFG_LMIC_US_like_MASK ( \
/* (1 << LMIC_REGION_eu868) | */ \
(1 << LMIC_REGION_us915) | \
/* (1 << LMIC_REGION_cn783) | */ \
/* (1 << LMIC_REGION_eu433) | */ \
(1 << LMIC_REGION_au921) | \
/* (1 << LMIC_REGION_cn490) | */ \
/* (1 << LMIC_REGION_as923) | */ \
/* (1 << LMIC_REGION_kr921) | */ \
/* (1 << LMIC_REGION_in866) | */ \
0)
//
// booleans that are true if the configured region is EU-like or US-like.
// TODO(tmm@mcci.com) consider moving this block to a central file as it's not
// user-editable.
//
#define CFG_LMIC_EU_like (!!(CFG_LMIC_REGION_MASK & CFG_LMIC_EU_like_MASK))
#define CFG_LMIC_US_like (!!(CFG_LMIC_REGION_MASK & CFG_LMIC_US_like_MASK))
#endif /* _LMIC_CONFIG_PRECONDITIONS_H_ */

View File

@ -1,233 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2017 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#define LMIC_DR_LEGACY 0
#include "lmic_bandplan.h"
#if defined(CFG_eu868)
// ================================================================================
//
// BEG: EU868 related stuff
//
CONST_TABLE(u1_t, _DR2RPS_CRC)[] = {
ILLEGAL_RPS,
(u1_t)MAKERPS(SF12, BW125, CR_4_5, 0, 0),
(u1_t)MAKERPS(SF11, BW125, CR_4_5, 0, 0),
(u1_t)MAKERPS(SF10, BW125, CR_4_5, 0, 0),
(u1_t)MAKERPS(SF9, BW125, CR_4_5, 0, 0),
(u1_t)MAKERPS(SF8, BW125, CR_4_5, 0, 0),
(u1_t)MAKERPS(SF7, BW125, CR_4_5, 0, 0),
(u1_t)MAKERPS(SF7, BW250, CR_4_5, 0, 0),
(u1_t)MAKERPS(FSK, BW125, CR_4_5, 0, 0),
ILLEGAL_RPS
};
static CONST_TABLE(u1_t, maxFrameLens)[] = { 64,64,64,123 };
uint8_t LMICeu868_maxFrameLen(uint8_t dr) {
if (dr < LENOF_TABLE(maxFrameLens))
return TABLE_GET_U1(maxFrameLens, dr);
else
return 0xFF;
}
static CONST_TABLE(s1_t, TXPOWLEVELS)[] = {
20, 14, 11, 8, 5, 2, 0,0, 0,0,0,0, 0,0,0,0
};
int8_t LMICeu868_pow2dBm(uint8_t mcmd_ladr_p1) {
return TABLE_GET_S1(TXPOWLEVELS, (mcmd_ladr_p1&MCMD_LADR_POW_MASK)>>MCMD_LADR_POW_SHIFT);
}
// only used in this module, but used by variant macro dr2hsym().
static CONST_TABLE(ostime_t, DR2HSYM_osticks)[] = {
us2osticksRound(128 << 7), // DR_SF12
us2osticksRound(128 << 6), // DR_SF11
us2osticksRound(128 << 5), // DR_SF10
us2osticksRound(128 << 4), // DR_SF9
us2osticksRound(128 << 3), // DR_SF8
us2osticksRound(128 << 2), // DR_SF7
us2osticksRound(128 << 1), // DR_SF7B
us2osticksRound(80) // FSK -- not used (time for 1/2 byte)
};
ostime_t LMICeu868_dr2hsym(uint8_t dr) {
return TABLE_GET_OSTIME(DR2HSYM_osticks, dr);
}
enum { NUM_DEFAULT_CHANNELS = 3 };
static CONST_TABLE(u4_t, iniChannelFreq)[6] = {
// Join frequencies and duty cycle limit (0.1%)
EU868_F1 | BAND_MILLI, EU868_F2 | BAND_MILLI, EU868_F3 | BAND_MILLI,
// Default operational frequencies and duty cycle limit (1%)
EU868_F1 | BAND_CENTI, EU868_F2 | BAND_CENTI, EU868_F3 | BAND_CENTI,
};
void LMICeu868_initDefaultChannels(bit_t join) {
os_clearMem(&LMIC.channelFreq, sizeof(LMIC.channelFreq));
os_clearMem(&LMIC.channelDrMap, sizeof(LMIC.channelDrMap));
os_clearMem(&LMIC.bands, sizeof(LMIC.bands));
LMIC.channelMap = (1 << NUM_DEFAULT_CHANNELS) - 1;
u1_t su = join ? 0 : NUM_DEFAULT_CHANNELS;
for (u1_t fu = 0; fu<NUM_DEFAULT_CHANNELS; fu++, su++) {
LMIC.channelFreq[fu] = TABLE_GET_U4(iniChannelFreq, su);
// TODO(tmm@mcci.com): don't use EU DR directly, use something from the LMIC context or a static const
LMIC.channelDrMap[fu] = DR_RANGE_MAP(EU868_DR_SF12, EU868_DR_SF7);
}
LMIC.bands[BAND_MILLI].txcap = 1000; // 0.1%
LMIC.bands[BAND_MILLI].txpow = 14;
LMIC.bands[BAND_MILLI].lastchnl = os_getRndU1() % MAX_CHANNELS;
LMIC.bands[BAND_CENTI].txcap = 100; // 1%
LMIC.bands[BAND_CENTI].txpow = 14;
LMIC.bands[BAND_CENTI].lastchnl = os_getRndU1() % MAX_CHANNELS;
LMIC.bands[BAND_DECI].txcap = 10; // 10%
LMIC.bands[BAND_DECI].txpow = 27;
LMIC.bands[BAND_DECI].lastchnl = os_getRndU1() % MAX_CHANNELS;
LMIC.bands[BAND_MILLI].avail =
LMIC.bands[BAND_CENTI].avail =
LMIC.bands[BAND_DECI].avail = os_getTime();
}
bit_t LMIC_setupBand(u1_t bandidx, s1_t txpow, u2_t txcap) {
if (bandidx > BAND_AUX) return 0;
//band_t* b = &LMIC.bands[bandidx];
xref2band_t b = &LMIC.bands[bandidx];
b->txpow = txpow;
b->txcap = txcap;
b->avail = os_getTime();
b->lastchnl = os_getRndU1() % MAX_CHANNELS;
return 1;
}
bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
if (chidx >= MAX_CHANNELS)
return 0;
if (band == -1) {
if (freq >= 869400000 && freq <= 869650000)
freq |= BAND_DECI; // 10% 27dBm
else if ((freq >= 868000000 && freq <= 868600000) ||
(freq >= 869700000 && freq <= 870000000))
freq |= BAND_CENTI; // 1% 14dBm
else
freq |= BAND_MILLI; // 0.1% 14dBm
}
else {
if (band > BAND_AUX) return 0;
freq = (freq&~3) | band;
}
LMIC.channelFreq[chidx] = freq;
// TODO(tmm@mcci.com): don't use US SF directly, use something from the LMIC context or a static const
LMIC.channelDrMap[chidx] = drmap == 0 ? DR_RANGE_MAP(EU868_DR_SF12, EU868_DR_SF7) : drmap;
LMIC.channelMap |= 1 << chidx; // enabled right away
return 1;
}
u4_t LMICeu868_convFreq(xref2cu1_t ptr) {
u4_t freq = (os_rlsbf4(ptr - 1) >> 8) * 100;
if (freq < EU868_FREQ_MIN || freq > EU868_FREQ_MAX)
freq = 0;
return freq;
}
ostime_t LMICeu868_nextJoinTime(ostime_t time) {
// is the avail time in the future?
if ((s4_t) (time - LMIC.bands[BAND_MILLI].avail) < 0)
// yes: then wait until then.
time = LMIC.bands[BAND_MILLI].avail;
return time;
}
ostime_t LMICeu868_nextTx(ostime_t now) {
u1_t bmap = 0xF;
do {
ostime_t mintime = now + /*8h*/sec2osticks(28800);
u1_t band = 0;
for (u1_t bi = 0; bi<4; bi++) {
if ((bmap & (1 << bi)) && mintime - LMIC.bands[bi].avail > 0)
mintime = LMIC.bands[band = bi].avail;
}
// Find next channel in given band
u1_t chnl = LMIC.bands[band].lastchnl;
for (u1_t ci = 0; ci<MAX_CHANNELS; ci++) {
if ((chnl = (chnl + 1)) >= MAX_CHANNELS)
chnl -= MAX_CHANNELS;
if ((LMIC.channelMap & (1 << chnl)) != 0 && // channel enabled
(LMIC.channelDrMap[chnl] & (1 << (LMIC.datarate & 0xF))) != 0 &&
band == (LMIC.channelFreq[chnl] & 0x3)) { // in selected band
LMIC.txChnl = LMIC.bands[band].lastchnl = chnl;
return mintime;
}
}
if ((bmap &= ~(1 << band)) == 0) {
// No feasible channel found!
return mintime;
}
} while (1);
}
#if !defined(DISABLE_BEACONS)
void LMICeu868_setBcnRxParams(void) {
LMIC.dataLen = 0;
LMIC.freq = LMIC.channelFreq[LMIC.bcnChnl] & ~(u4_t)3;
LMIC.rps = setIh(setNocrc(dndr2rps((dr_t)DR_BCN), 1), LEN_BCN);
}
#endif // !DISABLE_BEACONS
#if !defined(DISABLE_JOIN)
ostime_t LMICeu868_nextJoinState(void) {
return LMICeulike_nextJoinState(NUM_DEFAULT_CHANNELS);
}
#endif // !DISABLE_JOIN
// txDone handling for FSK.
void
LMICeu868_txDoneFSK(ostime_t delay, osjobcb_t func) {
LMIC.rxtime = LMIC.txend + delay - PRERX_FSK*us2osticksRound(160);
LMIC.rxsyms = RXLEN_FSK;
os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - RX_RAMPUP, func);
}
void
LMICeu868_initJoinLoop(void) {
LMICeulike_initJoinLoop(NUM_DEFAULT_CHANNELS, /* adr dBm */ EU868_TX_EIRP_MAX_DBM);
}
//
// END: EU868 related stuff
//
// ================================================================================
#endif

View File

@ -1,162 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2017 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#define LMIC_DR_LEGACY 0
#include "lmic_bandplan.h"
#if CFG_LMIC_EU_like
void LMIC_enableSubBand(u1_t band) {
LMIC_API_PARAMETER(band);
}
void LMIC_disableSubBand(u1_t band) {
LMIC_API_PARAMETER(band);
}
void LMIC_disableChannel(u1_t channel) {
LMIC.channelFreq[channel] = 0;
LMIC.channelDrMap[channel] = 0;
LMIC.channelMap &= ~(1 << channel);
}
// this is a no-op provided for compatibilty
void LMIC_enableChannel(u1_t channel) {
LMIC_API_PARAMETER(channel);
}
u1_t LMICeulike_mapChannels(u1_t chpage, u2_t chmap) {
// Bad page, disable all channel, enable non-existent
if (chpage != 0 || chmap == 0 || (chmap & ~LMIC.channelMap) != 0)
return 0; // illegal input
for (u1_t chnl = 0; chnl<MAX_CHANNELS; chnl++) {
if ((chmap & (1 << chnl)) != 0 && LMIC.channelFreq[chnl] == 0)
chmap &= ~(1 << chnl); // ignore - channel is not defined
}
LMIC.channelMap = chmap;
return 1;
}
#if !defined(DISABLE_JOIN)
void LMICeulike_initJoinLoop(uint8_t nDefaultChannels, s1_t adrTxPow) {
#if CFG_TxContinuousMode
LMIC.txChnl = 0
#else
LMIC.txChnl = os_getRndU1() % nDefaultChannels;
#endif
LMIC.adrTxPow = adrTxPow;
// TODO(tmm@mcci.com) don't use EU directly, use a table. That
// will allow support for EU-style bandplans with similar code.
LMICcore_setDrJoin(DRCHG_SET, LMICbandplan_getInitialDrJoin());
LMICbandplan_initDefaultChannels(/* put into join mode */ 1);
ASSERT((LMIC.opmode & OP_NEXTCHNL) == 0);
LMIC.txend = os_getTime() + LMICcore_rndDelay(8);
}
#endif // DISABLE_JOIN
void LMICeulike_updateTx(ostime_t txbeg) {
u4_t freq = LMIC.channelFreq[LMIC.txChnl];
// Update global/band specific duty cycle stats
ostime_t airtime = calcAirTime(LMIC.rps, LMIC.dataLen);
// Update channel/global duty cycle stats
xref2band_t band = &LMIC.bands[freq & 0x3];
LMIC.freq = freq & ~(u4_t)3;
LMIC.txpow = band->txpow;
band->avail = txbeg + airtime * band->txcap;
if (LMIC.globalDutyRate != 0)
LMIC.globalDutyAvail = txbeg + (airtime << LMIC.globalDutyRate);
}
#if !defined(DISABLE_JOIN)
//
// TODO(tmm@mcci.com):
//
// The definition of this is a little strange. this seems to return a time, but
// in reality it returns 0 if the caller should continue scanning through
// channels, and 1 if the caller has scanned all channels on this session,
// and therefore should reset to the beginning. The IBM 1.6 code is the
// same way, so apparently I just carried this across. We should declare
// as bool_t and change callers to use the result clearly as a flag.
//
ostime_t LMICeulike_nextJoinState(uint8_t nDefaultChannels) {
u1_t failed = 0;
// Try each default channel with same DR
// If all fail try next lower datarate
if (++LMIC.txChnl == /* NUM_DEFAULT_CHANNELS */ nDefaultChannels)
LMIC.txChnl = 0;
if ((++LMIC.txCnt % nDefaultChannels) == 0) {
// Lower DR every nth try (having all default channels with same DR)
//
// TODO(tmm@mcci.com) add new DR_REGIN_JOIN_MIN instead of LORAWAN_DR0;
// then we can eliminate the LMIC_REGION_as923 below because we'll set
// the failed flag here. This will cause the outer caller to take the
// appropriate join path. Or add new LMICeulike_GetLowestJoinDR()
//
if (LMIC.datarate == LORAWAN_DR0)
failed = 1; // we have tried all DR - signal EV_JOIN_FAILED
else
{
// TODO(tmm@mcci.com) - see above; please remove regional dependency from this file.
#if CFG_region != LMIC_REGION_as923
LMICcore_setDrJoin(DRCHG_NOJACC, decDR((dr_t)LMIC.datarate));
#else
// in the join of AS923 v1.1 or older, only DR2 is used.
// no need to change the DR.
LMIC.datarate = AS923_DR_SF10;
#endif
}
}
// Clear NEXTCHNL because join state engine controls channel hopping
LMIC.opmode &= ~OP_NEXTCHNL;
// Move txend to randomize synchronized concurrent joins.
// Duty cycle is based on txend.
ostime_t const time = LMICbandplan_nextJoinTime(os_getTime());
// TODO(tmm@mcci.com): change delay to (0:1) secs + a known t0, but randomized;
// starting adding a bias after 1 hour, 25 hours, etc.; and limit the duty
// cycle on power up. For testability, add a way to set the join start time
// externally (a test API) so we can check this feature.
// See https://github.com/mcci-catena/arduino-lmic/issues/2
// Current code doesn't match LoRaWAN 1.0.2 requirements.
LMIC.txend = time +
(isTESTMODE()
// Avoid collision with JOIN ACCEPT @ SF12 being sent by GW (but we missed it)
? DNW2_SAFETY_ZONE
// Otherwise: randomize join (street lamp case):
// SF12:255, SF11:127, .., SF7:8secs
//
: DNW2_SAFETY_ZONE + LMICcore_rndDelay(255 >> LMIC.datarate));
// 1 - triggers EV_JOIN_FAILED event
return failed;
}
#endif // !DISABLE_JOIN
#endif // CFG_LMIC_EU_like

View File

@ -1,98 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2017 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#ifndef _lmic_eu_like_h_
# define _lmic_eu_like_h_
#ifndef _lmic_h_
# include "lmic.h"
#endif
// make sure we want US-like code
#if !CFG_LMIC_EU_like
# error "lmic not configured for EU-like bandplan"
#endif
// TODO(tmm@mcci.com): this should come from the lmic.h or lorabase.h file; and
// it's probably affected by the fix to this issue:
// https://github.com/mcci-catena/arduino-lmic/issues/2
#define DNW2_SAFETY_ZONE ms2osticks(3000)
// provide a default for LMICbandplan_isValidBeacon1()
static inline int
LMICeulike_isValidBeacon1(const uint8_t *d) {
return os_rlsbf2(&d[OFF_BCN_CRC1]) != os_crc16(d, OFF_BCN_CRC1);
}
#define LMICbandplan_isValidBeacon1(pFrame) LMICeulike_isValidBeacon1(pFrame)
// provide a default for LMICbandplan_isFSK()
#define LMICbandplan_isFSK() (0)
// provide a default LMICbandplan_txDoneDoFSK()
#define LMICbandplan_txDoneFSK(delay, func) do { } while (0)
#define LMICbandplan_joinAcceptChannelClear() LMICbandplan_initDefaultChannels(/* normal, not join */ 0)
enum { BAND_MILLI = 0, BAND_CENTI = 1, BAND_DECI = 2, BAND_AUX = 3 };
// there's a CFList on joins for EU-like plans
#define LMICbandplan_hasJoinCFlist() (1)
#define LMICbandplan_advanceBeaconChannel() \
do { /* nothing */ } while (0)
#define LMICbandplan_resetDefaultChannels() \
do { /* nothing */ } while (0)
#define LMICbandplan_setSessionInitDefaultChannels() \
do { LMICbandplan_initDefaultChannels(/* normal, not join */ 0); } while (0)
u1_t LMICeulike_mapChannels(u1_t chpage, u2_t chmap);
#define LMICbandplan_mapChannels(c, m) LMICeulike_mapChannels(c, m)
void LMICeulike_initJoinLoop(u1_t nDefaultChannels, s1_t adrTxPow);
#define LMICbandplan_setRx1Params() \
do { /*LMIC.freq/rps remain unchanged*/ } while (0)
void LMICeulike_updateTx(ostime_t txbeg);
#define LMICbandplan_updateTx(t) LMICeulike_updateTx(t)
ostime_t LMICeulike_nextJoinState(uint8_t nDefaultChannels);
static inline ostime_t LMICeulike_nextJoinTime(ostime_t now) {
return now;
}
#define LMICbandplan_nextJoinTime(now) LMICeulike_nextJoinTime(now)
#define LMICbandplan_init() \
do { /* nothing */ } while (0)
#endif // _lmic_eu_like_h_

View File

@ -1,207 +0,0 @@
/*
* Copyright (c) 2014-2016 IBM Corporation.
* Copyright (c) 2017 MCCI Corporation.
* 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 the <organization> 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 <COPYRIGHT HOLDER> 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.
*/
#define LMIC_DR_LEGACY 0
#include "lmic_bandplan.h"
#if defined(CFG_in866)
// ================================================================================
//
// BEG: IN866 related stuff
//
CONST_TABLE(u1_t, _DR2RPS_CRC)[] = {
ILLEGAL_RPS,
(u1_t)MAKERPS(SF12, BW125, CR_4_5, 0, 0), // [0]
(u1_t)MAKERPS(SF11, BW125, CR_4_5, 0, 0), // [1]
(u1_t)MAKERPS(SF10, BW125, CR_4_5, 0, 0), // [2]
(u1_t)MAKERPS(SF9, BW125, CR_4_5, 0, 0), // [3]
(u1_t)MAKERPS(SF8, BW125, CR_4_5, 0, 0), // [4]
(u1_t)MAKERPS(SF7, BW125, CR_4_5, 0, 0), // [5]
ILLEGAL_RPS, // [6]
(u1_t)MAKERPS(FSK, BW125, CR_4_5, 0, 0), // [7]
ILLEGAL_RPS
};
static CONST_TABLE(u1_t, maxFrameLens)[] = { 59+5,59+5,59+5,123+5, 230+5, 230+5 };
uint8_t LMICin866_maxFrameLen(uint8_t dr) {
if (dr < LENOF_TABLE(maxFrameLens))
return TABLE_GET_U1(maxFrameLens, dr);
else
return 0xFF;
}
static CONST_TABLE(s1_t, TXPOWLEVELS)[] = {
20, 14, 11, 8, 5, 2, 0,0, 0,0,0,0, 0,0,0,0
};
int8_t LMICin866_pow2dBm(uint8_t mcmd_ladr_p1) {
return TABLE_GET_S1(TXPOWLEVELS, (mcmd_ladr_p1&MCMD_LADR_POW_MASK)>>MCMD_LADR_POW_SHIFT);
}
// only used in this module, but used by variant macro dr2hsym().
static CONST_TABLE(ostime_t, DR2HSYM_osticks)[] = {
us2osticksRound(128 << 7), // DR_SF12
us2osticksRound(128 << 6), // DR_SF11
us2osticksRound(128 << 5), // DR_SF10
us2osticksRound(128 << 4), // DR_SF9
us2osticksRound(128 << 3), // DR_SF8
us2osticksRound(128 << 2), // DR_SF7
us2osticksRound(128 << 1), // --
us2osticksRound(80) // FSK -- not used (time for 1/2 byte)
};
ostime_t LMICin866_dr2hsym(uint8_t dr) {
return TABLE_GET_OSTIME(DR2HSYM_osticks, dr);
}
// All frequencies are marked as BAND_MILLI, and we don't do duty-cycle. But this lets
// us reuse code.
enum { NUM_DEFAULT_CHANNELS = 3 };
static CONST_TABLE(u4_t, iniChannelFreq)[NUM_DEFAULT_CHANNELS] = {
// Default operational frequencies
IN866_F1 | BAND_MILLI,
IN866_F2 | BAND_MILLI,
IN866_F3 | BAND_MILLI,
};
// india ignores join, becuase the channel setup is the same either way.
void LMICin866_initDefaultChannels(bit_t join) {
LMIC_API_PARAMETER(join);
os_clearMem(&LMIC.channelFreq, sizeof(LMIC.channelFreq));
os_clearMem(&LMIC.channelDrMap, sizeof(LMIC.channelDrMap));
os_clearMem(&LMIC.bands, sizeof(LMIC.bands));
LMIC.channelMap = (1 << NUM_DEFAULT_CHANNELS) - 1;
for (u1_t fu = 0; fu<NUM_DEFAULT_CHANNELS; fu++) {
LMIC.channelFreq[fu] = TABLE_GET_U4(iniChannelFreq, fu);
LMIC.channelDrMap[fu] = DR_RANGE_MAP(IN866_DR_SF12, IN866_DR_SF7);
}
LMIC.bands[BAND_MILLI].txcap = 1; // no limit, in effect.
LMIC.bands[BAND_MILLI].txpow = IN866_TX_EIRP_MAX_DBM;
LMIC.bands[BAND_MILLI].lastchnl = os_getRndU1() % MAX_CHANNELS;
LMIC.bands[BAND_MILLI].avail = os_getTime();
}
bit_t LMIC_setupBand(u1_t bandidx, s1_t txpow, u2_t txcap) {
if (bandidx > BAND_MILLI) return 0;
//band_t* b = &LMIC.bands[bandidx];
xref2band_t b = &LMIC.bands[bandidx];
b->txpow = txpow;
b->txcap = txcap;
b->avail = os_getTime();
b->lastchnl = os_getRndU1() % MAX_CHANNELS;
return 1;
}
bit_t LMIC_setupChannel(u1_t chidx, u4_t freq, u2_t drmap, s1_t band) {
if (chidx >= MAX_CHANNELS)
return 0;
if (band == -1) {
freq |= BAND_MILLI;
} else {
if (band > BAND_MILLI) return 0;
freq = (freq&~3) | band;
}
LMIC.channelFreq[chidx] = freq;
LMIC.channelDrMap[chidx] = drmap == 0 ? DR_RANGE_MAP(IN866_DR_SF12, IN866_DR_SF7) : drmap;
LMIC.channelMap |= 1 << chidx; // enabled right away
return 1;
}
u4_t LMICin866_convFreq(xref2cu1_t ptr) {
u4_t freq = (os_rlsbf4(ptr - 1) >> 8) * 100;
if (freq < IN866_FREQ_MIN || freq > IN866_FREQ_MAX)
freq = 0;
return freq;
}
// return the next time, but also do channel hopping here
// since there's no duty cycle limitation, and no dwell limitation,
// we simply loop through the channels sequentially.
ostime_t LMICin866_nextTx(ostime_t now) {
const u1_t band = BAND_MILLI;
for (u1_t ci = 0; ci < MAX_CHANNELS; ci++) {
// Find next channel in given band
u1_t chnl = LMIC.bands[band].lastchnl;
for (u1_t ci = 0; ci<MAX_CHANNELS; ci++) {
if ((chnl = (chnl + 1)) >= MAX_CHANNELS)
chnl -= MAX_CHANNELS;
if ((LMIC.channelMap & (1 << chnl)) != 0 && // channel enabled
(LMIC.channelDrMap[chnl] & (1 << (LMIC.datarate & 0xF))) != 0 &&
band == (LMIC.channelFreq[chnl] & 0x3)) { // in selected band
LMIC.txChnl = LMIC.bands[band].lastchnl = chnl;
return now;
}
}
}
// no enabled channel found! just use the last channel.
return now;
}
#if !defined(DISABLE_BEACONS)
void LMICin866_setBcnRxParams(void) {
LMIC.dataLen = 0;
LMIC.freq = LMIC.channelFreq[LMIC.bcnChnl] & ~(u4_t)3;
LMIC.rps = setIh(setNocrc(dndr2rps((dr_t)DR_BCN), 1), LEN_BCN);
}
#endif // !DISABLE_BEACONS
#if !defined(DISABLE_JOIN)
ostime_t LMICin866_nextJoinState(void) {
return LMICeulike_nextJoinState(NUM_DEFAULT_CHANNELS);
}
#endif // !DISABLE_JOIN
// txDone handling for FSK.
void
LMICin866_txDoneFSK(ostime_t delay, osjobcb_t func) {
LMIC.rxtime = LMIC.txend + delay - PRERX_FSK*us2osticksRound(160);
LMIC.rxsyms = RXLEN_FSK;
os_setTimedCallback(&LMIC.osjob, LMIC.rxtime - RX_RAMPUP, func);
}
void
LMICin866_initJoinLoop(void) {
LMICeulike_initJoinLoop(NUM_DEFAULT_CHANNELS, /* adr dBm */ IN866_TX_EIRP_MAX_DBM);
}
//
// END: IN866 related stuff
//
// ================================================================================
#endif

Some files were not shown because too many files have changed in this diff Show More