การใช้ LILYGO TTGO T-Beam V1.2 ESP32 Lora32 เน้นการใช้งาน GPS Ublox NEO-6M

Somsak Lima
9 min readFeb 27, 2024

ปุ่มขวาสุดเป็นปุ่ม Hard Reset (RST) สั่งให้ Reboot หลังจาก Flash โปรแกรมหากไม่เริ่มทำงานอัตโนมัติให้กดปุ่มขวาสุดหนึ่งครั้ง

  1. ScanI2C.py
    ใช้ SCAN ดูว่ามีอุปกรณ์ I2C ต่อกี่ตัวและใช้ Address อะไรในการเรียกใช้งาน
from machine import Pin, SoftI2C
import machine
i2c = SoftI2C(scl=Pin(22), sda=Pin(21), freq=10000)
print('Scan i2c bus...')
devices = i2c.scan()

if len(devices) == 0:
print("No i2c device !")
else:
print('i2c devices found:',len(devices))

for device in devices:
print("Decimal address: ",device," | Hexa address: ",hex(device))

ผลการ RUN

Scan i2c bus…
i2c devices found: 2
Decimal address: 52 | Hexa address: 0x34
Decimal address: 60 | Hexa address: 0x3c

2.TestOLED.py
ทดสอบจอ OLED

import machine, ssd1306
from machine import Pin, SoftI2C
i2c = SoftI2C(scl=Pin(22), sda=Pin(21), freq=10000)
oled = ssd1306.SSD1306_I2C(128,64, i2c)
oled.fill(0)
oled.text('MicroPython', 10, 10)
oled.text('on T-Beam', 10, 30)
oled.show()

หรือ

from machine import Pin, SoftI2C
import ssd1306
i2c = SoftI2C(scl=Pin(22), sda=Pin(21), freq=10000)
display = ssd1306.SSD1306_I2C(128, 64, i2c)
display.text('Hello, World!', 0, 0, 1)
display.show()
display.fill(0)
display.fill_rect(0, 0, 32, 32, 1)
display.fill_rect(2, 2, 28, 28, 0)
display.vline(9, 8, 22, 1)
display.vline(16, 2, 22, 1)
display.vline(23, 8, 22, 1)
display.fill_rect(26, 24, 2, 4, 1)
display.text('MicroPython', 40, 0, 1)
display.text('SSD1306', 40, 12, 1)
display.text('OLED 128x64', 40, 24, 1)
display.show()

3.UARTGPS.py

from machine import UART
from time import sleep
uart1 = UART(1, 9600)
uart1.init(9600, bits=8, parity=None, stop=1, tx=12, rx=34)
sleep(1)
while True:
print(uart1.readline())
sleep(2)

ถ้าต่อปรกติ และรับข้อมูลจาก GPS ได้

b'$GPGLL,1347.96291,N,10020.30377,E,021301.00,A,A*6F\r\n'
b'$GPRMC,021302.00,A,1347.96286,N,10020.30398,E,0.445,,280224,,,A*79\r\n'
b'$GPVTG,,T,,M,0.445,N,0.824,K,A*28\r\n'
b'$GPGGA,021302.00,1347.96286,N,10020.30398,E,1,06,1.53,-1.7,M,-28.5,M,,*56\r\n'
b'$GPGSA,A,3,31,26,16,08,03,27,,,,,,,2.69,1.53,2.22*05\r\n'
b'$GPGSV,3V,3,2,11,09,18,323,,16,43,012,21,21,09,181,,26,19,036,10*70\r\n'
b'$GPGSV,3,3,11,27,65,098,10,28,08,091,,31,24,070,15*42\r\n'
b'$GPGLL,1347.96416,N,10020.30326,E,021312.00,A,A*60\r\n'
b'1,,08,53,180,27*75\r\n'
b'$GPGSV,3,2,11,09,18,323,,16,43,012,20,21,09,181,,26,19,036,12*73\r\n'
b'$GPGSV,3,3,11,27,65,098,,28,08,09121,09,181,,26,19,036,14*75\r\n'

