Revert "normalize code to clang-format"

This commit is contained in:
Verkehrsrot 2018-06-10 21:46:58 +02:00 committed by GitHub
parent 6d5799cd23
commit 283f512028
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
29 changed files with 3079 additions and 2271 deletions

View File

@ -1,108 +0,0 @@
---
Language: Cpp
# BasedOnStyle: LLVM
AccessModifierOffset: -2
AlignAfterOpenBracket: Align
AlignConsecutiveAssignments: false
AlignConsecutiveDeclarations: false
AlignEscapedNewlines: Right
AlignOperands: true
AlignTrailingComments: true
AllowAllParametersOfDeclarationOnNextLine: true
AllowShortBlocksOnASingleLine: false
AllowShortCaseLabelsOnASingleLine: false
AllowShortFunctionsOnASingleLine: All
AllowShortIfStatementsOnASingleLine: false
AllowShortLoopsOnASingleLine: false
AlwaysBreakAfterDefinitionReturnType: None
AlwaysBreakAfterReturnType: None
AlwaysBreakBeforeMultilineStrings: false
AlwaysBreakTemplateDeclarations: false
BinPackArguments: true
BinPackParameters: true
BraceWrapping:
AfterClass: false
AfterControlStatement: false
AfterEnum: false
AfterFunction: false
AfterNamespace: false
AfterObjCDeclaration: false
AfterStruct: false
AfterUnion: false
BeforeCatch: false
BeforeElse: false
IndentBraces: false
SplitEmptyFunction: true
SplitEmptyRecord: true
SplitEmptyNamespace: true
BreakBeforeBinaryOperators: None
BreakBeforeBraces: Attach
BreakBeforeInheritanceComma: false
BreakBeforeTernaryOperators: true
BreakConstructorInitializersBeforeComma: false
BreakConstructorInitializers: BeforeColon
BreakAfterJavaFieldAnnotations: false
BreakStringLiterals: true
ColumnLimit: 80
CommentPragmas: '^ IWYU pragma:'
CompactNamespaces: false
ConstructorInitializerAllOnOneLineOrOnePerLine: false
ConstructorInitializerIndentWidth: 4
ContinuationIndentWidth: 4
Cpp11BracedListStyle: true
DerivePointerAlignment: false
DisableFormat: false
ExperimentalAutoDetectBinPacking: false
FixNamespaceComments: true
ForEachMacros:
- foreach
- Q_FOREACH
- BOOST_FOREACH
IncludeCategories:
- Regex: '^"(llvm|llvm-c|clang|clang-c)/'
Priority: 2
- Regex: '^(<|"(gtest|gmock|isl|json)/)'
Priority: 3
- Regex: '.*'
Priority: 1
IncludeIsMainRegex: '(Test)?$'
IndentCaseLabels: false
IndentWidth: 2
IndentWrappedFunctionNames: false
JavaScriptQuotes: Leave
JavaScriptWrapImports: true
KeepEmptyLinesAtTheStartOfBlocks: true
MacroBlockBegin: ''
MacroBlockEnd: ''
MaxEmptyLinesToKeep: 1
NamespaceIndentation: None
ObjCBlockIndentWidth: 2
ObjCSpaceAfterProperty: false
ObjCSpaceBeforeProtocolList: true
PenaltyBreakAssignment: 2
PenaltyBreakBeforeFirstCallParameter: 19
PenaltyBreakComment: 300
PenaltyBreakFirstLessLess: 120
PenaltyBreakString: 1000
PenaltyExcessCharacter: 1000000
PenaltyReturnTypeOnItsOwnLine: 60
PointerAlignment: Right
ReflowComments: true
SortIncludes: true
SortUsingDeclarations: true
SpaceAfterCStyleCast: false
SpaceAfterTemplateKeyword: true
SpaceBeforeAssignmentOperators: true
SpaceBeforeParens: ControlStatements
SpaceInEmptyParentheses: false
SpacesBeforeTrailingComments: 1
SpacesInAngles: false
SpacesInContainerLiterals: true
SpacesInCStyleCastParentheses: false
SpacesInParentheses: false
SpacesInSquareBrackets: false
Standard: Cpp11
TabWidth: 8
UseTab: Never
...

View File

@ -5,57 +5,52 @@
#include <driver/adc.h> #include <driver/adc.h>
#include <esp_adc_cal.h> #include <esp_adc_cal.h>
#define DEFAULT_VREF \ #define DEFAULT_VREF 1100 // to be done: use adc2_vref_to_gpio() to obtain a better estimate
1100 // to be done: use adc2_vref_to_gpio() to obtain a better estimate #define NO_OF_SAMPLES 64 // we do multisampling
#define NO_OF_SAMPLES 64 // we do multisampling
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = "main";
static void print_char_val_type(esp_adc_cal_value_t val_type) { static void print_char_val_type(esp_adc_cal_value_t val_type)
if (val_type == ESP_ADC_CAL_VAL_EFUSE_TP) { {
ESP_LOGI(TAG, if (val_type == ESP_ADC_CAL_VAL_EFUSE_TP) {
"ADC characterization based on Two Point values stored in eFuse"); ESP_LOGI(TAG,"ADC characterization based on Two Point values stored in eFuse");
} else if (val_type == ESP_ADC_CAL_VAL_EFUSE_VREF) { } else if (val_type == ESP_ADC_CAL_VAL_EFUSE_VREF) {
ESP_LOGI(TAG, ESP_LOGI(TAG,"ADC characterization based on reference voltage stored in eFuse");
"ADC characterization based on reference voltage stored in eFuse"); } else {
} else { ESP_LOGI(TAG,"ADC characterization based on default reference voltage");
ESP_LOGI(TAG, "ADC characterization based on default reference voltage"); }
}
} }
uint16_t read_voltage(void) { uint16_t read_voltage(void)
static const adc1_channel_t channel = HAS_BATTERY_PROBE; {
static const adc_atten_t atten = ADC_ATTEN_DB_11; static const adc1_channel_t channel = HAS_BATTERY_PROBE;
static const adc_unit_t unit = ADC_UNIT_1; static const adc_atten_t atten = ADC_ATTEN_DB_11;
static const adc_unit_t unit = ADC_UNIT_1;
// configure ADC1 //configure ADC1
ESP_ERROR_CHECK(adc1_config_width(ADC_WIDTH_BIT_12)); ESP_ERROR_CHECK(adc1_config_width(ADC_WIDTH_BIT_12));
ESP_ERROR_CHECK(adc1_config_channel_atten(channel, atten)); ESP_ERROR_CHECK(adc1_config_channel_atten(channel, atten));
// calibrate ADC1 //calibrate ADC1
esp_adc_cal_characteristics_t *adc_chars = esp_adc_cal_characteristics_t *adc_chars = (esp_adc_cal_characteristics_t *) calloc(1, sizeof(esp_adc_cal_characteristics_t));
(esp_adc_cal_characteristics_t *)calloc( esp_adc_cal_value_t val_type = esp_adc_cal_characterize(unit, atten, ADC_WIDTH_BIT_12, DEFAULT_VREF, adc_chars);
1, sizeof(esp_adc_cal_characteristics_t)); print_char_val_type(val_type);
esp_adc_cal_value_t val_type = esp_adc_cal_characterize(
unit, atten, ADC_WIDTH_BIT_12, DEFAULT_VREF, adc_chars);
print_char_val_type(val_type);
// multisample ADC1 //multisample ADC1
uint32_t adc_reading = 0; uint32_t adc_reading = 0;
for (int i = 0; i < NO_OF_SAMPLES; i++) { for (int i = 0; i < NO_OF_SAMPLES; i++) {
adc_reading += adc1_get_raw(channel); adc_reading += adc1_get_raw(channel);
} }
adc_reading /= NO_OF_SAMPLES; adc_reading /= NO_OF_SAMPLES;
// Convert adc_reading to voltage in mV //Convert adc_reading to voltage in mV
uint16_t voltage = uint16_t voltage = (uint16_t) esp_adc_cal_raw_to_voltage(adc_reading, adc_chars);
(uint16_t)esp_adc_cal_raw_to_voltage(adc_reading, adc_chars); #ifdef BATT_FACTOR
#ifdef BATT_FACTOR voltage *= BATT_FACTOR;
voltage *= BATT_FACTOR; #endif
#endif ESP_LOGI(TAG,"Raw: %d / Voltage: %dmV", adc_reading, voltage);
ESP_LOGI(TAG, "Raw: %d / Voltage: %dmV", adc_reading, voltage); return voltage;
return voltage;
} }
#endif // HAS_BATTERY_PROBE #endif // HAS_BATTERY_PROBE

View File

@ -1,5 +1,4 @@
/* switches wifi antenna, if board has switch to select internal and external /* switches wifi antenna, if board has switch to select internal and external antenna */
* antenna */
#ifdef HAS_ANTENNA_SWITCH #ifdef HAS_ANTENNA_SWITCH
@ -8,32 +7,35 @@
// Local logging tag // Local logging tag
static const char TAG[] = "wifi"; static const char TAG[] = "wifi";
typedef enum { ANTENNA_INT = 0, ANTENNA_EXT } antenna_type_t; typedef enum {
ANTENNA_INT = 0,
ANTENNA_EXT
} antenna_type_t;
void antenna_init(void) { void antenna_init(void) {
gpio_config_t gpioconf = {.pin_bit_mask = 1ull << HAS_ANTENNA_SWITCH, gpio_config_t gpioconf = {.pin_bit_mask = 1ull << HAS_ANTENNA_SWITCH,
.mode = GPIO_MODE_OUTPUT, .mode = GPIO_MODE_OUTPUT,
.pull_up_en = GPIO_PULLUP_DISABLE, .pull_up_en = GPIO_PULLUP_DISABLE,
.pull_down_en = GPIO_PULLDOWN_DISABLE, .pull_down_en = GPIO_PULLDOWN_DISABLE,
.intr_type = GPIO_INTR_DISABLE}; .intr_type = GPIO_INTR_DISABLE};
gpio_config(&gpioconf); gpio_config(&gpioconf);
} }
void antenna_select(const uint8_t _ant) { void antenna_select (const uint8_t _ant) {
if (HAS_ANTENNA_SWITCH < 32) { if (HAS_ANTENNA_SWITCH < 32) {
if (_ant == ANTENNA_EXT) { if (_ant == ANTENNA_EXT) {
GPIO_REG_WRITE(GPIO_OUT_W1TS_REG, 1 << HAS_ANTENNA_SWITCH); GPIO_REG_WRITE(GPIO_OUT_W1TS_REG, 1 << HAS_ANTENNA_SWITCH);
} else { } else {
GPIO_REG_WRITE(GPIO_OUT_W1TC_REG, 1 << HAS_ANTENNA_SWITCH); GPIO_REG_WRITE(GPIO_OUT_W1TC_REG, 1 << HAS_ANTENNA_SWITCH);
} }
} else { } else {
if (_ant == ANTENNA_EXT) { if (_ant == ANTENNA_EXT) {
GPIO_REG_WRITE(GPIO_OUT1_W1TS_REG, 1 << (HAS_ANTENNA_SWITCH & 31)); GPIO_REG_WRITE(GPIO_OUT1_W1TS_REG, 1 << (HAS_ANTENNA_SWITCH & 31));
} else { } else {
GPIO_REG_WRITE(GPIO_OUT1_W1TC_REG, 1 << (HAS_ANTENNA_SWITCH & 31)); GPIO_REG_WRITE(GPIO_OUT1_W1TC_REG, 1 << (HAS_ANTENNA_SWITCH & 31));
} }
} }
ESP_LOGI(TAG, "Wifi Antenna switched to %s", _ant ? "external" : "internal"); ESP_LOGI(TAG, "Wifi Antenna switched to %s", _ant ? "external" : "internal");
} }
#endif #endif

View File

