diff --git a/boards/gat562_mesh_trial_tracker.json b/boards/gat562_mesh_trial_tracker.json new file mode 100644 index 000000000..7bedb7603 --- /dev/null +++ b/boards/gat562_mesh_trial_tracker.json @@ -0,0 +1,74 @@ +{ + "build": { + "arduino": { + "ldscript": "nrf52840_s140_v6.ld" + }, + "core": "nRF5", + "cpu": "cortex-m4", + "extra_flags": "-DARDUINO_NRF52840_FEATHER -DNRF52840_XXAA", + "f_cpu": "64000000L", + "hwids": [ + [ + "0x239A", + "0x8029" + ], + [ + "0x239A", + "0x0029" + ], + [ + "0x239A", + "0x002A" + ], + [ + "0x239A", + "0x802A" + ] + ], + "usb_product": "GAT562 Mesh Trial Tracker", + "mcu": "nrf52840", + "variant": "gat562_mesh_trial_tracker", + "bsp": { + "name": "adafruit" + }, + "softdevice": { + "sd_flags": "-DS140", + "sd_name": "s140", + "sd_version": "6.1.1", + "sd_fwid": "0x00B6" + }, + "bootloader": { + "settings_addr": "0xFF000" + } + }, + "connectivity": [ + "bluetooth" + ], + "debug": { + "jlink_device": "nRF52840_xxAA", + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" + }, + "frameworks": [ + "arduino", + "freertos" + ], + "name": "GAT562 Mesh Trial Tracker", + "upload": { + "maximum_ram_size": 248832, + "maximum_size": 815104, + "speed": 115200, + "protocol": "nrfutil", + "protocols": [ + "jlink", + "nrfjprog", + "nrfutil", + "stlink" + ], + "use_1200bps_touch": true, + "require_upload_port": true, + "wait_for_upload_port": true + }, + "url": "http://www.gat-iot.com/", + "vendor": "GAT-IOT" +} diff --git a/boards/meshtiny.json b/boards/meshtiny.json new file mode 100644 index 000000000..0418dc3bb --- /dev/null +++ b/boards/meshtiny.json @@ -0,0 +1,74 @@ +{ + "build": { + "arduino": { + "ldscript": "nrf52840_s140_v6.ld" + }, + "core": "nRF5", + "cpu": "cortex-m4", + "extra_flags": "-DARDUINO_NRF52840_FEATHER -DNRF52840_XXAA", + "f_cpu": "64000000L", + "hwids": [ + [ + "0x239A", + "0x8029" + ], + [ + "0x239A", + "0x0029" + ], + [ + "0x239A", + "0x002A" + ], + [ + "0x239A", + "0x802A" + ] + ], + "usb_product": "Meshtiny", + "mcu": "nrf52840", + "variant": "meshtiny", + "bsp": { + "name": "adafruit" + }, + "softdevice": { + "sd_flags": "-DS140", + "sd_name": "s140", + "sd_version": "6.1.1", + "sd_fwid": "0x00B6" + }, + "bootloader": { + "settings_addr": "0xFF000" + } + }, + "connectivity": [ + "bluetooth" + ], + "debug": { + "jlink_device": "nRF52840_xxAA", + "svd_path": "nrf52840.svd", + "openocd_target": "nrf52840-mdk-rs" + }, + "frameworks": [ + "arduino", + "freertos" + ], + "name": "Meshtiny", + "upload": { + "maximum_ram_size": 248832, + "maximum_size": 815104, + "speed": 115200, + "protocol": "nrfutil", + "protocols": [ + "jlink", + "nrfjprog", + "nrfutil", + "stlink" + ], + "use_1200bps_touch": true, + "require_upload_port": true, + "wait_for_upload_port": true + }, + "url": "https://shop.mtoolstec.com/product/meshtiny", + "vendor": "MTools Tec" +} diff --git a/variants/gat562_mesh_trial_tracker/GAT562MeshTrialTrackerBoard.cpp b/variants/gat562_mesh_trial_tracker/GAT562MeshTrialTrackerBoard.cpp new file mode 100644 index 000000000..d01c2e9d4 --- /dev/null +++ b/variants/gat562_mesh_trial_tracker/GAT562MeshTrialTrackerBoard.cpp @@ -0,0 +1,86 @@ +#include "GAT562MeshTrialTrackerBoard.h" + +#include +#include +#include + +static BLEDfu bledfu; + +static void connect_callback(uint16_t conn_handle) { + (void)conn_handle; + MESH_DEBUG_PRINTLN("BLE client connected"); +} + +static void disconnect_callback(uint16_t conn_handle, uint8_t reason) { + (void)conn_handle; + (void)reason; + + MESH_DEBUG_PRINTLN("BLE client disconnected"); +} + +void GAT562MeshTrialTrackerBoard::begin() { + // for future use, sub-classes SHOULD call this from their begin() + startup_reason = BD_STARTUP_NORMAL; + btn_prev_state = HIGH; + + pinMode(BATTERY_PIN, INPUT); // VBAT ADC input + + // Set all button pins to INPUT_PULLUP + pinMode(PIN_USER_BTN, INPUT_PULLUP); + +#if defined(PIN_WIRE_SDA) && defined(PIN_WIRE_SCL) + Wire.setPins(PIN_WIRE_SDA, PIN_WIRE_SCL); +#endif + + Wire.begin(); + + delay(10); // give sx1262 some time to power up +} + +bool GAT562MeshTrialTrackerBoard::startOTAUpdate(const char *id, char reply[]) { + // Config the peripheral connection with maximum bandwidth + // more SRAM required by SoftDevice + // Note: All config***() function must be called before begin() + Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); + Bluefruit.configPrphConn(92, BLE_GAP_EVENT_LENGTH_MIN, 16, 16); + + Bluefruit.begin(1, 0); + // Set max power. Accepted values are: -40, -30, -20, -16, -12, -8, -4, 0, 4 + Bluefruit.setTxPower(4); + // Set the BLE device name + Bluefruit.setName("GAT562_TRIAL_TRACKER_OTA"); + + Bluefruit.Periph.setConnectCallback(connect_callback); + Bluefruit.Periph.setDisconnectCallback(disconnect_callback); + + // To be consistent OTA DFU should be added first if it exists + bledfu.begin(); + + // Set up and start advertising + // Advertising packet + Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); + Bluefruit.Advertising.addTxPower(); + Bluefruit.Advertising.addName(); + + /* Start Advertising + - Enable auto advertising if disconnected + - Interval: fast mode = 20 ms, slow mode = 152.5 ms + - Timeout for fast mode is 30 seconds + - Start(timeout) with timeout = 0 will advertise forever (until connected) + + For recommended advertising interval + https://developer.apple.com/library/content/qa/qa1931/_index.html + */ + Bluefruit.Advertising.restartOnDisconnect(true); + Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms + Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode + Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds + + uint8_t mac_addr[6]; + memset(mac_addr, 0, sizeof(mac_addr)); + Bluefruit.getAddr(mac_addr); + sprintf(reply, "OK - mac: %02X:%02X:%02X:%02X:%02X:%02X", mac_addr[5], mac_addr[4], mac_addr[3], + mac_addr[2], mac_addr[1], mac_addr[0]); + + return true; +} diff --git a/variants/gat562_mesh_trial_tracker/GAT562MeshTrialTrackerBoard.h b/variants/gat562_mesh_trial_tracker/GAT562MeshTrialTrackerBoard.h new file mode 100644 index 000000000..3aacf626a --- /dev/null +++ b/variants/gat562_mesh_trial_tracker/GAT562MeshTrialTrackerBoard.h @@ -0,0 +1,68 @@ +#pragma once + +#include +#include + +class GAT562MeshTrialTrackerBoard : public mesh::MainBoard { +protected: + uint8_t startup_reason; + uint8_t btn_prev_state; + +public: + void begin(); + uint8_t getStartupReason() const override { return startup_reason; } + + uint16_t getBattMilliVolts() override { + int adcvalue = 0; + analogReadResolution(12); + analogReference(AR_INTERNAL_3_0); + delay(10); + adcvalue = analogRead(BATTERY_PIN); + return (adcvalue * ADC_MULTIPLIER * AREF_VOLTAGE) / 4.096; + } + + const char *getManufacturerName() const override { +#if defined(GAT562_MESH_TRACKER_PRO) + return "GAT562 TRACKER PRO"; +#else + return "GAT562 TRIAL TRACKER"; +#endif + } + + void reboot() override { NVIC_SystemReset(); } + + void powerOff() override { + +#ifdef PIN_USER_BTN + while (digitalRead(PIN_USER_BTN) == LOW) { + delay(10); + } +#endif + +#ifdef PIN_3V3_EN + digitalWrite(PIN_3V3_EN, LOW); + pinMode(PIN_3V3_EN, OUTPUT); +#endif + +#ifdef PIN_VIBRATION + digitalWrite(PIN_VIBRATION, LOW); + pinMode(PIN_VIBRATION, INPUT); +#endif + +#ifdef PIN_LED1 + digitalWrite(PIN_LED1, LOW); +#endif + +#ifdef PIN_LED2 + digitalWrite(PIN_LED2, LOW); +#endif + +#ifdef PIN_USER_BTN + nrf_gpio_cfg_sense_input(g_ADigitalPinMap[PIN_USER_BTN], NRF_GPIO_PIN_PULLUP, NRF_GPIO_PIN_SENSE_LOW); +#endif + + sd_power_system_off(); + } + + bool startOTAUpdate(const char *id, char reply[]) override; +}; diff --git a/variants/gat562_mesh_trial_tracker/platformio.ini b/variants/gat562_mesh_trial_tracker/platformio.ini new file mode 100644 index 000000000..183e8d4f7 --- /dev/null +++ b/variants/gat562_mesh_trial_tracker/platformio.ini @@ -0,0 +1,157 @@ +[GAT562_MESH_BASE] +extends = nrf52_base +board = gat562_mesh_trial_tracker +board_build.ldscript = boards/nrf52840_s140_v6.ld +build_flags = ${nrf52_base.build_flags} + -I lib/nrf52/s140_nrf52_6.1.1_API/include + -I lib/nrf52/s140_nrf52_6.1.1_API/include/nrf52 + -I variants/gat562_mesh_trial_tracker + -D RADIO_CLASS=CustomSX1262 + -D WRAPPER_CLASS=CustomSX1262Wrapper + -D LORA_TX_POWER=22 + -D SX126X_CURRENT_LIMIT=140 + -D SX126X_RX_BOOSTED_GAIN=1 + -D PIN_3V3_EN=34 + -D GAT562_MESH_BASE +build_src_filter = ${nrf52_base.build_src_filter} + +<../variants/gat562_mesh_trial_tracker> + + +lib_deps = + ${nrf52_base.lib_deps} + adafruit/Adafruit SSD1306 @ ^2.5.13 + +[env:GAT562_mesh_trial_tracker_companion_radio_usb] +extends = GAT562_MESH_BASE +build_flags = + ${GAT562_MESH_BASE.build_flags} + ${sensor_base.build_flags} + -I examples/companion_radio/ui-new + -D GAT562_MESH_TRIAL_TRACKER + -D GPS_BAUD_RATE=9600 + -D PIN_GPS_TX=16 + -D PIN_GPS_RX=15 + -D PIN_GPS_EN=34 + -D ENV_INCLUDE_GPS=1 + -D PIN_USER_BTN=9 + -D DISPLAY_CLASS=SSD1306Display + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 + -D OFFLINE_QUEUE_SIZE=256 +; -D GPS_NMEA_DEBUG +; -D PERSISTANT_GPS +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${GAT562_MESH_BASE.build_src_filter} + + + +<../examples/companion_radio/*.cpp> + +<../examples/companion_radio/ui-new/*.cpp> +lib_deps = + ${GAT562_MESH_BASE.lib_deps} + ${sensor_base.lib_deps} + densaugeo/base64 @ ~1.4.0 + +[env:GAT562_mesh_trial_tracker_companion_radio_ble] +extends = GAT562_MESH_BASE +build_flags = + ${GAT562_MESH_BASE.build_flags} + ${sensor_base.build_flags} + -I examples/companion_radio/ui-new + -D GAT562_MESH_TRIAL_TRACKER + -D GPS_BAUD_RATE=9600 + -D PIN_GPS_TX=16 + -D PIN_GPS_RX=15 + -D PIN_GPS_EN=34 + -D ENV_INCLUDE_GPS=1 + -D PIN_USER_BTN=9 + -D DISPLAY_CLASS=SSD1306Display + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 + -D BLE_PIN_CODE=123456 + -D OFFLINE_QUEUE_SIZE=256 +; -D GPS_NMEA_DEBUG +; -D PERSISTANT_GPS +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +; -D BLE_DEBUG_LOGGING=1 +build_src_filter = ${GAT562_MESH_BASE.build_src_filter} + + + + + +<../examples/companion_radio/*.cpp> + +<../examples/companion_radio/ui-new/*.cpp> +lib_deps = + ${GAT562_MESH_BASE.lib_deps} + ${sensor_base.lib_deps} + densaugeo/base64 @ ~1.4.0 + +[env:GAT562_mesh_tracker_pro_companion_radio_usb] +extends = GAT562_MESH_BASE +build_flags = + ${GAT562_MESH_BASE.build_flags} + ${sensor_base.build_flags} + -I examples/companion_radio/ui-new + -D GAT562_MESH_TRACKER_PRO + -D GPS_BAUD_RATE=9600 + -D PIN_GPS_TX=16 + -D PIN_GPS_RX=15 + -D PIN_GPS_EN=34 + -D ENV_INCLUDE_GPS=1 + -D PIN_USER_BTN=9 + -D DISPLAY_CLASS=SSD1306Display + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 + -D OFFLINE_QUEUE_SIZE=256 + -D JOYSTICK_UP=28 ; P0.28 + -D JOYSTICK_DOWN=4 ; P0.04 + -D JOYSTICK_LEFT=30 ; P0.30 + -D JOYSTICK_RIGHT=31 ; P0.31 + -D JOYSTICK_ENTER=26 ; P0.26 (ENTER) +; -D GPS_NMEA_DEBUG +; -D PERSISTANT_GPS +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${GAT562_MESH_BASE.build_src_filter} + + + +<../examples/companion_radio/*.cpp> + +<../examples/companion_radio/ui-new/*.cpp> +lib_deps = + ${GAT562_MESH_BASE.lib_deps} + ${sensor_base.lib_deps} + densaugeo/base64 @ ~1.4.0 + +[env:GAT562_mesh_tracker_pro_companion_radio_ble] +extends = GAT562_MESH_BASE +build_flags = + ${GAT562_MESH_BASE.build_flags} + ${sensor_base.build_flags} + -I examples/companion_radio/ui-new + -D GAT562_MESH_TRACKER_PRO + -D GPS_BAUD_RATE=9600 + -D PIN_GPS_TX=16 + -D PIN_GPS_RX=15 + -D PIN_GPS_EN=34 + -D ENV_INCLUDE_GPS=1 + -D PIN_USER_BTN=9 + -D DISPLAY_CLASS=SSD1306Display + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 + -D BLE_PIN_CODE=123456 + -D OFFLINE_QUEUE_SIZE=256 + -D JOYSTICK_UP=28 ; P0.28 + -D JOYSTICK_DOWN=4 ; P0.04 + -D JOYSTICK_LEFT=30 ; P0.30 + -D JOYSTICK_RIGHT=31 ; P0.31 + -D JOYSTICK_ENTER=26 ; P0.26 (ENTER) +; -D GPS_NMEA_DEBUG +; -D PERSISTANT_GPS +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +; -D BLE_DEBUG_LOGGING=1 +build_src_filter = ${GAT562_MESH_BASE.build_src_filter} + + + + + +<../examples/companion_radio/*.cpp> + +<../examples/companion_radio/ui-new/*.cpp> +lib_deps = + ${GAT562_MESH_BASE.lib_deps} + ${sensor_base.lib_deps} + densaugeo/base64 @ ~1.4.0 diff --git a/variants/gat562_mesh_trial_tracker/target.cpp b/variants/gat562_mesh_trial_tracker/target.cpp new file mode 100644 index 000000000..d3daba06c --- /dev/null +++ b/variants/gat562_mesh_trial_tracker/target.cpp @@ -0,0 +1,73 @@ +#include "target.h" + +#include +#include + +GAT562MeshTrialTrackerBoard board; + +RADIO_CLASS radio = new Module(P_LORA_NSS, P_LORA_DIO_1, P_LORA_RESET, P_LORA_BUSY, SPI); + +WRAPPER_CLASS radio_driver(radio, board); + +VolatileRTCClock fallback_clock; +AutoDiscoverRTCClock rtc_clock(fallback_clock); +#if ENV_INCLUDE_GPS +#include +MicroNMEALocationProvider nmea = MicroNMEALocationProvider(Serial1, &rtc_clock); +EnvironmentSensorManager sensors = EnvironmentSensorManager(nmea); +#else +EnvironmentSensorManager sensors = EnvironmentSensorManager(); +#endif + +#ifdef DISPLAY_CLASS +DISPLAY_CLASS display; + +MomentaryButton user_btn(PIN_USER_BTN, 1000, true, true); + +#ifdef JOYSTICK_UP +MomentaryButton joystick_up(JOYSTICK_UP, 1000, true); +#endif + +#ifdef JOYSTICK_DOWN +MomentaryButton joystick_down(JOYSTICK_DOWN, 1000, true); +#endif + +#ifdef JOYSTICK_LEFT +MomentaryButton joystick_left(JOYSTICK_LEFT, 1000, true); +#endif + +#ifdef JOYSTICK_RIGHT +MomentaryButton joystick_right(JOYSTICK_RIGHT, 1000, true); +#endif + +#ifdef JOYSTICK_ENTER +MomentaryButton joystick_enter(JOYSTICK_ENTER, 1000, true); +#endif + +#endif + +bool radio_init() { + rtc_clock.begin(Wire); + + return radio.std_init(&SPI); +} + +uint32_t radio_get_rng_seed() { + return radio.random(0x7FFFFFFF); +} + +void radio_set_params(float freq, float bw, uint8_t sf, uint8_t cr) { + radio.setFrequency(freq); + radio.setSpreadingFactor(sf); + radio.setBandwidth(bw); + radio.setCodingRate(cr); +} + +void radio_set_tx_power(uint8_t dbm) { + radio.setOutputPower(dbm); +} + +mesh::LocalIdentity radio_new_identity() { + RadioNoiseListener rng(radio); + return mesh::LocalIdentity(&rng); // create new random identity +} diff --git a/variants/gat562_mesh_trial_tracker/target.h b/variants/gat562_mesh_trial_tracker/target.h new file mode 100644 index 000000000..3c15fa2e9 --- /dev/null +++ b/variants/gat562_mesh_trial_tracker/target.h @@ -0,0 +1,45 @@ +#pragma once + +#define RADIOLIB_STATIC_ONLY 1 +#include +#include +#include +#include +#include +#include +#ifdef DISPLAY_CLASS +#include +#include +#endif +#include + +extern GAT562MeshTrialTrackerBoard board; +extern WRAPPER_CLASS radio_driver; +extern AutoDiscoverRTCClock rtc_clock; +extern EnvironmentSensorManager sensors; + +#ifdef DISPLAY_CLASS +extern DISPLAY_CLASS display; +extern MomentaryButton user_btn; +#ifdef JOYSTICK_UP +extern MomentaryButton joystick_up; +#endif +#ifdef JOYSTICK_DOWN +extern MomentaryButton joystick_down; +#endif +#ifdef JOYSTICK_LEFT +extern MomentaryButton joystick_left; +#endif +#ifdef JOYSTICK_RIGHT +extern MomentaryButton joystick_right; +#endif +#ifdef JOYSTICK_ENTER +extern MomentaryButton joystick_enter; +#endif +#endif + +bool radio_init(); +uint32_t radio_get_rng_seed(); +void radio_set_params(float freq, float bw, uint8_t sf, uint8_t cr); +void radio_set_tx_power(uint8_t dbm); +mesh::LocalIdentity radio_new_identity(); \ No newline at end of file diff --git a/variants/gat562_mesh_trial_tracker/variant.cpp b/variants/gat562_mesh_trial_tracker/variant.cpp new file mode 100644 index 000000000..4df356c8d --- /dev/null +++ b/variants/gat562_mesh_trial_tracker/variant.cpp @@ -0,0 +1,51 @@ +/* + Copyright (c) 2014-2015 Arduino LLC. All right reserved. + Copyright (c) 2016 Sandeep Mistry All right reserved. + Copyright (c) 2018, Adafruit Industries (adafruit.com) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "variant.h" + +#include "nrf.h" +#include "wiring_constants.h" +#include "wiring_digital.h" + +const uint32_t g_ADigitalPinMap[] = { + // P0 + 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, + 29, 30, 31, + + // P1 + 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47 +}; + +void initVariant() { + // LED1 & LED2 +#ifdef PIN_LED1 + pinMode(PIN_LED1, OUTPUT); + ledOff(PIN_LED1); +#endif + +#ifdef PIN_LED2 + pinMode(PIN_LED2, OUTPUT); + ledOff(PIN_LED2); +#endif + + // 3V3 Power Rail + pinMode(PIN_3V3_EN, OUTPUT); + digitalWrite(PIN_3V3_EN, HIGH); +} diff --git a/variants/gat562_mesh_trial_tracker/variant.h b/variants/gat562_mesh_trial_tracker/variant.h new file mode 100644 index 000000000..d33d860b1 --- /dev/null +++ b/variants/gat562_mesh_trial_tracker/variant.h @@ -0,0 +1,139 @@ +#ifndef _GAT562_MESH_TRIAL_TRACKER_H_ +#define _GAT562_MESH_TRIAL_TRACKER_H_ + +/** Master clock frequency */ +#define VARIANT_MCK (64000000ul) + +#define USE_LFXO // Board uses 32khz crystal for LF + +/*---------------------------------------------------------------------------- + * Headers + *----------------------------------------------------------------------------*/ + +#include "WVariant.h" + +#define PINS_COUNT (48) +#define NUM_DIGITAL_PINS (48) +#define NUM_ANALOG_INPUTS (6) +#define NUM_ANALOG_OUTPUTS (0) + +// LEDs +#define PIN_LED1 (35) +#define PIN_LED2 (36) + +#define LED_RED (-1) +#define LED_GREEN PIN_LED1 +#define LED_BLUE PIN_LED2 + +#define P_LORA_TX_LED LED_BLUE +#define PIN_STATUS_LED LED_GREEN +#define LED_BUILTIN LED_GREEN +#define PIN_LED LED_BUILTIN +#define LED_PIN LED_BUILTIN +#define LED_STATE_ON HIGH + +// Buttons +#define PIN_BUTTON1 (9) // Pin for button on E-ink button module or IO expansion +// #define PIN_BUTTON2 (12) +// #define PIN_BUTTON3 (24) +// #define PIN_BUTTON4 (25) +#define PIN_USER_BTN PIN_BUTTON1 +// #define BUTTON_NEED_PULLUP + +// Analog pins +#define PIN_A0 (5) +// #define PIN_A1 (31) // Duplicate pin assignment +// #define PIN_A2 (28) +// #define PIN_A3 (29) +// #define PIN_A4 (30) +// #define PIN_A5 (31) // Duplicate pin assignment +// #define PIN_A6 (0xff) +// #define PIN_A7 (0xff) + +// Battery +#define BATTERY_PIN PIN_A0 +#define PIN_VBAT_READ BATTERY_PIN +#define BATTERY_SENSE_RESOLUTION_BITS 12 +#define BATTERY_SENSE_RESOLUTION 4096.0 +#define AREF_VOLTAGE 3.0 +#define VBAT_AR_INTERNAL AR_INTERNAL_3_0 +#define ADC_MULTIPLIER 1.73 +#define ADC_RESOLUTION 14 + +// Other pins +// #define PIN_AREF (2) +// #define PIN_NFC1 (9) // Conflicts with PIN_BUTTON1 +// #define PIN_NFC2 (10) + +// Serial interfaces +#define PIN_SERIAL1_RX (15) +#define PIN_SERIAL1_TX (16) +#define PIN_SERIAL2_RX (8) // Connected to Jlink CDC +#define PIN_SERIAL2_TX (6) + +// SPI Interfaces +#define SPI_INTERFACES_COUNT 2 + +#define PIN_SPI_MISO (45) +#define PIN_SPI_MOSI (44) +#define PIN_SPI_SCK (43) + +#define PIN_SPI1_MISO (29) // (0 + 29) +#define PIN_SPI1_MOSI (30) // (0 + 30) +#define PIN_SPI1_SCK (3) // (0 + 3) + +// LoRa SX1262 module pins +#define P_LORA_SCLK PIN_SPI_SCK +#define P_LORA_MISO PIN_SPI_MISO +#define P_LORA_MOSI PIN_SPI_MOSI +#define P_LORA_DIO_1 (47) +#define P_LORA_RESET (38) +#define P_LORA_BUSY (46) +#define P_LORA_NSS (42) +#define SX126X_RXEN (37) +#define SX126X_TXEN RADIOLIB_NC +#define SX126X_DIO2_AS_RF_SWITCH true +#define SX126X_DIO3_TCXO_VOLTAGE (1.8f) + +// Wire Interfaces +#define WIRE_INTERFACES_COUNT 1 +#define PIN_WIRE_SDA (13) +#define PIN_WIRE_SCL (14) +#define PIN_BOARD_SDA (13) +#define PIN_BOARD_SCL (14) + +// Second I2C interface (not available on this board) +// #define PIN_WIRE1_SDA (xx) +// #define PIN_WIRE1_SCL (xx) + +// Display +// #define HAS_SCREEN 1 +// #define USE_SSD1306 +// #define PIN_OLED_RESET (-1) + +// Power control +#define PIN_3V3_EN (34) // enables 3.3V periphery like GPS or IO Module + +// GPS L76K +#define GPS_BAUD_RATE 9600 +#define PIN_GPS_TX PIN_SERIAL1_TX // Uses Serial1 TX pin +#define PIN_GPS_RX PIN_SERIAL1_RX // Uses Serial1 RX pin +#define PIN_GPS_EN PIN_3V3_EN +#define PIN_GPS_PPS (17) // Pulse per second input from the GPS + +// QSPI Pins +// #define PIN_QSPI_SCK (3) +// #define PIN_QSPI_CS (26) +// #define PIN_QSPI_IO0 (30) +// #define PIN_QSPI_IO1 (29) +// #define PIN_QSPI_IO2 (28) +// #define PIN_QSPI_IO3 (2) + +// On-board QSPI Flash +// #define EXTERNAL_FLASH_DEVICES W25Q16JV_IQ +// #define EXTERNAL_FLASH_USE_QSPI + +// Testing USB detection +// #define NRF_APM + +#endif diff --git a/variants/meshtiny/MeshtinyBoard.cpp b/variants/meshtiny/MeshtinyBoard.cpp new file mode 100644 index 000000000..90fcda5a0 --- /dev/null +++ b/variants/meshtiny/MeshtinyBoard.cpp @@ -0,0 +1,86 @@ +#include "MeshtinyBoard.h" + +#include +#include +#include + +static BLEDfu bledfu; + +static void connect_callback(uint16_t conn_handle) { + (void)conn_handle; + MESH_DEBUG_PRINTLN("BLE client connected"); +} + +static void disconnect_callback(uint16_t conn_handle, uint8_t reason) { + (void)conn_handle; + (void)reason; + + MESH_DEBUG_PRINTLN("BLE client disconnected"); +} + +void MeshtinyBoard::begin() { + // for future use, sub-classes SHOULD call this from their begin() + startup_reason = BD_STARTUP_NORMAL; + btn_prev_state = HIGH; + + pinMode(BATTERY_PIN, INPUT); // VBAT ADC input + + // Set all button pins to INPUT_PULLUP + pinMode(PIN_USER_BTN, INPUT_PULLUP); + +#if defined(PIN_WIRE_SDA) && defined(PIN_WIRE_SCL) + Wire.setPins(PIN_WIRE_SDA, PIN_WIRE_SCL); +#endif + + Wire.begin(); + + delay(10); // give sx1262 some time to power up +} + +bool MeshtinyBoard::startOTAUpdate(const char *id, char reply[]) { + // Config the peripheral connection with maximum bandwidth + // more SRAM required by SoftDevice + // Note: All config***() function must be called before begin() + Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); + Bluefruit.configPrphConn(92, BLE_GAP_EVENT_LENGTH_MIN, 16, 16); + + Bluefruit.begin(1, 0); + // Set max power. Accepted values are: -40, -30, -20, -16, -12, -8, -4, 0, 4 + Bluefruit.setTxPower(4); + // Set the BLE device name + Bluefruit.setName("MESHTINY_OTA"); + + Bluefruit.Periph.setConnectCallback(connect_callback); + Bluefruit.Periph.setDisconnectCallback(disconnect_callback); + + // To be consistent OTA DFU should be added first if it exists + bledfu.begin(); + + // Set up and start advertising + // Advertising packet + Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); + Bluefruit.Advertising.addTxPower(); + Bluefruit.Advertising.addName(); + + /* Start Advertising + - Enable auto advertising if disconnected + - Interval: fast mode = 20 ms, slow mode = 152.5 ms + - Timeout for fast mode is 30 seconds + - Start(timeout) with timeout = 0 will advertise forever (until connected) + + For recommended advertising interval + https://developer.apple.com/library/content/qa/qa1931/_index.html + */ + Bluefruit.Advertising.restartOnDisconnect(true); + Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms + Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode + Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds + + uint8_t mac_addr[6]; + memset(mac_addr, 0, sizeof(mac_addr)); + Bluefruit.getAddr(mac_addr); + sprintf(reply, "OK - mac: %02X:%02X:%02X:%02X:%02X:%02X", mac_addr[5], mac_addr[4], mac_addr[3], + mac_addr[2], mac_addr[1], mac_addr[0]); + + return true; +} diff --git a/variants/meshtiny/MeshtinyBoard.h b/variants/meshtiny/MeshtinyBoard.h new file mode 100644 index 000000000..391a8935f --- /dev/null +++ b/variants/meshtiny/MeshtinyBoard.h @@ -0,0 +1,62 @@ +#pragma once + +#include +#include + +class MeshtinyBoard : public mesh::MainBoard { +protected: + uint8_t startup_reason; + uint8_t btn_prev_state; + +public: + void begin(); + uint8_t getStartupReason() const override { return startup_reason; } + + uint16_t getBattMilliVolts() override { + int adcvalue = 0; + analogReadResolution(12); + analogReference(AR_INTERNAL_3_0); + delay(10); + adcvalue = analogRead(BATTERY_PIN); + return (adcvalue * ADC_MULTIPLIER * AREF_VOLTAGE) / 4.096; + } + + const char *getManufacturerName() const override { return "MESHTINY"; } + + void reboot() override { NVIC_SystemReset(); } + + void powerOff() override { + +#ifdef PIN_USER_BTN + while (digitalRead(PIN_USER_BTN) == LOW) { + delay(10); + } +#endif + +#ifdef PIN_3V3_EN + digitalWrite(PIN_3V3_EN, LOW); + pinMode(PIN_3V3_EN, OUTPUT); +#endif + +#ifdef PIN_VIBRATION + digitalWrite(PIN_VIBRATION, LOW); + pinMode(PIN_VIBRATION, INPUT); +#endif + +#ifdef PIN_LED1 + digitalWrite(PIN_LED1, LOW); +#endif + +#ifdef PIN_LED2 + digitalWrite(PIN_LED2, LOW); +#endif + +#ifdef PIN_USER_BTN + nrf_gpio_cfg_sense_input(g_ADigitalPinMap[PIN_USER_BTN], NRF_GPIO_PIN_PULLUP, NRF_GPIO_PIN_SENSE_LOW); +#endif + + sd_power_system_off(); + } + + bool startOTAUpdate(const char *id, char reply[]) override; +}; diff --git a/variants/meshtiny/platformio.ini b/variants/meshtiny/platformio.ini new file mode 100644 index 000000000..5bcc734f0 --- /dev/null +++ b/variants/meshtiny/platformio.ini @@ -0,0 +1,75 @@ +[MESHTINY_BASE] +extends = nrf52_base +board = meshtiny +board_build.ldscript = boards/nrf52840_s140_v6.ld +build_flags = ${nrf52_base.build_flags} + -I lib/nrf52/s140_nrf52_6.1.1_API/include + -I lib/nrf52/s140_nrf52_6.1.1_API/include/nrf52 + -I variants/meshtiny + -D RADIO_CLASS=CustomSX1262 + -D WRAPPER_CLASS=CustomSX1262Wrapper + -D LORA_TX_POWER=22 + -D SX126X_CURRENT_LIMIT=140 + -D SX126X_RX_BOOSTED_GAIN=1 + -D PIN_3V3_EN=34 + -D MESHTINY_BASE +build_src_filter = ${nrf52_base.build_src_filter} + +<../variants/meshtiny> + + + + + + +lib_deps = + ${nrf52_base.lib_deps} + adafruit/Adafruit SSD1306 @ ^2.5.13 + end2endzone/NonBlockingRTTTL@^1.3.0 + +[env:Meshtiny_companion_radio_usb] +extends = MESHTINY_BASE +build_flags = + ${MESHTINY_BASE.build_flags} + -I examples/companion_radio/ui-new + -D MESHTINY + -D PIN_USER_BTN=9 + -D JOYSTICK_LEFT=4 + -D JOYSTICK_RIGHT=26 + -D JOYSTICK_ENTER=28 + -D PIN_BUZZER=30 + -D DISPLAY_CLASS=SSD1306Display + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 + -D OFFLINE_QUEUE_SIZE=256 +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${MESHTINY_BASE.build_src_filter} + +<../examples/companion_radio/*.cpp> + +<../examples/companion_radio/ui-new/*.cpp> +lib_deps = + ${MESHTINY_BASE.lib_deps} + densaugeo/base64 @ ~1.4.0 + +[env:Meshtiny_companion_radio_ble] +extends = MESHTINY_BASE +build_flags = + ${MESHTINY_BASE.build_flags} + -I examples/companion_radio/ui-new + -D MESHTINY + -D PIN_USER_BTN=9 + -D JOYSTICK_LEFT=4 + -D JOYSTICK_RIGHT=26 + -D JOYSTICK_ENTER=28 + -D PIN_BUZZER=30 + -D DISPLAY_CLASS=SSD1306Display + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 + -D BLE_PIN_CODE=123456 + -D OFFLINE_QUEUE_SIZE=256 +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +; -D BLE_DEBUG_LOGGING=1 +build_src_filter = ${MESHTINY_BASE.build_src_filter} + + + +<../examples/companion_radio/*.cpp> + +<../examples/companion_radio/ui-new/*.cpp> +lib_deps = + ${MESHTINY_BASE.lib_deps} + densaugeo/base64 @ ~1.4.0 diff --git a/variants/meshtiny/target.cpp b/variants/meshtiny/target.cpp new file mode 100644 index 000000000..69fb22a43 --- /dev/null +++ b/variants/meshtiny/target.cpp @@ -0,0 +1,65 @@ +#include "target.h" + +#include +#include + +MeshtinyBoard board; + +RADIO_CLASS radio = new Module(P_LORA_NSS, P_LORA_DIO_1, P_LORA_RESET, P_LORA_BUSY, SPI); + +WRAPPER_CLASS radio_driver(radio, board); + +VolatileRTCClock fallback_clock; +AutoDiscoverRTCClock rtc_clock(fallback_clock); +#if ENV_INCLUDE_GPS +#include +MicroNMEALocationProvider nmea = MicroNMEALocationProvider(Serial1, &rtc_clock); +EnvironmentSensorManager sensors = EnvironmentSensorManager(nmea); +#else +EnvironmentSensorManager sensors = EnvironmentSensorManager(); +#endif + +#ifdef DISPLAY_CLASS +DISPLAY_CLASS display; + +MomentaryButton user_btn(PIN_USER_BTN, 1000, true, true); + +#ifdef JOYSTICK_LEFT +MomentaryButton joystick_left(JOYSTICK_LEFT, 1000, true, true); +#endif + +#ifdef JOYSTICK_RIGHT +MomentaryButton joystick_right(JOYSTICK_RIGHT, 1000, true, true); +#endif + +#ifdef JOYSTICK_ENTER +MomentaryButton joystick_enter(JOYSTICK_ENTER, 1000, true, true); +#endif + +#endif + +bool radio_init() { + rtc_clock.begin(Wire); + + return radio.std_init(&SPI); +} + +uint32_t radio_get_rng_seed() { + return radio.random(0x7FFFFFFF); +} + +void radio_set_params(float freq, float bw, uint8_t sf, uint8_t cr) { + radio.setFrequency(freq); + radio.setSpreadingFactor(sf); + radio.setBandwidth(bw); + radio.setCodingRate(cr); +} + +void radio_set_tx_power(uint8_t dbm) { + radio.setOutputPower(dbm); +} + +mesh::LocalIdentity radio_new_identity() { + RadioNoiseListener rng(radio); + return mesh::LocalIdentity(&rng); // create new random identity +} diff --git a/variants/meshtiny/target.h b/variants/meshtiny/target.h new file mode 100644 index 000000000..431a8dbf1 --- /dev/null +++ b/variants/meshtiny/target.h @@ -0,0 +1,39 @@ +#pragma once + +#define RADIOLIB_STATIC_ONLY 1 +#include +#include +#include +#include +#include +#include +#ifdef DISPLAY_CLASS +#include +#include +#endif +#include + +extern MeshtinyBoard board; +extern WRAPPER_CLASS radio_driver; +extern AutoDiscoverRTCClock rtc_clock; +extern EnvironmentSensorManager sensors; + +#ifdef DISPLAY_CLASS +extern DISPLAY_CLASS display; +extern MomentaryButton user_btn; +#ifdef JOYSTICK_LEFT +extern MomentaryButton joystick_left; +#endif +#ifdef JOYSTICK_RIGHT +extern MomentaryButton joystick_right; +#endif +#ifdef JOYSTICK_ENTER +extern MomentaryButton joystick_enter; +#endif +#endif + +bool radio_init(); +uint32_t radio_get_rng_seed(); +void radio_set_params(float freq, float bw, uint8_t sf, uint8_t cr); +void radio_set_tx_power(uint8_t dbm); +mesh::LocalIdentity radio_new_identity(); diff --git a/variants/meshtiny/variant.cpp b/variants/meshtiny/variant.cpp new file mode 100644 index 000000000..4df356c8d --- /dev/null +++ b/variants/meshtiny/variant.cpp @@ -0,0 +1,51 @@ +/* + Copyright (c) 2014-2015 Arduino LLC. All right reserved. + Copyright (c) 2016 Sandeep Mistry All right reserved. + Copyright (c) 2018, Adafruit Industries (adafruit.com) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "variant.h" + +#include "nrf.h" +#include "wiring_constants.h" +#include "wiring_digital.h" + +const uint32_t g_ADigitalPinMap[] = { + // P0 + 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, + 29, 30, 31, + + // P1 + 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47 +}; + +void initVariant() { + // LED1 & LED2 +#ifdef PIN_LED1 + pinMode(PIN_LED1, OUTPUT); + ledOff(PIN_LED1); +#endif + +#ifdef PIN_LED2 + pinMode(PIN_LED2, OUTPUT); + ledOff(PIN_LED2); +#endif + + // 3V3 Power Rail + pinMode(PIN_3V3_EN, OUTPUT); + digitalWrite(PIN_3V3_EN, HIGH); +} diff --git a/variants/meshtiny/variant.h b/variants/meshtiny/variant.h new file mode 100644 index 000000000..663cbd8f8 --- /dev/null +++ b/variants/meshtiny/variant.h @@ -0,0 +1,139 @@ +#ifndef _MESHTINY_H_ +#define _MESHTINY_H_ + +/** Master clock frequency */ +#define VARIANT_MCK (64000000ul) + +#define USE_LFXO // Board uses 32khz crystal for LF + +/*---------------------------------------------------------------------------- + * Headers + *----------------------------------------------------------------------------*/ + +#include "WVariant.h" + +#define PINS_COUNT (48) +#define NUM_DIGITAL_PINS (48) +#define NUM_ANALOG_INPUTS (6) +#define NUM_ANALOG_OUTPUTS (0) + +// LEDs +#define PIN_LED1 (35) +#define PIN_LED2 (36) + +#define LED_RED (-1) +#define LED_GREEN PIN_LED1 +#define LED_BLUE PIN_LED2 + +#define P_LORA_TX_LED LED_BLUE +#define PIN_STATUS_LED LED_GREEN +#define LED_BUILTIN LED_GREEN +#define PIN_LED LED_BUILTIN +#define LED_PIN LED_BUILTIN +#define LED_STATE_ON HIGH + +// Buttons +#define PIN_BUTTON1 (9) // Pin for button on E-ink button module or IO expansion +// #define PIN_BUTTON2 (12) +// #define PIN_BUTTON3 (24) +// #define PIN_BUTTON4 (25) +#define PIN_USER_BTN PIN_BUTTON1 +// #define BUTTON_NEED_PULLUP + +// Analog pins +#define PIN_A0 (5) +// #define PIN_A1 (31) // Duplicate pin assignment +// #define PIN_A2 (28) +// #define PIN_A3 (29) +// #define PIN_A4 (30) +// #define PIN_A5 (31) // Duplicate pin assignment +// #define PIN_A6 (0xff) +// #define PIN_A7 (0xff) + +// Battery +#define BATTERY_PIN PIN_A0 +#define PIN_VBAT_READ BATTERY_PIN +#define BATTERY_SENSE_RESOLUTION_BITS 12 +#define BATTERY_SENSE_RESOLUTION 4096.0 +#define AREF_VOLTAGE 3.0 +#define VBAT_AR_INTERNAL AR_INTERNAL_3_0 +#define ADC_MULTIPLIER 1.73 +#define ADC_RESOLUTION 14 + +// Other pins +// #define PIN_AREF (2) +// #define PIN_NFC1 (9) // Conflicts with PIN_BUTTON1 +// #define PIN_NFC2 (10) + +// Serial interfaces +#define PIN_SERIAL1_RX (15) +#define PIN_SERIAL1_TX (16) +#define PIN_SERIAL2_RX (8) // Connected to Jlink CDC +#define PIN_SERIAL2_TX (6) + +// SPI Interfaces +#define SPI_INTERFACES_COUNT 2 + +#define PIN_SPI_MISO (45) +#define PIN_SPI_MOSI (44) +#define PIN_SPI_SCK (43) + +#define PIN_SPI1_MISO (29) // (0 + 29) +#define PIN_SPI1_MOSI (30) // (0 + 30) +#define PIN_SPI1_SCK (3) // (0 + 3) + +// LoRa SX1262 module pins +#define P_LORA_SCLK PIN_SPI_SCK +#define P_LORA_MISO PIN_SPI_MISO +#define P_LORA_MOSI PIN_SPI_MOSI +#define P_LORA_DIO_1 (47) +#define P_LORA_RESET (38) +#define P_LORA_BUSY (46) +#define P_LORA_NSS (42) +#define SX126X_RXEN (37) +#define SX126X_TXEN RADIOLIB_NC +#define SX126X_DIO2_AS_RF_SWITCH true +#define SX126X_DIO3_TCXO_VOLTAGE (1.8f) + +// Wire Interfaces +#define WIRE_INTERFACES_COUNT 1 +#define PIN_WIRE_SDA (13) +#define PIN_WIRE_SCL (14) +#define PIN_BOARD_SDA (13) +#define PIN_BOARD_SCL (14) + +// Second I2C interface (not available on this board) +// #define PIN_WIRE1_SDA (xx) +// #define PIN_WIRE1_SCL (xx) + +// Display +// #define HAS_SCREEN 1 +// #define USE_SSD1306 +// #define PIN_OLED_RESET (-1) + +// Power control +#define PIN_3V3_EN (34) // enables 3.3V periphery like GPS or IO Module + +// GPS L76K +#define GPS_BAUD_RATE 9600 +#define PIN_GPS_TX PIN_SERIAL1_TX // Uses Serial1 TX pin +#define PIN_GPS_RX PIN_SERIAL1_RX // Uses Serial1 RX pin +#define PIN_GPS_EN PIN_3V3_EN +#define PIN_GPS_PPS (17) // Pulse per second input from the GPS + +// QSPI Pins +// #define PIN_QSPI_SCK (3) +// #define PIN_QSPI_CS (26) +// #define PIN_QSPI_IO0 (30) +// #define PIN_QSPI_IO1 (29) +// #define PIN_QSPI_IO2 (28) +// #define PIN_QSPI_IO3 (2) + +// On-board QSPI Flash +// #define EXTERNAL_FLASH_DEVICES W25Q16JV_IQ +// #define EXTERNAL_FLASH_USE_QSPI + +// Testing USB detection +// #define NRF_APM + +#endif