กรณีต้องการใช้ภาษา C เพื่ออ่านค่า GPS ดูว่าเชื่อมต่อ GPS ปรกติรึเปล่า

#include <HardwareSerial.h>
#define GPS_SERIAL_NUM 1
#define GPS_RX_PIN 34
#define GPS_TX_PIN 12

HardwareSerial GPSSerial(GPS_SERIAL_NUM);

void setup() {
Serial.begin(115200);
GPSSerial.begin(9600, SERIAL_8N1, GPS_RX_PIN, GPS_TX_PIN);

Serial.println("Hello GPS");
}

void loop() {
if (Serial.available()) {
char c = Serial.read();
GPSSerial.write(c);
}
if (GPSSerial.available()) {
char c = GPSSerial.read();
Serial.write(c);
}
}

ตอน Compile ด้วย Arduino IDE ให้เลือก Board Tbeam

ตั้งค่าตรงบรรทัด GPSSerial.begin(115200 ให้ตรงที่ SAVE ไว้ใน Ublox โมดูล ปรกติจะเป็น 9600 แต่หากติดตั้งโปรแกรมบางตัวลงไปค่านี้อาจจะถูกเปลี่ยน

เช่น หากลง โปรแกรม https://github.com/Max-Plastix/tbeam-helium-mapper.

ไฟล์ https://github.com/Max-Plastix/tbeam-helium-mapper/blob/main/main/configuration.h บรรทัดที่ 193 มีการกำหนดค่าเป็น 115200

#define GPS_BAUDRATE 115200 // Make haste! NMEA is big.. go fast

4.GPS_Lat_lon.py

import machine
from machine import UART, SoftI2C
from time import sleep
from micropyGPS import MicropyGPS
uart1 = UART(1, 9600)
uart1.init(9600, bits=8, parity=None, stop=1, tx=12, rx=34)
sleep(1)
my_gps = MicropyGPS(+7)
while True:

my_sentence = uart1.readline()
sleep(3)
print (my_sentence)
for x in str(my_sentence):
my_gps.update(x)


print('Latitude:',my_gps.latitude)
print('Logitude:',my_gps.longitude)
print('Latitude:',my_gps.latitude_string())
print('Logitude:',my_gps.longitude_string())
print('Date:',my_gps.date_string("long"))
print('Time:',my_gps.timestamp)
print('Speed (Km/hr):',my_gps.speed_string('kph'))
print('Direction:',my_gps.course)
print('satellites_in_use',my_gps.satellites_in_use)
#print('satellites_used',my_gps.satellites_used)
print('my_gps.altitude',my_gps.altitude)
print('--------------------------- ')
lat1=my_gps.latitude[0]+my_gps.latitude[1]/60
lon1=my_gps.longitude[0]+my_gps.longitude[1]/60
print('LATITUDE %2.6f' % float(lat1))
print('LONGIITUDE %2.6f' % float(lon1))
print('ALTITUDE %f' % float(my_gps.altitude))
print('--------------------------- ')

ผลการ RUN

b'$GPGGA,021626.00,1347.96507,N,10020.29739,E,1,04,3.21,15.9,M,-28.5,M,,*4F\r\n'
Latitude: [13, 9.96507, 'N']
Logitude: [100, 50.29739, 'E']
Latitude: 13 90.96507' N
Logitude: 100 400.29739' E
Date: February 28th, 2024
Time: [9, 16, 26.0]
Speed (Km/hr): 0.409292 km/h
Direction: 0.0
satellites_in_use 4
my_gps.altitude 15.9
---------------------------
LATITUDE 13.999417
LONGIITUDE 100.438287
ALTITUDE 15.900000
---------------------------

5. ใช้ภาษา C แสดงผล GPS เช่น ค่า Lat Long และ เวลา โดยใช้ lib TinyGPSPlus

#include <TinyGPSPlus.h>
#include <SoftwareSerial.h>
/*
This sample sketch demonstrates the normal use of a TinyGPSPlus (TinyGPSPlus) object.
It requires the use of SoftwareSerial, and assumes that you have a
4800-baud serial GPS device hooked up on pins 4(rx) and 3(tx).
*/
static const int RXPin = 34, TXPin = 12;
static const uint32_t GPSBaud = 115200;

// The TinyGPSPlus object
TinyGPSPlus gps;

// The serial connection to the GPS device
SoftwareSerial ss(RXPin, TXPin);

void setup()
{
Serial.begin(115200);
ss.begin(GPSBaud);

Serial.println(F("DeviceExample.ino"));
Serial.println(F("A simple demonstration of TinyGPSPlus with an attached GPS module"));
Serial.print(F("Testing TinyGPSPlus library v. ")); Serial.println(TinyGPSPlus::libraryVersion());
Serial.println(F("by Mikal Hart"));
Serial.println();
}

void loop()
{
// This sketch displays information every time a new sentence is correctly encoded.
while (ss.available() > 0)
if (gps.encode(ss.read()))
displayInfo();

if (millis() > 5000 && gps.charsProcessed() < 10)
{
Serial.println(F("No GPS detected: check wiring."));
while(true);
}
}

void displayInfo()
{
Serial.print(F("Location: "));
if (gps.location.isValid())
{
Serial.print(gps.location.lat(), 6);
Serial.print(F(","));
Serial.print(gps.location.lng(), 6);
}
else
{
Serial.print(F("INVALID"));
}

Serial.print(F(" Date/Time: "));
if (gps.date.isValid())
{
Serial.print(gps.date.month());
Serial.print(F("/"));
Serial.print(gps.date.day());
Serial.print(F("/"));
Serial.print(gps.date.year());
}
else
{
Serial.print(F("INVALID"));
}

Serial.print(F(" "));
if (gps.time.isValid())
{
if (gps.time.hour() < 10) Serial.print(F("0"));
Serial.print(gps.time.hour()+7);
Serial.print(F(":"));
if (gps.time.minute() < 10) Serial.print(F("0"));
Serial.print(gps.time.minute());
Serial.print(F(":"));
if (gps.time.second() < 10) Serial.print(F("0"));
Serial.print(gps.time.second());
Serial.print(F("."));
if (gps.time.centisecond() < 10) Serial.print(F("0"));
Serial.print(gps.time.centisecond());
}
else
{
Serial.print(F("INVALID"));
}

Serial.println();
}

ต้องติดตั้ง Lib EspSoftwareSerial Dirk Kaar, Peter Lerup

และ Lib TinyGPSPlus ของ Mikal Hart ด้วย

6.ลิ้งค์วิธีการใช้โปรแกรม U Center เพื่อ Enable หรือ disable NMEA datasets in u-blox GPS module

7.โปรแกรมไว้ Reset เป็น NMEA Protocol และ Reset Baud Rate กลับไป 9600 bps

https://github.com/eriktheV-king/TTGO_T-beam_GPS-reset/blob/master/T22-GPS-restoreFactory-v2/T22-GPS-restoreFactory-v2.ino

/*************************************************************************
Original sketch by LilyGO
https://github.com/LilyGO/TTGO-T-Beam/tree/master/GPS-T22_v1.0-20190612

Modified by ErikThevking on August 25, 2020. Updated on August 27, 2020.

Purpose: to reset U-blox NEO GPS devices
on TTGO T-beam T22- V1.0 and 1.1 and maybe on 0.7 T-beams (uncomment yours)
This sketch will bring back U-blox GPS N6M & N8M factory settings
so that NMEA 9600 over the GPS serial output is enabled.

Thanks to Kizniche for his advice on
https://github.com/kizniche/ttgo-tbeam-ttn-tracker/issues/20

Based on SparkFun's Ublox Arduino Library and examples
https://github.com/sparkfun/SparkFun_Ublox_Arduino_Library
where you can download the necessary SparkFun library.

For T22_v1.0 20190612 and the T22_v1.1 20191212 boards
As the power management chipset changed, it
requires the axp20x library that can be found // AXP192 for T-beam; AXP202 for T-watch
https://github.com/lewisxhe/AXP202X_Library
**************************************************************************/

// Select your board version
//#define T_BEAM_V07 // AKA Rev0 (first board released)
#define T_BEAM_V10 // AKA Rev1 for board versions T-beam_V1.0 and V1.1 (second board released)

#if defined(T_BEAM_V07)
#define GPS_RX_PIN 12
#define GPS_TX_PIN 15
#elif defined(T_BEAM_V10)
#include <Wire.h>
#include <axp20x.h>
AXP20X_Class axp;
#define I2C_SDA 21
#define I2C_SCL 22
#define GPS_RX_PIN 34
#define GPS_TX_PIN 12
#endif

#include <SparkFun_Ublox_Arduino_Library.h> //http://librarymanager/All#SparkFun_Ublox_GPS
SFE_UBLOX_GPS myGPS;
int state = 0; // steps through states
HardwareSerial SerialGPS(1);


void setup()
{
Serial.begin(115200);
while (!Serial); // Wait for user to open the terminal
Serial.println("Connected to Serial");
Wire.begin(I2C_SDA, I2C_SCL);

#if defined(T_BEAM_V10)
if (!axp.begin(Wire, AXP192_SLAVE_ADDRESS)) {
Serial.println("AXP192 Begin PASS");
} else {
Serial.println("AXP192 Begin FAIL");
}
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON); // GPS main power
axp.setPowerOutPut(AXP192_LDO2, AXP202_ON); // provides power to GPS backup battery
axp.setPowerOutPut(AXP192_LDO3, AXP202_ON);
axp.setPowerOutPut(AXP192_DCDC2, AXP202_ON);
axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
axp.setPowerOutPut(AXP192_DCDC1, AXP202_ON); // enables power to ESP32 on T-beam
axp.setPowerOutPut(AXP192_DCDC3, AXP202_ON); // I foresee similar benefit for restting T-watch
// where ESP32 is on DCDC3 but remember to change I2C pins and GPS pins!
#endif
SerialGPS.begin(115200, SERIAL_8N1, GPS_RX_PIN, GPS_TX_PIN);
Serial.println("All comms started");
delay(100);

} // endofsetup