@ -8,14 +8,13 @@ https://github.com/nkolban/esp32-snippets/tree/master/BLE/scanner
#include "globals.h" #include "globals.h"
// Bluetooth specific includes // Bluetooth specific includes
#include <bt_types.h>
#include <esp_blufi_api.h> // needed for BLE_ADDR types, do not remove
#include <esp_bt.h> #include <esp_bt.h>
#include <esp_bt_main.h> #include <esp_bt_main.h>
#include <esp_gap_ble_api.h> #include <esp_gap_ble_api.h>
#include <esp_blufi_api.h> // needed for BLE_ADDR types, do not remove
#include <bt_types.h>
#define BT_BD_ADDR_HEX(addr) \ #define BT_BD_ADDR_HEX(addr) addr[0], addr[1], addr[2], addr[3], addr[4], addr[5]
addr[0], addr[1], addr[2], addr[3], addr[4], addr[5]
// local Tag for logging // local Tag for logging
static const char TAG[] = "bluetooth"; static const char TAG[] = "bluetooth";
@ -24,256 +23,208 @@ static const char TAG[] = "bluetooth";
bool mac_add(uint8_t *paddr, int8_t rssi, bool sniff_type); bool mac_add(uint8_t *paddr, int8_t rssi, bool sniff_type);
const char *bt_addr_t_to_string(esp_ble_addr_type_t type) { const char *bt_addr_t_to_string(esp_ble_addr_type_t type) {
switch (type) { switch(type) {
case BLE_ADDR_TYPE_PUBLIC: case BLE_ADDR_TYPE_PUBLIC:
return "BLE_ADDR_TYPE_PUBLIC"; return "BLE_ADDR_TYPE_PUBLIC";
case BLE_ADDR_TYPE_RANDOM: case BLE_ADDR_TYPE_RANDOM:
return "BLE_ADDR_TYPE_RANDOM"; return "BLE_ADDR_TYPE_RANDOM";
case BLE_ADDR_TYPE_RPA_PUBLIC: case BLE_ADDR_TYPE_RPA_PUBLIC:
return "BLE_ADDR_TYPE_RPA_PUBLIC"; return "BLE_ADDR_TYPE_RPA_PUBLIC";
case BLE_ADDR_TYPE_RPA_RANDOM: case BLE_ADDR_TYPE_RPA_RANDOM:
return "BLE_ADDR_TYPE_RPA_RANDOM"; return "BLE_ADDR_TYPE_RPA_RANDOM";
default: default:
return "Unknown addr_t"; return "Unknown addr_t";
} }
} // bt_addr_t_to_string } // bt_addr_t_to_string
const char *btsig_gap_type(uint32_t gap_type) { const char *btsig_gap_type(uint32_t gap_type) {
switch (gap_type) { switch (gap_type)
case 0x01: {
return "Flags"; case 0x01: return "Flags";
case 0x02: case 0x02: return "Incomplete List of 16-bit Service Class UUIDs";
return "Incomplete List of 16-bit Service Class UUIDs"; case 0x03: return "Complete List of 16-bit Service Class UUIDs";
case 0x03: case 0x04: return "Incomplete List of 32-bit Service Class UUIDs";
return "Complete List of 16-bit Service Class UUIDs"; case 0x05: return "Complete List of 32-bit Service Class UUIDs";
case 0x04: case 0x06: return "Incomplete List of 128-bit Service Class UUIDs";
return "Incomplete List of 32-bit Service Class UUIDs"; case 0x07: return "Complete List of 128-bit Service Class UUIDs";
case 0x05: case 0x08: return "Shortened Local Name";
return "Complete List of 32-bit Service Class UUIDs"; case 0x09: return "Complete Local Name";
case 0x06: case 0x0A: return "Tx Power Level";
return "Incomplete List of 128-bit Service Class UUIDs"; case 0x0D: return "Class of Device";
case 0x07: case 0x0E: return "Simple Pairing Hash C/C-192";
return "Complete List of 128-bit Service Class UUIDs"; case 0x0F: return "Simple Pairing Randomizer R/R-192";
case 0x08: case 0x10: return "Device ID/Security Manager TK Value";
return "Shortened Local Name"; case 0x11: return "Security Manager Out of Band Flags";
case 0x09: case 0x12: return "Slave Connection Interval Range";
return "Complete Local Name"; case 0x14: return "List of 16-bit Service Solicitation UUIDs";
case 0x0A: case 0x1F: return "List of 32-bit Service Solicitation UUIDs";
return "Tx Power Level"; case 0x15: return "List of 128-bit Service Solicitation UUIDs";
case 0x0D: case 0x16: return "Service Data - 16-bit UUID";
return "Class of Device"; case 0x20: return "Service Data - 32-bit UUID";
case 0x0E: case 0x21: return "Service Data - 128-bit UUID";
return "Simple Pairing Hash C/C-192"; case 0x22: return "LE Secure Connections Confirmation Value";
case 0x0F: case 0x23: return "LE Secure Connections Random Value";
return "Simple Pairing Randomizer R/R-192"; case 0x24: return "URI";
case 0x10: case 0x25: return "Indoor Positioning";
return "Device ID/Security Manager TK Value"; case 0x26: return "Transport Discovery Data";
case 0x11: case 0x17: return "Public Target Address";
return "Security Manager Out of Band Flags"; case 0x18: return "Random Target Address";
case 0x12: case 0x19: return "Appearance";
return "Slave Connection Interval Range"; case 0x1A: return "Advertising Interval";
case 0x14: case 0x1B: return "LE Bluetooth Device Address";
return "List of 16-bit Service Solicitation UUIDs"; case 0x1C: return "LE Role";
case 0x1F: case 0x1D: return "Simple Pairing Hash C-256";
return "List of 32-bit Service Solicitation UUIDs"; case 0x1E: return "Simple Pairing Randomizer R-256";
case 0x15: case 0x3D: return "3D Information Data";
return "List of 128-bit Service Solicitation UUIDs"; case 0xFF: return "Manufacturer Specific Data";
case 0x16:
return "Service Data - 16-bit UUID"; default:
case 0x20: return "Unknown type";
return "Service Data - 32-bit UUID"; }
case 0x21:
return "Service Data - 128-bit UUID";
case 0x22:
return "LE Secure Connections Confirmation Value";
case 0x23:
return "LE Secure Connections Random Value";
case 0x24:
return "URI";
case 0x25:
return "Indoor Positioning";
case 0x26:
return "Transport Discovery Data";
case 0x17:
return "Public Target Address";
case 0x18:
return "Random Target Address";
case 0x19:
return "Appearance";
case 0x1A:
return "Advertising Interval";
case 0x1B:
return "LE Bluetooth Device Address";
case 0x1C:
return "LE Role";
case 0x1D:
return "Simple Pairing Hash C-256";
case 0x1E:
return "Simple Pairing Randomizer R-256";
case 0x3D:
return "3D Information Data";
case 0xFF:
return "Manufacturer Specific Data";
default:
return "Unknown type";
}
} // btsig_gap_type } // btsig_gap_type
// using IRAM_:ATTR here to speed up callback function // using IRAM_:ATTR here to speed up callback function
IRAM_ATTR void gap_callback_handler(esp_gap_ble_cb_event_t event, IRAM_ATTR void gap_callback_handler(esp_gap_ble_cb_event_t event, esp_ble_gap_cb_param_t *param)
esp_ble_gap_cb_param_t *param) { {
esp_ble_gap_cb_param_t *p = (esp_ble_gap_cb_param_t *)param; esp_ble_gap_cb_param_t *p = (esp_ble_gap_cb_param_t *)param;
ESP_LOGD(TAG, "BT payload rcvd -> type: 0x%.2x -> %s", *p->scan_rst.ble_adv, btsig_gap_type(*p->scan_rst.ble_adv));
ESP_LOGD(TAG, "BT payload rcvd -> type: 0x%.2x -> %s", *p->scan_rst.ble_adv, switch (event)
btsig_gap_type(*p->scan_rst.ble_adv)); {
case ESP_GAP_BLE_SCAN_PARAM_SET_COMPLETE_EVT:
// restart scan
ESP_ERROR_CHECK(esp_ble_gap_start_scanning(BLESCANTIME));
break;
case ESP_GAP_BLE_SCAN_RESULT_EVT:
// evaluate scan results
if ( p->scan_rst.search_evt == ESP_GAP_SEARCH_INQ_CMPL_EVT) // Inquiry complete, scan is done
{ // restart scan
ESP_ERROR_CHECK(esp_ble_gap_start_scanning(BLESCANTIME));
return;
}
if (p->scan_rst.search_evt == ESP_GAP_SEARCH_INQ_RES_EVT) // Inquiry result for a peer device
{ // evaluate sniffed packet
ESP_LOGD(TAG, "Device address (bda): %02x:%02x:%02x:%02x:%02x:%02x", BT_BD_ADDR_HEX(p->scan_rst.bda));
ESP_LOGD(TAG, "Addr_type : %s", bt_addr_t_to_string(p->scan_rst.ble_addr_type));
ESP_LOGD(TAG, "RSSI : %d", p->scan_rst.rssi);
switch (event) { if ((cfg.rssilimit) && (p->scan_rst.rssi < cfg.rssilimit )) { // rssi is negative value
case ESP_GAP_BLE_SCAN_PARAM_SET_COMPLETE_EVT: ESP_LOGI(TAG, "BLTH RSSI %d -> ignoring (limit: %d)", p->scan_rst.rssi, cfg.rssilimit);
// restart scan break;
ESP_ERROR_CHECK(esp_ble_gap_start_scanning(BLESCANTIME)); }
break;
case ESP_GAP_BLE_SCAN_RESULT_EVT: #ifdef VENDORFILTER
// evaluate scan results
if (p->scan_rst.search_evt == if ((p->scan_rst.ble_addr_type == BLE_ADDR_TYPE_RANDOM) || (p->scan_rst.ble_addr_type == BLE_ADDR_TYPE_RPA_RANDOM)) {
ESP_GAP_SEARCH_INQ_CMPL_EVT) // Inquiry complete, scan is done ESP_LOGD(TAG, "BT device filtered");
{ // restart scan break;
ESP_ERROR_CHECK(esp_ble_gap_start_scanning(BLESCANTIME)); }
return;
}
if (p->scan_rst.search_evt == #endif
ESP_GAP_SEARCH_INQ_RES_EVT) // Inquiry result for a peer device
{ // evaluate sniffed packet
ESP_LOGD(TAG, "Device address (bda): %02x:%02x:%02x:%02x:%02x:%02x",
BT_BD_ADDR_HEX(p->scan_rst.bda));
ESP_LOGD(TAG, "Addr_type : %s",
bt_addr_t_to_string(p->scan_rst.ble_addr_type));
ESP_LOGD(TAG, "RSSI : %d", p->scan_rst.rssi);
if ((cfg.rssilimit) && // add this device and show new count total if it was not previously added
(p->scan_rst.rssi < cfg.rssilimit)) { // rssi is negative value mac_add((uint8_t *) p->scan_rst.bda, p->scan_rst.rssi, MAC_SNIFF_BLE);
ESP_LOGI(TAG, "BLTH RSSI %d -> ignoring (limit: %d)", p->scan_rst.rssi,
cfg.rssilimit); /* to be improved in vendorfilter if:
// you can search for elements in the payload using the
// function esp_ble_resolve_adv_data()
//
// Like this, that scans for the "Complete name" (looking inside the payload buffer)
// uint8_t len;
// uint8_t *data = esp_ble_resolve_adv_data(p->scan_rst.ble_adv, ESP_BLE_AD_TYPE_NAME_CMPL, &len);
filter BLE devices using their advertisements to get filter alternative to vendor OUI
if vendorfiltering is on, we ...
- want to count: mobile phones and tablets
- don't want to count: beacons, peripherals (earphones, headsets, printers), cars and machines
see
https://github.com/nkolban/ESP32_BLE_Arduino/blob/master/src/BLEAdvertisedDevice.cpp
http://www.libelium.com/products/meshlium/smartphone-detection/
https://www.question-defense.com/2013/01/12/bluetooth-cod-bluetooth-class-of-deviceclass-of-service-explained
https://www.bluetooth.com/specifications/assigned-numbers/baseband
"The Class of Device (CoD) in case of Bluetooth which allows us to differentiate the type of
device (smartphone, handsfree, computer, LAN/network AP). With this parameter we can
differentiate among pedestrians and vehicles."
*/
} // evaluate sniffed packet
break;
default:
break; break;
} }
#ifdef VENDORFILTER
if ((p->scan_rst.ble_addr_type == BLE_ADDR_TYPE_RANDOM) ||
(p->scan_rst.ble_addr_type == BLE_ADDR_TYPE_RPA_RANDOM)) {
ESP_LOGD(TAG, "BT device filtered");
break;
}
#endif
// add this device and show new count total if it was not previously added
mac_add((uint8_t *)p->scan_rst.bda, p->scan_rst.rssi, MAC_SNIFF_BLE);
/* to be improved in vendorfilter if:
// you can search for elements in the payload using the
// function esp_ble_resolve_adv_data()
//
// Like this, that scans for the "Complete name" (looking inside the
payload buffer)
// uint8_t len;
// uint8_t *data = esp_ble_resolve_adv_data(p->scan_rst.ble_adv,
ESP_BLE_AD_TYPE_NAME_CMPL, &len);
filter BLE devices using their advertisements to get filter alternative to
vendor OUI if vendorfiltering is on, we ...
- want to count: mobile phones and tablets
- don't want to count: beacons, peripherals (earphones, headsets,
printers), cars and machines see
https://github.com/nkolban/ESP32_BLE_Arduino/blob/master/src/BLEAdvertisedDevice.cpp
http://www.libelium.com/products/meshlium/smartphone-detection/
https://www.question-defense.com/2013/01/12/bluetooth-cod-bluetooth-class-of-deviceclass-of-service-explained
https://www.bluetooth.com/specifications/assigned-numbers/baseband
"The Class of Device (CoD) in case of Bluetooth which allows us to
differentiate the type of device (smartphone, handsfree, computer,
LAN/network AP). With this parameter we can differentiate among
pedestrians and vehicles."
*/
} // evaluate sniffed packet
break;
default:
break;
}
} // gap_callback_handler } // gap_callback_handler
esp_err_t register_ble_callback(void) { esp_err_t register_ble_callback(void) {
ESP_LOGI(TAG, "Register GAP callback"); ESP_LOGI(TAG, "Register GAP callback");
// This function is called to occur gap event, such as scan result.
//register the scan callback function to the gap module
ESP_ERROR_CHECK(esp_ble_gap_register_callback(&gap_callback_handler));
// This function is called to occur gap event, such as scan result. static esp_ble_scan_params_t ble_scan_params =
// register the scan callback function to the gap module {
ESP_ERROR_CHECK(esp_ble_gap_register_callback(&gap_callback_handler)); .scan_type = BLE_SCAN_TYPE_PASSIVE,
.own_addr_type = BLE_ADDR_TYPE_RANDOM,
#ifdef VENDORFILTER
.scan_filter_policy = BLE_SCAN_FILTER_ALLOW_WLIST_PRA_DIR,
// ADV_IND, ADV_NONCONN_IND, ADV_SCAN_IND packets are used for broadcasting
// data in broadcast applications (e.g., Beacons), so we don't want them in vendorfilter mode
#else
.scan_filter_policy = BLE_SCAN_FILTER_ALLOW_ALL,
#endif
static esp_ble_scan_params_t ble_scan_params = { .scan_interval = (uint16_t) (cfg.blescantime * 10 / 0.625), // Time = N * 0.625 msec
.scan_type = BLE_SCAN_TYPE_PASSIVE, .scan_window = (uint16_t) (BLESCANWINDOW / 0.625) // Time = N * 0.625 msec
.own_addr_type = BLE_ADDR_TYPE_RANDOM, };
#ifdef VENDORFILTER ESP_LOGI(TAG, "Set GAP scan parameters");
.scan_filter_policy = BLE_SCAN_FILTER_ALLOW_WLIST_PRA_DIR,
// ADV_IND, ADV_NONCONN_IND, ADV_SCAN_IND packets are used for broadcasting
// data in broadcast applications (e.g., Beacons), so we don't want them in
// vendorfilter mode
#else
.scan_filter_policy = BLE_SCAN_FILTER_ALLOW_ALL,
#endif
.scan_interval = // This function is called to set scan parameters.
(uint16_t)(cfg.blescantime * 10 / 0.625), // Time = N * 0.625 msec ESP_ERROR_CHECK(esp_ble_gap_set_scan_params(&ble_scan_params));
.scan_window = (uint16_t)(BLESCANWINDOW / 0.625) // Time = N * 0.625 msec
}; return ESP_OK;
ESP_LOGI(TAG, "Set GAP scan parameters");
// This function is called to set scan parameters.
ESP_ERROR_CHECK(esp_ble_gap_set_scan_params(&ble_scan_params));
return ESP_OK;
} // register_ble_callback } // register_ble_callback
void start_BLEscan(void) { void start_BLEscan(void){
ESP_LOGI(TAG, "Initializing bluetooth scanner ..."); ESP_LOGI(TAG, "Initializing bluetooth scanner ...");
// Initialize BT controller to allocate task and other resource. // Initialize BT controller to allocate task and other resource.
esp_bt_controller_config_t bt_cfg = BT_CONTROLLER_INIT_CONFIG_DEFAULT(); esp_bt_controller_config_t bt_cfg = BT_CONTROLLER_INIT_CONFIG_DEFAULT();
bt_cfg.controller_task_stack_size = bt_cfg.controller_task_stack_size = BLESTACKSIZE; // set BT stack size to value configured in paxcounter.conf
BLESTACKSIZE; // set BT stack size to value configured in paxcounter.conf ESP_ERROR_CHECK(esp_bt_controller_init(&bt_cfg));
ESP_ERROR_CHECK(esp_bt_controller_init(&bt_cfg)); ESP_ERROR_CHECK(esp_bt_controller_enable(ESP_BT_MODE_BTDM));
ESP_ERROR_CHECK(esp_bt_controller_enable(ESP_BT_MODE_BTDM));
// Init and alloc the resource for bluetooth stack, must be done prior to // Init and alloc the resource for bluetooth stack, must be done prior to every bluetooth stuff
// every bluetooth stuff ESP_ERROR_CHECK(esp_bluedroid_init());
ESP_ERROR_CHECK(esp_bluedroid_init()); ESP_ERROR_CHECK(esp_bluedroid_enable());
ESP_ERROR_CHECK(esp_bluedroid_enable());
// Register callback function for capturing bluetooth packets // Register callback function for capturing bluetooth packets
ESP_ERROR_CHECK(register_ble_callback()); ESP_ERROR_CHECK(register_ble_callback());
ESP_LOGI(TAG, "Bluetooth scanner started"); ESP_LOGI(TAG, "Bluetooth scanner started");
} // start_BLEscan } // start_BLEscan
void stop_BLEscan(void) { void stop_BLEscan(void){
ESP_LOGI(TAG, "Shutting down bluetooth scanner ..."); ESP_LOGI(TAG, "Shutting down bluetooth scanner ...");
ESP_ERROR_CHECK(esp_ble_gap_register_callback(NULL)); ESP_ERROR_CHECK(esp_ble_gap_register_callback(NULL));
ESP_ERROR_CHECK(esp_bluedroid_disable()); ESP_ERROR_CHECK(esp_bluedroid_disable());
ESP_ERROR_CHECK(esp_bluedroid_deinit()); ESP_ERROR_CHECK(esp_bluedroid_deinit());
ESP_ERROR_CHECK(esp_bt_controller_disable()); ESP_ERROR_CHECK(esp_bt_controller_disable());
ESP_ERROR_CHECK(esp_bt_controller_deinit()); ESP_ERROR_CHECK(esp_bt_controller_deinit());
ESP_LOGI(TAG, "Bluetooth scanner stopped"); ESP_LOGI(TAG, "Bluetooth scanner stopped");
} // stop_BLEscan } // stop_BLEscan
#endif // BLECOUNTER #endif // BLECOUNTER

View File

@ -13,152 +13,130 @@ esp_err_t err;
// defined in antenna.cpp // defined in antenna.cpp
#ifdef HAS_ANTENNA_SWITCH #ifdef HAS_ANTENNA_SWITCH
void antenna_select(const uint8_t _ant); void antenna_select(const uint8_t _ant);
#endif #endif
// populate cfg vars with factory settings // populate cfg vars with factory settings
void defaultConfig() { void defaultConfig() {
cfg.lorasf = LORASFDEFAULT; // 7-12, initial lora spreadfactor defined in cfg.lorasf = LORASFDEFAULT; // 7-12, initial lora spreadfactor defined in paxcounter.conf
// paxcounter.conf cfg.txpower = 15; // 2-15, lora tx power
cfg.txpower = 15; // 2-15, lora tx power cfg.adrmode = 1; // 0=disabled, 1=enabled
cfg.adrmode = 1; // 0=disabled, 1=enabled cfg.screensaver = 0; // 0=disabled, 1=enabled
cfg.screensaver = 0; // 0=disabled, 1=enabled cfg.screenon = 1; // 0=disabled, 1=enabled
cfg.screenon = 1; // 0=disabled, 1=enabled cfg.countermode = 0; // 0=cyclic, 1=cumulative, 2=cyclic confirmed
cfg.countermode = 0; // 0=cyclic, 1=cumulative, 2=cyclic confirmed cfg.rssilimit = 0; // threshold for rssilimiter, negative value!
cfg.rssilimit = 0; // threshold for rssilimiter, negative value! cfg.sendcycle = SEND_SECS; // payload send cycle [seconds/2]
cfg.sendcycle = SEND_SECS; // payload send cycle [seconds/2] cfg.wifichancycle = WIFI_CHANNEL_SWITCH_INTERVAL; // wifi channel switch cycle [seconds/100]
cfg.wifichancycle = cfg.blescantime = BLESCANINTERVAL / 10; // BT channel scan cycle duration [seconds/100], default 1 (= 10ms)
WIFI_CHANNEL_SWITCH_INTERVAL; // wifi channel switch cycle [seconds/100] cfg.blescan = 1; // 0=disabled, 1=enabled
cfg.blescantime = cfg.wifiant = 0; // 0=internal, 1=external (for LoPy/LoPy4)
BLESCANINTERVAL / cfg.vendorfilter = 1; // 0=disabled, 1=enabled
10; // BT channel scan cycle duration [seconds/100], default 1 (= 10ms) cfg.rgblum = RGBLUMINOSITY; // RGB Led luminosity (0..100%)
cfg.blescan = 1; // 0=disabled, 1=enabled cfg.gpsmode = 1; // 0=disabled, 1=enabled
cfg.wifiant = 0; // 0=internal, 1=external (for LoPy/LoPy4)
cfg.vendorfilter = 1; // 0=disabled, 1=enabled
cfg.rgblum = RGBLUMINOSITY; // RGB Led luminosity (0..100%)
cfg.gpsmode = 1; // 0=disabled, 1=enabled
strncpy(cfg.version, PROGVERSION, sizeof(cfg.version) - 1); strncpy( cfg.version, PROGVERSION, sizeof(cfg.version)-1 );
} }
void open_storage() { void open_storage() {
err = nvs_flash_init();
if (err == ESP_ERR_NVS_NO_FREE_PAGES) {
// NVS partition was truncated and needs to be erased
// Retry nvs_flash_init
ESP_ERROR_CHECK(nvs_flash_erase());
err = nvs_flash_init(); err = nvs_flash_init();
} if (err == ESP_ERR_NVS_NO_FREE_PAGES) {
ESP_ERROR_CHECK(err); // NVS partition was truncated and needs to be erased
// Retry nvs_flash_init
ESP_ERROR_CHECK(nvs_flash_erase());
err = nvs_flash_init();
}
ESP_ERROR_CHECK( err );
// Open // Open
ESP_LOGI(TAG, "Opening NVS"); ESP_LOGI(TAG, "Opening NVS");
err = nvs_open("config", NVS_READWRITE, &my_handle); err = nvs_open("config", NVS_READWRITE, &my_handle);
if (err != ESP_OK) if (err != ESP_OK)
ESP_LOGI(TAG, "Error (%d) opening NVS handle", err); ESP_LOGI(TAG, "Error (%d) opening NVS handle", err);
else else
ESP_LOGI(TAG, "Done"); ESP_LOGI(TAG, "Done");
} }
// erase all keys and values in NVRAM // erase all keys and values in NVRAM
void eraseConfig() { void eraseConfig() {
ESP_LOGI(TAG, "Clearing settings in NVS"); ESP_LOGI(TAG, "Clearing settings in NVS");
open_storage(); open_storage();
if (err == ESP_OK) { if (err == ESP_OK) {
nvs_erase_all(my_handle); nvs_erase_all(my_handle);
nvs_commit(my_handle); nvs_commit(my_handle);
nvs_close(my_handle); nvs_close(my_handle);
ESP_LOGI(TAG, "Done"); ESP_LOGI(TAG, "Done");}
} else { else {
ESP_LOGW(TAG, "NVS erase failed"); ESP_LOGW(TAG, "NVS erase failed"); }
}
} }
// save current configuration from RAM to NVRAM // save current configuration from RAM to NVRAM
void saveConfig() { void saveConfig() {
ESP_LOGI(TAG, "Storing settings in NVS"); ESP_LOGI(TAG, "Storing settings in NVS");
open_storage(); open_storage();
if (err == ESP_OK) { if (err == ESP_OK) {
int8_t flash8 = 0; int8_t flash8 = 0;
int16_t flash16 = 0; int16_t flash16 = 0;
size_t required_size; size_t required_size;
char storedversion[10]; char storedversion[10];
if (nvs_get_str(my_handle, "version", storedversion, &required_size) != if( nvs_get_str(my_handle, "version", storedversion, &required_size) != ESP_OK || strcmp(storedversion, cfg.version) != 0 )
ESP_OK || nvs_set_str(my_handle, "version", cfg.version);
strcmp(storedversion, cfg.version) != 0)
nvs_set_str(my_handle, "version", cfg.version);
if (nvs_get_i8(my_handle, "lorasf", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "lorasf", &flash8) != ESP_OK || flash8 != cfg.lorasf )
flash8 != cfg.lorasf) nvs_set_i8(my_handle, "lorasf", cfg.lorasf);
nvs_set_i8(my_handle, "lorasf", cfg.lorasf);
if (nvs_get_i8(my_handle, "txpower", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "txpower", &flash8) != ESP_OK || flash8 != cfg.txpower )
flash8 != cfg.txpower) nvs_set_i8(my_handle, "txpower", cfg.txpower);
nvs_set_i8(my_handle, "txpower", cfg.txpower);
if (nvs_get_i8(my_handle, "adrmode", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "adrmode", &flash8) != ESP_OK || flash8 != cfg.adrmode )
flash8 != cfg.adrmode) nvs_set_i8(my_handle, "adrmode", cfg.adrmode);
nvs_set_i8(my_handle, "adrmode", cfg.adrmode);
if (nvs_get_i8(my_handle, "screensaver", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "screensaver", &flash8) != ESP_OK || flash8 != cfg.screensaver )
flash8 != cfg.screensaver) nvs_set_i8(my_handle, "screensaver", cfg.screensaver);
nvs_set_i8(my_handle, "screensaver", cfg.screensaver);
if (nvs_get_i8(my_handle, "screenon", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "screenon", &flash8) != ESP_OK || flash8 != cfg.screenon )
flash8 != cfg.screenon) nvs_set_i8(my_handle, "screenon", cfg.screenon);
nvs_set_i8(my_handle, "screenon", cfg.screenon);
if (nvs_get_i8(my_handle, "countermode", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "countermode", &flash8) != ESP_OK || flash8 != cfg.countermode )
flash8 != cfg.countermode) nvs_set_i8(my_handle, "countermode", cfg.countermode);
nvs_set_i8(my_handle, "countermode", cfg.countermode);
if (nvs_get_i8(my_handle, "sendcycle", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "sendcycle", &flash8) != ESP_OK || flash8 != cfg.sendcycle )
flash8 != cfg.sendcycle) nvs_set_i8(my_handle, "sendcycle", cfg.sendcycle);
nvs_set_i8(my_handle, "sendcycle", cfg.sendcycle);
if (nvs_get_i8(my_handle, "wifichancycle", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "wifichancycle", &flash8) != ESP_OK || flash8 != cfg.wifichancycle )
flash8 != cfg.wifichancycle) nvs_set_i8(my_handle, "wifichancycle", cfg.wifichancycle);
nvs_set_i8(my_handle, "wifichancycle", cfg.wifichancycle);
if (nvs_get_i8(my_handle, "blescantime", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "blescantime", &flash8) != ESP_OK || flash8 != cfg.blescantime )
flash8 != cfg.blescantime) nvs_set_i8(my_handle, "blescantime", cfg.blescantime);
nvs_set_i8(my_handle, "blescantime", cfg.blescantime);
if (nvs_get_i8(my_handle, "blescanmode", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "blescanmode", &flash8) != ESP_OK || flash8 != cfg.blescan )
flash8 != cfg.blescan) nvs_set_i8(my_handle, "blescanmode", cfg.blescan);
nvs_set_i8(my_handle, "blescanmode", cfg.blescan);
if (nvs_get_i8(my_handle, "wifiant", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "wifiant", &flash8) != ESP_OK || flash8 != cfg.wifiant )
flash8 != cfg.wifiant) nvs_set_i8(my_handle, "wifiant", cfg.wifiant);
nvs_set_i8(my_handle, "wifiant", cfg.wifiant);
if (nvs_get_i8(my_handle, "vendorfilter", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "vendorfilter", &flash8) != ESP_OK || flash8 != cfg.vendorfilter )
flash8 != cfg.vendorfilter) nvs_set_i8(my_handle, "vendorfilter", cfg.vendorfilter);
nvs_set_i8(my_handle, "vendorfilter", cfg.vendorfilter);
if (nvs_get_i8(my_handle, "rgblum", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "rgblum", &flash8) != ESP_OK || flash8 != cfg.rgblum )
flash8 != cfg.rgblum) nvs_set_i8(my_handle, "rgblum", cfg.rgblum);
nvs_set_i8(my_handle, "rgblum", cfg.rgblum);
if (nvs_get_i8(my_handle, "gpsmode", &flash8) != ESP_OK || if( nvs_get_i8(my_handle, "gpsmode", &flash8) != ESP_OK || flash8 != cfg.gpsmode )
flash8 != cfg.gpsmode)
nvs_set_i8(my_handle, "gpsmode", cfg.gpsmode); nvs_set_i8(my_handle, "gpsmode", cfg.gpsmode);
if (nvs_get_i16(my_handle, "rssilimit", &flash16) != ESP_OK || if( nvs_get_i16(my_handle, "rssilimit", &flash16) != ESP_OK || flash16 != cfg.rssilimit )
flash16 != cfg.rssilimit) nvs_set_i16(my_handle, "rssilimit", cfg.rssilimit);
nvs_set_i16(my_handle, "rssilimit", cfg.rssilimit);
err = nvs_commit(my_handle); err = nvs_commit(my_handle);
nvs_close(my_handle); nvs_close(my_handle);
if (err == ESP_OK) { if ( err == ESP_OK ) {
ESP_LOGI(TAG, "Done"); ESP_LOGI(TAG, "Done");
} else {
ESP_LOGW(TAG, "NVS config write failed");
}
} else { } else {
ESP_LOGW(TAG, "NVS config write failed"); ESP_LOGW(TAG, "Error (%d) opening NVS handle", err);
} }
} else {
ESP_LOGW(TAG, "Error (%d) opening NVS handle", err);
}
} }
// set and save cfg.version // set and save cfg.version
@ -174,33 +152,31 @@ void loadConfig() {
ESP_LOGI(TAG, "Reading settings from NVS"); ESP_LOGI(TAG, "Reading settings from NVS");
open_storage(); open_storage();
if (err != ESP_OK) { if (err != ESP_OK) {
ESP_LOGW(TAG, "Error (%d) opening NVS handle, storing defaults", err); ESP_LOGW(TAG,"Error (%d) opening NVS handle, storing defaults", err);
saveConfig(); saveConfig(); } // saves factory settings to NVRAM
} // saves factory settings to NVRAM
else { else {
int8_t flash8 = 0; int8_t flash8 = 0;
int16_t flash16 = 0; int16_t flash16 = 0;
size_t required_size; size_t required_size;
// check if configuration stored in NVRAM matches PROGVERSION // check if configuration stored in NVRAM matches PROGVERSION
if (nvs_get_str(my_handle, "version", NULL, &required_size) == ESP_OK) { if( nvs_get_str(my_handle, "version", NULL, &required_size) == ESP_OK ) {
nvs_get_str(my_handle, "version", cfg.version, &required_size); nvs_get_str(my_handle, "version", cfg.version, &required_size);
ESP_LOGI(TAG, "NVRAM settings version = %s", cfg.version); ESP_LOGI(TAG, "NVRAM settings version = %s", cfg.version);
if (strcmp(cfg.version, PROGVERSION)) { if (strcmp(cfg.version, PROGVERSION)) {
ESP_LOGI(TAG, "migrating NVRAM settings to new version %s", ESP_LOGI(TAG, "migrating NVRAM settings to new version %s", PROGVERSION);
PROGVERSION);
nvs_close(my_handle); nvs_close(my_handle);
migrateVersion(); migrateVersion();
} }
} else { } else {
ESP_LOGI(TAG, "new version %s, deleting NVRAM settings", PROGVERSION); ESP_LOGI(TAG, "new version %s, deleting NVRAM settings", PROGVERSION);
nvs_close(my_handle); nvs_close(my_handle);
eraseConfig(); eraseConfig();
migrateVersion(); migrateVersion();
} }
// overwrite defaults with valid values from NVRAM // overwrite defaults with valid values from NVRAM
if (nvs_get_i8(my_handle, "lorasf", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "lorasf", &flash8) == ESP_OK ) {
cfg.lorasf = flash8; cfg.lorasf = flash8;
ESP_LOGI(TAG, "lorasf = %d", flash8); ESP_LOGI(TAG, "lorasf = %d", flash8);
} else { } else {
@ -208,7 +184,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "txpower", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "txpower", &flash8) == ESP_OK ) {
cfg.txpower = flash8; cfg.txpower = flash8;
ESP_LOGI(TAG, "txpower = %d", flash8); ESP_LOGI(TAG, "txpower = %d", flash8);
} else { } else {
@ -216,7 +192,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "adrmode", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "adrmode", &flash8) == ESP_OK ) {
cfg.adrmode = flash8; cfg.adrmode = flash8;
ESP_LOGI(TAG, "adrmode = %d", flash8); ESP_LOGI(TAG, "adrmode = %d", flash8);
} else { } else {
@ -224,7 +200,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "screensaver", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "screensaver", &flash8) == ESP_OK ) {
cfg.screensaver = flash8; cfg.screensaver = flash8;
ESP_LOGI(TAG, "screensaver = %d", flash8); ESP_LOGI(TAG, "screensaver = %d", flash8);
} else { } else {
@ -232,7 +208,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "screenon", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "screenon", &flash8) == ESP_OK ) {
cfg.screenon = flash8; cfg.screenon = flash8;
ESP_LOGI(TAG, "screenon = %d", flash8); ESP_LOGI(TAG, "screenon = %d", flash8);
} else { } else {
@ -240,7 +216,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "countermode", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "countermode", &flash8) == ESP_OK ) {
cfg.countermode = flash8; cfg.countermode = flash8;
ESP_LOGI(TAG, "countermode = %d", flash8); ESP_LOGI(TAG, "countermode = %d", flash8);
} else { } else {
@ -248,7 +224,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "sendcycle", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "sendcycle", &flash8) == ESP_OK ) {
cfg.sendcycle = flash8; cfg.sendcycle = flash8;
ESP_LOGI(TAG, "sendcycle = %d", flash8); ESP_LOGI(TAG, "sendcycle = %d", flash8);
} else { } else {
@ -256,7 +232,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "wifichancycle", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "wifichancycle", &flash8) == ESP_OK ) {
cfg.wifichancycle = flash8; cfg.wifichancycle = flash8;
ESP_LOGI(TAG, "wifichancycle = %d", flash8); ESP_LOGI(TAG, "wifichancycle = %d", flash8);
} else { } else {
@ -264,7 +240,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "wifiant", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "wifiant", &flash8) == ESP_OK ) {
cfg.wifiant = flash8; cfg.wifiant = flash8;
ESP_LOGI(TAG, "wifiantenna = %d", flash8); ESP_LOGI(TAG, "wifiantenna = %d", flash8);
} else { } else {
@ -272,7 +248,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "vendorfilter", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "vendorfilter", &flash8) == ESP_OK ) {
cfg.vendorfilter = flash8; cfg.vendorfilter = flash8;
ESP_LOGI(TAG, "vendorfilter = %d", flash8); ESP_LOGI(TAG, "vendorfilter = %d", flash8);
} else { } else {
@ -280,7 +256,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "rgblum", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "rgblum", &flash8) == ESP_OK ) {
cfg.rgblum = flash8; cfg.rgblum = flash8;
ESP_LOGI(TAG, "rgbluminosity = %d", flash8); ESP_LOGI(TAG, "rgbluminosity = %d", flash8);
} else { } else {
@ -288,7 +264,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "blescantime", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "blescantime", &flash8) == ESP_OK ) {
cfg.blescantime = flash8; cfg.blescantime = flash8;
ESP_LOGI(TAG, "blescantime = %d", flash8); ESP_LOGI(TAG, "blescantime = %d", flash8);
} else { } else {
@ -296,7 +272,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "blescanmode", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "blescanmode", &flash8) == ESP_OK ) {
cfg.blescan = flash8; cfg.blescan = flash8;
ESP_LOGI(TAG, "BLEscanmode = %d", flash8); ESP_LOGI(TAG, "BLEscanmode = %d", flash8);
} else { } else {
@ -304,7 +280,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i16(my_handle, "rssilimit", &flash16) == ESP_OK) { if( nvs_get_i16(my_handle, "rssilimit", &flash16) == ESP_OK ) {
cfg.rssilimit = flash16; cfg.rssilimit = flash16;
ESP_LOGI(TAG, "rssilimit = %d", flash16); ESP_LOGI(TAG, "rssilimit = %d", flash16);
} else { } else {
@ -312,7 +288,7 @@ void loadConfig() {
saveConfig(); saveConfig();
} }
if (nvs_get_i8(my_handle, "gpsmode", &flash8) == ESP_OK) { if( nvs_get_i8(my_handle, "gpsmode", &flash8) == ESP_OK ) {
cfg.gpsmode = flash8; cfg.gpsmode = flash8;
ESP_LOGI(TAG, "GPSmode = %d", flash8); ESP_LOGI(TAG, "GPSmode = %d", flash8);
} else { } else {
@ -324,9 +300,9 @@ void loadConfig() {
ESP_LOGI(TAG, "Done"); ESP_LOGI(TAG, "Done");
// put actions to be triggered after config loaded here // put actions to be triggered after config loaded here
#ifdef HAS_ANTENNA_SWITCH // set antenna type, if device has one #ifdef HAS_ANTENNA_SWITCH // set antenna type, if device has one
antenna_select(cfg.wifiant); antenna_select(cfg.wifiant);
#endif #endif
} }
} }

