Skip to content
This repository has been archived by the owner on Aug 8, 2024. It is now read-only.

Update #10

Merged
merged 20 commits into from
Mar 16, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
20 commits
Select commit Hold shift + click to select a range
58cdf36
(1/3) Support L76B GNSS chip found on pico waveshare shield. Original…
caveman99 Mar 14, 2024
ec6bdee
NodeInfo broadcast ensure default on 0 and enforce 1 hour minimum (#3…
thebentern Mar 15, 2024
50cc4cf
We don't use Lorawan (#3417)
caveman99 Mar 15, 2024
876a052
[create-pull-request] automated change (#3418)
github-actions[bot] Mar 15, 2024
cbc0aa1
fix compilation
caveman99 Mar 15, 2024
b06c77d
don't fix this to a hardware model.
caveman99 Mar 15, 2024
da7cd5f
new Accelerometer lib (#3413)
caveman99 Mar 15, 2024
2eb78fe
Merge branch 'master' into gnss-l76b
caveman99 Mar 15, 2024
b900415
that should work now
caveman99 Mar 15, 2024
e8ec167
Merge branch 'gnss-l76b' of github.com:meshtastic/firmware into gnss-…
caveman99 Mar 15, 2024
cb37407
Merge pull request #3410 from meshtastic/gnss-l76b
caveman99 Mar 15, 2024
34bc22f
(2/3) Add Slow Clock Support for RP2040 platform. This will disable U…
caveman99 Mar 14, 2024
4d0d82f
Merge pull request #3411 from meshtastic/rp2040-slowclock
caveman99 Mar 15, 2024
52cfec2
More comprehensive client proxy queue guards (#3414)
thebentern Mar 15, 2024
0dda20b
fix for I2C scan getting stuck (#3375)
andrekir Mar 15, 2024
0de36fb
[create-pull-request] automated change (#3419)
github-actions[bot] Mar 15, 2024
9586606
Handle for heartbeat toradio packets (#3420)
thebentern Mar 15, 2024
611f291
Factory reset GNSS_MODEL_MTK GPS modules with PCAS10,3 (#3388)
titan098 Mar 16, 2024
54a2a4b
[create-pull-request] automated change (#3422)
github-actions[bot] Mar 16, 2024
13cc1b0
(3/3) Add variant for pico with waveshare and GPS hat (#3412)
caveman99 Mar 16, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions arch/rp2040/rp2040.ini
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
; Common settings for rp2040 Processor based targets
[rp2040_base]
platform = https://github.com/maxgerhardt/platform-raspberrypi.git#612de5399d68b359053f1307ed223d400aea975c
platform = https://github.com/maxgerhardt/platform-raspberrypi.git#60d6ae81fcc73c34b1493ca9e261695e471bc0c2
extends = arduino_base
platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.6.2
platform_packages = framework-arduinopico@https://github.com/earlephilhower/arduino-pico.git#3.7.2

board_build.core = earlephilhower
board_build.filesystem_size = 0.5m
Expand Down
5 changes: 3 additions & 2 deletions platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@ build_flags = -Wno-missing-field-initializers
-DRADIOLIB_EXCLUDE_PAGER
-DRADIOLIB_EXCLUDE_FSK4
-DRADIOLIB_EXCLUDE_APRS
-DRADIOLIB_EXCLUDE_LORAWAN

monitor_speed = 115200

Expand All @@ -77,7 +78,7 @@ lib_deps =
https://github.com/meshtastic/esp8266-oled-ssd1306.git#ee628ee6c9588d4c56c9e3da35f0fc9448ad54a8 ; ESP8266_SSD1306
mathertel/OneButton@^2.5.0 ; OneButton library for non-blocking button debounce
https://github.com/meshtastic/arduino-fsm.git#7db3702bf0cfe97b783d6c72595e3f38e0b19159
https://github.com/meshtastic/TinyGPSPlus.git#2044b2c51e91ab4cd8cc93b15e40658cd808dd06
https://github.com/meshtastic/TinyGPSPlus.git#f9f4fef2183514aa52be91d714c1455dd6f26e45
https://github.com/meshtastic/ArduinoThread.git#72921ac222eed6f526ba1682023cee290d9aa1b3
nanopb/Nanopb@^0.4.7
erriez/ErriezCRC32@^1.0.1
Expand Down Expand Up @@ -130,4 +131,4 @@ lib_deps =
adafruit/Adafruit PM25 AQI Sensor@^1.0.6
adafruit/Adafruit MPU6050@^2.2.4
adafruit/Adafruit LIS3DH@^1.2.4
https://github.com/lewisxhe/BMA423_Library@^0.0.1
https://github.com/lewisxhe/SensorLib#27fd0f721e20cd09e1f81383f0ba58a54fe84a17
2 changes: 1 addition & 1 deletion protobufs
68 changes: 23 additions & 45 deletions src/AccelerometerThread.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,16 +7,16 @@
#include <Adafruit_LIS3DH.h>
#include <Adafruit_MPU6050.h>
#include <Arduino.h>
#include <SensorBMA423.hpp>
#include <Wire.h>
#include <bma.h>

BMA423 bmaSensor;
SensorBMA423 bmaSensor;
bool BMA_IRQ = false;

#define ACCELEROMETER_CHECK_INTERVAL_MS 100
#define ACCELEROMETER_CLICK_THRESHOLD 40

uint16_t readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len)
int readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint8_t len)
{
Wire.beginTransmission(address);
Wire.write(reg);
Expand All @@ -29,7 +29,7 @@ uint16_t readRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len)
return 0; // Pass
}

uint16_t writeRegister(uint8_t address, uint8_t reg, uint8_t *data, uint16_t len)
int writeRegister(uint8_t address, uint8_t reg, uint8_t *data, uint8_t len)
{
Wire.beginTransmission(address);
Wire.write(reg);
Expand Down Expand Up @@ -72,24 +72,14 @@ class AccelerometerThread : public concurrency::OSThread
lis.setRange(LIS3DH_RANGE_2_G);
// Adjust threshold, higher numbers are less sensitive
lis.setClick(config.device.double_tap_as_button_press ? 2 : 1, ACCELEROMETER_CLICK_THRESHOLD);
} else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.begin(readRegister, writeRegister, delay)) {
} else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 &&
bmaSensor.begin(accelerometer_found.address, &readRegister, &writeRegister)) {
LOG_DEBUG("BMA423 initializing\n");
Acfg cfg;
cfg.odr = BMA4_OUTPUT_DATA_RATE_100HZ;
cfg.range = BMA4_ACCEL_RANGE_2G;
cfg.bandwidth = BMA4_ACCEL_NORMAL_AVG4;
cfg.perf_mode = BMA4_CONTINUOUS_MODE;
bmaSensor.setAccelConfig(cfg);
bmaSensor.enableAccel();

struct bma4_int_pin_config pin_config;
pin_config.edge_ctrl = BMA4_LEVEL_TRIGGER;
pin_config.lvl = BMA4_ACTIVE_HIGH;
pin_config.od = BMA4_PUSH_PULL;
pin_config.output_en = BMA4_OUTPUT_ENABLE;
pin_config.input_en = BMA4_INPUT_DISABLE;
// The correct trigger interrupt needs to be configured as needed
bmaSensor.setINTPinConfig(pin_config, BMA4_INTR1_MAP);
bmaSensor.configAccelerometer(bmaSensor.RANGE_2G, bmaSensor.ODR_100HZ, bmaSensor.BW_NORMAL_AVG4,
bmaSensor.PERF_CONTINUOUS_MODE);
bmaSensor.enableAccelerometer();
bmaSensor.configInterrupt(BMA4_LEVEL_TRIGGER, BMA4_ACTIVE_HIGH, BMA4_PUSH_PULL, BMA4_OUTPUT_ENABLE,
BMA4_INPUT_DISABLE);

#ifdef BMA423_INT
pinMode(BMA4XX_INT, INPUT);
Expand All @@ -102,34 +92,22 @@ class AccelerometerThread : public concurrency::OSThread
RISING); // Select the interrupt mode according to the actual circuit
#endif

struct bma423_axes_remap remap_data;
#ifdef T_WATCH_S3
remap_data.x_axis = 1;
remap_data.x_axis_sign = 0;
remap_data.y_axis = 0;
remap_data.y_axis_sign = 0;
remap_data.z_axis = 2;
remap_data.z_axis_sign = 1;
// Need to raise the wrist function, need to set the correct axis
bmaSensor.setReampAxes(bmaSensor.REMAP_TOP_LAYER_RIGHT_CORNER);
#else
remap_data.x_axis = 0;
remap_data.x_axis_sign = 1;
remap_data.y_axis = 1;
remap_data.y_axis_sign = 0;
remap_data.z_axis = 2;
remap_data.z_axis_sign = 1;
bmaSensor.setReampAxes(bmaSensor.REMAP_BOTTOM_LAYER_BOTTOM_LEFT_CORNER);
#endif
// Need to raise the wrist function, need to set the correct axis
bmaSensor.setRemapAxes(&remap_data);
// sensor.enableFeature(BMA423_STEP_CNTR, true);
bmaSensor.enableFeature(BMA423_TILT, true);
bmaSensor.enableFeature(BMA423_WAKEUP, true);
// sensor.resetStepCounter();
// bmaSensor.enableFeature(bmaSensor.FEATURE_STEP_CNTR, true);
bmaSensor.enableFeature(bmaSensor.FEATURE_TILT, true);
bmaSensor.enableFeature(bmaSensor.FEATURE_WAKEUP, true);
// bmaSensor.resetPedometer();

// Turn on feature interrupt
bmaSensor.enableStepCountInterrupt();
bmaSensor.enableTiltInterrupt();
bmaSensor.enablePedometerIRQ();
bmaSensor.enableTiltIRQ();
// It corresponds to isDoubleClick interrupt
bmaSensor.enableWakeupInterrupt();
bmaSensor.enableWakeupIRQ();
}
}

Expand All @@ -150,8 +128,8 @@ class AccelerometerThread : public concurrency::OSThread
buttonPress();
return 500;
}
} else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.getINT()) {
if (bmaSensor.isTilt() || bmaSensor.isDoubleClick()) {
} else if (acceleremoter_type == ScanI2C::DeviceType::BMA423 && bmaSensor.readIrqStatus() != DEV_WIRE_NONE) {
if (bmaSensor.isTilt() || bmaSensor.isDoubleTap()) {
wakeScreen();
return 500;
}
Expand Down
10 changes: 9 additions & 1 deletion src/SerialConsole.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,11 @@
#include "PowerFSM.h"
#include "configuration.h"

#ifdef RP2040_SLOW_CLOCK
#define Port Serial2
#else
#define Port Serial
#endif
// Defaulting to the formerly removed phone_timeout_secs value of 15 minutes
#define SERIAL_CONNECTION_TIMEOUT (15 * 60) * 1000UL

Expand Down Expand Up @@ -31,6 +35,10 @@ SerialConsole::SerialConsole() : StreamAPI(&Port), RedirectablePrint(&Port), con
canWrite = false; // We don't send packets to our port until it has talked to us first
// setDestination(&noopPrint); for testing, try turning off 'all' debug output and see what leaks

#ifdef RP2040_SLOW_CLOCK
Port.setTX(SERIAL2_TX);
Port.setRX(SERIAL2_RX);
#endif
Port.begin(SERIAL_BAUD);
#if defined(ARCH_NRF52) || defined(CONFIG_IDF_TARGET_ESP32S2) || defined(CONFIG_IDF_TARGET_ESP32S3) || defined(ARCH_RP2040)
time_t timeout = millis();
Expand Down Expand Up @@ -64,7 +72,7 @@ bool SerialConsole::checkIsConnected()

/**
* we override this to notice when we've received a protobuf over the serial
* stream. Then we shunt off debug serial output.
* stream. Then we shut off debug serial output.
*/
bool SerialConsole::handleToRadio(const uint8_t *buf, size_t len)
{
Expand Down
1 change: 1 addition & 0 deletions src/configuration.h
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#define MCP9808_ADDR 0x18
#define INA_ADDR 0x40
#define INA_ADDR_ALTERNATE 0x41
#define INA_ADDR_WAVESHARE_UPS 0x43
#define INA3221_ADDR 0x42
#define QMC6310_ADDR 0x1C
#define QMI8658_ADDR 0x6B
Expand Down
10 changes: 8 additions & 2 deletions src/detect/ScanI2CTwoWire.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,8 +183,13 @@ void ScanI2CTwoWire::scanPort(I2CPort port)

#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL)
case ATECC608B_ADDR:
type = ATECC608B;
if (atecc.begin(addr.address) == true) {
#ifdef RP2040_SLOW_CLOCK
if (atecc.begin(addr.address, Wire, Serial2) == true)
#else
if (atecc.begin(addr.address) == true)
#endif

{
LOG_INFO("ATECC608B initialized\n");
} else {
LOG_WARN("ATECC608B initialization failed\n");
Expand Down Expand Up @@ -254,6 +259,7 @@ void ScanI2CTwoWire::scanPort(I2CPort port)

case INA_ADDR:
case INA_ADDR_ALTERNATE:
case INA_ADDR_WAVESHARE_UPS:
registerValue = getRegisterValue(ScanI2CTwoWire::RegisterLocation(addr, 0xFE), 2);
LOG_DEBUG("Register MFG_UID: 0x%x\n", registerValue);
if (registerValue == 0x5449) {
Expand Down
56 changes: 53 additions & 3 deletions src/gps/GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -290,6 +290,26 @@ bool GPS::setup()
// Switch to Vehicle Mode, since SoftRF enables Aviation < 2g
_serial_gps->write("$PCAS11,3*1E\r\n");
delay(250);
} else if (gnssModel == GNSS_MODEL_MTK_L76B) {
// Waveshare Pico-GPS hat uses the L76B with 9600 baud
// Initialize the L76B Chip, use GPS + GLONASS
// See note in L76_Series_GNSS_Protocol_Specification, chapter 3.29
_serial_gps->write("$PMTK353,1,1,0,0,0*2B\r\n");
// Above command will reset the GPS and takes longer before it will accept new commands
delay(1000);
// only ask for RMC and GGA (GNRMC and GNGGA)
// See note in L76_Series_GNSS_Protocol_Specification, chapter 2.1
_serial_gps->write("$PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28\r\n");
delay(250);
// Enable SBAS
_serial_gps->write("$PMTK301,2*2E\r\n");
delay(250);
// Enable PPS for 2D/3D fix only
_serial_gps->write("$PMTK285,3,100*3F\r\n");
delay(250);
// Switch to Fitness Mode, for running and walking purpose with low speed (<5 m/s)
_serial_gps->write("$PMTK886,1*29\r\n");
delay(250);
} else if (gnssModel == GNSS_MODEL_UC6580) {
// The Unicore UC6580 can use a lot of sat systems, enable it to
// use GPS L1 & L5 + BDS B1I & B2a + GLONASS L1 + GALILEO E1 & E5a + SBAS
Expand Down Expand Up @@ -625,17 +645,27 @@ void GPS::setGPSPower(bool on, bool standbyOnly, uint32_t sleepTime)
return;
}
#endif
#ifdef PIN_GPS_STANDBY // Specifically the standby pin for L76K and clones
#ifdef PIN_GPS_STANDBY // Specifically the standby pin for L76B, L76K and clones
if (on) {
LOG_INFO("Waking GPS\n");
pinMode(PIN_GPS_STANDBY, OUTPUT);
// Some PCB's use an inverse logic due to a transistor driver
// Example for this is the Pico-Waveshare Lora+GPS HAT
#ifdef PIN_GPS_STANDBY_INVERTED
digitalWrite(PIN_GPS_STANDBY, 0);
#else
digitalWrite(PIN_GPS_STANDBY, 1);
#endif
return;
} else {
LOG_INFO("GPS entering sleep\n");
// notifyGPSSleep.notifyObservers(NULL);
pinMode(PIN_GPS_STANDBY, OUTPUT);
#ifdef PIN_GPS_STANDBY_INVERTED
digitalWrite(PIN_GPS_STANDBY, 1);
#else
digitalWrite(PIN_GPS_STANDBY, 0);
#endif
return;
}
#endif
Expand Down Expand Up @@ -916,7 +946,7 @@ GnssModel_t GPS::probe(int serialSpeed)
uint8_t buffer[768] = {0};
delay(100);

// Close all NMEA sentences , Only valid for MTK platform
// Close all NMEA sentences , Only valid for L76K MTK platform
_serial_gps->write("$PCAS03,0,0,0,0,0,0,0,0,0,0,,,0,0*02\r\n");
delay(20);

Expand All @@ -928,6 +958,18 @@ GnssModel_t GPS::probe(int serialSpeed)
return GNSS_MODEL_MTK;
}

// Close all NMEA sentences, valid for L76B MTK platform (Waveshare Pico GPS)
_serial_gps->write("$PMTK514,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*2E\r\n");
delay(20);

// Get version information
clearBuffer();
_serial_gps->write("$PMTK605*31\r\n");
if (getACK("Quectel-L76B", 500) == GNSS_RESPONSE_OK) {
LOG_INFO("L76B GNSS init succeeded, using L76B GNSS Module\n");
return GNSS_MODEL_MTK_L76B;
}

uint8_t cfg_rate[] = {0xB5, 0x62, 0x06, 0x08, 0x00, 0x00, 0x00, 0x00};
UBXChecksum(cfg_rate, sizeof(cfg_rate));
clearBuffer();
Expand Down Expand Up @@ -1109,7 +1151,6 @@ GPS *GPS::createGps()
LOG_DEBUG("Using GPIO%d for GPS RX\n", new_gps->rx_gpio);
LOG_DEBUG("Using GPIO%d for GPS TX\n", new_gps->tx_gpio);
_serial_gps->begin(GPS_BAUDRATE, SERIAL_8N1, new_gps->rx_gpio, new_gps->tx_gpio);

#else
_serial_gps->begin(GPS_BAUDRATE);
#endif
Expand Down Expand Up @@ -1168,7 +1209,16 @@ bool GPS::factoryReset()
// byte _message_CFG_RST_COLDSTART[] = {0xB5, 0x62, 0x06, 0x04, 0x04, 0x00, 0xFF, 0xB9, 0x00, 0x00, 0xC6, 0x8B};
// _serial_gps->write(_message_CFG_RST_COLDSTART, sizeof(_message_CFG_RST_COLDSTART));
// delay(1000);
} else if (gnssModel == GNSS_MODEL_MTK) {
// send the CAS10 to perform a factory restart of the device (and other device that support PCAS statements)
LOG_INFO("GNSS Factory Reset via PCAS10,3\n");
_serial_gps->write("$PCAS10,3*1F\r\n");
delay(100);
} else {
// fire this for good measure, if we have an L76B - won't harm other devices.
_serial_gps->write("$PMTK104*37\r\n");
// No PMTK_ACK for this command.
delay(100);
// send the UBLOX Factory Reset Command regardless of detect state, something is very wrong, just assume it's UBLOX.
// Factory Reset
byte _message_reset[] = {0xB5, 0x62, 0x06, 0x09, 0x0D, 0x00, 0xFF, 0xFB, 0x00, 0x00, 0x00,
Expand Down
12 changes: 5 additions & 7 deletions src/gps/GPS.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,7 @@ struct uBloxGnssModelInfo {
char extension[10][30];
};

typedef enum {
GNSS_MODEL_MTK,
GNSS_MODEL_UBLOX,
GNSS_MODEL_UC6580,
GNSS_MODEL_UNKNOWN,
} GnssModel_t;
typedef enum { GNSS_MODEL_MTK, GNSS_MODEL_UBLOX, GNSS_MODEL_UC6580, GNSS_MODEL_UNKNOWN, GNSS_MODEL_MTK_L76B } GnssModel_t;

typedef enum {
GNSS_RESPONSE_NONE,
Expand Down Expand Up @@ -92,8 +87,11 @@ class GPS : private concurrency::OSThread

public:
/** If !NULL we will use this serial port to construct our GPS */
#if defined(RPI_PICO_WAVESHARE)
static SerialUART *_serial_gps;
#else
static HardwareSerial *_serial_gps;

#endif
static uint8_t _message_PMREQ[];
static uint8_t _message_PMREQ_10[];
static const uint8_t _message_CFG_RXM_PSM[];
Expand Down
4 changes: 2 additions & 2 deletions src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ void setup()
#if defined(TTGO_T_ECHO) && defined(PIN_POWER_EN)
pinMode(PIN_POWER_EN, OUTPUT);
digitalWrite(PIN_POWER_EN, HIGH);
digitalWrite(PIN_POWER_EN1, INPUT);
// digitalWrite(PIN_POWER_EN1, INPUT);
#endif

#if defined(LORA_TCXO_GPIO)
Expand Down Expand Up @@ -965,4 +965,4 @@ void loop()
mainDelay.delay(delayMsec);
}
// if (didWake) LOG_DEBUG("wake!\n");
}
}
Loading
Loading