void loop()
{
Serial.println();
Serial.print("===== STATE ");
Serial.println(state);
switch (state) {
case 0: // soft solution, should be sufficient and works in most (all) cases
do {
if (myGPS.begin(SerialGPS)) {
Serial.println("Connected to GPS");
myGPS.setUART1Output(COM_TYPE_NMEA); //Set the UART port to output NMEA only
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
Serial.println("GPS serial connected, output set to NMEA");
myGPS.disableNMEAMessage(UBX_NMEA_GLL, COM_PORT_UART1);
myGPS.disableNMEAMessage(UBX_NMEA_GSA, COM_PORT_UART1);
myGPS.disableNMEAMessage(UBX_NMEA_GSV, COM_PORT_UART1);
myGPS.disableNMEAMessage(UBX_NMEA_VTG, COM_PORT_UART1);
myGPS.disableNMEAMessage(UBX_NMEA_RMC, COM_PORT_UART1);
myGPS.enableNMEAMessage(UBX_NMEA_GGA, COM_PORT_UART1);
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
break;
}
delay(1000);
} while(1);
Serial.println("Saved config");
state++;
break;

case 1: // hardReset
Serial.println("Issuing hardReset (cold start)");
myGPS.hardReset();
delay(3000);
SerialGPS.begin(115200, SERIAL_8N1, GPS_RX_PIN, GPS_TX_PIN);
if (myGPS.begin(SerialGPS)) {
Serial.println("Success.");
state++;
} else {
Serial.println("*** GPS did not respond, starting over.");
state = 0;
}
break;

case 2: // factoryReset, expect to see GPS back at 9600 baud
Serial.println("Issuing factoryReset");
myGPS.factoryReset();
delay(3000); // takes more than one second... a loop to resync would be best
SerialGPS.begin(9600, SERIAL_8N1, GPS_RX_PIN, GPS_TX_PIN);
if (myGPS.begin(SerialGPS)) {
Serial.println("Success.");
Serial.println("Now GPS has been reset with factory settings,");
Serial.println("give us some time to acquire satellites...");
Serial.println();
state++;
} else {
Serial.println("*** GPS did not respond, starting over.");
state = 0;
}
break;

case 3: //
for (uint32_t thisNr = 1; thisNr < 300000000; thisNr++) {
if (SerialGPS.available()) {
Serial.write(SerialGPS.read()); // print anything comes in from the GPS
}
}


} // endofswitchstate




} // endofloop