View File

@ -2,63 +2,63 @@
#include <Arduino.h> #include <Arduino.h>
// std::set for unified array functions // std::set for unified array functions
#include <algorithm>
#include <array>
#include <set> #include <set>
#include <array>
#include <algorithm>
// OLED Display // OLED Display
#ifdef HAS_DISPLAY #ifdef HAS_DISPLAY
#include <U8x8lib.h> #include <U8x8lib.h>
#endif #endif
// GPS //GPS
#ifdef HAS_GPS #ifdef HAS_GPS
#include <TinyGPS++.h> #include <TinyGPS++.h>
#endif #endif
// LMIC-Arduino LoRaWAN Stack // LMIC-Arduino LoRaWAN Stack
#include <hal/hal.h>
#include <lmic.h> #include <lmic.h>
#include <hal/hal.h>
// LED controls // LED controls
#ifdef HAS_RGB_LED #ifdef HAS_RGB_LED
#include <SmartLeds.h> #include <SmartLeds.h>
#endif #endif
#include "rgb_led.h"
#include "macsniff.h" #include "macsniff.h"
#include "main.h" #include "main.h"
#include "rgb_led.h"
// Struct holding devices's runtime configuration // Struct holding devices's runtime configuration
typedef struct { typedef struct {
uint8_t lorasf; // 7-12, lora spreadfactor uint8_t lorasf; // 7-12, lora spreadfactor
uint8_t txpower; // 2-15, lora tx power uint8_t txpower; // 2-15, lora tx power
uint8_t adrmode; // 0=disabled, 1=enabled uint8_t adrmode; // 0=disabled, 1=enabled
uint8_t screensaver; // 0=disabled, 1=enabled uint8_t screensaver; // 0=disabled, 1=enabled
uint8_t screenon; // 0=disabled, 1=enabled uint8_t screenon; // 0=disabled, 1=enabled
uint8_t countermode; // 0=cyclic unconfirmed, 1=cumulative, 2=cyclic confirmed uint8_t countermode; // 0=cyclic unconfirmed, 1=cumulative, 2=cyclic confirmed
int16_t rssilimit; // threshold for rssilimiter, negative value! int16_t rssilimit; // threshold for rssilimiter, negative value!
uint8_t sendcycle; // payload send cycle [seconds/2] uint8_t sendcycle; // payload send cycle [seconds/2]
uint8_t wifichancycle; // wifi channel switch cycle [seconds/100] uint8_t wifichancycle; // wifi channel switch cycle [seconds/100]
uint8_t blescantime; // BLE scan cycle duration [seconds] uint8_t blescantime; // BLE scan cycle duration [seconds]
uint8_t blescan; // 0=disabled, 1=enabled uint8_t blescan; // 0=disabled, 1=enabled
uint8_t wifiant; // 0=internal, 1=external (for LoPy/LoPy4) uint8_t wifiant; // 0=internal, 1=external (for LoPy/LoPy4)
uint8_t vendorfilter; // 0=disabled, 1=enabled uint8_t vendorfilter; // 0=disabled, 1=enabled
uint8_t rgblum; // RGB Led luminosity (0..100%) uint8_t rgblum; // RGB Led luminosity (0..100%)
uint8_t gpsmode; // 0=disabled, 1=enabled uint8_t gpsmode; // 0=disabled, 1=enabled
char version[10]; // Firmware version char version[10]; // Firmware version
} configData_t; } configData_t;
#ifdef HAS_GPS #ifdef HAS_GPS
typedef struct { typedef struct {
uint32_t latitude; uint32_t latitude;
uint32_t longitude; uint32_t longitude;
uint8_t satellites; uint8_t satellites;
uint16_t hdop; uint16_t hdop;
uint16_t altitude; uint16_t altitude;
} gpsStatus_t; } gpsStatus_t;
extern gpsStatus_t gps_status; // struct for storing gps data extern gpsStatus_t gps_status; // struct for storing gps data
extern TinyGPSPlus gps; // Make TinyGPS++ instance globally availabe extern TinyGPSPlus gps; // Make TinyGPS++ instance globally availabe
#endif #endif
extern configData_t cfg; extern configData_t cfg;
@ -68,7 +68,6 @@ extern char display_lora[], display_lmic[];
extern int countermode, screensaver, adrmode, lorasf, txpower, rlim; extern int countermode, screensaver, adrmode, lorasf, txpower, rlim;
extern uint16_t macs_total, macs_wifi, macs_ble; // MAC counters extern uint16_t macs_total, macs_wifi, macs_ble; // MAC counters
extern std::set<uint16_t> macs; extern std::set<uint16_t> macs;
extern hw_timer_t extern hw_timer_t * channelSwitch; // hardware timer used for wifi channel switching
*channelSwitch; // hardware timer used for wifi channel switching extern xref2u1_t rcmd_data; // buffer for rcommand results size
extern xref2u1_t rcmd_data; // buffer for rcommand results size extern u1_t rcmd_data_size; // buffer for rcommand results size
extern u1_t rcmd_data_size; // buffer for rcommand results size

View File

@ -7,73 +7,74 @@ static const char TAG[] = "main";
// read GPS data and cast to global struct // read GPS data and cast to global struct
void gps_read() { void gps_read() {
gps_status.latitude = (uint32_t)(gps.location.lat() * 1000000); gps_status.latitude = (uint32_t) (gps.location.lat() * 1000000);
gps_status.longitude = (uint32_t)(gps.location.lng() * 1000000); gps_status.longitude = (uint32_t) (gps.location.lng() * 1000000);
gps_status.satellites = (uint8_t)gps.satellites.value(); gps_status.satellites = (uint8_t) gps.satellites.value();
gps_status.hdop = (uint16_t)gps.hdop.value(); gps_status.hdop = (uint16_t) gps.hdop.value();
gps_status.altitude = (uint16_t)gps.altitude.meters(); gps_status.altitude = (uint16_t) gps.altitude.meters();
} }
// GPS serial feed FreeRTos Task // GPS serial feed FreeRTos Task
void gps_loop(void *pvParameters) { void gps_loop(void * pvParameters) {
configASSERT(((uint32_t)pvParameters) == 1); // FreeRTOS check configASSERT( ( ( uint32_t ) pvParameters ) == 1 ); // FreeRTOS check
// initialize and, if needed, configure, GPS // initialize and, if needed, configure, GPS
#if defined GPS_SERIAL #if defined GPS_SERIAL
HardwareSerial GPS_Serial(1); HardwareSerial GPS_Serial(1);
#elif defined GPS_I2C #elif defined GPS_I2C
// to be done // to be done
#endif #endif
while (1) { while(1) {
if (cfg.gpsmode) { if (cfg.gpsmode)
#if defined GPS_SERIAL {
#if defined GPS_SERIAL
// serial connect to GPS device
GPS_Serial.begin(GPS_SERIAL);
while(cfg.gpsmode) {
// feed GPS decoder with serial NMEA data from GPS device
while (GPS_Serial.available()) {
gps.encode(GPS_Serial.read());
}
vTaskDelay(1/portTICK_PERIOD_MS); // reset watchdog
}
// after GPS function was disabled, close connect to GPS device
GPS_Serial.end();
// serial connect to GPS device #elif defined GPS_I2C
GPS_Serial.begin(GPS_SERIAL);
// I2C connect to GPS device with 100 kHz
Wire.begin(GPS_I2C_PINS, 100000);
Wire.beginTransmission(GPS_I2C_ADDRESS_WRITE);
Wire.write(0x00);
while (cfg.gpsmode) { i2c_ret == Wire.beginTransmission(GPS_I2C_ADDRESS_READ);
// feed GPS decoder with serial NMEA data from GPS device if (i2c_ret == 0) { // check if device seen on i2c bus
while (GPS_Serial.available()) { while(cfg.gpsmode) {
gps.encode(GPS_Serial.read()); // feed GPS decoder with serial NMEA data from GPS device
while (Wire.available()) {
Wire.requestFrom(GPS_I2C_ADDRESS_READ, 255);
gps.encode(Wire.read());
vTaskDelay(1/portTICK_PERIOD_MS); // reset watchdog
}
}
// after GPS function was disabled, close connect to GPS device
Wire.endTransmission();
Wire.setClock(400000); // Set back to 400KHz to speed up OLED
}
#endif
} }
vTaskDelay(1 / portTICK_PERIOD_MS); // reset watchdog
} vTaskDelay(1/portTICK_PERIOD_MS); // reset watchdog
// after GPS function was disabled, close connect to GPS device
GPS_Serial.end();
#elif defined GPS_I2C } // end of infinite loop
// I2C connect to GPS device with 100 kHz
Wire.begin(GPS_I2C_PINS, 100000);
Wire.beginTransmission(GPS_I2C_ADDRESS_WRITE);
Wire.write(0x00);
i2c_ret == Wire.beginTransmission(GPS_I2C_ADDRESS_READ);
if (i2c_ret == 0) { // check if device seen on i2c bus
while (cfg.gpsmode) {
// feed GPS decoder with serial NMEA data from GPS device
while (Wire.available()) {
Wire.requestFrom(GPS_I2C_ADDRESS_READ, 255);
gps.encode(Wire.read());
vTaskDelay(1 / portTICK_PERIOD_MS); // reset watchdog
}
}
// after GPS function was disabled, close connect to GPS device
Wire.endTransmission();
Wire.setClock(400000); // Set back to 400KHz to speed up OLED
}
#endif
}
vTaskDelay(1 / portTICK_PERIOD_MS); // reset watchdog
} // end of infinite loop
} // gps_loop() } // gps_loop()
#endif // HAS_GPS #endif // HAS_GPS

View File

@ -1,19 +1,19 @@
// Hardware related definitions for Pycom FiPy Board // Hardware related definitions for Pycom FiPy Board
#define CFG_sx1272_radio 1 #define CFG_sx1272_radio 1
#define HAS_LED NOT_A_PIN // FiPy has no on board LED, so we use RGB LED #define HAS_LED NOT_A_PIN // FiPy has no on board LED, so we use RGB LED
#define HAS_RGB_LED GPIO_NUM_0 // WS2812B RGB LED on GPIO0 #define HAS_RGB_LED GPIO_NUM_0 // WS2812B RGB LED on GPIO0
// Hardware pin definitions for Pycom FiPy board // Hardware pin definitions for Pycom FiPy board
#define PIN_SPI_SS GPIO_NUM_18 #define PIN_SPI_SS GPIO_NUM_18
#define PIN_SPI_MOSI GPIO_NUM_27 #define PIN_SPI_MOSI GPIO_NUM_27
#define PIN_SPI_MISO GPIO_NUM_19 #define PIN_SPI_MISO GPIO_NUM_19
#define PIN_SPI_SCK GPIO_NUM_5 #define PIN_SPI_SCK GPIO_NUM_5
#define RST LMIC_UNUSED_PIN #define RST LMIC_UNUSED_PIN
#define DIO0 GPIO_NUM_23 // LoRa IRQ #define DIO0 GPIO_NUM_23 // LoRa IRQ
#define DIO1 GPIO_NUM_23 // workaround #define DIO1 GPIO_NUM_23 // workaround
#define DIO2 LMIC_UNUSED_PIN #define DIO2 LMIC_UNUSED_PIN
// select WIFI antenna (internal = onboard / external = u.fl socket) // select WIFI antenna (internal = onboard / external = u.fl socket)
#define HAS_ANTENNA_SWITCH GPIO_NUM_21 // pin for switching wifi antenna #define HAS_ANTENNA_SWITCH GPIO_NUM_21 // pin for switching wifi antenna
#define WIFI_ANTENNA 0 // 0 = internal, 1 = external #define WIFI_ANTENNA 0 // 0 = internal, 1 = external

View File

