Moar LR1110 Targets

This commit is contained in:
Thomas Göttgens 2024-06-20 16:26:04 +02:00
parent ca560d64ea
commit ecf5519b56
39 changed files with 772 additions and 22 deletions

View File

@ -1,7 +1,7 @@
{
"build": {
"arduino": {
"ldscript": "nrf52840_s140_v6.ld"
"ldscript": "nrf52840_s140_v7.ld"
},
"core": "nRF5",
"cpu": "cortex-m4",
@ -22,8 +22,8 @@
"softdevice": {
"sd_flags": "-DS140",
"sd_name": "s140",
"sd_version": "6.1.1",
"sd_fwid": "0x00B6"
"sd_version": "7.3.0",
"sd_fwid": "0x0123"
},
"bootloader": {
"settings_addr": "0xFF000"

58
boards/wio-t1000-s.json Normal file
View File

@ -0,0 +1,58 @@
{
"build": {
"arduino": {
"ldscript": "nrf52840_s140_v7.ld"
},
"core": "nRF5",
"cpu": "cortex-m4",
"extra_flags": "-DARDUINO_WIO_WM1110 -DNRF52840_XXAA",
"f_cpu": "64000000L",
"hwids": [
["0x239A", "0x8029"],
["0x239A", "0x0029"],
["0x239A", "0x002A"],
["0x239A", "0x802A"]
],
"usb_product": "WIO-BOOT",
"mcu": "nrf52840",
"variant": "Seeed_WIO_WM1110",
"bsp": {
"name": "adafruit"
},
"softdevice": {
"sd_flags": "-DS140",
"sd_name": "s140",
"sd_version": "7.3.0",
"sd_fwid": "0x0123"
},
"bootloader": {
"settings_addr": "0xFF000"
}
},
"connectivity": ["bluetooth"],
"debug": {
"jlink_device": "nRF52840_xxAA",
"svd_path": "nrf52840.svd"
},
"frameworks": ["arduino"],
"name": "Seeed WIO WM1110",
"upload": {
"maximum_ram_size": 248832,
"maximum_size": 815104,
"speed": 115200,
"protocol": "nrfutil",
"protocols": [
"jlink",
"nrfjprog",
"nrfutil",
"stlink",
"cmsis-dap",
"blackmagic"
],
"use_1200bps_touch": true,
"require_upload_port": true,
"wait_for_upload_port": true
},
"url": "https://www.seeedstudio.com/LoRaWAN-Tracker-c-1938.html",
"vendor": "Seeed Studio"
}

View File

@ -1,7 +1,7 @@
{
"build": {
"arduino": {
"ldscript": "nrf52840_s140_v6.ld"
"ldscript": "nrf52840_s140_v7.ld"
},
"core": "nRF5",
"cpu": "cortex-m4",
@ -22,7 +22,7 @@
"softdevice": {
"sd_flags": "-DS140",
"sd_name": "s140",
"sd_version": "6.1.1",
"sd_version": "7.3.0",
"sd_fwid": "0x00B6"
},
"bootloader": {
@ -53,6 +53,6 @@
"require_upload_port": true,
"wait_for_upload_port": true
},
"url": "https://www.seeedstudio.com/Wio-WM1110-Dev-Kit-p-5677.html",
"url": "https://www.seeedstudio.com/Wio-Tracker-1110-Dev-Board-p-5799.html",
"vendor": "Seeed Studio"
}

View File

@ -43,6 +43,8 @@ ButtonThread::ButtonThread() : OSThread("Button")
int pin = config.device.button_gpio ? config.device.button_gpio : BUTTON_PIN; // Resolved button pin
#if defined(HELTEC_CAPSULE_SENSOR_V3)
this->userButton = OneButton(pin, false, false);
#elif defined(BUTTON_ACTIVE_LOW) // change by WayenWeng
this->userButton = OneButton(pin, BUTTON_ACTIVE_LOW, BUTTON_ACTIVE_PULLUP);
#else
this->userButton = OneButton(pin, true, true);
#endif
@ -51,8 +53,12 @@ ButtonThread::ButtonThread() : OSThread("Button")
#ifdef INPUT_PULLUP_SENSE
// Some platforms (nrf52) have a SENSE variant which allows wake from sleep - override what OneButton did
#ifdef BUTTON_SENSE_TYPE // change by WayenWeng
pinMode(pin, BUTTON_SENSE_TYPE);
#else
pinMode(pin, INPUT_PULLUP_SENSE);
#endif
#endif
#if defined(BUTTON_PIN) || defined(ARCH_PORTDUINO)
userButton.attachClick(userButtonPressed);
@ -322,4 +328,4 @@ void ButtonThread::userButtonPressedLongStop()
if (millis() > c_holdOffTime) {
btnEvent = BUTTON_EVENT_LONG_RELEASED;
}
}
}

View File

@ -7,8 +7,12 @@
#ifdef RP2040_SLOW_CLOCK
#define Port Serial2
#else
#ifdef USER_DEBUG_PORT // change by WayenWeng
#define Port USER_DEBUG_PORT
#else
#define Port Serial
#endif
#endif
// Defaulting to the formerly removed phone_timeout_secs value of 15 minutes
#define SERIAL_CONNECTION_TIMEOUT (15 * 60) * 1000UL

View File

@ -390,8 +390,13 @@ bool GPS::setup()
int msglen = 0;
if (!didSerialInit) {
#ifdef GNSS_Airoha // change by WayenWeng
if (tx_gpio && gnssModel == GNSS_MODEL_UNKNOWN) {
probe(GPS_BAUDRATE);
LOG_INFO("GPS setting to %d.\n", GPS_BAUDRATE);
}
#else
#if !defined(GPS_UC6580)
if (tx_gpio && gnssModel == GNSS_MODEL_UNKNOWN) {
LOG_DEBUG("Probing for GPS at %d \n", serialSpeeds[speedSelect]);
gnssModel = probe(serialSpeeds[speedSelect]);
@ -762,6 +767,7 @@ bool GPS::setup()
LOG_INFO("GNSS module configuration saved!\n");
}
}
#endif // !GNSS_Airoha
didSerialInit = true;
}
@ -869,6 +875,14 @@ void GPS::setGPSPower(bool on, bool standbyOnly, uint32_t sleepTime)
}
gps->_serial_gps->write(gps->UBXscratch, msglen);
}
#ifdef GNSS_Airoha // add by WayenWeng
else {
if ((config.position.gps_update_interval * 1000) >= (GPS_FIX_HOLD_TIME * 2)) {
// TODO, send rtc mode command
digitalWrite(PIN_GPS_EN, LOW);
}
}
#endif
} else {
if (gnssModel == GNSS_MODEL_UBLOX) {
gps->_serial_gps->write(0xFF);
@ -908,6 +922,9 @@ void GPS::setAwake(bool wantAwake)
if (wantAwake) {
// Record the time we start looking for a lock
lastWakeStartMsec = millis();
#ifdef GNSS_Airoha
lastFixStartMsec = 0;
#endif
} else {
// Record by how much we missed our ideal target postion.gps_update_interval (for logging only)
// Need to calculate this before we update lastSleepStartMsec, to make the new prediction
@ -1147,6 +1164,9 @@ GnssModel_t GPS::probe(int serialSpeed)
_serial_gps->updateBaudRate(serialSpeed);
}
#endif
#ifdef GNSS_Airoha // add by WayenWeng
return GNSS_MODEL_UNKNOWN;
#else
#ifdef GPS_DEBUG
for (int i = 0; i < 20; i++) {
getACK("$GP", 200);
@ -1293,6 +1313,7 @@ GnssModel_t GPS::probe(int serialSpeed)
}
return GNSS_MODEL_UBLOX;
#endif // !GNSS_Airoha
}
GPS *GPS::createGps()
@ -1460,6 +1481,25 @@ bool GPS::factoryReset()
*/
bool GPS::lookForTime()
{
#ifdef GNSS_Airoha // add by WayenWeng
uint8_t fix = reader.fixQuality();
uint32_t now = millis();
if (fix > 0) {
if (lastFixStartMsec > 0) {
if ((now - lastFixStartMsec) < GPS_FIX_HOLD_TIME) {
return false;
} else {
clearBuffer();
}
} else {
lastFixStartMsec = now;
return false;
}
} else {
return false;
}
#endif
auto ti = reader.time;
auto d = reader.date;
if (ti.isValid() && d.isValid()) { // Note: we don't check for updated, because we'll only be called if needed
@ -1494,6 +1534,27 @@ The Unix epoch (or Unix time or POSIX time or Unix timestamp) is the number of s
*/
bool GPS::lookForLocation()
{
#ifdef GNSS_Airoha // add by WayenWeng
if ((config.position.gps_update_interval * 1000) >= (GPS_FIX_HOLD_TIME * 2)) {
uint8_t fix = reader.fixQuality();
uint32_t now = millis();
if (fix > 0) {
if (lastFixStartMsec > 0) {
if ((now - lastFixStartMsec) < GPS_FIX_HOLD_TIME) {
return false;
} else {
clearBuffer();
}
} else {
lastFixStartMsec = now;
return false;
}
} else {
return false;
}
}
#endif
// By default, TinyGPS++ does not parse GPGSA lines, which give us
// the 2D/3D fixType (see NMEAGPS.h)
// At a minimum, use the fixQuality indicator in GPGGA (FIXME?)
@ -1702,6 +1763,12 @@ void GPS::toggleGpsMode()
if (config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_ENABLED) {
config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_DISABLED;
LOG_DEBUG("Flag set to false for gps power. GpsMode: DISABLED\n");
#ifdef GNSS_Airoha
if (powerState != GPS_ACTIVE) {
LOG_DEBUG("User power Off GPS\n");
digitalWrite(PIN_GPS_EN, LOW);
}
#endif
disable();
} else if (config.position.gps_mode == meshtastic_Config_PositionConfig_GpsMode_DISABLED) {
config.position.gps_mode = meshtastic_Config_PositionConfig_GpsMode_ENABLED;

View File

@ -67,7 +67,7 @@ class GPS : private concurrency::OSThread
uint8_t fixType = 0; // fix type from GPGSA
#endif
private:
uint32_t lastWakeStartMsec = 0, lastSleepStartMsec = 0;
uint32_t lastWakeStartMsec = 0, lastSleepStartMsec = 0, lastFixStartMsec = 0;
const int serialSpeeds[6] = {9600, 4800, 38400, 57600, 115200, 9600};
uint32_t rx_gpio = 0;

View File

@ -33,6 +33,9 @@
#include "Sensor/SHT31Sensor.h"
#include "Sensor/SHT4XSensor.h"
#include "Sensor/SHTC3Sensor.h"
#ifdef T1000X_SENSOR_EN
#include "Sensor/T1000xSensor.h"
#endif
#include "Sensor/TSL2591Sensor.h"
#include "Sensor/VEML7700Sensor.h"
@ -53,6 +56,9 @@ AHT10Sensor aht10Sensor;
MLX90632Sensor mlx90632Sensor;
DFRobotLarkSensor dfRobotLarkSensor;
NAU7802Sensor nau7802Sensor;
#ifdef T1000X_SENSOR_EN
T1000xSensor t1000xSensor;
#endif
#define FAILED_STATE_SENSOR_READ_MULTIPLIER 10
#define DISPLAY_RECEIVEID_MEASUREMENTS_ON_SCREEN true
@ -91,6 +97,9 @@ int32_t EnvironmentTelemetryModule::runOnce()
LOG_INFO("Environment Telemetry: Initializing\n");
// it's possible to have this module enabled, only for displaying values on the screen.
// therefore, we should only enable the sensor loop if measurement is also enabled
#ifdef T1000X_SENSOR_EN // add by WayenWeng
result = t1000xSensor.runOnce();
#else
if (dfRobotLarkSensor.hasSensor())
result = dfRobotLarkSensor.runOnce();
if (bmp085Sensor.hasSensor())
@ -129,6 +138,7 @@ int32_t EnvironmentTelemetryModule::runOnce()
result = mlx90632Sensor.runOnce();
if (nau7802Sensor.hasSensor())
result = nau7802Sensor.runOnce();
#endif
}
return result;
} else {
@ -278,6 +288,10 @@ bool EnvironmentTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
m.time = getTime();
m.which_variant = meshtastic_Telemetry_environment_metrics_tag;
#ifdef T1000X_SENSOR_EN // add by WayenWeng
valid = valid && t1000xSensor.getMetrics(&m);
hasSensor = true;
#else
if (dfRobotLarkSensor.hasSensor()) {
valid = valid && dfRobotLarkSensor.getMetrics(&m);
hasSensor = true;
@ -358,7 +372,7 @@ bool EnvironmentTelemetryModule::sendTelemetry(NodeNum dest, bool phoneOnly)
m.variant.environment_metrics.relative_humidity = m_ahtx.variant.environment_metrics.relative_humidity;
}
}
#endif
valid = valid && hasSensor;
if (valid) {

View File

@ -0,0 +1,116 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && defined(T1000X_SENSOR_EN)
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "T1000xSensor.h"
#include "TelemetrySensor.h"
#include <Adafruit_Sensor.h>
#define T1000X_SENSE_SAMPLES 15
#define T1000X_LIGHT_REF_VCC 2400
#define HEATER_NTC_BX 4250 // thermistor coefficient B
#define HEATER_NTC_RP 8250 // ohm, series resistance to thermistor
#define HEATER_NTC_KA 273.15 // 25 Celsius at Kelvin
#define NTC_REF_VCC 3000 // mV, output voltage of LDO
// ntc res table
uint32_t ntc_res2[136] = {
113347, 107565, 102116, 96978, 92132, 87559, 83242, 79166, 75316, 71677, 68237, 64991, 61919, 59011, 56258, 53650, 51178,
48835, 46613, 44506, 42506, 40600, 38791, 37073, 35442, 33892, 32420, 31020, 29689, 28423, 27219, 26076, 24988, 23951,
22963, 22021, 21123, 20267, 19450, 18670, 17926, 17214, 16534, 15886, 15266, 14674, 14108, 13566, 13049, 12554, 12081,
11628, 11195, 10780, 10382, 10000, 9634, 9284, 8947, 8624, 8315, 8018, 7734, 7461, 7199, 6948, 6707, 6475,
6253, 6039, 5834, 5636, 5445, 5262, 5086, 4917, 4754, 4597, 4446, 4301, 4161, 4026, 3896, 3771, 3651,
3535, 3423, 3315, 3211, 3111, 3014, 2922, 2834, 2748, 2666, 2586, 2509, 2435, 2364, 2294, 2228, 2163,
2100, 2040, 1981, 1925, 1870, 1817, 1766, 1716, 1669, 1622, 1578, 1535, 1493, 1452, 1413, 1375, 1338,
1303, 1268, 1234, 1202, 1170, 1139, 1110, 1081, 1053, 1026, 999, 974, 949, 925, 902, 880, 858,
};
int8_t ntc_temp2[136] = {
-30, -29, -28, -27, -26, -25, -24, -23, -22, -21, -20, -19, -18, -17, -16, -15, -14, -13, -12, -11, -10, -9, -8,
-7, -6, -5, -4, -3, -2, -1, 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, 32, 33, 34, 35, 36, 37, 38,
39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61,
62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84,
85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105,
};
T1000xSensor::T1000xSensor() : TelemetrySensor(meshtastic_TelemetrySensorType_SENSOR_UNSET, "T1000x") {}
int32_t T1000xSensor::runOnce()
{
LOG_INFO("Init sensor: %s\n", sensorName);
if (!hasSensor()) {
return DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS;
}
return DEFAULT_SENSOR_MINIMUM_WAIT_TIME_BETWEEN_READS;
}
void T1000xSensor::setup()
{
// Set up oversampling and filter initialization
}
float T1000xSensor::getLux()
{
uint32_t lux_vot = 0;
float lux_level = 0;
for (uint32_t i = 0; i < T1000X_SENSE_SAMPLES; i++) {
lux_vot += analogRead(T1000X_LUX_PIN);
}
lux_vot = lux_vot / T1000X_SENSE_SAMPLES;
lux_vot = ((1000 * AREF_VOLTAGE) / pow(2, BATTERY_SENSE_RESOLUTION_BITS)) * lux_vot;
if (lux_vot <= 80)
lux_level = 0;
else if (lux_vot >= 2480)
lux_level = 100;
else
lux_level = 100 * (lux_vot - 80) / T1000X_LIGHT_REF_VCC;
return lux_level;
}
float T1000xSensor::getTemp()
{
uint32_t vcc_vot = 0, ntc_vot = 0;
uint8_t u8i = 0;
float Vout = 0, Rt = 0, temp = 0;
float Temp = 0;
for (uint32_t i = 0; i < T1000X_SENSE_SAMPLES; i++) {
vcc_vot += analogRead(T1000X_VCC_PIN);
}
vcc_vot = vcc_vot / T1000X_SENSE_SAMPLES;
vcc_vot = 2 * ((1000 * AREF_VOLTAGE) / pow(2, BATTERY_SENSE_RESOLUTION_BITS)) * vcc_vot;
for (uint32_t i = 0; i < T1000X_SENSE_SAMPLES; i++) {
ntc_vot += analogRead(T1000X_NTC_PIN);
}
ntc_vot = ntc_vot / T1000X_SENSE_SAMPLES;
ntc_vot = ((1000 * AREF_VOLTAGE) / pow(2, BATTERY_SENSE_RESOLUTION_BITS)) * ntc_vot;
Vout = ntc_vot;
Rt = (HEATER_NTC_RP * vcc_vot) / Vout - HEATER_NTC_RP;
for (u8i = 0; u8i < 136; u8i++) {
if (Rt >= ntc_res2[u8i]) {
break;
}
}
temp = ntc_temp2[u8i - 1] + 1 * (ntc_res2[u8i - 1] - Rt) / (float)(ntc_res2[u8i - 1] - ntc_res2[u8i]);
Temp = (temp * 100 + 5) / 100; // half adjust
return Temp;
}
bool T1000xSensor::getMetrics(meshtastic_Telemetry *measurement)
{
measurement->variant.environment_metrics.temperature = getTemp();
measurement->variant.environment_metrics.lux = getLux();
return true;
}
#endif

View File

@ -0,0 +1,22 @@
#include "configuration.h"
#if !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR
#include "../mesh/generated/meshtastic/telemetry.pb.h"
#include "TelemetrySensor.h"
class T1000xSensor : public TelemetrySensor
{
private:
protected:
virtual void setup() override;
public:
T1000xSensor();
virtual int32_t runOnce() override;
virtual bool getMetrics(meshtastic_Telemetry *measurement) override;
virtual float getLux();
virtual float getTemp();
};
#endif

View File

@ -0,0 +1,144 @@
/**************************************************************************/
/*!
@file BLEDfu.cpp
@author hathach (tinyusb.org)
@section LICENSE
Software License Agreement (BSD License)
Copyright (c) 2018, Adafruit Industries (adafruit.com)
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
3. Neither the name of the copyright holders nor the
names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**************************************************************************/
#include "BLEDfuSecure.h"
#include "bluefruit.h"
#define DFU_REV_APPMODE 0x0001
const uint16_t UUID16_SVC_DFU_OTA = 0xFE59;
const uint8_t UUID128_CHR_DFU_CONTROL[16] = {0x50, 0xEA, 0xDA, 0x30, 0x88, 0x83, 0xB8, 0x9F,
0x60, 0x4F, 0x15, 0xF3, 0x03, 0x00, 0xC9, 0x8E};
extern "C" void bootloader_util_app_start(uint32_t start_addr);
static uint16_t crc16(const uint8_t *data_p, uint8_t length)
{
uint8_t x;
uint16_t crc = 0xFFFF;
while (length--) {
x = crc >> 8 ^ *data_p++;
x ^= x >> 4;
crc = (crc << 8) ^ ((uint16_t)(x << 12)) ^ ((uint16_t)(x << 5)) ^ ((uint16_t)x);
}
return crc;
}
static void bledfu_control_wr_authorize_cb(uint16_t conn_hdl, BLECharacteristic *chr, ble_gatts_evt_write_t *request)
{
if ((request->handle == chr->handles().value_handle) && (request->op != BLE_GATTS_OP_PREP_WRITE_REQ) &&
(request->op != BLE_GATTS_OP_EXEC_WRITE_REQ_NOW) && (request->op != BLE_GATTS_OP_EXEC_WRITE_REQ_CANCEL)) {
BLEConnection *conn = Bluefruit.Connection(conn_hdl);
ble_gatts_rw_authorize_reply_params_t reply = {.type = BLE_GATTS_AUTHORIZE_TYPE_WRITE};
if (!chr->indicateEnabled(conn_hdl)) {
reply.params.write.gatt_status = BLE_GATT_STATUS_ATTERR_CPS_CCCD_CONFIG_ERROR;
sd_ble_gatts_rw_authorize_reply(conn_hdl, &reply);
return;
}
reply.params.write.gatt_status = BLE_GATT_STATUS_SUCCESS;
sd_ble_gatts_rw_authorize_reply(conn_hdl, &reply);
enum { START_DFU = 1 };
if (request->data[0] == START_DFU) {
// Peer data information so that bootloader could re-connect after reboot
typedef struct {
ble_gap_addr_t addr;
ble_gap_irk_t irk;
ble_gap_enc_key_t enc_key;
uint8_t sys_attr[8];
uint16_t crc16;
} peer_data_t;
VERIFY_STATIC(offsetof(peer_data_t, crc16) == 60);
/* Save Peer data
* Peer data address is defined in bootloader linker @0x20007F80
* - If bonded : save Security information
* - Otherwise : save Address for direct advertising
*
* TODO may force bonded only for security reason
*/
peer_data_t *peer_data = (peer_data_t *)(0x20007F80UL);
varclr(peer_data);
// Get CCCD
uint16_t sysattr_len = sizeof(peer_data->sys_attr);
sd_ble_gatts_sys_attr_get(conn_hdl, peer_data->sys_attr, &sysattr_len, BLE_GATTS_SYS_ATTR_FLAG_SYS_SRVCS);
// Get Bond Data or using Address if not bonded
peer_data->addr = conn->getPeerAddr();
if (conn->secured()) {
bond_keys_t bkeys;
if (conn->loadBondKey(&bkeys)) {
peer_data->addr = bkeys.peer_id.id_addr_info;
peer_data->irk = bkeys.peer_id.id_info;
peer_data->enc_key = bkeys.own_enc;
}
}
// Calculate crc
peer_data->crc16 = crc16((uint8_t *)peer_data, offsetof(peer_data_t, crc16));
// Initiate DFU Sequence and reboot into DFU OTA mode
Bluefruit.Advertising.restartOnDisconnect(false);
conn->disconnect();
NRF_POWER->GPREGRET = 0xB1;
NVIC_SystemReset();
}
}
}
BLEDfuSecure::BLEDfuSecure(void) : BLEService(UUID16_SVC_DFU_OTA), _chr_control(UUID128_CHR_DFU_CONTROL) {}
err_t BLEDfuSecure::begin(void)
{
// Invoke base class begin()
VERIFY_STATUS(BLEService::begin());
_chr_control.setProperties(CHR_PROPS_WRITE | CHR_PROPS_INDICATE);
_chr_control.setMaxLen(23);
_chr_control.setWriteAuthorizeCallback(bledfu_control_wr_authorize_cb);
VERIFY_STATUS(_chr_control.begin());
return ERROR_NONE;
}

View File

@ -0,0 +1,55 @@
/**************************************************************************/
/*!
@file BLEDfu.h
@author hathach (tinyusb.org)
@section LICENSE
Software License Agreement (BSD License)
Copyright (c) 2018, Adafruit Industries (adafruit.com)
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
3. Neither the name of the copyright holders nor the
names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**************************************************************************/
#ifndef BLEDFUSECURE_H_
#define BLEDFUSECURE_H_
#include "bluefruit_common.h"
#include "BLECharacteristic.h"
#include "BLEService.h"
class BLEDfuSecure : public BLEService
{
protected:
BLECharacteristic _chr_control;
public:
BLEDfuSecure(void);
virtual err_t begin(void);
};
#endif /* BLEDFUSECURE_H_ */

View File

@ -1,4 +1,5 @@
#include "NRF52Bluetooth.h"
#include "BLEDfuSecure.h"
#include "BluetoothCommon.h"
#include "PowerFSM.h"
#include "configuration.h"
@ -13,9 +14,10 @@ static BLECharacteristic fromNum = BLECharacteristic(BLEUuid(FROMNUM_UUID_16));
static BLECharacteristic fromRadio = BLECharacteristic(BLEUuid(FROMRADIO_UUID_16));
static BLECharacteristic toRadio = BLECharacteristic(BLEUuid(TORADIO_UUID_16));
static BLEDis bledis; // DIS (Device Information Service) helper class instance
static BLEBas blebas; // BAS (Battery Service) helper class instance
static BLEDfu bledfu; // DFU software update helper service
static BLEDis bledis; // DIS (Device Information Service) helper class instance
static BLEBas blebas; // BAS (Battery Service) helper class instance
static BLEDfu bledfu; // DFU software update helper service
static BLEDfuSecure bledfusecure; // DFU software update helper service
// This scratch buffer is used for various bluetooth reads/writes - but it is safe because only one bt operation can be in
// process at once
@ -273,9 +275,13 @@ void NRF52Bluetooth::setup()
Bluefruit.Periph.setConnectCallback(onConnect);
Bluefruit.Periph.setDisconnectCallback(onDisconnect);
#ifndef BLE_DFU_SECURE
bledfu.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM);
bledfu.begin(); // Install the DFU helper
#else
bledfusecure.setPermission(SECMODE_ENC_WITH_MITM, SECMODE_ENC_WITH_MITM); // add by WayenWeng
bledfusecure.begin(); // Install the DFU helper
#endif
// Configure and Start the Device Information Service
LOG_INFO("Configuring the Device Information Service\n");
bledis.setModel(optstr(HW_VERSION));

View File

@ -242,6 +242,24 @@ void doDeepSleep(uint32_t msecToWake, bool skipPreflight = false)
if (gps)
gps->setGPSPower(false, false, 0);
#endif
#ifdef GNSS_Airoha // add by WayenWeng
digitalWrite(GPS_VRTC_EN, LOW);
digitalWrite(PIN_GPS_RESET, LOW);
digitalWrite(GPS_SLEEP_INT, LOW);
digitalWrite(GPS_RTC_INT, LOW);
pinMode(GPS_RESETB_OUT, OUTPUT);
digitalWrite(GPS_RESETB_OUT, LOW);
#endif
#ifdef BUZZER_EN_PIN // add by WayenWeng
digitalWrite(BUZZER_EN_PIN, LOW);
#endif
#ifdef PIN_3V3_EN // add by WayenWeng
digitalWrite(PIN_3V3_EN, LOW);
#endif
setLed(false);
#ifdef RESET_OLED

View File

@ -1,12 +1,12 @@
; The very slick RAK wireless RAK 4631 / 4630 board - Unified firmware for 5005/19003, with or without OLED RAK 1921
; The black Wio-WM1110 Dev Kit with sensors and the WM1110 module
[env:wio-sdk-wm1110]
extends = nrf52840_base
board = wio-sdk-wm1110
board_level = extra
; platform = https://github.com/maxgerhardt/platform-nordicnrf52#cac6fcf943a41accd2aeb4f3659ae297a73f422e
build_flags = ${nrf52840_base.build_flags} -Ivariants/wio-sdk-wm1110 -DWIO_WM1110
build_flags = ${nrf52840_base.build_flags} -Ivariants/wio-sdk-wm1110 -Isrc/platform/nrf52/softdevice -Isrc/platform/nrf52/softdevice/nrf52 -DWIO_WM1110
-L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard"
-DGPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely.
board_build.ldscript = src/platform/nrf52/nrf52840_s140_v7.ld
build_src_filter = ${nrf52_base.build_src_filter} +<../variants/wio-sdk-wm1110>
lib_deps =
${nrf52840_base.lib_deps}

View File

@ -0,0 +1,15 @@
; The very slick RAK wireless RAK 4631 / 4630 board - Unified firmware for 5005/19003, with or without OLED RAK 1921
[env:wio-t1000-s]
extends = nrf52840_base
board = wio-t1000-s
board_level = extra
build_flags = ${nrf52840_base.build_flags} -Ivariants/wio-t1000-s -Isrc/platform/nrf52/softdevice -Isrc/platform/nrf52/softdevice/nrf52 -DWIO_WM1110
-L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard"
-DGPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely.
board_build.ldscript = src/platform/nrf52/nrf52840_s140_v7.ld
build_src_filter = ${nrf52_base.build_src_filter} +<../variants/wio-t1000-s>
lib_deps =
${nrf52840_base.lib_deps}
debug_tool = jlink
; If not set we will default to uploading over serial (first it forces bootloader entry by talking 1200bps to cdcacm)
upload_protocol = jlink

View File

@ -0,0 +1,64 @@
/*
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
pinMode(LED_PIN, OUTPUT);
digitalWrite(LED_PIN, LOW);
pinMode(PIN_3V3_EN, OUTPUT);
digitalWrite(PIN_3V3_EN, HIGH);
pinMode(PIN_3V3_ACC_EN, OUTPUT);
digitalWrite(PIN_3V3_ACC_EN, LOW);
pinMode(BUZZER_EN_PIN, OUTPUT);
digitalWrite(BUZZER_EN_PIN, HIGH);
pinMode(PIN_GPS_EN, OUTPUT);
digitalWrite(PIN_GPS_EN, LOW);
pinMode(GPS_VRTC_EN, OUTPUT);
digitalWrite(GPS_VRTC_EN, HIGH);
pinMode(PIN_GPS_RESET, OUTPUT);
digitalWrite(PIN_GPS_RESET, LOW);
pinMode(GPS_SLEEP_INT, OUTPUT);
digitalWrite(GPS_SLEEP_INT, HIGH);
pinMode(GPS_RTC_INT, OUTPUT);
digitalWrite(GPS_RTC_INT, LOW);
pinMode(GPS_RESETB_OUT, INPUT);
}

View File

@ -0,0 +1,161 @@
/*
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
*/
#ifndef _VARIANT_WIO_SDK_WM1110_
#define _VARIANT_WIO_SDK_WM1110_
/** Master clock frequency */
#define VARIANT_MCK (64000000ul)
#define USE_LFXO // Board uses 32khz crystal for LF
// define USE_LFRC // Board uses RC for LF
#define BLE_DFU_SECURE // we use the 7.x softdevice signing keys
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "WVariant.h"
#ifdef __cplusplus
extern "C" {
#endif // __cplusplus
// Number of pins defined in PinDescription array
#define PINS_COUNT (48)
#define NUM_DIGITAL_PINS (48)
#define NUM_ANALOG_INPUTS (6)
#define NUM_ANALOG_OUTPUTS (0)
#define PIN_3V3_EN (32 + 6) // P1.6, Power to Sensors
#define PIN_3V3_ACC_EN (32 + 7) // P1.7, Power to Acc
#define PIN_LED1 (0 + 24) // P0.24
#define LED_PIN PIN_LED1
#define LED_BUILTIN -1
#define LED_BLUE -1 // Actually green
#define LED_STATE_ON 1 // State when LED is lit
#define BUTTON_PIN (0 + 6) // P0.6
#define BUTTON_ACTIVE_LOW false
#define BUTTON_ACTIVE_PULLUP false
#define BUTTON_SENSE_TYPE INPUT_SENSE_HIGH
#define HAS_WIRE 0
#define WIRE_INTERFACES_COUNT 1
#define PIN_WIRE_SDA (0 + 26) // P0.26
#define PIN_WIRE_SCL (0 + 27) // P0.27
/*
* Serial interfaces
*/
#define PIN_SERIAL1_RX (0 + 14) // P0.14
#define PIN_SERIAL1_TX (0 + 13) // P0.13
#define PIN_SERIAL2_RX (0 + 17) // P0.17
#define PIN_SERIAL2_TX (0 + 16) // P0.16
#define USER_DEBUG_PORT Serial2
#define SPI_INTERFACES_COUNT 1
#define PIN_SPI_MISO (32 + 8) // P1.08
#define PIN_SPI_MOSI (32 + 9) // P1.09
#define PIN_SPI_SCK (0 + 11) // P0.11
#define PIN_SPI_NSS (0 + 12) // P0.12
#define LORA_RESET (32 + 10) // P1.10 // RST
#define LORA_DIO1 (32 + 1) // P1.01 // IRQ
#define LORA_DIO2 (0 + 7) // P0.07 // BUSY
#define LORA_SCK PIN_SPI_SCK
#define LORA_MISO PIN_SPI_MISO
#define LORA_MOSI PIN_SPI_MOSI
#define LORA_CS PIN_SPI_NSS
// supported modules list
#define USE_LR1110
#define LR1110_IRQ_PIN LORA_DIO1
#define LR1110_NRESER_PIN LORA_RESET
#define LR1110_BUSY_PIN LORA_DIO2
#define LR1110_SPI_NSS_PIN LORA_CS
#define LR1110_SPI_SCK_PIN LORA_SCK
#define LR1110_SPI_MOSI_PIN LORA_MOSI
#define LR1110_SPI_MISO_PIN LORA_MISO
#define LR11X0_DIO3_TCXO_VOLTAGE 1.6
#define LR11X0_DIO_AS_RF_SWITCH
#define LR11X0_DIO_RF_SWITCH_CONFIG 0x0f, 0x0, 0x09, 0x0B, 0x0A, 0x0, 0x4, 0x0
#define HAS_GPS 1
#define GNSS_Airoha
#define GPS_RX_PIN PIN_SERIAL1_RX
#define GPS_TX_PIN PIN_SERIAL1_TX
#define GPS_BAUDRATE 115200
#define PIN_GPS_EN (32 + 11) // P1.11
#define GPS_EN_ACTIVE HIGH
#define PIN_GPS_RESET (32 + 15) // P1.15
#define GPS_RESET_MODE HIGH
#define GPS_VRTC_EN (0 + 8) // P0.8, awlays high
#define GPS_SLEEP_INT (32 + 12) // P1.12, awlays high
#define GPS_RTC_INT (0 + 15) // P0.15, normal is LOW, wake by HIGH
#define GPS_RESETB_OUT (32 + 14) // P1.14, awlays input pull_up
// #define GPS_THREAD_INTERVAL 50
#define GPS_FIX_HOLD_TIME 15000 // ms
#define BATTERY_PIN 2
// #define ADC_CHANNEL ADC1_GPIO2_CHANNEL
#define ADC_MULTIPLIER (2.0F)
#define ADC_RESOLUTION 14
#define BATTERY_SENSE_RESOLUTION_BITS 12
// #define BATTERY_SENSE_RESOLUTION 4096.0
#undef AREF_VOLTAGE
#define AREF_VOLTAGE 3.0
#define VBAT_AR_INTERNAL AR_INTERNAL_3_0
// #define ADC_CTRL (32 + 6)
// #define ADC_CTRL_ENABLED HIGH
// Buzzer
#define BUZZER_EN_PIN (32 + 5) // P1.05, awlays high
#define PIN_BUZZER (0 + 25) // P0.25, pwm output
#define T1000X_SENSOR_EN
#define T1000X_VCC_PIN (0 + 4) // P0.4
#define T1000X_NTC_PIN (0 + 31) // P0.31
#define T1000X_LUX_PIN (0 + 29) // P0.29
#ifdef __cplusplus
}
#endif
/*----------------------------------------------------------------------------
* Arduino objects - C++ only
*----------------------------------------------------------------------------*/
#endif // _VARIANT_WIO_SDK_WM1110_

View File

@ -1,11 +1,11 @@
; The very slick RAK wireless RAK 4631 / 4630 board - Unified firmware for 5005/19003, with or without OLED RAK 1921
; The red tracker Dev Board with the WM1110 module
[env:wio-tracker-wm1110]
extends = nrf52840_base
board = wio-tracker-wm1110
; platform = https://github.com/maxgerhardt/platform-nordicnrf52#cac6fcf943a41accd2aeb4f3659ae297a73f422e
build_flags = ${nrf52840_base.build_flags} -Ivariants/wio-tracker-wm1110 -DWIO_WM1110
build_flags = ${nrf52840_base.build_flags} -Ivariants/wio-tracker-wm1110 -Isrc/platform/nrf52/softdevice -Isrc/platform/nrf52/softdevice/nrf52 -DWIO_WM1110
-L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard"
-DGPS_POWER_TOGGLE ; comment this line to disable triple press function on the user button to turn off gps entirely.
board_build.ldscript = src/platform/nrf52/nrf52840_s140_v7.ld
build_src_filter = ${nrf52_base.build_src_filter} +<../variants/wio-tracker-wm1110>
lib_deps =
${nrf52840_base.lib_deps}

View File

@ -3,9 +3,9 @@
extends = nrf52840_base
board = xiao_ble_sense
board_level = extra
build_flags = ${nrf52840_base.build_flags} -Ivariants/xiao_ble -Ivariants/xiao_ble/softdevice -Ivariants/xiao_ble/softdevice/nrf52 -D EBYTE_E22 -DPRIVATE_HW
build_flags = ${nrf52840_base.build_flags} -Ivariants/xiao_ble -Isrc/platform/nrf52/softdevice -Isrc/platform/nrf52/softdevice/nrf52 -D EBYTE_E22 -DPRIVATE_HW
-L "${platformio.libdeps_dir}/${this.__env__}/bsec2/src/cortex-m4/fpv4-sp-d16-hard"
board_build.ldscript = variants/xiao_ble/nrf52840_s140_v7.ld
board_build.ldscript = src/platform/nrf52/nrf52840_s140_v7.ld
build_src_filter = ${nrf52_base.build_src_filter} +<../variants/xiao_ble>
lib_deps =
${nrf52840_base.lib_deps}