8. ใช้ภาษา C ทำ Serial Port Pass Through เพื่อให้ เสมือน U Center ต่อเข้ามอดูล Ublox โดยตรง ****ยังไม่มีตัวอย่างที่ใช้ภาษา MicroPython

void setup() {
Serial.begin(9600);
Serial1.begin(9600, SERIAL_8N1, 34, 12, false, 1000);
}

void loop() {
if (Serial.available()) {
Serial1.write(Serial.read());
}

if (Serial1.available()) {
Serial.write(Serial1.read());
}
}

Download UBlox U-Center จากเวป https://www.u-blox.com/en/product/u-center

ติดตั้ง U-Center แล้วเปิดโปรแกรม u-center

กด Connect เลือก Port ให้ถูก แล้วเปิด Text Console

ดูบรรทัด $GPRMC เป็นบรรทัดที่มีข้อมูล Lat และ Long

ด้านขวาของจอจะเห็นข้อมูลเป็นรูป graphic

เลือก View Sky view หรือ Deviation View ได้ตามรูป

9.ลิ้งค์วิธีตั้ง Baud rate ให้เร็วขึ้น

10.ตัวอย่างการใช้ LoRaWAN ส่ง Dummy Data อุณหภูมิ ความชื้นและส่ง Lat Long ของ GPS มอดูล