@ -4,36 +4,22 @@
#define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C // OLED-Display on board #define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C // OLED-Display on board
//#define DISPLAY_FLIP 1 // uncomment this for rotated display //#define DISPLAY_FLIP 1 // uncomment this for rotated display
#define HAS_LED GPIO_NUM_25 // white LED on board #define HAS_LED GPIO_NUM_25 // white LED on board
#define HAS_BUTTON GPIO_NUM_0 // button "PROG" on board #define HAS_BUTTON GPIO_NUM_0 // button "PROG" on board
// re-define pin definitions of pins_arduino.h // re-define pin definitions of pins_arduino.h
#define PIN_SPI_SS \ #define PIN_SPI_SS GPIO_NUM_18 // ESP32 GPIO18 (Pin18) -- SX1276 NSS (Pin19) SPI Chip Select Input
GPIO_NUM_18 // ESP32 GPIO18 (Pin18) -- SX1276 NSS (Pin19) SPI Chip Select #define PIN_SPI_MOSI GPIO_NUM_27 // ESP32 GPIO27 (Pin27) -- SX1276 MOSI (Pin18) SPI Data Input
// Input #define PIN_SPI_MISO GPIO_NUM_19 // ESP32 GPIO19 (Pin19) -- SX1276 MISO (Pin17) SPI Data Output
#define PIN_SPI_MOSI \ #define PIN_SPI_SCK GPIO_NUM_5 // ESP32 GPIO5 (Pin5) -- SX1276 SCK (Pin16) SPI Clock Input
GPIO_NUM_27 // ESP32 GPIO27 (Pin27) -- SX1276 MOSI (Pin18) SPI Data Input
#define PIN_SPI_MISO \
GPIO_NUM_19 // ESP32 GPIO19 (Pin19) -- SX1276 MISO (Pin17) SPI Data Output
#define PIN_SPI_SCK \
GPIO_NUM_5 // ESP32 GPIO5 (Pin5) -- SX1276 SCK (Pin16) SPI Clock Input
// non arduino pin definitions // non arduino pin definitions
#define RST \ #define RST GPIO_NUM_14 // ESP32 GPIO14 (Pin14) -- SX1276 NRESET (Pin7) Reset Trigger Input
GPIO_NUM_14 // ESP32 GPIO14 (Pin14) -- SX1276 NRESET (Pin7) Reset Trigger #define DIO0 GPIO_NUM_26 // ESP32 GPIO26 (Pin15) -- SX1276 DIO0 (Pin8) used by LMIC for detecting LoRa RX_Done & TX_Done
// Input #define DIO1 GPIO_NUM_33 // ESP32 GPIO33 (Pin13) -- SX1276 DIO1 (Pin9) used by LMIC for detecting LoRa RX_Timeout
#define DIO0 \ #define DIO2 LMIC_UNUSED_PIN // 32 ESP32 GPIO32 (Pin12) -- SX1276 DIO2 (Pin10) not used by LMIC for LoRa (Timeout for FSK only)
GPIO_NUM_26 // ESP32 GPIO26 (Pin15) -- SX1276 DIO0 (Pin8) used by LMIC for
// detecting LoRa RX_Done & TX_Done
#define DIO1 \
GPIO_NUM_33 // ESP32 GPIO33 (Pin13) -- SX1276 DIO1 (Pin9) used by LMIC for
// detecting LoRa RX_Timeout
#define DIO2 \
LMIC_UNUSED_PIN // 32 ESP32 GPIO32 (Pin12) -- SX1276 DIO2 (Pin10) not used by
// LMIC for LoRa (Timeout for FSK only)
// Hardware pin definitions for Heltec LoRa-32 Board with OLED SSD1306 I2C // Hardware pin definitions for Heltec LoRa-32 Board with OLED SSD1306 I2C Display
// Display
#define OLED_RST GPIO_NUM_16 // ESP32 GPIO16 (Pin16) -- SD1306 RST #define OLED_RST GPIO_NUM_16 // ESP32 GPIO16 (Pin16) -- SD1306 RST
#define OLED_SDA GPIO_NUM_4 // ESP32 GPIO4 (Pin4) -- SD1306 D1+D2 #define OLED_SDA GPIO_NUM_4 // ESP32 GPIO4 (Pin4) -- SD1306 D1+D2
#define OLED_SCL GPIO_NUM_15 // ESP32 GPIO15 (Pin15) -- SD1306 D0 #define OLED_SCL GPIO_NUM_15 // ESP32 GPIO15 (Pin15) -- SD1306 D0

View File

@ -6,50 +6,33 @@
#define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C // OLED-Display on board #define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C // OLED-Display on board
//#define DISPLAY_FLIP 1 // uncomment this for rotated display //#define DISPLAY_FLIP 1 // uncomment this for rotated display
#define HAS_LED \ #define HAS_LED NOT_A_PIN // Led os on same pin as Lora SS pin, to avoid problems, we don't use it
NOT_A_PIN // Led os on same pin as Lora SS pin, to avoid problems, we don't #define LED_ACTIVE_LOW 1 // Onboard LED is active when pin is LOW
// use it // Anyway shield is on over the LoLin32 board, so we won't be able to see this LED
#define LED_ACTIVE_LOW \ #define HAS_RGB_LED 13 // ESP32 GPIO13 (pin13) On Board Shield WS2812B RGB LED
1 // Onboard LED is active when pin is LOW #define HAS_BUTTON 15 // ESP32 GPIO15 (pin15) Button is on the LoraNode32 shield
// Anyway shield is on over the LoLin32 board, so we won't be able to see #define BUTTON_PULLUP 1 // Button need pullup instead of default pulldown
// this LED
#define HAS_RGB_LED 13 // ESP32 GPIO13 (pin13) On Board Shield WS2812B RGB LED
#define HAS_BUTTON 15 // ESP32 GPIO15 (pin15) Button is on the LoraNode32 shield
#define BUTTON_PULLUP 1 // Button need pullup instead of default pulldown
#define CFG_sx1276_radio 1 // RFM95 module #define CFG_sx1276_radio 1 // RFM95 module
// re-define pin definitions of pins_arduino.h // re-define pin definitions of pins_arduino.h
#define PIN_SPI_SS \ #define PIN_SPI_SS 5 // ESP32 GPIO5 (Pin5) -- SX1276 NSS (Pin19) SPI Chip Select Input
5 // ESP32 GPIO5 (Pin5) -- SX1276 NSS (Pin19) SPI Chip Select Input #define PIN_SPI_MOSI 23 // ESP32 GPIO23 (Pin23) -- SX1276 MOSI (Pin18) SPI Data Input
#define PIN_SPI_MOSI \ #define PIN_SPI_MISO 19 // ESP32 GPIO19 (Pin19) -- SX1276 MISO (Pin17) SPI Data Output
23 // ESP32 GPIO23 (Pin23) -- SX1276 MOSI (Pin18) SPI Data Input #define PIN_SPI_SCK 18 // ESP32 GPIO18 (Pin18 -- SX1276 SCK (Pin16) SPI Clock Input
#define PIN_SPI_MISO \
19 // ESP32 GPIO19 (Pin19) -- SX1276 MISO (Pin17) SPI Data Output
#define PIN_SPI_SCK \
18 // ESP32 GPIO18 (Pin18 -- SX1276 SCK (Pin16) SPI Clock Input
// non arduino pin definitions // non arduino pin definitions
#define RST \ #define RST 25 // ESP32 GPIO25 (Pin25) -- SX1276 NRESET (Pin7) Reset Trigger Input
25 // ESP32 GPIO25 (Pin25) -- SX1276 NRESET (Pin7) Reset Trigger Input #define DIO0 27 // ESP32 GPIO27 (Pin27) -- SX1276 DIO0 (Pin8) used by LMIC for detecting LoRa RX_Done & TX_Done
#define DIO0 \ #define DIO1 26 // ESP32 GPIO26 (Pin26) -- SX1276 DIO1 (Pin9) used by LMIC for detecting LoRa RX_Timeout
27 // ESP32 GPIO27 (Pin27) -- SX1276 DIO0 (Pin8) used by LMIC for detecting #define DIO2 LMIC_UNUSED_PIN // 4 ESP32 GPIO4 (Pin4) -- SX1276 DIO2 (Pin10) not used by LMIC for LoRa (Timeout for FSK only)
// LoRa RX_Done & TX_Done #define DIO5 LMIC_UNUSED_PIN // 35 ESP32 GPIO35 (Pin35) -- SX1276 DIO5 not used by LMIC for LoRa (Timeout for FSK only)
#define DIO1 \
26 // ESP32 GPIO26 (Pin26) -- SX1276 DIO1 (Pin9) used by LMIC for detecting
// LoRa RX_Timeout
#define DIO2 \
LMIC_UNUSED_PIN // 4 ESP32 GPIO4 (Pin4) -- SX1276 DIO2 (Pin10) not used by
// LMIC for LoRa (Timeout for FSK only)
#define DIO5 \
LMIC_UNUSED_PIN // 35 ESP32 GPIO35 (Pin35) -- SX1276 DIO5 not used by LMIC
// for LoRa (Timeout for FSK only)
// Hardware pin definitions for LoRaNode32 Board with OLED I2C Display // Hardware pin definitions for LoRaNode32 Board with OLED I2C Display
#define OLED_RST U8X8_PIN_NONE // Not reset pin #define OLED_RST U8X8_PIN_NONE // Not reset pin
#define OLED_SDA 21 // ESP32 GPIO21 (Pin21) -- OLED SDA #define OLED_SDA 21 // ESP32 GPIO21 (Pin21) -- OLED SDA
#define OLED_SCL 22 // ESP32 GPIO22 (Pin22) -- OLED SCL #define OLED_SCL 22 // ESP32 GPIO22 (Pin22) -- OLED SCL
// I2C config for Microchip 24AA02E64 DEVEUI unique address // I2C config for Microchip 24AA02E64 DEVEUI unique address
#define MCP_24AA02E64_I2C_ADDRESS 0x50 // I2C address for the 24AA02E64 #define MCP_24AA02E64_I2C_ADDRESS 0x50 // I2C address for the 24AA02E64
#define MCP_24AA02E64_MAC_ADDRESS 0xF8 // Memory adress of unique deveui 64 bits #define MCP_24AA02E64_MAC_ADDRESS 0xF8 // Memory adress of unique deveui 64 bits

View File

@ -6,45 +6,32 @@
#define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C // OLED-Display on board #define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C // OLED-Display on board
//#define DISPLAY_FLIP 1 // uncomment this for rotated display //#define DISPLAY_FLIP 1 // uncomment this for rotated display
#define HAS_LED 22 // ESP32 GPIO12 (pin22) On Board LED #define HAS_LED 22 // ESP32 GPIO12 (pin22) On Board LED
#define LED_ACTIVE_LOW 1 // Onboard LED is active when pin is LOW #define LED_ACTIVE_LOW 1 // Onboard LED is active when pin is LOW
#define HAS_RGB_LED 13 // ESP32 GPIO13 (pin13) On Board Shield WS2812B RGB LED #define HAS_RGB_LED 13 // ESP32 GPIO13 (pin13) On Board Shield WS2812B RGB LED
#define HAS_BUTTON 15 // ESP32 GPIO15 (pin15) Button is on the LoraNode32 shield #define HAS_BUTTON 15 // ESP32 GPIO15 (pin15) Button is on the LoraNode32 shield
#define BUTTON_PULLUP 1 // Button need pullup instead of default pulldown #define BUTTON_PULLUP 1 // Button need pullup instead of default pulldown
#define CFG_sx1276_radio 1 // RFM95 module #define CFG_sx1276_radio 1 // RFM95 module
// re-define pin definitions of pins_arduino.h // re-define pin definitions of pins_arduino.h
#define PIN_SPI_SS \ #define PIN_SPI_SS 5 // ESP32 GPIO5 (Pin5) -- SX1276 NSS (Pin19) SPI Chip Select Input
5 // ESP32 GPIO5 (Pin5) -- SX1276 NSS (Pin19) SPI Chip Select Input #define PIN_SPI_MOSI 23 // ESP32 GPIO23 (Pin23) -- SX1276 MOSI (Pin18) SPI Data Input
#define PIN_SPI_MOSI \ #define PIN_SPI_MISO 19 // ESP32 GPIO19 (Pin19) -- SX1276 MISO (Pin17) SPI Data Output
23 // ESP32 GPIO23 (Pin23) -- SX1276 MOSI (Pin18) SPI Data Input #define PIN_SPI_SCK 18 // ESP32 GPIO18 (Pin18 -- SX1276 SCK (Pin16) SPI Clock Input
#define PIN_SPI_MISO \
19 // ESP32 GPIO19 (Pin19) -- SX1276 MISO (Pin17) SPI Data Output
#define PIN_SPI_SCK \
18 // ESP32 GPIO18 (Pin18 -- SX1276 SCK (Pin16) SPI Clock Input
// non arduino pin definitions // non arduino pin definitions
#define RST \ #define RST 25 // ESP32 GPIO25 (Pin25) -- SX1276 NRESET (Pin7) Reset Trigger Input
25 // ESP32 GPIO25 (Pin25) -- SX1276 NRESET (Pin7) Reset Trigger Input #define DIO0 27 // ESP32 GPIO27 (Pin27) -- SX1276 DIO0 (Pin8) used by LMIC for detecting LoRa RX_Done & TX_Done
#define DIO0 \ #define DIO1 26 // ESP32 GPIO26 (Pin26) -- SX1276 DIO1 (Pin9) used by LMIC for detecting LoRa RX_Timeout
27 // ESP32 GPIO27 (Pin27) -- SX1276 DIO0 (Pin8) used by LMIC for detecting #define DIO2 LMIC_UNUSED_PIN // 4 ESP32 GPIO4 (Pin4) -- SX1276 DIO2 (Pin10) not used by LMIC for LoRa (Timeout for FSK only)
// LoRa RX_Done & TX_Done #define DIO5 LMIC_UNUSED_PIN // 35 ESP32 GPIO35 (Pin35) -- SX1276 DIO5 not used by LMIC for LoRa (Timeout for FSK only)
#define DIO1 \
26 // ESP32 GPIO26 (Pin26) -- SX1276 DIO1 (Pin9) used by LMIC for detecting
// LoRa RX_Timeout
#define DIO2 \
LMIC_UNUSED_PIN // 4 ESP32 GPIO4 (Pin4) -- SX1276 DIO2 (Pin10) not used by
// LMIC for LoRa (Timeout for FSK only)
#define DIO5 \
LMIC_UNUSED_PIN // 35 ESP32 GPIO35 (Pin35) -- SX1276 DIO5 not used by LMIC
// for LoRa (Timeout for FSK only)
// Hardware pin definitions for LoRaNode32 Board with OLED I2C Display // Hardware pin definitions for LoRaNode32 Board with OLED I2C Display
#define OLED_RST U8X8_PIN_NONE // Not reset pin #define OLED_RST U8X8_PIN_NONE // Not reset pin
#define OLED_SDA 14 // ESP32 GPIO14 (Pin14) -- OLED SDA #define OLED_SDA 14 // ESP32 GPIO14 (Pin14) -- OLED SDA
#define OLED_SCL 12 // ESP32 GPIO12 (Pin12) -- OLED SCL #define OLED_SCL 12 // ESP32 GPIO12 (Pin12) -- OLED SCL
// I2C config for Microchip 24AA02E64 DEVEUI unique address // I2C config for Microchip 24AA02E64 DEVEUI unique address
#define MCP_24AA02E64_I2C_ADDRESS 0x50 // I2C address for the 24AA02E64 #define MCP_24AA02E64_I2C_ADDRESS 0x50 // I2C address for the 24AA02E64
#define MCP_24AA02E64_MAC_ADDRESS 0xF8 // Memory adress of unique deveui 64 bits #define MCP_24AA02E64_MAC_ADDRESS 0xF8 // Memory adress of unique deveui 64 bits

View File

@ -1,14 +1,12 @@
// Hardware related definitions for Pycom LoPy Board (not: LoPy4) // Hardware related definitions for Pycom LoPy Board (not: LoPy4)
#define CFG_sx1272_radio 1 #define CFG_sx1272_radio 1
#define HAS_LED \ #define HAS_LED NOT_A_PIN // LoPy4 has no on board LED, so we use RGB LED on LoPy4
NOT_A_PIN // LoPy4 has no on board LED, so we use RGB LED on LoPy4 #define HAS_RGB_LED GPIO_NUM_0 // WS2812B RGB LED on GPIO0
#define HAS_RGB_LED GPIO_NUM_0 // WS2812B RGB LED on GPIO0
// !!EXPERIMENTAL - not tested yet!! // !!EXPERIMENTAL - not tested yet!!
// uncomment this only if your LoPy lives on a Pytrack expansion board with GPS // uncomment this only if your LoPy lives on a Pytrack expansion board with GPS
// see // see http://www.quectel.com/UploadImage/Downlad/Quectel_L76-L_I2C_Application_Note_V1.0.pdf
// http://www.quectel.com/UploadImage/Downlad/Quectel_L76-L_I2C_Application_Note_V1.0.pdf
//#define HAS_GPS 1 //#define HAS_GPS 1
//#define GPS_I2C_PINS GPIO_NUM_9, GPIO_NUM_8 // SDA, SCL //#define GPS_I2C_PINS GPIO_NUM_9, GPIO_NUM_8 // SDA, SCL
//#define GPS_I2C_ADDRESS_READ 0x21 //#define GPS_I2C_ADDRESS_READ 0x21
@ -16,15 +14,15 @@
//#define HAS_BUTTON GPIO_NUM_4 //#define HAS_BUTTON GPIO_NUM_4
// Hardware pin definitions for Pycom LoPy board // Hardware pin definitions for Pycom LoPy board
#define PIN_SPI_SS GPIO_NUM_17 #define PIN_SPI_SS GPIO_NUM_17
#define PIN_SPI_MOSI GPIO_NUM_27 #define PIN_SPI_MOSI GPIO_NUM_27
#define PIN_SPI_MISO GPIO_NUM_19 #define PIN_SPI_MISO GPIO_NUM_19
#define PIN_SPI_SCK GPIO_NUM_5 #define PIN_SPI_SCK GPIO_NUM_5
#define RST GPIO_NUM_18 #define RST GPIO_NUM_18
#define DIO0 GPIO_NUM_23 // LoRa IRQ #define DIO0 GPIO_NUM_23 // LoRa IRQ
#define DIO1 GPIO_NUM_23 // workaround #define DIO1 GPIO_NUM_23 // workaround
#define DIO2 LMIC_UNUSED_PIN #define DIO2 LMIC_UNUSED_PIN
// select WIFI antenna (internal = onboard / external = u.fl socket) // select WIFI antenna (internal = onboard / external = u.fl socket)
#define HAS_ANTENNA_SWITCH 16 // pin for switching wifi antenna #define HAS_ANTENNA_SWITCH 16 // pin for switching wifi antenna
#define WIFI_ANTENNA 0 // 0 = internal, 1 = external #define WIFI_ANTENNA 0 // 0 = internal, 1 = external

View File

@ -1,14 +1,12 @@
// Hardware related definitions for Pycom LoPy Board (not: LoPy4) // Hardware related definitions for Pycom LoPy Board (not: LoPy4)
#define CFG_sx1276_radio 1 #define CFG_sx1276_radio 1
#define HAS_LED \ #define HAS_LED NOT_A_PIN // LoPy4 has no on board LED, so we use RGB LED on LoPy4
NOT_A_PIN // LoPy4 has no on board LED, so we use RGB LED on LoPy4 #define HAS_RGB_LED GPIO_NUM_0 // WS2812B RGB LED on GPIO0
#define HAS_RGB_LED GPIO_NUM_0 // WS2812B RGB LED on GPIO0
// !!EXPERIMENTAL - not tested yet!!f // !!EXPERIMENTAL - not tested yet!!f
// uncomment this only if your LoPy lives on a Pytrack expansion board with GPS // uncomment this only if your LoPy lives on a Pytrack expansion board with GPS
// see // see http://www.quectel.com/UploadImage/Downlad/Quectel_L76-L_I2C_Application_Note_V1.0.pdf
// http://www.quectel.com/UploadImage/Downlad/Quectel_L76-L_I2C_Application_Note_V1.0.pdf
//#define HAS_GPS 1 //#define HAS_GPS 1
//#define GPS_I2C_PINS GPIO_NUM_9, GPIO_NUM_8 // SDA, SCL //#define GPS_I2C_PINS GPIO_NUM_9, GPIO_NUM_8 // SDA, SCL
//#define GPS_I2C_ADDRESS_READ 0x21 //#define GPS_I2C_ADDRESS_READ 0x21
@ -16,15 +14,15 @@
//#define HAS_BUTTON GPIO_NUM_4 //#define HAS_BUTTON GPIO_NUM_4
// Hardware pin definitions for Pycom LoPy4 board // Hardware pin definitions for Pycom LoPy4 board
#define PIN_SPI_SS GPIO_NUM_18 #define PIN_SPI_SS GPIO_NUM_18
#define PIN_SPI_MOSI GPIO_NUM_27 #define PIN_SPI_MOSI GPIO_NUM_27
#define PIN_SPI_MISO GPIO_NUM_19 #define PIN_SPI_MISO GPIO_NUM_19
#define PIN_SPI_SCK GPIO_NUM_5 #define PIN_SPI_SCK GPIO_NUM_5
#define RST LMIC_UNUSED_PIN #define RST LMIC_UNUSED_PIN
#define DIO0 GPIO_NUM_23 // LoRa IRQ #define DIO0 GPIO_NUM_23 // LoRa IRQ
#define DIO1 GPIO_NUM_23 // workaround #define DIO1 GPIO_NUM_23 // workaround
#define DIO2 LMIC_UNUSED_PIN #define DIO2 LMIC_UNUSED_PIN
// select WIFI antenna (internal = onboard / external = u.fl socket) // select WIFI antenna (internal = onboard / external = u.fl socket)
#define HAS_ANTENNA_SWITCH 21 // pin for switching wifi antenna #define HAS_ANTENNA_SWITCH 21 // pin for switching wifi antenna
#define WIFI_ANTENNA 0 // 0 = internal, 1 = external #define WIFI_ANTENNA 0 // 0 = internal, 1 = external

View File

@ -3,31 +3,20 @@
#define CFG_sx1276_radio 1 // HPD13A LoRa SoC #define CFG_sx1276_radio 1 // HPD13A LoRa SoC
#define HAS_LED GPIO_NUM_21 // on board green LED_G1 #define HAS_LED GPIO_NUM_21 // on board green LED_G1
//#define HAS_BUTTON GPIO_NUM_39 // on board button "BOOT" (next to reset //#define HAS_BUTTON GPIO_NUM_39 // on board button "BOOT" (next to reset button) !! seems not to work!!
// button) !! seems not to work!! #define HAS_BATTERY_PROBE ADC1_GPIO35_CHANNEL // battery probe GPIO pin -> ADC1_CHANNEL_7
#define HAS_BATTERY_PROBE \
ADC1_GPIO35_CHANNEL // battery probe GPIO pin -> ADC1_CHANNEL_7
#define BATT_FACTOR 2 // voltage divider 100k/100k on board #define BATT_FACTOR 2 // voltage divider 100k/100k on board
#define HAS_GPS 1 // use on board GPS #define HAS_GPS 1 // use on board GPS
#define GPS_SERIAL \ #define GPS_SERIAL 9600, SERIAL_8N1, GPIO_NUM_12, GPIO_NUM_15 // UBlox NEO 6M or 7M with default configuration
9600, SERIAL_8N1, GPIO_NUM_12, \
GPIO_NUM_15 // UBlox NEO 6M or 7M with default configuration
// re-define pin definitions of pins_arduino.h // re-define pin definitions of pins_arduino.h
#define PIN_SPI_SS \ #define PIN_SPI_SS GPIO_NUM_18 // ESP32 GPIO18 (Pin18) -- HPD13A NSS/SEL (Pin4) SPI Chip Select Input
GPIO_NUM_18 // ESP32 GPIO18 (Pin18) -- HPD13A NSS/SEL (Pin4) SPI Chip Select #define PIN_SPI_MOSI GPIO_NUM_27 // ESP32 GPIO27 (Pin27) -- HPD13A MOSI/DSI (Pin6) SPI Data Input
// Input #define PIN_SPI_MISO GPIO_NUM_19 // ESP32 GPIO19 (Pin19) -- HPD13A MISO/DSO (Pin7) SPI Data Output
#define PIN_SPI_MOSI \ #define PIN_SPI_SCK GPIO_NUM_5 // ESP32 GPIO5 (Pin5) -- HPD13A SCK (Pin5) SPI Clock Input
GPIO_NUM_27 // ESP32 GPIO27 (Pin27) -- HPD13A MOSI/DSI (Pin6) SPI Data Input
#define PIN_SPI_MISO \
GPIO_NUM_19 // ESP32 GPIO19 (Pin19) -- HPD13A MISO/DSO (Pin7) SPI Data Output
#define PIN_SPI_SCK \
GPIO_NUM_5 // ESP32 GPIO5 (Pin5) -- HPD13A SCK (Pin5) SPI Clock Input
// non arduino pin definitions // non arduino pin definitions
#define RST LMIC_UNUSED_PIN // connected to ESP32 RST/EN #define RST LMIC_UNUSED_PIN // connected to ESP32 RST/EN
#define DIO0 GPIO_NUM_26 // ESP32 GPIO26 <-> HPD13A IO0 #define DIO0 GPIO_NUM_26 // ESP32 GPIO26 <-> HPD13A IO0
#define DIO1 GPIO_NUM_33 // Lora1 <-> HPD13A IO1 // !! NEEDS EXTERNAL WIRING !! #define DIO1 GPIO_NUM_33 // Lora1 <-> HPD13A IO1 // !! NEEDS EXTERNAL WIRING !!
#define DIO2 \ #define DIO2 LMIC_UNUSED_PIN // Lora2 <-> HPD13A IO2 // needs external wiring, but not necessary for LoRa, only FSK
LMIC_UNUSED_PIN // Lora2 <-> HPD13A IO2 // needs external wiring, but not
// necessary for LoRa, only FSK

View File

@ -4,34 +4,21 @@
#define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C // OLED-Display on board #define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C // OLED-Display on board
//#define DISPLAY_FLIP 1 // uncomment this for rotated display //#define DISPLAY_FLIP 1 // uncomment this for rotated display
#define HAS_LED GPIO_NUM_2 // white LED on board #define HAS_LED GPIO_NUM_2 // white LED on board
#define LED_ACTIVE_LOW 1 // Onboard LED is active when pin is LOW #define LED_ACTIVE_LOW 1 // Onboard LED is active when pin is LOW
#define HAS_BUTTON GPIO_NUM_0 // button "PRG" on board #define HAS_BUTTON GPIO_NUM_0 // button "PRG" on board
// re-define pin definitions of pins_arduino.h // re-define pin definitions of pins_arduino.h
#define PIN_SPI_SS \ #define PIN_SPI_SS GPIO_NUM_18 // ESP32 GPIO18 (Pin18) -- SX1276 NSS (Pin19) SPI Chip Select Input
GPIO_NUM_18 // ESP32 GPIO18 (Pin18) -- SX1276 NSS (Pin19) SPI Chip Select #define PIN_SPI_MOSI GPIO_NUM_27 // ESP32 GPIO27 (Pin27) -- SX1276 MOSI (Pin18) SPI Data Input
// Input #define PIN_SPI_MISO GPIO_NUM_19 // ESP32 GPIO19 (Pin19) -- SX1276 MISO (Pin17) SPI Data Output
#define PIN_SPI_MOSI \ #define PIN_SPI_SCK GPIO_NUM_5 // ESP32 GPIO5 (Pin5) -- SX1276 SCK (Pin16) SPI Clock Input
GPIO_NUM_27 // ESP32 GPIO27 (Pin27) -- SX1276 MOSI (Pin18) SPI Data Input
#define PIN_SPI_MISO \
GPIO_NUM_19 // ESP32 GPIO19 (Pin19) -- SX1276 MISO (Pin17) SPI Data Output
#define PIN_SPI_SCK \
GPIO_NUM_5 // ESP32 GPIO5 (Pin5) -- SX1276 SCK (Pin16) SPI Clock Input
// non arduino pin definitions // non arduino pin definitions
#define RST \ #define RST GPIO_NUM_14 // ESP32 GPIO14 (Pin14) -- SX1276 NRESET (Pin7) Reset Trigger Input
GPIO_NUM_14 // ESP32 GPIO14 (Pin14) -- SX1276 NRESET (Pin7) Reset Trigger #define DIO0 GPIO_NUM_26 // ESP32 GPIO26 (Pin15) -- SX1276 DIO0 (Pin8) used by LMIC for detecting LoRa RX_Done & TX_Done
// Input #define DIO1 GPIO_NUM_33 // ESP32 GPIO33 (Pin13) -- SX1276 DIO1 (Pin9) used by LMIC for detecting LoRa RX_Timeout
#define DIO0 \ #define DIO2 LMIC_UNUSED_PIN // 32 ESP32 GPIO32 (Pin12) -- SX1276 DIO2 (Pin10) not used by LMIC for LoRa (Timeout for FSK only)
GPIO_NUM_26 // ESP32 GPIO26 (Pin15) -- SX1276 DIO0 (Pin8) used by LMIC for
// detecting LoRa RX_Done & TX_Done
#define DIO1 \
GPIO_NUM_33 // ESP32 GPIO33 (Pin13) -- SX1276 DIO1 (Pin9) used by LMIC for
// detecting LoRa RX_Timeout
#define DIO2 \
LMIC_UNUSED_PIN // 32 ESP32 GPIO32 (Pin12) -- SX1276 DIO2 (Pin10) not used by
// LMIC for LoRa (Timeout for FSK only)
// Hardware pin definitions for TTGOv1 Board with OLED SSD1306 I2C Display // Hardware pin definitions for TTGOv1 Board with OLED SSD1306 I2C Display
#define OLED_RST GPIO_NUM_16 // ESP32 GPIO16 (Pin16) -- SD1306 Reset #define OLED_RST GPIO_NUM_16 // ESP32 GPIO16 (Pin16) -- SD1306 Reset

View File

@ -4,37 +4,28 @@
#define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C #define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C
//#define DISPLAY_FLIP 1 // uncomment this for rotated display //#define DISPLAY_FLIP 1 // uncomment this for rotated display
#define HAS_LED \ #define HAS_LED NOT_A_PIN // on-board LED is wired to SCL (used by display) therefore totally useless
NOT_A_PIN // on-board LED is wired to SCL (used by display) therefore totally
// useless
// disable brownout detection (needed on TTGOv2 for battery powered operation) // disable brownout detection (needed on TTGOv2 for battery powered operation)
#define DISABLE_BROWNOUT 1 // comment out if you want to keep brownout feature #define DISABLE_BROWNOUT 1 // comment out if you want to keep brownout feature
// re-define pin definitions of pins_arduino.h // re-define pin definitions of pins_arduino.h
#define PIN_SPI_SS \ #define PIN_SPI_SS GPIO_NUM_18 // ESP32 GPIO18 (Pin18) -- HPD13A NSS/SEL (Pin4) SPI Chip Select Input
GPIO_NUM_18 // ESP32 GPIO18 (Pin18) -- HPD13A NSS/SEL (Pin4) SPI Chip Select #define PIN_SPI_MOSI GPIO_NUM_27 // ESP32 GPIO27 (Pin27) -- HPD13A MOSI/DSI (Pin6) SPI Data Input
// Input #define PIN_SPI_MISO GPIO_NUM_19 // ESP32 GPIO19 (Pin19) -- HPD13A MISO/DSO (Pin7) SPI Data Output
#define PIN_SPI_MOSI \ #define PIN_SPI_SCK GPIO_NUM_5 // ESP32 GPIO5 (Pin5) -- HPD13A SCK (Pin5) SPI Clock Input
GPIO_NUM_27 // ESP32 GPIO27 (Pin27) -- HPD13A MOSI/DSI (Pin6) SPI Data Input
#define PIN_SPI_MISO \
GPIO_NUM_19 // ESP32 GPIO19 (Pin19) -- HPD13A MISO/DSO (Pin7) SPI Data Output
#define PIN_SPI_SCK \
GPIO_NUM_5 // ESP32 GPIO5 (Pin5) -- HPD13A SCK (Pin5) SPI Clock Input
// non arduino pin definitions // non arduino pin definitions
#define RST LMIC_UNUSED_PIN // connected to ESP32 RST/EN #define RST LMIC_UNUSED_PIN // connected to ESP32 RST/EN
#define DIO0 GPIO_NUM_26 // ESP32 GPIO26 wired on PCB to HPD13A #define DIO0 GPIO_NUM_26 // ESP32 GPIO26 wired on PCB to HPD13A
#define DIO1 GPIO_NUM_33 // HPDIO1 on pcb, needs to be wired external to GPIO33 #define DIO1 GPIO_NUM_33 // HPDIO1 on pcb, needs to be wired external to GPIO33
#define DIO2 \ #define DIO2 LMIC_UNUSED_PIN // 32 HPDIO2 on pcb, needs to be wired external to GPIO32 (not necessary for LoRa, only FSK)
LMIC_UNUSED_PIN // 32 HPDIO2 on pcb, needs to be wired external to GPIO32 (not
// necessary for LoRa, only FSK)
// Hardware pin definitions for TTGO V2 Board with OLED SSD1306 0,96" I2C // Hardware pin definitions for TTGO V2 Board with OLED SSD1306 0,96" I2C Display
// Display
#define OLED_RST U8X8_PIN_NONE // connected to CPU RST/EN #define OLED_RST U8X8_PIN_NONE // connected to CPU RST/EN
#define OLED_SDA GPIO_NUM_21 // ESP32 GPIO4 (Pin4) -- SD1306 D1+D2 #define OLED_SDA GPIO_NUM_21 // ESP32 GPIO4 (Pin4) -- SD1306 D1+D2
#define OLED_SCL GPIO_NUM_22 // ESP32 GPIO15 (Pin15) -- SD1306 D0 #define OLED_SCL GPIO_NUM_22 // ESP32 GPIO15 (Pin15) -- SD1306 D0
/* /*
ESP32 LoRa module (SPI) OLED display (I2C) ESP32 LoRa module (SPI) OLED display (I2C)
@ -57,6 +48,6 @@
{2} Must be manually wired! {2} Must be manually wired!
DIO2 is wired to a separate pin but is not wired on-board to pin/GPIO32. DIO2 is wired to a separate pin but is not wired on-board to pin/GPIO32.
Explicitly wire board pin labeled DIO2 to pin 32 (see TTGO V2.0 pinout). Explicitly wire board pin labeled DIO2 to pin 32 (see TTGO V2.0 pinout).
{3} The on-board LED is wired to SCL (used by display) therefore totally {3} The on-board LED is wired to SCL (used by display) therefore totally useless!
useless!
*/ */

View File

@ -3,32 +3,24 @@
#define CFG_sx1276_radio 1 // HPD13A LoRa SoC #define CFG_sx1276_radio 1 // HPD13A LoRa SoC
#define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C #define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C
#define DISPLAY_FLIP 1 // rotated display #define DISPLAY_FLIP 1 // rotated display
#define HAS_LED \ #define HAS_LED GPIO_NUM_23 // green on board LED_G3 (not in initial board version)
GPIO_NUM_23 // green on board LED_G3 (not in initial board version) #define HAS_BATTERY_PROBE ADC1_GPIO35_CHANNEL // battery probe GPIO pin -> ADC1_CHANNEL_7
#define HAS_BATTERY_PROBE \
ADC1_GPIO35_CHANNEL // battery probe GPIO pin -> ADC1_CHANNEL_7
#define BATT_FACTOR 2 // voltage divider 100k/100k on board #define BATT_FACTOR 2 // voltage divider 100k/100k on board
// re-define pin definitions of pins_arduino.h // re-define pin definitions of pins_arduino.h
#define PIN_SPI_SS \ #define PIN_SPI_SS GPIO_NUM_18 // ESP32 GPIO18 (Pin18) -- HPD13A NSS/SEL (Pin4) SPI Chip Select Input
GPIO_NUM_18 // ESP32 GPIO18 (Pin18) -- HPD13A NSS/SEL (Pin4) SPI Chip Select #define PIN_SPI_MOSI GPIO_NUM_27 // ESP32 GPIO27 (Pin27) -- HPD13A MOSI/DSI (Pin6) SPI Data Input
// Input #define PIN_SPI_MISO GPIO_NUM_19 // ESP32 GPIO19 (Pin19) -- HPD13A MISO/DSO (Pin7) SPI Data Output
#define PIN_SPI_MOSI \ #define PIN_SPI_SCK GPIO_NUM_5 // ESP32 GPIO5 (Pin5) -- HPD13A SCK (Pin5) SPI Clock Input
GPIO_NUM_27 // ESP32 GPIO27 (Pin27) -- HPD13A MOSI/DSI (Pin6) SPI Data Input
#define PIN_SPI_MISO \
GPIO_NUM_19 // ESP32 GPIO19 (Pin19) -- HPD13A MISO/DSO (Pin7) SPI Data Output
#define PIN_SPI_SCK \
GPIO_NUM_5 // ESP32 GPIO5 (Pin5) -- HPD13A SCK (Pin5) SPI Clock Input
// non arduino pin definitions // non arduino pin definitions
#define RST LMIC_UNUSED_PIN // connected to ESP32 RST/EN #define RST LMIC_UNUSED_PIN // connected to ESP32 RST/EN
#define DIO0 GPIO_NUM_26 // ESP32 GPIO26 <-> HPD13A IO0 #define DIO0 GPIO_NUM_26 // ESP32 GPIO26 <-> HPD13A IO0
#define DIO1 GPIO_NUM_33 // ESP32 GPIO33 <-> HPDIO1 <-> HPD13A IO1 #define DIO1 GPIO_NUM_33 // ESP32 GPIO33 <-> HPDIO1 <-> HPD13A IO1
#define DIO2 GPIO_NUM_32 // ESP32 GPIO32 <-> HPDIO2 <-> HPD13A IO2 #define DIO2 GPIO_NUM_32 // ESP32 GPIO32 <-> HPDIO2 <-> HPD13A IO2
// Hardware pin definitions for TTGO V2 Board with OLED SSD1306 0,96" I2C // Hardware pin definitions for TTGO V2 Board with OLED SSD1306 0,96" I2C Display
// Display
#define OLED_RST U8X8_PIN_NONE // connected to CPU RST/EN #define OLED_RST U8X8_PIN_NONE // connected to CPU RST/EN
#define OLED_SDA GPIO_NUM_21 // ESP32 GPIO4 (Pin4) -- SD1306 D1+D2 #define OLED_SDA GPIO_NUM_21 // ESP32 GPIO4 (Pin4) -- SD1306 D1+D2
#define OLED_SCL GPIO_NUM_22 // ESP32 GPIO15 (Pin15) -- SD1306 D0 #define OLED_SCL GPIO_NUM_22 // ESP32 GPIO15 (Pin15) -- SD1306 D0

View File

@ -1,31 +1,28 @@
/************************************************************ /************************************************************
* LMIC LoRaWAN configuration * LMIC LoRaWAN configuration
* *
* Read the values from TTN console (or whatever applies), insert them here, * Read the values from TTN console (or whatever applies), insert them here,
* and rename this file to src/loraconf.h * and rename this file to src/loraconf.h
* *
* Note that DEVEUI, APPEUI and APPKEY should all be specified in MSB format. * Note that DEVEUI, APPEUI and APPKEY should all be specified in MSB format.
* (This is different from standard LMIC-Arduino which expects DEVEUI and APPEUI * (This is different from standard LMIC-Arduino which expects DEVEUI and APPEUI in LSB format.)
in LSB format.)
* Set your DEVEUI here, if you have one. You can leave this untouched, * Set your DEVEUI here, if you have one. You can leave this untouched,
* then the DEVEUI will be generated during runtime from device's MAC adress * then the DEVEUI will be generated during runtime from device's MAC adress
* and will be displayed on device's screen as well as on serial console. * and will be displayed on device's screen as well as on serial console.
* *
* NOTE: Use MSB format (as displayed in TTN console, so you can cut & paste * NOTE: Use MSB format (as displayed in TTN console, so you can cut & paste from there)
from there)
* For TTN, APPEUI in MSB format always starts with 0x70, 0xB3, 0xD5 * For TTN, APPEUI in MSB format always starts with 0x70, 0xB3, 0xD5
* *
* Note: If using a board with Microchip 24AA02E64 Uinique ID for deveui, * Note: If using a board with Microchip 24AA02E64 Uinique ID for deveui,
* the DEVEUI will be overwriten by the one contained in the Microchip module * the DEVEUI will be overwriten by the one contained in the Microchip module
* *
************************************************************/ ************************************************************/
#include <Arduino.h> #include <Arduino.h>
static const u1_t DEVEUI[8] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; static const u1_t DEVEUI[8]={ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
static const u1_t APPEUI[8] = {0x70, 0xB3, 0xD5, 0x00, 0x00, 0x00, 0x00, 0x00}; static const u1_t APPEUI[8]={ 0x70, 0xB3, 0xD5, 0x00, 0x00, 0x00, 0x00, 0x00 };
static const u1_t APPKEY[16] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, static const u1_t APPKEY[16] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 };
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};

View File