from cayennelpp import CayenneLPP
from micropyGPS import MicropyGPS
import utime, time
from ulora import TTN, uLoRa
import machine

#TBEAM
LORA_CS = const(18)
LORA_SCK = const(5)
LORA_MOSI = const(27)
LORA_MISO = const(19)
LORA_IRQ = const(23)
LORA_RST = const(26)

LORA_DATARATE = "SF12BW125" # Choose from several available
DEVADDR = bytearray([0x26, 0x01, 0x15, 0x6A])
NWKEY = bytearray([0xA6, 0xC3, 0x0F, 0xB2, 0x91, 0xDB, 0x55, 0xC5,
0x31, 0x82, 0x53, 0xD4, 0x08, 0x08, 0x7A, 0x4E])
APP = bytearray([0x54, 0xBE, 0x2D, 0xE6, 0xB6, 0xB3, 0xF7, 0xC2,
0xD0, 0x33, 0x72, 0xB5, 0x27, 0x20, 0xD6, 0x20 ])
TTN_CONFIG = TTN(DEVADDR, NWKEY, APP, country="AS")
FPORT = 1
lora = uLoRa(
cs=LORA_CS,
sck=LORA_SCK,
mosi=LORA_MOSI,
miso=LORA_MISO,
irq=LORA_IRQ,
rst=LORA_RST,
ttn_config=TTN_CONFIG,
datarate=LORA_DATARATE,
fport=FPORT
)
temp = 30
pa = 1000.1
hum = 50
i2c = machine.SoftI2C(scl=machine.Pin(22), sda=machine.Pin(21))
com = machine.UART(2,baudrate=9600,rx=34,tx=12,timeout=10)
my_gps = MicropyGPS(7)
my_gps.local_offset
def get_GPS_values():
global gps_values,rtc
time.sleep(2)
cc = com.readline()
print (cc)
for x in cc:
my_gps.update(chr(x))
gps_values = str(my_gps.latitude[0] + (my_gps.latitude[1] / 60)) + ',' + str(my_gps.longitude[0] + (my_gps.longitude[1] / 60))
date = my_gps.date
timestamp = my_gps.timestamp
hour = timestamp[0]
rtc = str(int(timestamp[0]))+":"+str(int(timestamp[1]))+":"+str(int(timestamp[2]))
return gps_values,rtc
counter = 0
while True:
get_GPS_values()
print("LAT,LONG",gps_values)
lat,long=gps_values.split(",")
print (float(lat))
print (float(long))
c = CayenneLPP()
c.addTemperature(1, float(temp))
c.addRelativeHumidity(2, float(hum))
c.addBarometricPressure(3, float(pa))
c.addGPS(7, float(lat), float(long),2.0 )
data = c.getBuffer() # Get bytes
lora.frame_counter=counter
lora.send_data(data, len(data), lora.frame_counter)
time.sleep(2)
counter += 1