@ -3,11 +3,11 @@
// LMIC-Arduino LoRaWAN Stack // LMIC-Arduino LoRaWAN Stack
#include "loraconf.h" #include "loraconf.h"
#include <hal/hal.h>
#include <lmic.h> #include <lmic.h>
#include <hal/hal.h>
#ifdef MCP_24AA02E64_I2C_ADDRESS #ifdef MCP_24AA02E64_I2C_ADDRESS
#include <Wire.h> // Needed for 24AA02E64, does not hurt anything if included and not used #include <Wire.h> // Needed for 24AA02E64, does not hurt anything if included and not used
#endif #endif
// Local logging Tag // Local logging Tag
@ -19,257 +19,219 @@ void switch_lora(uint8_t sf, uint8_t tx);
// DevEUI generator using devices's MAC address // DevEUI generator using devices's MAC address
void gen_lora_deveui(uint8_t *pdeveui) { void gen_lora_deveui(uint8_t *pdeveui) {
uint8_t *p = pdeveui, dmac[6]; uint8_t *p = pdeveui, dmac[6];
int i = 0; int i = 0;
esp_efuse_mac_get_default(dmac); esp_efuse_mac_get_default(dmac);
// deveui is LSB, we reverse it so TTN DEVEUI display // deveui is LSB, we reverse it so TTN DEVEUI display
// will remain the same as MAC address // will remain the same as MAC address
// MAC is 6 bytes, devEUI 8, set first 2 ones // MAC is 6 bytes, devEUI 8, set first 2 ones
// with an arbitrary value // with an arbitrary value
*p++ = 0xFF; *p++ = 0xFF;
*p++ = 0xFE; *p++ = 0xFE;
// Then next 6 bytes are mac address reversed // Then next 6 bytes are mac address reversed
for (i = 0; i < 6; i++) { for ( i=0; i<6 ; i++) {
*p++ = dmac[5 - i]; *p++ = dmac[5-i];
} }
} }
// Function to do a byte swap in a byte array // Function to do a byte swap in a byte array
void RevBytes(unsigned char *b, size_t c) { void RevBytes(unsigned char* b, size_t c)
{
u1_t i; u1_t i;
for (i = 0; i < c / 2; i++) { for (i = 0; i < c / 2; i++)
unsigned char t = b[i]; { unsigned char t = b[i];
b[i] = b[c - 1 - i]; b[i] = b[c - 1 - i];
b[c - 1 - i] = t; b[c - 1 - i] = t; }
}
} }
void get_hard_deveui(uint8_t *pdeveui) { void get_hard_deveui(uint8_t *pdeveui) {
// read DEVEUI from Microchip 24AA02E64 2Kb serial eeprom if present // read DEVEUI from Microchip 24AA02E64 2Kb serial eeprom if present
#ifdef MCP_24AA02E64_I2C_ADDRESS #ifdef MCP_24AA02E64_I2C_ADDRESS
uint8_t i2c_ret; uint8_t i2c_ret;
// Init this just in case, no more to 100KHz // Init this just in case, no more to 100KHz
Wire.begin(OLED_SDA, OLED_SCL, 100000); Wire.begin(OLED_SDA, OLED_SCL, 100000);
Wire.beginTransmission(MCP_24AA02E64_I2C_ADDRESS);
Wire.write(MCP_24AA02E64_MAC_ADDRESS);
i2c_ret = Wire.endTransmission();
// check if device seen on i2c bus
if (i2c_ret == 0) {
char deveui[32] = "";
uint8_t data;
Wire.beginTransmission(MCP_24AA02E64_I2C_ADDRESS); Wire.beginTransmission(MCP_24AA02E64_I2C_ADDRESS);
Wire.write(MCP_24AA02E64_MAC_ADDRESS); Wire.write(MCP_24AA02E64_MAC_ADDRESS);
Wire.requestFrom(MCP_24AA02E64_I2C_ADDRESS, 8);
while (Wire.available()) {
data = Wire.read();
sprintf(deveui + strlen(deveui), "%02X ", data);
*pdeveui++ = data;
}
i2c_ret = Wire.endTransmission(); i2c_ret = Wire.endTransmission();
ESP_LOGI(TAG, "Serial EEPROM 24AA02E64 found, read DEVEUI %s", deveui); // check if device seen on i2c bus
} else { if (i2c_ret == 0) {
ESP_LOGI(TAG, "Serial EEPROM 24AA02E64 not found ret=%d", i2c_ret); char deveui[32]="";
} uint8_t data;
// Set back to 400KHz to speed up OLED Wire.beginTransmission(MCP_24AA02E64_I2C_ADDRESS);
Wire.setClock(400000); Wire.write(MCP_24AA02E64_MAC_ADDRESS);
#endif // MCP 24AA02E64 Wire.requestFrom(MCP_24AA02E64_I2C_ADDRESS, 8);
while (Wire.available()) {
data = Wire.read();
sprintf(deveui+strlen(deveui), "%02X ", data);
*pdeveui++ = data;
}
i2c_ret = Wire.endTransmission();
ESP_LOGI(TAG, "Serial EEPROM 24AA02E64 found, read DEVEUI %s", deveui);
} else {
ESP_LOGI(TAG, "Serial EEPROM 24AA02E64 not found ret=%d", i2c_ret);
}
// Set back to 400KHz to speed up OLED
Wire.setClock(400000);
#endif // MCP 24AA02E64
} }
#ifdef VERBOSE #ifdef VERBOSE
// Display a key // Display a key
void printKey(const char *name, const uint8_t *key, uint8_t len, bool lsb) { void printKey(const char * name, const uint8_t * key, uint8_t len, bool lsb) {
const uint8_t *p; const uint8_t * p ;
char keystring[len + 1] = "", keybyte[3]; char keystring[len+1] = "", keybyte[3];
for (uint8_t i = 0; i < len; i++) { for (uint8_t i=0; i<len ; i++) {
p = lsb ? key + len - i - 1 : key + i; p = lsb ? key+len-i-1 : key+i;
sprintf(keybyte, "%02X", *p); sprintf(keybyte, "%02X", * p);
strncat(keystring, keybyte, 2); strncat(keystring, keybyte, 2);
} }
ESP_LOGI(TAG, "%s: %s", name, keystring); ESP_LOGI(TAG, "%s: %s", name, keystring);
} }
// Display OTAA keys // Display OTAA keys
void printKeys(void) { void printKeys(void) {
// LMIC may not have used callback to fill // LMIC may not have used callback to fill
// all EUI buffer so we do it here to a temp // all EUI buffer so we do it here to a temp
// buffer to be able to display them // buffer to be able to display them
uint8_t buf[32]; uint8_t buf[32];
os_getDevEui((u1_t *)buf); os_getDevEui((u1_t*) buf);
printKey("DevEUI", buf, 8, true); printKey("DevEUI", buf, 8, true);
os_getArtEui((u1_t *)buf); os_getArtEui((u1_t*) buf);
printKey("AppEUI", buf, 8, true); printKey("AppEUI", buf, 8, true);
os_getDevKey((u1_t *)buf); os_getDevKey((u1_t*) buf);
printKey("AppKey", buf, 16, false); printKey("AppKey", buf, 16, false);
} }
#endif // VERBOSE #endif // VERBOSE
void do_send(osjob_t *j) { void do_send(osjob_t* j){
// Check if there is a pending TX/RX job running // Check if there is a pending TX/RX job running
if (LMIC.opmode & OP_TXRXPEND) { if (LMIC.opmode & OP_TXRXPEND) {
ESP_LOGI(TAG, "LoRa busy, rescheduling"); ESP_LOGI(TAG, "LoRa busy, rescheduling");
sprintf(display_lmic, "LORA BUSY"); sprintf(display_lmic, "LORA BUSY");
goto end; goto end;
} }
// prepare payload with sum of unique WIFI MACs seen // prepare payload with sum of unique WIFI MACs seen
static uint8_t mydata[4]; static uint8_t mydata[4];
mydata[0] = (macs_wifi & 0xff00) >> 8; mydata[0] = (macs_wifi & 0xff00) >> 8;
mydata[1] = macs_wifi & 0xff; mydata[1] = macs_wifi & 0xff;
if (cfg.blescan) {
// append sum of unique BLE MACs seen to payload
mydata[2] = (macs_ble & 0xff00) >> 8;
mydata[3] = macs_ble & 0xff;
} else {
mydata[2] = 0;
mydata[3] = 0;
}
if (cfg.blescan) { #ifdef HAS_GPS
// append sum of unique BLE MACs seen to payload static uint8_t gpsdata[18];
mydata[2] = (macs_ble & 0xff00) >> 8; if (cfg.gpsmode && gps.location.isValid()) {
mydata[3] = macs_ble & 0xff; gps_read();
} else { memcpy (gpsdata, mydata, 4);
mydata[2] = 0; memcpy (gpsdata+4, &gps_status, sizeof(gps_status));
mydata[3] = 0; ESP_LOGI(TAG, "lat=%.6f / lon=%.6f | %u Sats | HDOP=%.1f | Altitude=%u m", \
} gps_status.latitude / (float) 1000000, \
gps_status.longitude / (float) 1000000, \
gps_status.satellites, \
gps_status.hdop / (float) 100, \
gps_status.altitude);
LMIC_setTxData2(COUNTERPORT, gpsdata, sizeof(gpsdata), (cfg.countermode & 0x02));
ESP_LOGI(TAG, "%d bytes queued to send", sizeof(gpsdata));
}
else {
#endif
LMIC_setTxData2(COUNTERPORT, mydata, sizeof(mydata), (cfg.countermode & 0x02));
ESP_LOGI(TAG, "%d bytes queued to send", sizeof(mydata));
sprintf(display_lmic, "PACKET QUEUED");
#ifdef HAS_GPS #ifdef HAS_GPS
static uint8_t gpsdata[18]; }
if (cfg.gpsmode && gps.location.isValid()) { #endif
gps_read();
memcpy(gpsdata, mydata, 4); // clear counter if not in cumulative counter mode
memcpy(gpsdata + 4, &gps_status, sizeof(gps_status)); if (cfg.countermode != 1) {
ESP_LOGI(TAG, "lat=%.6f / lon=%.6f | %u Sats | HDOP=%.1f | Altitude=%u m", reset_counters(); // clear macs container and reset all counters
gps_status.latitude / (float)1000000, reset_salt(); // get new salt for salting hashes
gps_status.longitude / (float)1000000, gps_status.satellites, ESP_LOGI(TAG, "Counter cleared (countermode = %d)", cfg.countermode);
gps_status.hdop / (float)100, gps_status.altitude); }
LMIC_setTxData2(COUNTERPORT, gpsdata, sizeof(gpsdata),
(cfg.countermode & 0x02));
ESP_LOGI(TAG, "%d bytes queued to send", sizeof(gpsdata));
} else {
#endif
LMIC_setTxData2(COUNTERPORT, mydata, sizeof(mydata),
(cfg.countermode & 0x02));
ESP_LOGI(TAG, "%d bytes queued to send", sizeof(mydata));
sprintf(display_lmic, "PACKET QUEUED");
#ifdef HAS_GPS // Schedule next transmission
} end:
#endif os_setTimedCallback(&sendjob, os_getTime()+sec2osticks(cfg.sendcycle * 2), do_send);
// clear counter if not in cumulative counter mode
if (cfg.countermode != 1) {
reset_counters(); // clear macs container and reset all counters
reset_salt(); // get new salt for salting hashes
ESP_LOGI(TAG, "Counter cleared (countermode = %d)", cfg.countermode);
}
// Schedule next transmission
end:
os_setTimedCallback(&sendjob, os_getTime() + sec2osticks(cfg.sendcycle * 2),
do_send);
} // do_send() } // do_send()
void onEvent(ev_t ev) { void onEvent (ev_t ev) {
char buff[24] = ""; char buff[24]="";
switch (ev) { switch(ev) {
case EV_SCAN_TIMEOUT: case EV_SCAN_TIMEOUT: strcpy_P(buff, PSTR("SCAN TIMEOUT")); break;
strcpy_P(buff, PSTR("SCAN TIMEOUT")); case EV_BEACON_FOUND: strcpy_P(buff, PSTR("BEACON FOUND")); break;
break; case EV_BEACON_MISSED: strcpy_P(buff, PSTR("BEACON MISSED")); break;
case EV_BEACON_FOUND: case EV_BEACON_TRACKED: strcpy_P(buff, PSTR("BEACON TRACKED")); break;
strcpy_P(buff, PSTR("BEACON FOUND")); case EV_JOINING: strcpy_P(buff, PSTR("JOINING")); break;
break; case EV_LOST_TSYNC: strcpy_P(buff, PSTR("LOST TSYNC")); break;
case EV_BEACON_MISSED: case EV_RESET: strcpy_P(buff, PSTR("RESET")); break;
strcpy_P(buff, PSTR("BEACON MISSED")); case EV_RXCOMPLETE: strcpy_P(buff, PSTR("RX COMPLETE")); break;
break; case EV_LINK_DEAD: strcpy_P(buff, PSTR("LINK DEAD")); break;
case EV_BEACON_TRACKED: case EV_LINK_ALIVE: strcpy_P(buff, PSTR("LINK ALIVE")); break;
strcpy_P(buff, PSTR("BEACON TRACKED")); case EV_RFU1: strcpy_P(buff, PSTR("RFUI")); break;
break; case EV_JOIN_FAILED: strcpy_P(buff, PSTR("JOIN FAILED")); break;
case EV_JOINING: case EV_REJOIN_FAILED: strcpy_P(buff, PSTR("REJOIN FAILED")); break;
strcpy_P(buff, PSTR("JOINING"));
break; case EV_JOINED:
case EV_LOST_TSYNC:
strcpy_P(buff, PSTR("LOST TSYNC"));
break;
case EV_RESET:
strcpy_P(buff, PSTR("RESET"));
break;
case EV_RXCOMPLETE:
strcpy_P(buff, PSTR("RX COMPLETE"));
break;
case EV_LINK_DEAD:
strcpy_P(buff, PSTR("LINK DEAD"));
break;
case EV_LINK_ALIVE:
strcpy_P(buff, PSTR("LINK ALIVE"));
break;
case EV_RFU1:
strcpy_P(buff, PSTR("RFUI"));
break;
case EV_JOIN_FAILED:
strcpy_P(buff, PSTR("JOIN FAILED"));
break;
case EV_REJOIN_FAILED:
strcpy_P(buff, PSTR("REJOIN FAILED"));
break;
case EV_JOINED: strcpy_P(buff, PSTR("JOINED"));
sprintf(display_lora, " "); // clear previous lmic status message from display
strcpy_P(buff, PSTR("JOINED")); // set data rate adaptation
sprintf(display_lora, LMIC_setAdrMode(cfg.adrmode);
" "); // clear previous lmic status message from display // Set data rate and transmit power (note: txpower seems to be ignored by the library)
switch_lora(cfg.lorasf,cfg.txpower);
// show effective LoRa parameters after join
ESP_LOGI(TAG, "ADR=%d, SF=%d, TXPOWER=%d", cfg.adrmode, cfg.lorasf, cfg.txpower);
break;
// set data rate adaptation case EV_TXCOMPLETE:
LMIC_setAdrMode(cfg.adrmode);
// Set data rate and transmit power (note: txpower seems to be ignored by
// the library)
switch_lora(cfg.lorasf, cfg.txpower);
// show effective LoRa parameters after join strcpy_P(buff, (LMIC.txrxFlags & TXRX_ACK) ? PSTR("RECEIVED ACK") : PSTR("TX COMPLETE"));
ESP_LOGI(TAG, "ADR=%d, SF=%d, TXPOWER=%d", cfg.adrmode, cfg.lorasf, sprintf(display_lora, " "); // clear previous lmic status message from display
cfg.txpower);
break; if (LMIC.dataLen) {
ESP_LOGI(TAG, "Received %d bytes of payload, RSSI %d SNR %d", LMIC.dataLen, LMIC.rssi, (signed char)LMIC.snr / 4);
// LMIC.snr = SNR twos compliment [dB] * 4
// LMIC.rssi = RSSI [dBm] (-196...+63)
sprintf(display_lora, "RSSI %d SNR %d", LMIC.rssi, (signed char)LMIC.snr / 4 );
case EV_TXCOMPLETE: // check if payload received on command port, then call remote command interpreter
if ( (LMIC.txrxFlags & TXRX_PORT) && (LMIC.frame[LMIC.dataBeg-1] == RCMDPORT ) ) {
// caution: buffering LMIC values here because rcommand() can modify LMIC.frame
unsigned char* buffer = new unsigned char[MAX_LEN_FRAME];
memcpy(buffer, LMIC.frame, MAX_LEN_FRAME); //Copy data from cfg to char*
int i, k = LMIC.dataBeg, l = LMIC.dataBeg+LMIC.dataLen-2;
for (i=k; i<=l; i+=2) {
rcommand(buffer[i], buffer[i+1]);
}
delete[] buffer; //free memory
}
}
break;
strcpy_P(buff, (LMIC.txrxFlags & TXRX_ACK) ? PSTR("RECEIVED ACK") default: sprintf_P(buff, PSTR("UNKNOWN EVENT %d"), ev); break;
: PSTR("TX COMPLETE"));
sprintf(display_lora,
" "); // clear previous lmic status message from display
if (LMIC.dataLen) {
ESP_LOGI(TAG, "Received %d bytes of payload, RSSI %d SNR %d",
LMIC.dataLen, LMIC.rssi, (signed char)LMIC.snr / 4);
// LMIC.snr = SNR twos compliment [dB] * 4
// LMIC.rssi = RSSI [dBm] (-196...+63)
sprintf(display_lora, "RSSI %d SNR %d", LMIC.rssi,
(signed char)LMIC.snr / 4);
// check if payload received on command port, then call remote command
// interpreter
if ((LMIC.txrxFlags & TXRX_PORT) &&
(LMIC.frame[LMIC.dataBeg - 1] == RCMDPORT)) {
// caution: buffering LMIC values here because rcommand() can modify
// LMIC.frame
unsigned char *buffer = new unsigned char[MAX_LEN_FRAME];
memcpy(buffer, LMIC.frame, MAX_LEN_FRAME); // Copy data from cfg to
// char*
int i, k = LMIC.dataBeg, l = LMIC.dataBeg + LMIC.dataLen - 2;
for (i = k; i <= l; i += 2) {
rcommand(buffer[i], buffer[i + 1]);
}
delete[] buffer; // free memory
}
} }
break;
default:
sprintf_P(buff, PSTR("UNKNOWN EVENT %d"), ev);
break;
}
// Log & Display if asked
if (*buff) {
ESP_LOGI(TAG, "EV_%s", buff);
sprintf(display_lmic, buff);
}
// Log & Display if asked
if (*buff) {
ESP_LOGI(TAG, "EV_%s", buff);
sprintf(display_lmic, buff);
}
} // onEvent() } // onEvent()

View File

@ -2,9 +2,9 @@
#define LORAWAN_H #define LORAWAN_H
void onEvent(ev_t ev); void onEvent(ev_t ev);
void do_send(osjob_t *j); void do_send(osjob_t* j);
void gen_lora_deveui(uint8_t *pdeveui); void gen_lora_deveui(uint8_t * pdeveui);
void RevBytes(unsigned char *b, size_t c); void RevBytes(unsigned char* b, size_t c);
void get_hard_deveui(uint8_t *pdeveui); void get_hard_deveui(uint8_t *pdeveui);
#endif #endif

View File

@ -3,136 +3,114 @@
#include "globals.h" #include "globals.h"
#ifdef VENDORFILTER #ifdef VENDORFILTER
#include "vendor_array.h" #include "vendor_array.h"
#endif #endif
// Local logging tag // Local logging tag
static const char TAG[] = "wifi"; static const char TAG[] = "wifi";
static wifi_country_t wifi_country = {.cc = WIFI_MY_COUNTRY, static wifi_country_t wifi_country = {.cc=WIFI_MY_COUNTRY, .schan=WIFI_CHANNEL_MIN, .nchan=WIFI_CHANNEL_MAX, .policy=WIFI_COUNTRY_POLICY_MANUAL};
.schan = WIFI_CHANNEL_MIN,
.nchan = WIFI_CHANNEL_MAX,
.policy = WIFI_COUNTRY_POLICY_MANUAL};
// globals // globals
uint16_t salt; uint16_t salt;
uint16_t reset_salt(void) { uint16_t reset_salt(void) {
salt = random( salt = random(65536); // get new 16bit random for salting hashes and set global salt var
65536); // get new 16bit random for salting hashes and set global salt var return salt;
return salt;
} }
bool mac_add(uint8_t *paddr, int8_t rssi, bool sniff_type) { bool mac_add(uint8_t *paddr, int8_t rssi, bool sniff_type) {
char buff[16]; // temporary buffer for printf char buff[16]; // temporary buffer for printf
bool added = false; bool added = false;
uint32_t addr2int, vendor2int; // temporary buffer for MAC and Vendor OUI uint32_t addr2int, vendor2int; // temporary buffer for MAC and Vendor OUI
uint16_t hashedmac; // temporary buffer for generated hash value uint16_t hashedmac; // temporary buffer for generated hash value
// only last 3 MAC Address bytes are used for MAC address anonymization // only last 3 MAC Address bytes are used for MAC address anonymization
// but since it's uint32 we take 4 bytes to avoid 1st value to be 0 // but since it's uint32 we take 4 bytes to avoid 1st value to be 0
addr2int = ((uint32_t)paddr[2]) | ((uint32_t)paddr[3] << 8) | addr2int = ( (uint32_t)paddr[2] ) | ( (uint32_t)paddr[3] << 8 ) | ( (uint32_t)paddr[4] << 16 ) | ( (uint32_t)paddr[5] << 24 );
((uint32_t)paddr[4] << 16) | ((uint32_t)paddr[5] << 24);
#ifdef VENDORFILTER #ifdef VENDORFILTER
vendor2int = ((uint32_t)paddr[2]) | ((uint32_t)paddr[1] << 8) | vendor2int = ( (uint32_t)paddr[2] ) | ( (uint32_t)paddr[1] << 8 ) | ( (uint32_t)paddr[0] << 16 );
((uint32_t)paddr[0] << 16); // use OUI vendor filter list only on Wifi, not on BLE
// use OUI vendor filter list only on Wifi, not on BLE if ( (sniff_type==MAC_SNIFF_BLE) || std::find(vendors.begin(), vendors.end(), vendor2int) != vendors.end() )
if ((sniff_type == MAC_SNIFF_BLE) || {
std::find(vendors.begin(), vendors.end(), vendor2int) != vendors.end()) { #endif
#endif
// salt and hash MAC, and if new unique one, store identifier in container // salt and hash MAC, and if new unique one, store identifier in container and increment counter on display
// and increment counter on display // https://en.wikipedia.org/wiki/MAC_Address_Anonymization
// https://en.wikipedia.org/wiki/MAC_Address_Anonymization
addr2int += (uint32_t)salt; // add 16-bit salt to pseudo MAC
addr2int += (uint32_t)salt; // add 16-bit salt to pseudo MAC snprintf(buff, sizeof(buff), "%08X", addr2int); // convert unsigned 32-bit salted MAC to 8 digit hex string
snprintf( hashedmac = rokkit(&buff[3], 5); // hash MAC last string value, use 5 chars to fit hash in uint16_t container
buff, sizeof(buff), "%08X", auto newmac = macs.insert(hashedmac); // add hashed MAC to total container if new unique
addr2int); // convert unsigned 32-bit salted MAC to 8 digit hex string added = newmac.second ? true:false; // true if hashed MAC is unique in container
hashedmac = rokkit(&buff[3], 5); // hash MAC last string value, use 5 chars
// to fit hash in uint16_t container
auto newmac = macs.insert(
hashedmac); // add hashed MAC to total container if new unique
added = newmac.second ? true
: false; // true if hashed MAC is unique in container
// Count only if MAC was not yet seen // Count only if MAC was not yet seen
if (added) { if (added) {
// increment counter and one blink led // increment counter and one blink led
if (sniff_type == MAC_SNIFF_WIFI) { if (sniff_type == MAC_SNIFF_WIFI ) {
macs_wifi++; // increment Wifi MACs counter macs_wifi++; // increment Wifi MACs counter
#if (HAS_LED != NOT_A_PIN) || defined(HAS_RGB_LED) #if (HAS_LED != NOT_A_PIN) || defined (HAS_RGB_LED)
blink_LED(COLOR_GREEN, 50); blink_LED(COLOR_GREEN, 50);
#endif #endif
} }
#ifdef BLECOUNTER #ifdef BLECOUNTER
else if (sniff_type == MAC_SNIFF_BLE) { else if (sniff_type == MAC_SNIFF_BLE ) {
macs_ble++; // increment BLE Macs counter macs_ble++; // increment BLE Macs counter
#if (HAS_LED != NOT_A_PIN) || defined(HAS_RGB_LED) #if (HAS_LED != NOT_A_PIN) || defined (HAS_RGB_LED)
blink_LED(COLOR_MAGENTA, 50); blink_LED(COLOR_MAGENTA, 50);
#endif #endif
} }
#endif #endif
} }
// Log scan result // Log scan result
ESP_LOGI(TAG, ESP_LOGI(TAG, "%s %s RSSI %ddBi -> MAC %s -> Hash %04X -> WiFi:%d BLTH:%d -> %d Bytes left",
"%s %s RSSI %ddBi -> MAC %s -> Hash %04X -> WiFi:%d BLTH:%d -> " added ? "new " : "known",
"%d Bytes left", sniff_type==MAC_SNIFF_WIFI ? "WiFi":"BLTH",
added ? "new " : "known", rssi, buff, hashedmac, macs_wifi, macs_ble,
sniff_type == MAC_SNIFF_WIFI ? "WiFi" : "BLTH", rssi, buff, ESP.getFreeHeap());
hashedmac, macs_wifi, macs_ble, ESP.getFreeHeap());
#ifdef VENDORFILTER #ifdef VENDORFILTER
} else { } else {
// Very noisy // Very noisy
// ESP_LOGD(TAG, "Filtered MAC %02X:%02X:%02X:%02X:%02X:%02X", // ESP_LOGD(TAG, "Filtered MAC %02X:%02X:%02X:%02X:%02X:%02X", paddr[0],paddr[1],paddr[2],paddr[3],paddr[5],paddr[5]);
// paddr[0],paddr[1],paddr[2],paddr[3],paddr[5],paddr[5]); }
} #endif
#endif
// True if MAC WiFi/BLE was new // True if MAC WiFi/BLE was new
return added; // function returns bool if a new and unique Wifi or BLE mac was return added; // function returns bool if a new and unique Wifi or BLE mac was counted (true) or not (false)
// counted (true) or not (false)
} }
void wifi_sniffer_init(void) { void wifi_sniffer_init(void) {
wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT(); wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT();
cfg.nvs_enable = 0; // we don't need any wifi settings from NVRAM cfg.nvs_enable = 0; // we don't need any wifi settings from NVRAM
wifi_promiscuous_filter_t filter = { wifi_promiscuous_filter_t filter = {.filter_mask = WIFI_PROMIS_FILTER_MASK_MGMT}; // we need only MGMT frames
.filter_mask = WIFI_PROMIS_FILTER_MASK_MGMT}; // we need only MGMT frames ESP_ERROR_CHECK(esp_wifi_init(&cfg)); // configure Wifi with cfg
ESP_ERROR_CHECK(esp_wifi_init(&cfg)); // configure Wifi with cfg ESP_ERROR_CHECK(esp_wifi_set_country(&wifi_country)); // set locales for RF and channels
ESP_ERROR_CHECK( ESP_ERROR_CHECK(esp_wifi_set_storage(WIFI_STORAGE_RAM)); // we don't need NVRAM
esp_wifi_set_country(&wifi_country)); // set locales for RF and channels //ESP_ERROR_CHECK(esp_wifi_set_mode(WIFI_MODE_NULL));
ESP_ERROR_CHECK( ESP_ERROR_CHECK(esp_wifi_set_promiscuous_filter(&filter)); // set MAC frame filter
esp_wifi_set_storage(WIFI_STORAGE_RAM)); // we don't need NVRAM ESP_ERROR_CHECK(esp_wifi_set_promiscuous_rx_cb(&wifi_sniffer_packet_handler));
// ESP_ERROR_CHECK(esp_wifi_set_mode(WIFI_MODE_NULL)); ESP_ERROR_CHECK(esp_wifi_set_promiscuous(true)); // now switch on monitor mode
ESP_ERROR_CHECK(
esp_wifi_set_promiscuous_filter(&filter)); // set MAC frame filter
ESP_ERROR_CHECK(esp_wifi_set_promiscuous_rx_cb(&wifi_sniffer_packet_handler));
ESP_ERROR_CHECK(esp_wifi_set_promiscuous(true)); // now switch on monitor mode
} }
void wifi_sniffer_set_channel(uint8_t channel) { void wifi_sniffer_set_channel(uint8_t channel) {
esp_wifi_set_channel(channel, WIFI_SECOND_CHAN_NONE); esp_wifi_set_channel(channel, WIFI_SECOND_CHAN_NONE);
} }
// using IRAM_:ATTR here to speed up callback function // using IRAM_:ATTR here to speed up callback function
IRAM_ATTR void wifi_sniffer_packet_handler(void *buff, IRAM_ATTR void wifi_sniffer_packet_handler(void* buff, wifi_promiscuous_pkt_type_t type) {
wifi_promiscuous_pkt_type_t type) { const wifi_promiscuous_pkt_t *ppkt = (wifi_promiscuous_pkt_t *)buff;
const wifi_promiscuous_pkt_t *ppkt = (wifi_promiscuous_pkt_t *)buff; const wifi_ieee80211_packet_t *ipkt = (wifi_ieee80211_packet_t *)ppkt->payload;
const wifi_ieee80211_packet_t *ipkt = const wifi_ieee80211_mac_hdr_t *hdr = &ipkt->hdr;
(wifi_ieee80211_packet_t *)ppkt->payload;
const wifi_ieee80211_mac_hdr_t *hdr = &ipkt->hdr; if ((cfg.rssilimit) && (ppkt->rx_ctrl.rssi < cfg.rssilimit )) { // rssi is negative value
ESP_LOGI(TAG, "WiFi RSSI %d -> ignoring (limit: %d)", ppkt->rx_ctrl.rssi, cfg.rssilimit);
if ((cfg.rssilimit) && } else {
(ppkt->rx_ctrl.rssi < cfg.rssilimit)) { // rssi is negative value uint8_t *p = (uint8_t *) hdr->addr2;
ESP_LOGI(TAG, "WiFi RSSI %d -> ignoring (limit: %d)", ppkt->rx_ctrl.rssi, mac_add(p, ppkt->rx_ctrl.rssi, MAC_SNIFF_WIFI) ;
cfg.rssilimit); }
} else {
uint8_t *p = (uint8_t *)hdr->addr2;
mac_add(p, ppkt->rx_ctrl.rssi, MAC_SNIFF_WIFI);
}
} }

View File

@ -5,21 +5,21 @@
#include <esp_wifi.h> #include <esp_wifi.h>
#define MAC_SNIFF_WIFI 0 #define MAC_SNIFF_WIFI 0
#define MAC_SNIFF_BLE 1 #define MAC_SNIFF_BLE 1
typedef struct { typedef struct {
unsigned frame_ctrl : 16; unsigned frame_ctrl:16;
unsigned duration_id : 16; unsigned duration_id:16;
uint8_t addr1[6]; /* receiver address */ uint8_t addr1[6]; /* receiver address */
uint8_t addr2[6]; /* sender address */ uint8_t addr2[6]; /* sender address */
uint8_t addr3[6]; /* filtering address */ uint8_t addr3[6]; /* filtering address */
unsigned sequence_ctrl : 16; unsigned sequence_ctrl:16;
uint8_t addr4[6]; /* optional */ uint8_t addr4[6]; /* optional */
} wifi_ieee80211_mac_hdr_t; } wifi_ieee80211_mac_hdr_t;
typedef struct { typedef struct {
wifi_ieee80211_mac_hdr_t hdr; wifi_ieee80211_mac_hdr_t hdr;
uint8_t payload[0]; /* network data ended with 4 bytes csum (CRC32) */ uint8_t payload[0]; /* network data ended with 4 bytes csum (CRC32) */
} wifi_ieee80211_packet_t; } wifi_ieee80211_packet_t;
uint16_t reset_salt(void); uint16_t reset_salt(void);
@ -28,6 +28,6 @@ void wifi_sniffer_set_channel(uint8_t channel);
void wifi_sniffer_packet_handler(void *buff, wifi_promiscuous_pkt_type_t type); void wifi_sniffer_packet_handler(void *buff, wifi_promiscuous_pkt_type_t type);
// function defined in rokkithash.cpp // function defined in rokkithash.cpp
uint32_t rokkit(const char *, int); uint32_t rokkit(const char * , int );
#endif #endif

File diff suppressed because it is too large Load Diff

View File

@ -3,19 +3,21 @@
#include "lorawan.h" #include "lorawan.h"
#include "macsniff.h" #include "macsniff.h"
// program version - note: increment version after modifications to configData_t // program version - note: increment version after modifications to configData_t struct!!
// struct!! #define PROGVERSION "1.3.8" // use max 10 chars here!
#define PROGVERSION "1.3.8" // use max 10 chars here! #define PROGNAME "PAXCNT"
#define PROGNAME "PAXCNT"
//--- Declarations --- //--- Declarations ---
enum led_states { LED_OFF, LED_ON }; enum led_states {
LED_OFF,
LED_ON
};
#if defined(CFG_eu868) #if defined(CFG_eu868)
const char lora_datarate[] = {"1211100908077BFSNA"}; const char lora_datarate[] = {"1211100908077BFSNA"};
#elif defined(CFG_us915) #elif defined(CFG_us915)
const char lora_datarate[] = {"100908078CNA121110090807"}; const char lora_datarate[] = {"100908078CNA121110090807"};
#endif #endif
//--- Prototypes --- //--- Prototypes ---
@ -25,14 +27,15 @@ void reset_counters(void);
void blink_LED(uint16_t set_color, uint16_t set_blinkduration); void blink_LED(uint16_t set_color, uint16_t set_blinkduration);
void led_loop(void); void led_loop(void);
// defined in blescan.cpp // defined in blescan.cpp
#ifdef BLECOUNTER #ifdef BLECOUNTER
void start_BLEscan(void); void start_BLEscan(void);
void stop_BLEscan(void); void stop_BLEscan(void);
#endif #endif
// defined in gpsread.cpp //defined in gpsread.cpp
#ifdef HAS_GPS #ifdef HAS_GPS
void gps_read(void); void gps_read(void);
void gps_loop(void *pvParameters); void gps_loop(void * pvParameters);
#endif #endif

View File

@ -1,365 +1,310 @@
// remote command interpreter // remote command interpreter
// parses multiple number of command / value pairs from LoRaWAN remote command // parses multiple number of command / value pairs from LoRaWAN remote command port (RCMDPORT)
// port (RCMDPORT) checks commands and executes each command with 1 argument per // checks commands and executes each command with 1 argument per command
// command
// Basic Config // Basic Config
#include "globals.h" #include "globals.h"
// LMIC-Arduino LoRaWAN Stack // LMIC-Arduino LoRaWAN Stack
#include <hal/hal.h>
#include <lmic.h> #include <lmic.h>
#include <hal/hal.h>
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = "main";
// table of remote commands and assigned functions // table of remote commands and assigned functions
typedef struct { typedef struct {
const uint8_t nam; const uint8_t nam;
void (*func)(uint8_t); void (*func)(uint8_t);
const bool store; const bool store;
} cmd_t; } cmd_t;
// function defined in antenna.cpp // function defined in antenna.cpp
#ifdef HAS_ANTENNA_SWITCH #ifdef HAS_ANTENNA_SWITCH
void antenna_select(const uint8_t _ant); void antenna_select(const uint8_t _ant);
#endif #endif
// function defined in adcread.cpp // function defined in adcread.cpp
#ifdef HAS_BATTERY_PROBE #ifdef HAS_BATTERY_PROBE
uint32_t read_voltage(void); uint32_t read_voltage(void);
#endif #endif
// function sends result of get commands to LoRaWAN network // function sends result of get commands to LoRaWAN network
void do_transmit(osjob_t *j) { void do_transmit(osjob_t* j){
// check if there is a pending TX/RX job running, if yes then reschedule // check if there is a pending TX/RX job running, if yes then reschedule transmission
// transmission if (LMIC.opmode & OP_TXRXPEND) {
if (LMIC.opmode & OP_TXRXPEND) { ESP_LOGI(TAG, "LoRa busy, rescheduling");
ESP_LOGI(TAG, "LoRa busy, rescheduling"); sprintf(display_lmic, "LORA BUSY");
sprintf(display_lmic, "LORA BUSY"); os_setTimedCallback(&rcmdjob, os_getTime()+sec2osticks(RETRANSMIT_RCMD), do_transmit);
os_setTimedCallback(&rcmdjob, os_getTime() + sec2osticks(RETRANSMIT_RCMD), }
do_transmit); LMIC_setTxData2(RCMDPORT, rcmd_data, rcmd_data_size, 0); // send data unconfirmed on RCMD Port
} ESP_LOGI(TAG, "%d bytes queued to send", rcmd_data_size);
LMIC_setTxData2(RCMDPORT, rcmd_data, rcmd_data_size, sprintf(display_lmic, "PACKET QUEUED");
0); // send data unconfirmed on RCMD Port
ESP_LOGI(TAG, "%d bytes queued to send", rcmd_data_size);
sprintf(display_lmic, "PACKET QUEUED");
} }
// help function to transmit result of get commands, since callback function // help function to transmit result of get commands, since callback function do_transmit() cannot have params
// do_transmit() cannot have params void transmit(xref2u1_t mydata, u1_t mydata_size){
void transmit(xref2u1_t mydata, u1_t mydata_size) { rcmd_data = mydata;
rcmd_data = mydata; rcmd_data_size = mydata_size;
rcmd_data_size = mydata_size; do_transmit(&rcmdjob);
do_transmit(&rcmdjob);
} }
// help function to assign LoRa datarates to numeric spreadfactor values // help function to assign LoRa datarates to numeric spreadfactor values
void switch_lora(uint8_t sf, uint8_t tx) { void switch_lora (uint8_t sf, uint8_t tx) {
if (tx > 20) if ( tx > 20 ) return;
return; cfg.txpower = tx;
cfg.txpower = tx; switch (sf) {
switch (sf) { case 7: LMIC_setDrTxpow(DR_SF7,tx); cfg.lorasf=sf; break;
case 7: case 8: LMIC_setDrTxpow(DR_SF8,tx); cfg.lorasf=sf; break;
LMIC_setDrTxpow(DR_SF7, tx); case 9: LMIC_setDrTxpow(DR_SF9,tx); cfg.lorasf=sf; break;
cfg.lorasf = sf; case 10: LMIC_setDrTxpow(DR_SF10,tx); cfg.lorasf=sf; break;
break; case 11:
case 8: #if defined(CFG_eu868)
LMIC_setDrTxpow(DR_SF8, tx); LMIC_setDrTxpow(DR_SF11,tx); cfg.lorasf=sf; break;
cfg.lorasf = sf; #elif defined(CFG_us915)
break; LMIC_setDrTxpow(DR_SF11CR,tx); cfg.lorasf=sf; break;
case 9: #endif
LMIC_setDrTxpow(DR_SF9, tx); case 12:
cfg.lorasf = sf; #if defined(CFG_eu868)
break; LMIC_setDrTxpow(DR_SF12,tx); cfg.lorasf=sf; break;
case 10: #elif defined(CFG_us915)
LMIC_setDrTxpow(DR_SF10, tx); LMIC_setDrTxpow(DR_SF12CR,tx); cfg.lorasf=sf; break;
cfg.lorasf = sf; #endif
break; default: break;
case 11: }
#if defined(CFG_eu868)
LMIC_setDrTxpow(DR_SF11, tx);
cfg.lorasf = sf;
break;
#elif defined(CFG_us915)
LMIC_setDrTxpow(DR_SF11CR, tx);
cfg.lorasf = sf;
break;
#endif
case 12:
#if defined(CFG_eu868)
LMIC_setDrTxpow(DR_SF12, tx);
cfg.lorasf = sf;
break;
#elif defined(CFG_us915)
LMIC_setDrTxpow(DR_SF12CR, tx);
cfg.lorasf = sf;
break;
#endif
default:
break;
}
} }
// set of functions that can be triggered by remote commands // set of functions that can be triggered by remote commands
void set_reset(uint8_t val) { void set_reset(uint8_t val) {
switch (val) { switch (val) {
case 0: // restart device case 0: // restart device
ESP_LOGI(TAG, "Remote command: restart device"); ESP_LOGI(TAG, "Remote command: restart device");
sprintf(display_lora, "Reset pending"); sprintf(display_lora, "Reset pending");
vTaskDelay( vTaskDelay(10000/portTICK_PERIOD_MS); // wait for LMIC to confirm LoRa downlink to server
10000 / esp_restart();
portTICK_PERIOD_MS); // wait for LMIC to confirm LoRa downlink to server break;
esp_restart(); case 1: // reset MAC counter
break; ESP_LOGI(TAG, "Remote command: reset MAC counter");
case 1: // reset MAC counter reset_counters(); // clear macs
ESP_LOGI(TAG, "Remote command: reset MAC counter"); reset_salt(); // get new salt
reset_counters(); // clear macs sprintf(display_lora, "Reset counter");
reset_salt(); // get new salt break;
sprintf(display_lora, "Reset counter"); case 2: // reset device to factory settings
break; ESP_LOGI(TAG, "Remote command: reset device to factory settings");
case 2: // reset device to factory settings sprintf(display_lora, "Factory reset");
ESP_LOGI(TAG, "Remote command: reset device to factory settings"); eraseConfig();
sprintf(display_lora, "Factory reset"); break;
eraseConfig(); }
break;
}
}; };
void set_rssi(uint8_t val) { void set_rssi(uint8_t val) {
cfg.rssilimit = val * -1; cfg.rssilimit = val * -1;
ESP_LOGI(TAG, "Remote command: set RSSI limit to %d", cfg.rssilimit); ESP_LOGI(TAG, "Remote command: set RSSI limit to %d", cfg.rssilimit);
}; };
void set_sendcycle(uint8_t val) { void set_sendcycle(uint8_t val) {
cfg.sendcycle = val; cfg.sendcycle = val;
ESP_LOGI(TAG, "Remote command: set payload send cycle to %d seconds", ESP_LOGI(TAG, "Remote command: set payload send cycle to %d seconds", cfg.sendcycle*2);
cfg.sendcycle * 2); };
};
void set_wifichancycle(uint8_t val) { void set_wifichancycle(uint8_t val) {
cfg.wifichancycle = val; cfg.wifichancycle = val;
// modify wifi channel rotation IRQ // modify wifi channel rotation IRQ
timerAlarmWrite( timerAlarmWrite(channelSwitch, cfg.wifichancycle * 10000, true); // reload interrupt after each trigger of channel switch cycle
channelSwitch, cfg.wifichancycle * 10000, ESP_LOGI(TAG, "Remote command: set Wifi channel switch interval to %.1f seconds", cfg.wifichancycle/float(100));
true); // reload interrupt after each trigger of channel switch cycle };
ESP_LOGI(TAG,
"Remote command: set Wifi channel switch interval to %.1f seconds",
cfg.wifichancycle / float(100));
};
void set_blescantime(uint8_t val) { void set_blescantime(uint8_t val) {
cfg.blescantime = val; cfg.blescantime = val;
ESP_LOGI(TAG, "Remote command: set BLE scan time to %.1f seconds", ESP_LOGI(TAG, "Remote command: set BLE scan time to %.1f seconds", cfg.blescantime/float(100));
cfg.blescantime / float(100)); #ifdef BLECOUNTER
#ifdef BLECOUNTER // stop & restart BLE scan task to apply new parameter
// stop & restart BLE scan task to apply new parameter if (cfg.blescan)
if (cfg.blescan) { {
stop_BLEscan(); stop_BLEscan();
start_BLEscan(); start_BLEscan();
} }
#endif #endif
}; };
void set_countmode(uint8_t val) { void set_countmode(uint8_t val) {
switch (val) { switch (val) {
case 0: // cyclic unconfirmed case 0: // cyclic unconfirmed
cfg.countermode = 0; cfg.countermode = 0;
ESP_LOGI(TAG, "Remote command: set counter mode to cyclic unconfirmed"); ESP_LOGI(TAG, "Remote command: set counter mode to cyclic unconfirmed");
break; break;
case 1: // cumulative case 1: // cumulative
cfg.countermode = 1; cfg.countermode = 1;
ESP_LOGI(TAG, "Remote command: set counter mode to cumulative"); ESP_LOGI(TAG, "Remote command: set counter mode to cumulative");
break; break;
default: // cyclic confirmed default: // cyclic confirmed
cfg.countermode = 2; cfg.countermode = 2;
ESP_LOGI(TAG, "Remote command: set counter mode to cyclic confirmed"); ESP_LOGI(TAG, "Remote command: set counter mode to cyclic confirmed");
break; break;
} }
}; };
void set_screensaver(uint8_t val) { void set_screensaver(uint8_t val) {
ESP_LOGI(TAG, "Remote command: set screen saver to %s ", val ? "on" : "off"); ESP_LOGI(TAG, "Remote command: set screen saver to %s ", val ? "on" : "off");
switch (val) { switch (val) {
case 1: case 1: cfg.screensaver = val; break;
cfg.screensaver = val; default: cfg.screensaver = 0; break;
break; }
default:
cfg.screensaver = 0;
break;
}
}; };
void set_display(uint8_t val) { void set_display(uint8_t val) {
ESP_LOGI(TAG, "Remote command: set screen to %s", val ? "on" : "off"); ESP_LOGI(TAG, "Remote command: set screen to %s", val ? "on" : "off");
switch (val) { switch (val) {
case 1: case 1: cfg.screenon = val; break;
cfg.screenon = val; default: cfg.screenon = 0; break;
break; }
default:
cfg.screenon = 0;
break;
}
}; };
void set_gps(uint8_t val) { void set_gps(uint8_t val) {
ESP_LOGI(TAG, "Remote command: set GPS to %s", val ? "on" : "off"); ESP_LOGI(TAG, "Remote command: set GPS to %s", val ? "on" : "off");
switch (val) { switch (val) {
case 1: case 1: cfg.gpsmode = val; break;
cfg.gpsmode = val; default: cfg.gpsmode = 0; break;
break; }
default:
cfg.gpsmode = 0;
break;
}
}; };
void set_lorasf(uint8_t val) { void set_lorasf(uint8_t val) {
ESP_LOGI(TAG, "Remote command: set LoRa SF to %d", val); ESP_LOGI(TAG, "Remote command: set LoRa SF to %d", val);
switch_lora(val, cfg.txpower); switch_lora(val, cfg.txpower);
}; };
void set_loraadr(uint8_t val) { void set_loraadr(uint8_t val) {
ESP_LOGI(TAG, "Remote command: set LoRa ADR mode to %s", val ? "on" : "off"); ESP_LOGI(TAG, "Remote command: set LoRa ADR mode to %s", val ? "on" : "off");
switch (val) { switch (val) {
case 1: case 1: cfg.adrmode = val; break;
cfg.adrmode = val; default: cfg.adrmode = 0; break;
break; }
default: LMIC_setAdrMode(cfg.adrmode);
cfg.adrmode = 0;
break;
}
LMIC_setAdrMode(cfg.adrmode);
}; };
void set_blescan(uint8_t val) { void set_blescan(uint8_t val) {
ESP_LOGI(TAG, "Remote command: set BLE scanner to %s", val ? "on" : "off"); ESP_LOGI(TAG, "Remote command: set BLE scanner to %s", val ? "on" : "off");
switch (val) { switch (val) {
case 0: case 0:
cfg.blescan = 0; cfg.blescan = 0;
macs_ble = 0; // clear BLE counter macs_ble = 0; // clear BLE counter
#ifdef BLECOUNTER #ifdef BLECOUNTER
stop_BLEscan(); stop_BLEscan();
#endif #endif
break; break;
default: default:
cfg.blescan = 1; cfg.blescan = 1;
#ifdef BLECOUNTER #ifdef BLECOUNTER
start_BLEscan(); start_BLEscan();
#endif #endif
break; break;
} }
}; };
void set_wifiant(uint8_t val) { void set_wifiant(uint8_t val) {
ESP_LOGI(TAG, "Remote command: set Wifi antenna to %s", ESP_LOGI(TAG, "Remote command: set Wifi antenna to %s", val ? "external" : "internal");
val ? "external" : "internal"); switch (val) {
switch (val) { case 1: cfg.wifiant = val; break;
case 1: default: cfg.wifiant = 0; break;
cfg.wifiant = val; }
break; #ifdef HAS_ANTENNA_SWITCH
default: antenna_select(cfg.wifiant);
cfg.wifiant = 0; #endif
break;
}
#ifdef HAS_ANTENNA_SWITCH
antenna_select(cfg.wifiant);
#endif
}; };
void set_vendorfilter(uint8_t val) { void set_vendorfilter(uint8_t val) {
ESP_LOGI(TAG, "Remote command: set vendorfilter mode to %s", ESP_LOGI(TAG, "Remote command: set vendorfilter mode to %s", val ? "on" : "off");
val ? "on" : "off"); switch (val) {
switch (val) { case 1: cfg.vendorfilter = val; break;
case 1: default: cfg.vendorfilter = 0; break;
cfg.vendorfilter = val; }
break;
default:
cfg.vendorfilter = 0;
break;
}
}; };
void set_rgblum(uint8_t val) { void set_rgblum(uint8_t val) {
// Avoid wrong parameters // Avoid wrong parameters
cfg.rgblum = (val >= 0 && val <= 100) ? (uint8_t)val : RGBLUMINOSITY; cfg.rgblum = (val>=0 && val<=100) ? (uint8_t) val : RGBLUMINOSITY;
ESP_LOGI(TAG, "Remote command: set RGB Led luminosity %d", cfg.rgblum); ESP_LOGI(TAG, "Remote command: set RGB Led luminosity %d", cfg.rgblum);
}; };
void set_lorapower(uint8_t val) { void set_lorapower(uint8_t val) {
ESP_LOGI(TAG, "Remote command: set LoRa TXPOWER to %d", val); ESP_LOGI(TAG, "Remote command: set LoRa TXPOWER to %d", val);
switch_lora(cfg.lorasf, val); switch_lora(cfg.lorasf, val);
}; };
void get_config(uint8_t val) { void get_config (uint8_t val) {
ESP_LOGI(TAG, "Remote command: get configuration"); ESP_LOGI(TAG, "Remote command: get configuration");
transmit((byte *)&cfg, sizeof(cfg)); transmit((byte*)&cfg, sizeof(cfg));
}; };
void get_uptime(uint8_t val) { void get_uptime (uint8_t val) {
ESP_LOGI(TAG, "Remote command: get uptime"); ESP_LOGI(TAG, "Remote command: get uptime");
transmit((byte *)&uptimecounter, sizeof(uptimecounter)); transmit((byte*)&uptimecounter, sizeof(uptimecounter));
}; };
void get_cputemp(uint8_t val) { void get_cputemp (uint8_t val) {
ESP_LOGI(TAG, "Remote command: get cpu temperature"); ESP_LOGI(TAG, "Remote command: get cpu temperature");
float temp = temperatureRead(); float temp = temperatureRead();
transmit((byte *)&temp, sizeof(temp)); transmit((byte*)&temp, sizeof(temp));
}; };
void get_voltage(uint8_t val) { void get_voltage (uint8_t val) {
ESP_LOGI(TAG, "Remote command: get battery voltage"); ESP_LOGI(TAG, "Remote command: get battery voltage");
#ifdef HAS_BATTERY_PROBE #ifdef HAS_BATTERY_PROBE
uint16_t voltage = read_voltage(); uint16_t voltage = read_voltage();
#else #else
uint16_t voltage = 0; uint16_t voltage = 0;
#endif #endif
transmit((byte *)&voltage, sizeof(voltage)); transmit((byte*)&voltage, sizeof(voltage));
}; };
void get_gps(uint8_t val) { void get_gps (uint8_t val) {
ESP_LOGI(TAG, "Remote command: get gps status"); ESP_LOGI(TAG, "Remote command: get gps status");
#ifdef HAS_GPS #ifdef HAS_GPS
gps_read(); gps_read();
transmit((byte *)&gps_status, sizeof(gps_status)); transmit((byte*)&gps_status, sizeof(gps_status));
ESP_LOGI(TAG, "lat=%f / lon=%f | Sats=%u | HDOP=%u | Alti=%u", ESP_LOGI(TAG, "lat=%f / lon=%f | Sats=%u | HDOP=%u | Alti=%u", gps_status.latitude / 1000000, gps_status.longitude / 1000000, gps_status.satellites, gps_status.hdop, gps_status.altitude);
gps_status.latitude / 1000000, gps_status.longitude / 1000000, #else
gps_status.satellites, gps_status.hdop, gps_status.altitude); ESP_LOGE(TAG, "GPS not present");
#else #endif
ESP_LOGE(TAG, "GPS not present");
#endif
}; };
// assign previously defined functions to set of numeric remote commands // assign previously defined functions to set of numeric remote commands
// format: opcode, function, flag (1 = do make settings persistent / 0 = don't) // format: opcode, function, flag (1 = do make settings persistent / 0 = don't)
// //
cmd_t table[] = {{0x01, set_rssi, true}, {0x02, set_countmode, true}, cmd_t table[] = {
{0x03, set_gps, true}, {0x04, set_display, true}, {0x01, set_rssi, true},
{0x05, set_lorasf, true}, {0x06, set_lorapower, true}, {0x02, set_countmode, true},
{0x07, set_loraadr, true}, {0x08, set_screensaver, true}, {0x03, set_gps, true},
{0x09, set_reset, false}, {0x0a, set_sendcycle, true}, {0x04, set_display, true},
{0x0b, set_wifichancycle, true}, {0x0c, set_blescantime, true}, {0x05, set_lorasf, true},
{0x0d, set_vendorfilter, false}, {0x0e, set_blescan, true}, {0x06, set_lorapower, true},
{0x0f, set_wifiant, true}, {0x10, set_rgblum, true}, {0x07, set_loraadr, true},
{0x80, get_config, false}, {0x81, get_uptime, false}, {0x08, set_screensaver, true},
{0x82, get_cputemp, false}, {0x83, get_voltage, false}, {0x09, set_reset, false},
{0x84, get_gps, false}}; {0x0a, set_sendcycle, true},
{0x0b, set_wifichancycle, true},
{0x0c, set_blescantime, true},
{0x0d, set_vendorfilter, false},
{0x0e, set_blescan, true},
{0x0f, set_wifiant, true},
{0x10, set_rgblum, true},
{0x80, get_config, false},
{0x81, get_uptime, false},
{0x82, get_cputemp, false},
{0x83, get_voltage, false},
{0x84, get_gps, false}
};
// check and execute remote command // check and execute remote command
void rcommand(uint8_t cmd, uint8_t arg) { void rcommand(uint8_t cmd, uint8_t arg) {
int i = int i = sizeof(table) / sizeof(table[0]); // number of commands in command table
sizeof(table) / sizeof(table[0]); // number of commands in command table bool store_flag = false;
bool store_flag = false; while(i--) {
while (i--) { if(cmd == table[i].nam) { // check if valid command
if (cmd == table[i].nam) { // check if valid command table[i].func(arg); // then execute assigned function
table[i].func(arg); // then execute assigned function if ( table[i].store ) store_flag = true; // set save flag if function needs to store configuration
if (table[i].store) break; // exit check loop, since command was found
store_flag = }
true; // set save flag if function needs to store configuration
break; // exit check loop, since command was found
} }
} if (store_flag) saveConfig(); // if save flag is set: store new configuration in NVS to make it persistent
if (store_flag)
saveConfig(); // if save flag is set: store new configuration in NVS to make
// it persistent
} }

View File

@ -6,22 +6,23 @@
// RGB Led instance // RGB Led instance
SmartLed rgb_led(LED_WS2812, 1, HAS_RGB_LED); SmartLed rgb_led(LED_WS2812, 1, HAS_RGB_LED);
float rgb_CalcColor(float p, float q, float t) { float rgb_CalcColor(float p, float q, float t)
if (t < 0.0f) {
t += 1.0f; if (t < 0.0f)
if (t > 1.0f) t += 1.0f;
t -= 1.0f; if (t > 1.0f)
t -= 1.0f;
if (t < 1.0f / 6.0f) if (t < 1.0f / 6.0f)
return p + (q - p) * 6.0f * t; return p + (q - p) * 6.0f * t;
if (t < 0.5f) if (t < 0.5f)
return q; return q;
if (t < 2.0f / 3.0f) if (t < 2.0f / 3.0f)
return p + ((q - p) * (2.0f / 3.0f - t) * 6.0f); return p + ((q - p) * (2.0f / 3.0f - t) * 6.0f);
return p; return p;
} }
// ------------------------------------------------------------------------ // ------------------------------------------------------------------------
@ -29,41 +30,45 @@ float rgb_CalcColor(float p, float q, float t) {
// HslColor using H, S, L values (0.0 - 1.0) // HslColor using H, S, L values (0.0 - 1.0)
// L should be limited to between (0.0 - 0.5) // L should be limited to between (0.0 - 0.5)
// ------------------------------------------------------------------------ // ------------------------------------------------------------------------
RGBColor rgb_hsl2rgb(float h, float s, float l) { RGBColor rgb_hsl2rgb(float h, float s, float l)
RGBColor RGB_color; {
float r; RGBColor RGB_color;
float g; float r;
float b; float g;
float b;
if (s == 0.0f || l == 0.0f) { if (s == 0.0f || l == 0.0f)
r = g = b = l; // achromatic or black {
} else { r = g = b = l; // achromatic or black
float q = l < 0.5f ? l * (1.0f + s) : l + s - (l * s); }
float p = 2.0f * l - q; else
r = rgb_CalcColor(p, q, h + 1.0f / 3.0f); {
g = rgb_CalcColor(p, q, h); float q = l < 0.5f ? l * (1.0f + s) : l + s - (l * s);
b = rgb_CalcColor(p, q, h - 1.0f / 3.0f); float p = 2.0f * l - q;
} r = rgb_CalcColor(p, q, h + 1.0f / 3.0f);
g = rgb_CalcColor(p, q, h);
b = rgb_CalcColor(p, q, h - 1.0f / 3.0f);
}
RGB_color.R = (uint8_t)(r * 255.0f); RGB_color.R = (uint8_t)(r * 255.0f);
RGB_color.G = (uint8_t)(g * 255.0f); RGB_color.G = (uint8_t)(g * 255.0f);
RGB_color.B = (uint8_t)(b * 255.0f); RGB_color.B = (uint8_t)(b * 255.0f);
return RGB_color; return RGB_color;
} }
void rgb_set_color(uint16_t hue) { void rgb_set_color(uint16_t hue) {
if (hue == COLOR_NONE) { if (hue == COLOR_NONE) {
// Off // Off
rgb_led[0] = Rgb(0, 0, 0); rgb_led[0] = Rgb(0,0,0);
} else { } else {
// see http://www.workwithcolor.com/blue-color-hue-range-01.htm // see http://www.workwithcolor.com/blue-color-hue-range-01.htm
// H (is color from 0..360) should be between 0.0 and 1.0 // H (is color from 0..360) should be between 0.0 and 1.0
// S is saturation keep it to 1 // S is saturation keep it to 1
// L is brightness should be between 0.0 and 0.5 // L is brightness should be between 0.0 and 0.5
// cfg.rgblum is between 0 and 100 (percent) // cfg.rgblum is between 0 and 100 (percent)
RGBColor target = rgb_hsl2rgb(hue / 360.0f, 1.0f, 0.005f * cfg.rgblum); RGBColor target = rgb_hsl2rgb( hue / 360.0f, 1.0f, 0.005f * cfg.rgblum);
// uint32_t color = target.R<<16 | target.G<<8 | target.B; //uint32_t color = target.R<<16 | target.G<<8 | target.B;
rgb_led[0] = Rgb(target.R, target.G, target.B); rgb_led[0] = Rgb(target.R, target.G, target.B);
} }
// Show // Show

View File

@ -3,26 +3,27 @@
// value for HSL color // value for HSL color
// see http://www.workwithcolor.com/blue-color-hue-range-01.htm // see http://www.workwithcolor.com/blue-color-hue-range-01.htm
#define COLOR_RED 0 #define COLOR_RED 0
#define COLOR_ORANGE 30 #define COLOR_ORANGE 30
#define COLOR_ORANGE_YELLOW 45 #define COLOR_ORANGE_YELLOW 45
#define COLOR_YELLOW 60 #define COLOR_YELLOW 60
#define COLOR_YELLOW_GREEN 90 #define COLOR_YELLOW_GREEN 90
#define COLOR_GREEN 120 #define COLOR_GREEN 120
#define COLOR_GREEN_CYAN 165 #define COLOR_GREEN_CYAN 165
#define COLOR_CYAN 180 #define COLOR_CYAN 180
#define COLOR_CYAN_BLUE 210 #define COLOR_CYAN_BLUE 210
#define COLOR_BLUE 240 #define COLOR_BLUE 240
#define COLOR_BLUE_MAGENTA 275 #define COLOR_BLUE_MAGENTA 275
#define COLOR_MAGENTA 300 #define COLOR_MAGENTA 300
#define COLOR_PINK 350 #define COLOR_PINK 350
#define COLOR_WHITE 360 #define COLOR_WHITE 360
#define COLOR_NONE 999 #define COLOR_NONE 999
struct RGBColor { struct RGBColor
uint8_t R; {
uint8_t G; uint8_t R;
uint8_t B; uint8_t G;
uint8_t B;
}; };
// Exported Functions // Exported Functions

View File

@ -36,52 +36,48 @@
#include <inttypes.h> #include <inttypes.h>
uint32_t rokkit(const char *data, int len) { uint32_t rokkit(const char * data, int len) {
uint32_t hash, tmp; uint32_t hash, tmp;
int rem; int rem;
if (len <= 0 || data == 0) if (len <= 0 || data == 0) return 0;
return 0; hash = len;
hash = len; rem = len & 3;
rem = len & 3; len >>= 2;
len >>= 2;
/* Main loop */ /* Main loop */
while (len > 0) { while (len > 0) {
hash += *((uint16_t *)data); hash += *((uint16_t*)data);
tmp = (*((uint16_t *)(data + 2)) << 11) ^ hash; tmp = (*((uint16_t*)(data+2)) << 11) ^ hash;
hash = (hash << 16) ^ tmp; hash = (hash << 16) ^ tmp;
data += 2 * 2; data += 2*2;
hash += hash >> 11; hash += hash >> 11;
len--; len--;
} }
/* Handle end cases */ /* Handle end cases */
switch (rem) { switch (rem) {
case 3: case 3: hash += *((uint16_t*)data);
hash += *((uint16_t *)data); hash ^= hash << 16;
hash ^= hash << 16; hash ^= ((signed char)data[2]) << 18;
hash ^= ((signed char)data[2]) << 18; hash += hash >> 11;
hash += hash >> 11; break;
break; case 2: hash += *((uint16_t*)data);
case 2: hash ^= hash << 11;
hash += *((uint16_t *)data); hash += hash >> 17;
hash ^= hash << 11; break;
case 1: hash += (signed char)*data;
hash ^= hash << 10;
hash += hash >> 1;
}
/* Force "avalanching" of final 127 bits */
hash ^= hash << 3;
hash += hash >> 5;
hash ^= hash << 4;
hash += hash >> 17; hash += hash >> 17;
break; hash ^= hash << 25;
case 1: hash += hash >> 6;
hash += (signed char)*data;
hash ^= hash << 10;
hash += hash >> 1;
}
/* Force "avalanching" of final 127 bits */ return hash;
hash ^= hash << 3;
hash += hash >> 5;
hash ^= hash << 4;
hash += hash >> 17;
hash ^= hash << 25;
hash += hash >> 6;
return hash;
} }

File diff suppressed because it is too large Load Diff