ttn_as.py

#AS2
TTN_FREQS = {0: (0xe6, 0xCC, 0xF4), # 923.2 Mhz
1: (0xe6, 0xD9, 0xC0), # 923.4 Mhz
2: (0xe6, 0xe6, 0x66), # 923.6 Mhz
3: (0xe6, 0xf3, 0x33), # 923.8 Mhz
4: (0xe7, 0x00, 0x00), # 924.0 Mhz
5: (0xe7, 0x0C, 0xCC), # 924.2 Mhz
6: (0xe7, 0x19, 0x99), # 924.4 Mhz
7: (0xe7, 0x26, 0x66)} # 924.6 Mhz

ไฟล์อื่น เช่น micropyGPS.py, ulora.py และ ulora_encryption.py หาโหลดได้จาก Internet หรือสามารถ Download จาก คลิก

11.GPS_Lat_Long_OLED.py

import machine
from micropyGPS import MicropyGPS
from machine import UART, SoftI2C, Pin
from time import sleep
import ssd1306, machine
addrOled = 60 #0x3c
hSize = 64
wSize = 128
oledIsConnected = False
uart1 = UART(1, 9600)
uart1.init(9600, bits=8, parity=None, stop=1, tx=12, rx=34)
i2c = SoftI2C(scl=Pin(22), sda=Pin(21), freq=10000)
sleep(1)
my_gps = MicropyGPS(+7)

while True:
my_sentence = uart1.readline()
sleep(3)
print (my_sentence)
for x in str(my_sentence):
my_gps.update(x)

print('Latitude:',my_gps.latitude)
print('Logitude:',my_gps.longitude)
print('Latitude:',my_gps.latitude_string())
print('Logitude:',my_gps.longitude_string())
print('Date:',my_gps.date_string("long"))
print('Time:',my_gps.timestamp)
print('Speed (Km/hr):',my_gps.speed_string('kph'))
print('Direction:',my_gps.course)
print('satellites_in_use',my_gps.satellites_in_use)
print('my_gps.altitude',my_gps.altitude)

lat1=my_gps.latitude[0]+my_gps.latitude[1]/60
lon1=my_gps.longitude[0]+my_gps.longitude[1]/60
print('LATITUDE %2.6f' % float(lat1))
print('LONGIITUDE %2.6f' % float(lon1))
print('ALTITUDE %f' % float(my_gps.altitude))
print('--------------------------- ')
oled = ssd1306.SSD1306_I2C(wSize, hSize, i2c, addrOled)
oled.fill(0)
oled.text("Lat:", 0, 0)
oled.text(my_gps.latitude_string(), 0, 10)
oled.text("/Lon:", 25, 0)
oled.text(my_gps.longitude_string(), 0, 20)
oled.text("Date:"+my_gps.date_string("long"), 0, 30)
oled.text("LAT:"+str(float(lat1)), 0, 40)
oled.text("LON:"+str(float(lon1)), 0, 50)
oled.show()

หมายเหตุ ดาวน์โหลดไฟล์ตัวอย่างได้ที่

https://github.com/m2mlorawan/tbeam

--

--

Somsak Lima

สนับสนุนและส่งเสริมให้ผู้สนใจสามารถใช้งานเทคโนโลยี LoRa และ LoRaWAN ได้ โดยนำความรู้ที่ได้ไปต่อยอดเพื่อใช้งาน