kopia lustrzana https://github.com/lightaprs/LightTracker-1.0
Initial commit for sketch files
rodzic
841d612f1a
commit
bb647cdec4
Plik binarny nie jest wyświetlany.
Przed Szerokość: | Wysokość: | Rozmiar: 916 KiB |
|
@ -0,0 +1,703 @@
|
|||
|
||||
#include <RadioLib.h>
|
||||
#include <avr/dtostrf.h>
|
||||
#include <Adafruit_BMP085.h>
|
||||
#include "SparkFun_Ublox_Arduino_Library.h"
|
||||
#include <SPI.h>
|
||||
#include <MemoryFree.h>;
|
||||
#include <Adafruit_SSD1306.h>
|
||||
#include <math.h>
|
||||
#include <Wire.h>
|
||||
|
||||
#define d2r (M_PI / 180.0)
|
||||
|
||||
// SX1262 has the following connections:
|
||||
// NSS pin: 8
|
||||
// DIO1 pin: 3
|
||||
// NRST pin: 9
|
||||
// BUSY pin: 2
|
||||
SX1262 lora = new Module(8, 3, 9, 2);
|
||||
|
||||
#define BattPin A5
|
||||
#define GpsPwr 12
|
||||
#define GpsON digitalWrite(GpsPwr, LOW);
|
||||
#define GpsOFF digitalWrite(GpsPwr, HIGH);
|
||||
SFE_UBLOX_GPS myGPS;
|
||||
Adafruit_BMP085 bmp;
|
||||
|
||||
//#define DEVMODE // Development mode. Uncomment to enable for debugging.
|
||||
|
||||
//*********** General Settings ***********//
|
||||
int measurementSystem = 0; //0 for metric (meters, km, Celcius, etc.), 1 for imperial (feet, mile, Fahrenheit,etc.)
|
||||
float battMin=2.7; // min volts to run.
|
||||
|
||||
//********** GPS (uBlox) Settings ****************//
|
||||
uint8_t navigationFrequencyGPS = 1; //1-10. Set the number of GPS nav solutions sent per second. 10 is max and provide 10 GPS data per second.
|
||||
|
||||
//*********** LoRa Settings ***********//
|
||||
//Following frequencies were chosen arbitrarily; and should be same on the reciever (RX) module.
|
||||
//If necessary, users can select the appropriate channels according to their country regulations.
|
||||
|
||||
float loraFrequency = 865.2; //EU863-870
|
||||
//float loraFrequency = 907.4; //US902-928
|
||||
|
||||
int8_t outputPower = 16; //dBm (max outputPower is 16 dBm for EU868, AS923, KR920, RU864)
|
||||
//int8_t outputPower = 22; //dBm (max outputPower is 30 dBm for US915, AU915, IN865 but device limit is 22 dBm)
|
||||
|
||||
float loraBandWith = 125.0f; //do not change this, this is optimum for default payload size. //https://avbentem.github.io/airtime-calculator/
|
||||
uint8_t spreadingFactor = 8; ////do not change this, SF8 is optimum for default payload size. https://www.thethingsnetwork.org/docs/lorawan/spreading-factors/
|
||||
uint8_t codingRate = 5; //do not change this
|
||||
uint8_t syncWord = 0x12; //(private network)
|
||||
uint16_t preambleLength = 8; //do not change this
|
||||
int8_t lowDataRateOptimization = 0; //do not change this
|
||||
float dutyCyle = 0.01; //https://www.thethingsnetwork.org/docs/lorawan/duty-cycle.html
|
||||
int8_t loRaWANHeaderSize = 0; // aka overhead size, 13 for LoRAWAN, 0 for LoRa
|
||||
int explcttHdr = 0; //1 for LoRaWAN, 0 for LoRa
|
||||
int8_t CRC = 1; //do not change this
|
||||
|
||||
//********** OLED Display Settings ****************//
|
||||
|
||||
#define SCREEN_WIDTH 128 // OLED display width, in pixels
|
||||
#define SCREEN_HEIGHT 64 // OLED display height, in pixels
|
||||
|
||||
// Declaration for an SSD1306 display connected to I2C (SDA, SCL pins)
|
||||
#define OLED_RESET -1 // Reset pin # (or -1 if sharing Arduino reset pin)
|
||||
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);
|
||||
|
||||
int displayPageID = 2;
|
||||
int displayInterval = 8;
|
||||
uint32_t last_display_refreshed = 0;
|
||||
|
||||
//*********** Temp Veriables ***********//
|
||||
int rxCount = 0; //do not change this. counting LoRa RX messages...
|
||||
|
||||
float maxAltitude = 0; //do not change this.
|
||||
float minPressure = 0; //do not change this.
|
||||
|
||||
// flag to indicate that a packet was received
|
||||
volatile bool receivedFlag = false; //do not change this.
|
||||
|
||||
// disable interrupt when it's not needed
|
||||
volatile bool enableInterrupt = true; //do not change this.
|
||||
|
||||
uint32_t last_packet_send = 0; //do not change this. Last LoRa packet sent time
|
||||
uint32_t last_packet_received = 0; //do not change this. Last LoRa packet received time
|
||||
|
||||
static char tempUnit[2] = ""; //C or F
|
||||
static char speedUnit[7] = ""; //km/h or mph (mile per hour)
|
||||
static char altUnit[5] = ""; //meters or feet
|
||||
static char distUnit[5] = ""; //km or mile
|
||||
static char measureSystem[10] = ""; //Metric or Imperial
|
||||
|
||||
//latitude,longtitude,altitude,sattelite,speed,bearing,voltage,temp,pressure,etc. / 22 packets
|
||||
typedef union {
|
||||
float f[22]; // Assigning fVal.f will also populate fVal.bytes;
|
||||
unsigned char bytes[4]; // Both fVal.f and fVal.bytes share the same 4 bytes of memory.
|
||||
} floatArr2Val;
|
||||
|
||||
floatArr2Val telemetry;
|
||||
|
||||
void setup() {
|
||||
|
||||
pinMode(A1,INPUT_PULLUP);
|
||||
if(digitalRead(A1)==LOW) while(1);
|
||||
|
||||
delay(5000);
|
||||
|
||||
pinMode(GpsPwr, OUTPUT);
|
||||
GpsON;
|
||||
|
||||
SerialUSB.begin(115200);
|
||||
// Wait up to 5 seconds for serial to be opened, to allow catching
|
||||
// startup messages on native USB boards (that do not reset when
|
||||
// serial is opened).
|
||||
unsigned long start = millis();
|
||||
while (millis() - start < 5000 && !SerialUSB);
|
||||
|
||||
SerialUSB.println();
|
||||
SerialUSB.println(F("Starting"));
|
||||
SerialUSB.println();
|
||||
|
||||
SerialUSB.println(F("LoRa setup initiating.."));
|
||||
setupLoRa();
|
||||
//printLoRaSettings();
|
||||
|
||||
SerialUSB.println(F("GPS setup initiating..(NO GPS fix yet)"));
|
||||
setupGPS_BMP();
|
||||
delay(2000);
|
||||
|
||||
setupDisplay();
|
||||
|
||||
}
|
||||
|
||||
// this function is called when a complete packet
|
||||
// is received by the module
|
||||
// IMPORTANT: this function MUST be 'void' type
|
||||
// and MUST NOT have any arguments!
|
||||
void setFlag(void) {
|
||||
// check if the interrupt is enabled
|
||||
if(!enableInterrupt) {
|
||||
return;
|
||||
}
|
||||
|
||||
// we got a packet, set the flag
|
||||
receivedFlag = true;
|
||||
}
|
||||
|
||||
|
||||
void loop() {
|
||||
|
||||
if (readBatt() > battMin) {
|
||||
|
||||
if(receivedFlag) {
|
||||
|
||||
displayIncmng();
|
||||
|
||||
// disable the interrupt service routine while
|
||||
// processing the data
|
||||
enableInterrupt = false;
|
||||
|
||||
// reset flag
|
||||
receivedFlag = false;
|
||||
|
||||
// you can read received data as an Arduino String if sent as string...
|
||||
//String str;
|
||||
//int state = lora.readData(str);
|
||||
|
||||
// you can also read received data as byte array
|
||||
byte byteArr[sizeof(telemetry)];
|
||||
int state = lora.readData(byteArr, sizeof(telemetry));
|
||||
|
||||
byte tempData[4];
|
||||
int x = 0;
|
||||
for (int i = 0; i < sizeof(telemetry); i++) {
|
||||
|
||||
tempData[x] = byteArr[i];
|
||||
|
||||
if(x == 3) {
|
||||
telemetry.f[(int)(i/4)] = *((float*)(tempData));
|
||||
x=0;
|
||||
} else {
|
||||
++x;
|
||||
}
|
||||
}
|
||||
|
||||
if (state == ERR_NONE) {
|
||||
// packet was successfully received
|
||||
last_packet_received = millis();
|
||||
|
||||
// print data of the packet
|
||||
displayPageID = 1;
|
||||
printRXTelemetry();
|
||||
printLoRaSettings();
|
||||
++rxCount;
|
||||
|
||||
} else if (state == ERR_CRC_MISMATCH) {
|
||||
// packet was received, but is malformed
|
||||
SerialUSB.println(F("CRC error!"));
|
||||
displayIncmngError();
|
||||
|
||||
} else {
|
||||
// some other error occurred
|
||||
SerialUSB.print(F("failed, code "));
|
||||
SerialUSB.println(state);
|
||||
|
||||
}
|
||||
|
||||
// put module back to listen mode
|
||||
lora.startReceive();
|
||||
|
||||
// we're ready to receive more packets,
|
||||
// enable interrupt service routine
|
||||
enableInterrupt = true;
|
||||
|
||||
freeMem();
|
||||
}
|
||||
|
||||
//update GPS data
|
||||
myGPS.getPVT();
|
||||
|
||||
#if defined(DEVMODE)
|
||||
printGPSData();
|
||||
#endif
|
||||
|
||||
//update oled display
|
||||
if (millis() - last_display_refreshed > (displayInterval * 1000)) {
|
||||
|
||||
printDisplay(displayPageID);
|
||||
last_display_refreshed = millis();
|
||||
++displayPageID;
|
||||
|
||||
if(displayPageID == 6) {
|
||||
displayPageID = 2;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
} else {
|
||||
SerialUSB.println(F("Voltage is too low, please check your battery..."));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void displayIncmng(){
|
||||
display.clearDisplay();
|
||||
display.setCursor(0, 30);
|
||||
display.println("Incoming packet...");
|
||||
display.display();
|
||||
}
|
||||
|
||||
void displayIncmngError(){
|
||||
display.clearDisplay();
|
||||
display.setCursor(0, 30);
|
||||
display.println("CRC Error, packet malformed..");
|
||||
display.display();
|
||||
}
|
||||
|
||||
void printDisplay(int pageID){
|
||||
|
||||
display.clearDisplay();
|
||||
display.setCursor(0, 0);
|
||||
|
||||
|
||||
float tempAltitude = 0;
|
||||
float tempSpeed = 0;
|
||||
float tempTemperature = 0;
|
||||
|
||||
double distance = 0;
|
||||
|
||||
if(measurementSystem == 0){ //Metric
|
||||
//meter
|
||||
tempAltitude = myGPS.getAltitude() / 1000.f;
|
||||
//km/hour
|
||||
tempSpeed = myGPS.getGroundSpeed() * 0.0036f;
|
||||
//Celsius
|
||||
tempTemperature = bmp.readTemperature();
|
||||
|
||||
} else { //Imperial
|
||||
//feet
|
||||
tempAltitude = (myGPS.getAltitude() * 3.2808399) / 1000.f;
|
||||
//mile/hour
|
||||
tempSpeed = myGPS.getGroundSpeed() * 0.00223694f;
|
||||
//Fahrenheit
|
||||
tempTemperature = (bmp.readTemperature() * 1.8f) + 32;
|
||||
}
|
||||
|
||||
if ((myGPS.getFixType() !=0) && (myGPS.getSIV() > 3)) {
|
||||
|
||||
if(telemetry.f[0] ==0 || telemetry.f[1] ==0){
|
||||
distance = 0;
|
||||
} else {
|
||||
distance = haversine(telemetry.f[0], telemetry.f[1], myGPS.getLatitude() / 10000000.f, myGPS.getLongitude() / 10000000.f, measurementSystem);
|
||||
}
|
||||
}
|
||||
|
||||
//SerialUSB.println(last_packet_received);
|
||||
int lastPcktTimeSeconds = (int)((millis()-last_packet_received)/1000);
|
||||
//SerialUSB.println(lastPcktTimeSeconds);
|
||||
|
||||
if(last_packet_received==0) {lastPcktTimeSeconds=0;}
|
||||
int lastPcktTimeMinutes = lastPcktTimeSeconds / 60 ;
|
||||
|
||||
//SerialUSB.println(lastPcktTimeMinutes);
|
||||
//SerialUSB.println("--------------------");
|
||||
|
||||
switch(pageID) {
|
||||
case 1:
|
||||
display.println("New Packet Recieved");
|
||||
display.println("");
|
||||
display.print("ID :");display.println((int)telemetry.f[21]);
|
||||
display.print("RX/TX :");display.print(rxCount);display.print("/");display.println((int)telemetry.f[20]);
|
||||
display.print("RSSI :");display.print(lora.getRSSI()); display.println(" dBm");
|
||||
display.print("SNR :");display.print(lora.getSNR()); display.println(" dB");
|
||||
display.print("PcktLngth:");display.print(lora.getPacketLength()); display.println(" bytes");
|
||||
break;
|
||||
case 2:
|
||||
display.println("RX Basic Data (1/3)");
|
||||
display.println("");
|
||||
display.print("Battery :");display.print(telemetry.f[6]); display.println("V");
|
||||
display.print("Temp :");display.print(telemetry.f[7]);display.println(tempUnit);
|
||||
display.print("Pressure :");display.print(telemetry.f[8]); display.println("hPa");
|
||||
if(lastPcktTimeSeconds < 100) {
|
||||
display.print("Last Pckt:");display.print(lastPcktTimeSeconds); display.println(" secs ago");
|
||||
} else {
|
||||
display.print("Last Pckt:");display.print(lastPcktTimeMinutes); display.println(" mins ago");
|
||||
}
|
||||
|
||||
break;
|
||||
case 3:
|
||||
display.println("RX GPS Data (2/3)");
|
||||
display.println("");
|
||||
display.print("GPS Sats :");display.println((int)telemetry.f[3]);
|
||||
display.print("Speed :");display.print(telemetry.f[5]);display.println(speedUnit);
|
||||
display.print("Heading :");display.print((int)telemetry.f[4]);display.println(" degrees");
|
||||
display.print("Altitude :");display.print((int)telemetry.f[2]);display.println(altUnit);
|
||||
display.print("Latitude :");display.println(telemetry.f[0]);
|
||||
display.print("Longitude:");display.println(telemetry.f[1]);
|
||||
break;
|
||||
case 4:
|
||||
display.println("RX G Data (3/3)");
|
||||
display.println("");
|
||||
display.print("MnX:");display.print(telemetry.f[12]);display.print(" MxX:");display.println(telemetry.f[13]);
|
||||
display.print("MnY:");display.print(telemetry.f[14]);display.print(" MxY:");display.println(telemetry.f[15]);
|
||||
display.print("MnZ:");display.print(telemetry.f[16]);display.print(" MxZ:");display.println(telemetry.f[17]);
|
||||
display.print("Min Press:");display.print(telemetry.f[19]);display.println("hPa");
|
||||
display.print("Max Alt:");display.print(telemetry.f[18]);display.println(altUnit);
|
||||
break;
|
||||
case 5:
|
||||
display.println("Your Data");
|
||||
display.println("");
|
||||
display.print("GPS Sats :");display.println((int)myGPS.getSIV());
|
||||
display.print("Speed :");display.print(tempSpeed);display.println(speedUnit);
|
||||
display.print("Altitude :");display.print((int)tempAltitude);display.println(altUnit);
|
||||
display.print("Battery :");display.print(readBatt()); display.println("V");
|
||||
display.print("Temp :");display.print(tempTemperature);display.println(tempUnit);
|
||||
display.print("Distance :");display.print(distance);display.println(distUnit);
|
||||
break;
|
||||
default:
|
||||
SerialUSB.println("default");
|
||||
break;
|
||||
}
|
||||
|
||||
display.display();
|
||||
|
||||
}
|
||||
|
||||
//calculate haversine distance for linear distance
|
||||
double haversine(double lat1, double long1, double lat2, double long2, boolean km)
|
||||
{
|
||||
double distance = 0;
|
||||
double dlong = (long2 - long1) * d2r;
|
||||
double dlat = (lat2 - lat1) * d2r;
|
||||
double a = pow(sin(dlat/2.0), 2) + cos(lat1*d2r) * cos(lat2*d2r) * pow(sin(dlong/2.0), 2);
|
||||
double c = 2 * atan2(sqrt(a), sqrt(1-a));
|
||||
|
||||
if (km) {
|
||||
distance = 6367 * c; //km
|
||||
} else {
|
||||
distance = 3956 * c; //miles
|
||||
}
|
||||
|
||||
return distance;
|
||||
}
|
||||
|
||||
|
||||
void printRXTelemetry() {
|
||||
|
||||
SerialUSB.println(F("-------Incoming Packet Telemetry-------"));
|
||||
SerialUSB.print(F("lat :"));
|
||||
SerialUSB.println(telemetry.f[0]);
|
||||
SerialUSB.print(F("long :"));
|
||||
SerialUSB.println(telemetry.f[1]);
|
||||
SerialUSB.print(F("alt :"));
|
||||
SerialUSB.println(telemetry.f[2]);
|
||||
SerialUSB.print(F("sats :"));
|
||||
SerialUSB.println((int)telemetry.f[3]);
|
||||
SerialUSB.print(F("heading:"));
|
||||
SerialUSB.println((int)telemetry.f[4]);
|
||||
SerialUSB.print(F("speed :"));
|
||||
SerialUSB.println(telemetry.f[5]);
|
||||
SerialUSB.print(F("batt :"));
|
||||
SerialUSB.println(telemetry.f[6]);
|
||||
SerialUSB.print(F("temp :"));
|
||||
SerialUSB.println(telemetry.f[7]);
|
||||
SerialUSB.print(F("press :"));
|
||||
SerialUSB.println(telemetry.f[8]);
|
||||
SerialUSB.print(F("scaledGX :"));
|
||||
SerialUSB.println(telemetry.f[9]);
|
||||
SerialUSB.print(F("scaledGY :"));
|
||||
SerialUSB.println(telemetry.f[10]);
|
||||
SerialUSB.print(F("scaledGZ :"));
|
||||
SerialUSB.println(telemetry.f[11]);
|
||||
SerialUSB.print(F("minScaledGX :"));
|
||||
SerialUSB.println(telemetry.f[12]);
|
||||
SerialUSB.print(F("maxScaledGX :"));
|
||||
SerialUSB.println(telemetry.f[13]);
|
||||
SerialUSB.print(F("minScaledGY :"));
|
||||
SerialUSB.println(telemetry.f[14]);
|
||||
SerialUSB.print(F("maxScaledGY :"));
|
||||
SerialUSB.println(telemetry.f[15]);
|
||||
SerialUSB.print(F("minScaledGZ :"));
|
||||
SerialUSB.println(telemetry.f[16]);
|
||||
SerialUSB.print(F("maxScaledGZ :"));
|
||||
SerialUSB.println(telemetry.f[17]);
|
||||
SerialUSB.print(F("maxAltitude :"));
|
||||
SerialUSB.println(telemetry.f[18]);
|
||||
SerialUSB.print(F("minPressure :"));
|
||||
SerialUSB.println(telemetry.f[19]);
|
||||
SerialUSB.print(F("rxC :"));
|
||||
SerialUSB.println((int)telemetry.f[20]);
|
||||
SerialUSB.print(F("trackerID :"));
|
||||
SerialUSB.println((int)telemetry.f[21]);
|
||||
|
||||
}
|
||||
|
||||
void printLoRaSettings(){
|
||||
|
||||
SerialUSB.println(F("-------------------------Incoming Packet LoRa Settings ---------------------------------------------------------"));
|
||||
SerialUSB.print(F("RSSI: "));
|
||||
SerialUSB.print(lora.getRSSI());
|
||||
SerialUSB.print(F(" dBm"));
|
||||
SerialUSB.print(F(", SNR: "));
|
||||
SerialUSB.print(lora.getSNR());
|
||||
SerialUSB.print(F(" dB"));
|
||||
SerialUSB.print(F(", Freq: "));
|
||||
SerialUSB.print(loraFrequency);
|
||||
SerialUSB.print(F("mHz, Bandwith: "));
|
||||
SerialUSB.print(loraBandWith);
|
||||
SerialUSB.print(F("kHz, SF: "));
|
||||
SerialUSB.print(spreadingFactor);
|
||||
SerialUSB.print(F(", Power: "));
|
||||
SerialUSB.print(outputPower);
|
||||
SerialUSB.print(F("dBm, Payload Size: "));
|
||||
SerialUSB.print(sizeof(telemetry));
|
||||
SerialUSB.println(F(" bytes"));
|
||||
SerialUSB.println(F("---------------------------------------------------------------------------------------------------------------"));
|
||||
}
|
||||
|
||||
|
||||
void setupLoRa() {
|
||||
|
||||
// initialize SX1262 with default settings
|
||||
SerialUSB.print(F("[SX1262] LoRa Radio Module Initializing ... "));
|
||||
int state = lora.begin();
|
||||
|
||||
|
||||
if (state == ERR_NONE) {
|
||||
SerialUSB.println(F("success!"));
|
||||
} else {
|
||||
SerialUSB.print(F("failed, code "));
|
||||
SerialUSB.println(state);
|
||||
while (true);
|
||||
}
|
||||
|
||||
if (lora.setFrequency(loraFrequency,true) == ERR_INVALID_FREQUENCY) {
|
||||
SerialUSB.println(F("Selected frequency is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set bandwidth to 1250 kHz
|
||||
if (lora.setBandwidth(loraBandWith) == ERR_INVALID_BANDWIDTH) {
|
||||
SerialUSB.println(F("Selected bandwidth is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set spreading factor to 10
|
||||
if (lora.setSpreadingFactor(spreadingFactor) == ERR_INVALID_SPREADING_FACTOR) {
|
||||
SerialUSB.println(F("Selected spreading factor is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set coding rate to 5
|
||||
if (lora.setCodingRate(codingRate) == ERR_INVALID_CODING_RATE) {
|
||||
SerialUSB.println(F("Selected coding rate is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set LoRaWAN sync word to 0x34
|
||||
if (lora.setSyncWord(syncWord) != ERR_NONE) {
|
||||
SerialUSB.println(F("Unable to set sync word!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set over current protection limit to 140 mA (accepted range is 45 - 240 mA)
|
||||
if (lora.setCurrentLimit(140) == ERR_INVALID_CURRENT_LIMIT) {
|
||||
Serial.println(F("Selected current limit is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set output power to 14 dBm (accepted range is -17, 22 dBm)
|
||||
if (lora.setOutputPower(outputPower) == ERR_INVALID_OUTPUT_POWER) {
|
||||
SerialUSB.println(F("Selected output power is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set LoRa preamble length to 8 symbols (accepted range is 0 - 65535)
|
||||
if (lora.setPreambleLength(preambleLength) == ERR_INVALID_PREAMBLE_LENGTH) {
|
||||
SerialUSB.println(F("Selected preamble length is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// enable CRC
|
||||
if (lora.setCRC(CRC) == ERR_INVALID_CRC_CONFIGURATION) {
|
||||
SerialUSB.println(F("Selected CRC is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
SerialUSB.println(F("All settings succesfully changed!"));
|
||||
|
||||
// set the function that will be called
|
||||
// when new packet is received
|
||||
lora.setDio1Action(setFlag);
|
||||
|
||||
// start listening for LoRa packets
|
||||
SerialUSB.print(F("[SX1262] LoRa Radio Module Starting to listen ... "));
|
||||
state = lora.startReceive();
|
||||
if (state == ERR_NONE) {
|
||||
SerialUSB.println(F("success!"));
|
||||
} else {
|
||||
SerialUSB.print(F("failed, code "));
|
||||
SerialUSB.println(state);
|
||||
while (true);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
float readBatt() {
|
||||
|
||||
float R1 = 560000.0; // 560K
|
||||
float R2 = 100000.0; // 100K
|
||||
float value = 0.0f;
|
||||
do {
|
||||
value =analogRead(BattPin);
|
||||
value +=analogRead(BattPin);
|
||||
value +=analogRead(BattPin);
|
||||
value = value / 3.0f;
|
||||
value = (value * 3.3) / 1024.0f;
|
||||
value = value / (R2/(R1+R2));
|
||||
} while (value > 10.0);
|
||||
return value ;
|
||||
|
||||
}
|
||||
|
||||
|
||||
void setupGPS_BMP() {
|
||||
GpsON;
|
||||
delay(100);
|
||||
Wire.begin();
|
||||
bmp.begin();
|
||||
|
||||
Wire.setClock(400000);
|
||||
|
||||
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
|
||||
{
|
||||
SerialUSB.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
|
||||
while (1)
|
||||
;
|
||||
}
|
||||
|
||||
// do not overload the buffer system from the GPS, disable UART output
|
||||
myGPS.setUART1Output(0); //Disable the UART1 port output
|
||||
myGPS.setUART2Output(0); //Disable Set the UART2 port output
|
||||
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
|
||||
|
||||
//myGPS.enableDebugging(); //Enable debug messages over Serial (default)
|
||||
|
||||
myGPS.setNavigationFrequency(navigationFrequencyGPS);//Sadece roket için 10 yapalım. //Set output to 10 times a second
|
||||
byte rate = myGPS.getNavigationFrequency(); //Get the update rate of this module
|
||||
SerialUSB.print("Current GPS update rate:");
|
||||
SerialUSB.println(rate);
|
||||
|
||||
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
|
||||
|
||||
}
|
||||
|
||||
void setupDisplay(){
|
||||
// SSD1306_SWITCHCAPVCC = generate display voltage from 3.3V internally
|
||||
if(!display.begin(SSD1306_SWITCHCAPVCC, 0x3C)) { // Address 0x3D for 128x64
|
||||
SerialUSB.println(F("SSD1306 allocation failed"));
|
||||
for(;;); // Don't proceed, loop forever
|
||||
}
|
||||
display.clearDisplay();
|
||||
display.setTextSize(1); // Draw 2X-scale text
|
||||
display.setTextColor(SSD1306_WHITE);
|
||||
|
||||
if(measurementSystem == 0){ //Metric
|
||||
//meters
|
||||
sprintf(altUnit, "%s", " m");
|
||||
//km/hour
|
||||
sprintf(speedUnit, "%s", " km/h");
|
||||
//Celsius
|
||||
sprintf(tempUnit, "%s", "C");
|
||||
//km
|
||||
sprintf(distUnit, "%s", " km");
|
||||
//Metric
|
||||
sprintf(measureSystem, "%s", "Metric");
|
||||
|
||||
|
||||
} else { //Imperial
|
||||
|
||||
//feet
|
||||
sprintf(altUnit, "%s", " ft");
|
||||
//mile/hour
|
||||
sprintf(speedUnit, "%s", " mph");
|
||||
//Fahrenheit
|
||||
sprintf(tempUnit, "%s", "F");
|
||||
//mile
|
||||
sprintf(distUnit, "%s", " mi");
|
||||
//Imperial
|
||||
sprintf(measureSystem, "%s", "Imperial");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void printGPSData()
|
||||
{
|
||||
// Calling getPVT returns true if there actually is a fresh navigation solution available.
|
||||
|
||||
byte fixType = myGPS.getFixType();
|
||||
|
||||
SerialUSB.print(F("FixType: "));
|
||||
SerialUSB.print(fixType);
|
||||
|
||||
long latitude = myGPS.getLatitude();
|
||||
float flat = myGPS.getLatitude() / 10000000.f;
|
||||
|
||||
SerialUSB.print(F(" Lat: "));
|
||||
SerialUSB.print(latitude);
|
||||
SerialUSB.print(F(" - "));
|
||||
SerialUSB.print(flat);
|
||||
|
||||
long longitude = myGPS.getLongitude();
|
||||
float flong = myGPS.getLongitude() / 10000000.f;
|
||||
SerialUSB.print(F(" Long: "));
|
||||
SerialUSB.print(longitude);
|
||||
SerialUSB.print(F(" - "));
|
||||
SerialUSB.print(flong);
|
||||
|
||||
float altitude = myGPS.getAltitude() / 1000;
|
||||
SerialUSB.print(F(" Alt: "));
|
||||
SerialUSB.print(altitude);
|
||||
SerialUSB.print(F(" (m)"));
|
||||
|
||||
int SIV = myGPS.getSIV();
|
||||
SerialUSB.print(F(" SIV: "));
|
||||
SerialUSB.print(SIV);
|
||||
|
||||
float speed = myGPS.getGroundSpeed() * 0.0036f;
|
||||
SerialUSB.print(F(" Speed: "));
|
||||
SerialUSB.print(speed);
|
||||
SerialUSB.print(F(" (km/h)"));
|
||||
|
||||
long heading = myGPS.getHeading() / 100000;
|
||||
SerialUSB.print(F(" Heading: "));
|
||||
SerialUSB.print(heading);
|
||||
SerialUSB.print(F(" (degrees )"));
|
||||
|
||||
SerialUSB.print(" ");
|
||||
SerialUSB.print(myGPS.getYear());
|
||||
SerialUSB.print("-");
|
||||
SerialUSB.print(myGPS.getMonth());
|
||||
SerialUSB.print("-");
|
||||
SerialUSB.print(myGPS.getDay());
|
||||
SerialUSB.print(" ");
|
||||
SerialUSB.print(myGPS.getHour());
|
||||
SerialUSB.print(":");
|
||||
SerialUSB.print(myGPS.getMinute());
|
||||
SerialUSB.print(":");
|
||||
SerialUSB.print(myGPS.getSecond());
|
||||
SerialUSB.print(":");
|
||||
SerialUSB.print(myGPS.getMillisecond());
|
||||
|
||||
SerialUSB.println();
|
||||
delay(1000);
|
||||
|
||||
}
|
||||
|
||||
void freeMem() {
|
||||
#if defined(DEVMODE)
|
||||
SerialUSB.print(F("Free RAM: ")); SerialUSB.print(freeMemory(), DEC); SerialUSB.println(F(" byte"));
|
||||
#endif
|
||||
|
||||
}
|
|
@ -0,0 +1,830 @@
|
|||
#include <RadioLib.h>
|
||||
#include <avr/dtostrf.h>
|
||||
#include <Adafruit_BMP085.h>
|
||||
#include "SparkFun_Ublox_Arduino_Library.h"
|
||||
#include "SparkFunLIS3DH.h"
|
||||
#include <SPI.h>
|
||||
#include <MemoryFree.h>;
|
||||
#include <Adafruit_SSD1306.h>
|
||||
|
||||
// SX1262 LoRa Module has the following connections:
|
||||
// NSS pin: 8
|
||||
// DIO1 pin: 3
|
||||
// NRST pin: 9
|
||||
// BUSY pin: 2
|
||||
SX1262 lora = new Module(8, 3, 9, 2);
|
||||
|
||||
#define BattPin A5
|
||||
#define GpsPwr 12
|
||||
#define GpsON digitalWrite(GpsPwr, LOW);
|
||||
#define GpsOFF digitalWrite(GpsPwr, HIGH);
|
||||
SFE_UBLOX_GPS myGPS;
|
||||
Adafruit_BMP085 bmp;
|
||||
LIS3DH myIMU; //Default constructor is I2C, addr 0x19.
|
||||
|
||||
//#define DEVMODE // Development mode. Uncomment to enable for debugging.
|
||||
|
||||
boolean airborne = false; //if you want to put the tracker on a airborne device, set this variable true;
|
||||
|
||||
//*********** General Settings ***********//
|
||||
uint16_t trackerID = 1234; //change this and set a random unique trackerID to avoid conflicts if you have multiple trackers.
|
||||
uint16_t loRaTXinterval=60; //time interval (seconds) between two beacons (TX). This value is updated (increased) based on your LoRa Region settings and duty cycle.
|
||||
uint8_t measurementSystem = 0; //0 for metric (meters, km, Celcius, etc.), 1 for imperial (feet, mile, Fahrenheit,etc.)
|
||||
float battMin=2.7;// min volts to run.
|
||||
|
||||
//*********** LoRa Settings ***********//
|
||||
//following TX settings should be same on the reciever module,
|
||||
//otherwise RX module can not recieve LoRa packets.
|
||||
boolean loRaEnabled = true;
|
||||
|
||||
//Following frequencies were chosen arbitrarily; and should be same on the reciever (RX) module.
|
||||
//If necessary, users can select the appropriate channels according to their country regulations.
|
||||
float loraFrequency = 865.2; //EU863-870
|
||||
//float loraFrequency = 907.4; //US902-928
|
||||
|
||||
int8_t outputPower = 16; //dBm (max outputPower is 16 dBm for EU868, AS923, KR920, RU864)
|
||||
//int8_t outputPower = 22; //dBm (max outputPower is 30 dBm for US915, AU915, IN865 but device limit is 22 dBm)
|
||||
|
||||
float loraBandWith = 125.0f; //do not change this, 125kHz is optimum for default payload size. //https://avbentem.github.io/airtime-calculator/
|
||||
uint8_t spreadingFactor = 8; ////do not change this, SF8 is optimum for default payload size. https://www.thethingsnetwork.org/docs/lorawan/spreading-factors/
|
||||
uint8_t codingRate = 5; //do not change this
|
||||
uint8_t syncWord = 0x12; //(private network)
|
||||
uint16_t preambleLength = 8; //do not change this
|
||||
int8_t lowDataRateOptimization = 0; //do not change this
|
||||
float dutyCyle = 0.01; //https://www.thethingsnetwork.org/docs/lorawan/duty-cycle.html
|
||||
int8_t loRaWANHeaderSize = 0; // aka overhead size, 13 for LoRAWAN, 0 for LoRa
|
||||
int explcttHdr = 0; //1 for LoRaWAN, 0 for LoRa
|
||||
int8_t CRC = 1; //do not change this
|
||||
|
||||
//latitude,longtitude,altitude,sattelite,speed,bearing,voltage,temp,pressure,etc. / 22 packets x 4 = 88 bytes
|
||||
typedef union {
|
||||
float f[22]; // Assigning fVal.f will also populate fVal.bytes;
|
||||
unsigned char bytes[4]; // Both fVal.f and fVal.bytes share the same 4 bytes of memory.
|
||||
} floatArr2Val;
|
||||
|
||||
floatArr2Val telemetry;
|
||||
|
||||
//********** GPS (uBlox) Settings ****************//
|
||||
uint8_t navigationFrequencyGPS = 10; //1-10. Set the number of GPS nav solutions sent per second. 10 is max and provide 10 GPS data per second.
|
||||
#define defaultMaxWait 100 //do not change this. Overriding UBlox default setting (1100) to fetch data faster from GPS module via I2C
|
||||
#define getPVTmaxWait 100 //do not change this. Overriding UBlox default setting (1100) to fetch data faster from GPS module via I2C
|
||||
|
||||
//********** OLED Display Settings ****************//
|
||||
|
||||
#define SCREEN_WIDTH 128 // OLED display width, in pixels
|
||||
#define SCREEN_HEIGHT 64 // OLED display height, in pixels
|
||||
|
||||
// Declaration for an SSD1306 display connected to I2C (SDA, SCL pins)
|
||||
#define OLED_RESET -1 // Reset pin # (or -1 if sharing Arduino reset pin)
|
||||
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);
|
||||
|
||||
int displayPageID = 1;
|
||||
int displayInterval = 5;
|
||||
uint32_t last_display_refreshed = -10000;
|
||||
|
||||
//*********** Temp Veriables ***********//
|
||||
|
||||
boolean gpsFixed = false;
|
||||
int txCount = 1; //do not change this. counting LoRa TX messages...
|
||||
uint32_t last_packet_send = -60000; //do not change this. Last LoRa packet sent time
|
||||
float maxAltitude = 0; //do not change this.
|
||||
float minPressure = 101325; //do not change this.
|
||||
|
||||
float accelGX = 0;
|
||||
float accelGY = 0;
|
||||
float accelGZ = 0;
|
||||
|
||||
float minGX = 0;
|
||||
float maxGX = 0;
|
||||
float minGY = 0;
|
||||
float maxGY = 0;
|
||||
float minGZ = 0;
|
||||
float maxGZ = 0;
|
||||
|
||||
float tempAltitude = 0;
|
||||
float tempSpeed = 0;
|
||||
float tempTemperature = 0;
|
||||
float tempLatitude = 0;
|
||||
float tempLongitude = 0;
|
||||
float tempSats = 0;
|
||||
float tempHeading = 0;
|
||||
float tempVoltage = 0;
|
||||
float tempPressure = 0;
|
||||
|
||||
static char tempUnit[2] = ""; //C or F
|
||||
static char speedUnit[7] = ""; //km/h or mph (mile per hour)
|
||||
static char altUnit[5] = ""; //meters or feet
|
||||
static char distUnit[5] = ""; //km or mile
|
||||
static char measureSystem[10] = ""; //Metric or Imperial
|
||||
|
||||
void setup() {
|
||||
|
||||
pinMode(A1,INPUT_PULLUP);
|
||||
if(digitalRead(A1)==LOW) while(1);
|
||||
|
||||
delay(5000);
|
||||
|
||||
pinMode(GpsPwr, OUTPUT);
|
||||
GpsON;
|
||||
|
||||
SerialUSB.begin(115200);
|
||||
// Wait up to 5 seconds for serial to be opened, to allow catching
|
||||
// startup messages on native USB boards (that do not reset when
|
||||
// serial is opened).
|
||||
unsigned long start = millis();
|
||||
while (millis() - start < 5000 && !SerialUSB);
|
||||
|
||||
SerialUSB.println();
|
||||
SerialUSB.println(F("Starting"));
|
||||
SerialUSB.println();
|
||||
|
||||
SerialUSB.println(F("LoRa setup initiating.."));
|
||||
setupLoRa();
|
||||
printLoRaSettings();
|
||||
|
||||
SerialUSB.println(F("GPS setup initiating..(NO GPS fix yet)"));
|
||||
setupGPS_BMP();
|
||||
delay(2000);
|
||||
|
||||
if(airborne){
|
||||
SerialUSB.println(F("Airborne mode initiated..."));
|
||||
setupUBloxDynamicModel(); // Set the dynamic model to DYN_MODEL_AIRBORNE4g
|
||||
}
|
||||
|
||||
SerialUSB.println(F("Accelerometer setup initiating.."));
|
||||
setupAccel();
|
||||
|
||||
//OLED Display
|
||||
setupDisplay();
|
||||
|
||||
freeMem();
|
||||
|
||||
printDisplay(4);
|
||||
delay(7000);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
if (readBatt() > battMin) {
|
||||
|
||||
|
||||
if (myGPS.getPVT() && (myGPS.getFixType() !=0) && (myGPS.getSIV() > 3)) {
|
||||
|
||||
if(!gpsFixed){
|
||||
SerialUSB.println(F("GPS Fixed..."));
|
||||
gpsFixed = true;
|
||||
}
|
||||
|
||||
}
|
||||
#if defined(DEVMODE)
|
||||
printGPSData();
|
||||
#endif
|
||||
|
||||
updateTelemetry();
|
||||
getAccelerometerData();
|
||||
|
||||
//update display
|
||||
if (millis() - last_display_refreshed > (displayInterval * 1000)) {
|
||||
printDisplay(displayPageID);
|
||||
last_display_refreshed = millis();
|
||||
|
||||
++displayPageID;
|
||||
|
||||
if(displayPageID == 3) {
|
||||
displayPageID = 1;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
if(loRaEnabled) {
|
||||
if (millis() - last_packet_send > (loRaTXinterval * 1000)) {
|
||||
|
||||
printDisplay(3);
|
||||
|
||||
sendLoraPacket();
|
||||
printLoRaSettings();
|
||||
last_packet_send = millis();
|
||||
if(loraFrequency >= 863.f && loraFrequency <= 870.f){
|
||||
calculateTransmitInterval();
|
||||
}
|
||||
delay(1000);
|
||||
|
||||
printDisplay(2);
|
||||
last_display_refreshed = millis();
|
||||
|
||||
SerialUSB.print(F("Next TX is "));
|
||||
SerialUSB.print(loRaTXinterval);
|
||||
SerialUSB.println(F(" seconds later."));
|
||||
freeMem();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
} else {
|
||||
SerialUSB.println(F("Voltage is too low, please check your battery..."));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void printDisplay(int pageID){
|
||||
|
||||
display.clearDisplay();
|
||||
display.setCursor(0, 0);
|
||||
|
||||
switch(pageID) {
|
||||
|
||||
case 1:
|
||||
static char fixMessage[10] = "";
|
||||
if(myGPS.getFixType() !=0){
|
||||
sprintf(fixMessage, "%s", "Fixed");
|
||||
} else {
|
||||
sprintf(fixMessage, "%s", "Not Fixed");
|
||||
}
|
||||
|
||||
display.println("");
|
||||
display.print("GPS Fix : ");display.println(fixMessage);
|
||||
display.print("GPS Sats: ");display.println((int)tempSats);
|
||||
display.print("Lat : ");display.println(tempLatitude);
|
||||
display.print("Long : ");display.println(tempLongitude);
|
||||
display.print("Altitude: ");display.print((int)tempAltitude);display.println(altUnit);
|
||||
display.print("Speed : ");display.print((int)tempSpeed);display.println(speedUnit);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
display.println("");
|
||||
display.print("Battery :");display.print(tempVoltage); display.println("V");
|
||||
display.print("Temp :");display.print(tempTemperature);display.println(tempUnit);
|
||||
display.print("Pressure:");display.print(tempPressure); display.println("hPa");
|
||||
display.print("TX Count:");display.println(txCount-1);
|
||||
display.print("Next TX :");display.print(loRaTXinterval - ((millis() - last_packet_send)/1000)); display.println(" secs left");
|
||||
break;
|
||||
|
||||
case 3:
|
||||
display.println("");
|
||||
display.println("");
|
||||
display.println("LoRa Pckt Sending...");
|
||||
display.println("");
|
||||
break;
|
||||
|
||||
case 4:
|
||||
display.println("");
|
||||
display.print("Freq : ");display.print(loraFrequency);display.println("mHz");
|
||||
display.print("SF : ");display.println(spreadingFactor);
|
||||
display.print("Bandwith: ");display.print(loraBandWith);display.println("kHz");
|
||||
display.print("Power : ");display.print(outputPower);display.println("dBm");
|
||||
display.print("PcktSize: ");display.print(sizeof(telemetry));display.println(" bytes");
|
||||
display.print("Measure : ");display.println(measureSystem);
|
||||
|
||||
break;
|
||||
|
||||
default:
|
||||
SerialUSB.println("default");
|
||||
break;
|
||||
}
|
||||
|
||||
display.display();
|
||||
|
||||
}
|
||||
|
||||
void setupDisplay(){
|
||||
// SSD1306_SWITCHCAPVCC = generate display voltage from 3.3V internally
|
||||
if(!display.begin(SSD1306_SWITCHCAPVCC, 0x3C)) { // Address 0x3D for 128x64
|
||||
SerialUSB.println(F("SSD1306 allocation failed"));
|
||||
for(;;); // Don't proceed, loop forever
|
||||
}
|
||||
display.clearDisplay();
|
||||
display.setTextSize(1); // Draw 2X-scale text
|
||||
display.setTextColor(SSD1306_WHITE);
|
||||
|
||||
if(measurementSystem == 0){ //Metric
|
||||
//meters
|
||||
sprintf(altUnit, "%s", " m");
|
||||
//km/hour
|
||||
sprintf(speedUnit, "%s", " km/h");
|
||||
//Celsius
|
||||
sprintf(tempUnit, "%s", "C");
|
||||
//km
|
||||
sprintf(distUnit, "%s", " km");
|
||||
//Metric
|
||||
sprintf(measureSystem, "%s", "Metric");
|
||||
|
||||
|
||||
} else { //Imperial
|
||||
|
||||
//feet
|
||||
sprintf(altUnit, "%s", " ft");
|
||||
//mile/hour
|
||||
sprintf(speedUnit, "%s", " mph");
|
||||
//Fahrenheit
|
||||
sprintf(tempUnit, "%s", "F");
|
||||
//mile
|
||||
sprintf(distUnit, "%s", " mi");
|
||||
//Imperial
|
||||
sprintf(measureSystem, "%s", "Imperial");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void setupAccel() {
|
||||
|
||||
//********** Acceloremeter (LSM303DLHC) Settings **************//
|
||||
myIMU.settings.adcEnabled = 1;
|
||||
myIMU.settings.accelSampleRate = 400; //Hz. Can be: 0,1,10,25,50,100,200,400,1600,5000 Hz
|
||||
myIMU.settings.accelRange = 16; //Max G force readable. Can be: 2, 4, 8, 16
|
||||
myIMU.settings.xAccelEnabled = 1;
|
||||
myIMU.settings.yAccelEnabled = 1;
|
||||
myIMU.settings.zAccelEnabled = 1;
|
||||
|
||||
//Call .begin() to configure the IMU
|
||||
myIMU.begin();
|
||||
|
||||
delay(100);
|
||||
|
||||
}
|
||||
|
||||
void getAccelerometerData(){
|
||||
|
||||
accelGX = myIMU.readFloatAccelX();
|
||||
accelGY = myIMU.readFloatAccelY();
|
||||
accelGZ = myIMU.readFloatAccelZ();
|
||||
|
||||
|
||||
if (accelGX < minGX) {
|
||||
minGX = accelGX;
|
||||
} else if (accelGX > maxGX) {
|
||||
maxGX = accelGX;
|
||||
}
|
||||
|
||||
if (accelGY < minGY) {
|
||||
minGY = accelGY;
|
||||
} else if (accelGY > maxGY) {
|
||||
maxGY = accelGY;
|
||||
}
|
||||
|
||||
if (accelGZ < minGZ) {
|
||||
minGZ = accelGZ;
|
||||
} else if (accelGZ > maxGZ) {
|
||||
maxGZ = accelGZ;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
// Same functionality as Arduino's standard map function, except using floats
|
||||
float mapf(float x, float in_min, float in_max, float out_min, float out_max)
|
||||
{
|
||||
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||
}
|
||||
|
||||
|
||||
void sendLoraPacket(){
|
||||
|
||||
|
||||
SerialUSB.print(F("[SX1262] LoRa Radio Module Transmitting packet ... "));
|
||||
|
||||
|
||||
int state = lora.transmit(telemetry.bytes,sizeof(telemetry));
|
||||
|
||||
|
||||
if (state == ERR_NONE) {
|
||||
|
||||
// the packet was successfully transmitted
|
||||
SerialUSB.println(F("success!"));
|
||||
|
||||
// print measured data rate
|
||||
SerialUSB.print(F("[SX1262] Datarate:\t"));
|
||||
SerialUSB.print(lora.getDataRate());
|
||||
SerialUSB.println(F(" bps"));
|
||||
|
||||
} else if (state == ERR_PACKET_TOO_LONG) {
|
||||
|
||||
// the supplied packet was longer than 256 bytes
|
||||
SerialUSB.println(F("too long!"));
|
||||
|
||||
} else if (state == ERR_TX_TIMEOUT) {
|
||||
// timeout occured while transmitting packet
|
||||
SerialUSB.println(F("timeout!"));
|
||||
} else {
|
||||
// some other error occurred
|
||||
SerialUSB.print(F("failed, code "));
|
||||
SerialUSB.println(state);
|
||||
}
|
||||
lora.sleep();
|
||||
|
||||
txCount++;
|
||||
|
||||
}
|
||||
|
||||
|
||||
void updateTelemetry() {
|
||||
|
||||
if(measurementSystem == 0){ //Metric
|
||||
//meters
|
||||
tempAltitude = myGPS.getAltitude() / 1000.f;
|
||||
//km/hour
|
||||
tempSpeed = myGPS.getGroundSpeed() * 0.0036f;
|
||||
//Celsius
|
||||
tempTemperature = bmp.readTemperature();
|
||||
|
||||
} else { //Imperial
|
||||
//feet
|
||||
tempAltitude = (myGPS.getAltitude() * 3.2808399) / 1000.f;
|
||||
//mile/hour
|
||||
tempSpeed = myGPS.getGroundSpeed() * 0.00223694f;
|
||||
//Fahrenheit
|
||||
tempTemperature = (bmp.readTemperature() * 1.8f) + 32;
|
||||
}
|
||||
|
||||
tempLatitude = myGPS.getLatitude() / 10000000.f;
|
||||
tempLongitude = myGPS.getLongitude() / 10000000.f;
|
||||
tempSats = myGPS.getSIV();
|
||||
|
||||
if ((tempSats > 4) && (tempAltitude > maxAltitude)) {
|
||||
maxAltitude = tempAltitude;
|
||||
}
|
||||
|
||||
tempHeading = myGPS.getHeading() / 100000;
|
||||
tempVoltage = readBatt();
|
||||
tempPressure = bmp.readPressure() / 100.0;
|
||||
|
||||
if (tempPressure < minPressure) {
|
||||
minPressure = tempPressure;
|
||||
}
|
||||
|
||||
//prepare data for LoRa communcation...
|
||||
if(loRaEnabled) {
|
||||
telemetry.f[0] = tempLatitude;
|
||||
telemetry.f[1] = tempLongitude;
|
||||
telemetry.f[2] = tempAltitude;
|
||||
telemetry.f[3] = tempSats;
|
||||
telemetry.f[4] = tempHeading;
|
||||
telemetry.f[5] = tempSpeed;
|
||||
telemetry.f[6] = tempVoltage;
|
||||
telemetry.f[7] = tempTemperature;
|
||||
telemetry.f[8] = tempPressure;
|
||||
telemetry.f[9] = accelGX;
|
||||
telemetry.f[10] = accelGY;
|
||||
telemetry.f[11] = accelGZ;
|
||||
telemetry.f[12] = minGX;
|
||||
telemetry.f[13] = maxGX;
|
||||
telemetry.f[14] = minGY;
|
||||
telemetry.f[15] = maxGY;
|
||||
telemetry.f[16] = minGZ;
|
||||
telemetry.f[17] = maxGZ;
|
||||
telemetry.f[18] = maxAltitude;
|
||||
telemetry.f[19] = minPressure;
|
||||
telemetry.f[20] = txCount;
|
||||
telemetry.f[21] = trackerID;
|
||||
|
||||
}
|
||||
|
||||
#if defined(DEVMODE)
|
||||
SerialUSB.println(F(""));
|
||||
SerialUSB.print(F("Batt: "));
|
||||
SerialUSB.print(tempVoltage);
|
||||
SerialUSB.print(F(" Temp: "));
|
||||
SerialUSB.print(tempTemperature);
|
||||
SerialUSB.print(F(" Press: "));
|
||||
SerialUSB.print(tempPressure);
|
||||
SerialUSB.print(F(" GX: "));
|
||||
SerialUSB.print(accelGX);
|
||||
SerialUSB.print(F(" GY: "));
|
||||
SerialUSB.print(accelGY);
|
||||
SerialUSB.print(F(" GZ: "));
|
||||
SerialUSB.println(accelGZ);
|
||||
#endif
|
||||
|
||||
/**
|
||||
#if defined(DEVMODE)
|
||||
SerialUSB.println(F("----"));
|
||||
SerialUSB.print(F("lat :"));
|
||||
SerialUSB.println(telemetry.f[0]);
|
||||
SerialUSB.print(F("long :"));
|
||||
SerialUSB.println(telemetry.f[1]);
|
||||
SerialUSB.print(F("alt :"));
|
||||
SerialUSB.println(telemetry.f[2]);
|
||||
SerialUSB.print(F("sats :"));
|
||||
SerialUSB.println(telemetry.f[3]);
|
||||
SerialUSB.print(F("course:"));
|
||||
SerialUSB.println(telemetry.f[4]);
|
||||
SerialUSB.print(F("speed :"));
|
||||
SerialUSB.println(telemetry.f[5]);
|
||||
SerialUSB.print(F("batt :"));
|
||||
SerialUSB.println(telemetry.f[6]);
|
||||
SerialUSB.print(F("temp :"));
|
||||
SerialUSB.println(telemetry.f[7]);
|
||||
SerialUSB.print(F("press :"));
|
||||
SerialUSB.println(telemetry.f[8]);
|
||||
SerialUSB.print(F("scaledGX :"));
|
||||
SerialUSB.println(telemetry.f[9]);
|
||||
SerialUSB.print(F("scaledGY :"));
|
||||
SerialUSB.println(telemetry.f[10]);
|
||||
SerialUSB.print(F("scaledGZ :"));
|
||||
SerialUSB.println(telemetry.f[11]);
|
||||
SerialUSB.print(F("minScaledGX :"));
|
||||
SerialUSB.println(telemetry.f[12]);
|
||||
SerialUSB.print(F("maxScaledGX :"));
|
||||
SerialUSB.println(telemetry.f[13]);
|
||||
SerialUSB.print(F("minScaledGY :"));
|
||||
SerialUSB.println(telemetry.f[14]);
|
||||
SerialUSB.print(F("maxScaledGY :"));
|
||||
SerialUSB.println(telemetry.f[15]);
|
||||
SerialUSB.print(F("minScaledGZ :"));
|
||||
SerialUSB.println(telemetry.f[16]);
|
||||
SerialUSB.print(F("maxScaledGZ :"));
|
||||
SerialUSB.println(telemetry.f[17]);
|
||||
SerialUSB.print(F("maxAltitude :"));
|
||||
SerialUSB.println(telemetry.f[18]);
|
||||
SerialUSB.print(F("minPressure :"));
|
||||
SerialUSB.println(telemetry.f[19]);
|
||||
SerialUSB.print(F("txCount :"));
|
||||
SerialUSB.println(telemetry.f[20]);
|
||||
SerialUSB.print(F("trackerID :"));
|
||||
SerialUSB.println((int)telemetry.f[21]);
|
||||
SerialUSB.println(F("----"));
|
||||
#endif
|
||||
*/
|
||||
|
||||
}
|
||||
|
||||
|
||||
void setupLoRa() {
|
||||
|
||||
// initialize SX1262 with default settings
|
||||
SerialUSB.print(F("[SX1262] Initializing ... "));
|
||||
int state = lora.begin();
|
||||
|
||||
if (state == ERR_NONE) {
|
||||
SerialUSB.println(F("success!"));
|
||||
} else {
|
||||
SerialUSB.print(F("failed, code "));
|
||||
SerialUSB.println(state);
|
||||
while (true);
|
||||
}
|
||||
|
||||
if (lora.setFrequency(loraFrequency,true) == ERR_INVALID_FREQUENCY) {
|
||||
SerialUSB.println(F("Selected frequency is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set bandwidth to 1250 kHz
|
||||
if (lora.setBandwidth(loraBandWith) == ERR_INVALID_BANDWIDTH) {
|
||||
SerialUSB.println(F("Selected bandwidth is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set spreading factor to 10
|
||||
if (lora.setSpreadingFactor(spreadingFactor) == ERR_INVALID_SPREADING_FACTOR) {
|
||||
SerialUSB.println(F("Selected spreading factor is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set coding rate to 5
|
||||
if (lora.setCodingRate(codingRate) == ERR_INVALID_CODING_RATE) {
|
||||
SerialUSB.println(F("Selected coding rate is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set LoRaWAN sync word to 0x34
|
||||
if (lora.setSyncWord(syncWord) != ERR_NONE) {
|
||||
SerialUSB.println(F("Unable to set sync word!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set over current protection limit to 140 mA (accepted range is 45 - 240 mA)
|
||||
if (lora.setCurrentLimit(140) == ERR_INVALID_CURRENT_LIMIT) {
|
||||
Serial.println(F("Selected current limit is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set output power to outputPower dBm (accepted range is -17, 22 dBm)
|
||||
if (lora.setOutputPower(outputPower) == ERR_INVALID_OUTPUT_POWER) {
|
||||
SerialUSB.println(F("Selected output power is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// set LoRa preamble length to 8 symbols (accepted range is 0 - 65535)
|
||||
if (lora.setPreambleLength(preambleLength) == ERR_INVALID_PREAMBLE_LENGTH) {
|
||||
SerialUSB.println(F("Selected preamble length is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
// enable CRC
|
||||
if (lora.setCRC(CRC) == ERR_INVALID_CRC_CONFIGURATION) {
|
||||
SerialUSB.println(F("Selected CRC is invalid for this module!"));
|
||||
while (true);
|
||||
}
|
||||
|
||||
SerialUSB.println(F("All settings succesfully changed!"));
|
||||
|
||||
}
|
||||
|
||||
float readBatt() {
|
||||
|
||||
float R1 = 560000.0; // 560K
|
||||
float R2 = 100000.0; // 100K
|
||||
float value = 0.0f;
|
||||
do {
|
||||
value =analogRead(BattPin);
|
||||
value +=analogRead(BattPin);
|
||||
value +=analogRead(BattPin);
|
||||
value = value / 3.0f;
|
||||
value = (value * 3.3) / 1024.0f;
|
||||
value = value / (R2/(R1+R2));
|
||||
} while (value > 10.0);
|
||||
return value ;
|
||||
|
||||
}
|
||||
|
||||
|
||||
void printLoRaSettings(){
|
||||
|
||||
SerialUSB.println(F("-------------------------------LoRa Settings-----------------------------------------"));
|
||||
SerialUSB.print(F("Freq: "));
|
||||
SerialUSB.print(loraFrequency);
|
||||
SerialUSB.print(F("mHz, Bandwith: "));
|
||||
SerialUSB.print(loraBandWith);
|
||||
SerialUSB.print(F("kHz, SF: "));
|
||||
SerialUSB.print(spreadingFactor);
|
||||
SerialUSB.print(F(", Power: "));
|
||||
SerialUSB.print(outputPower);
|
||||
SerialUSB.print(F("dBm, Payload Size: "));
|
||||
SerialUSB.print(sizeof(telemetry));
|
||||
SerialUSB.println(F(" bytes"));
|
||||
SerialUSB.println(F("------------------------------------------------------------------------------------"));
|
||||
|
||||
}
|
||||
|
||||
//Every radio device must be compliant with the regulated duty cycle limits. This applies to both nodes and gateways.
|
||||
//In practice, this means that you should program your nodes in such a way, that they stay within the limits.
|
||||
//The easiest way to do this, is to calculate how much airtime each message consumes using one of the many
|
||||
//airtime calculators and use that information to choose a good transmit interval (duty cycle). https://www.thethingsnetwork.org/docs/lorawan/duty-cycle.html
|
||||
//Following function checks and enforce duty cycle limits based on your LoRa settings so you can not break the law.
|
||||
|
||||
void calculateTransmitInterval(){
|
||||
|
||||
if(spreadingFactor>= 11){
|
||||
lowDataRateOptimization = 1;
|
||||
}
|
||||
|
||||
if (loraFrequency >=868.7 && loraFrequency <=869.2) {
|
||||
dutyCyle = 0.001;
|
||||
} else if (loraFrequency >=869.4 && loraFrequency <=869.65) {
|
||||
dutyCyle = 0.1;
|
||||
} else {
|
||||
dutyCyle = 0.01;
|
||||
}
|
||||
|
||||
float symbolDuration = pow(2, spreadingFactor) / (loraBandWith * 1000.f);
|
||||
float a = (8 * (sizeof(telemetry) + loRaWANHeaderSize)) - (4 * spreadingFactor) + 28 + (16 * CRC) - (20 * (1-explcttHdr));
|
||||
float b = 4 * (spreadingFactor - (2 * lowDataRateOptimization));
|
||||
|
||||
int nbrSymbols = ceil(a/b) * codingRate;
|
||||
|
||||
if (nbrSymbols < 0){
|
||||
nbrSymbols = 0;
|
||||
}
|
||||
nbrSymbols += 8;
|
||||
|
||||
float preambuleDuration = (preambleLength + 4.25f) * symbolDuration;
|
||||
float payloadDuration = nbrSymbols * symbolDuration;
|
||||
float packetDuration = (preambuleDuration + payloadDuration) / dutyCyle;
|
||||
|
||||
if (loRaTXinterval < (int)packetDuration) {
|
||||
|
||||
#if defined(DEVMODE)
|
||||
SerialUSB.print(F("Updating "));
|
||||
SerialUSB.print(F("loRaTXinterval= "));
|
||||
SerialUSB.print(loRaTXinterval);
|
||||
SerialUSB.print(F(" to loRaTXinterval= "));
|
||||
SerialUSB.print((int)packetDuration);
|
||||
SerialUSB.println(F(" seconds..."));
|
||||
#endif
|
||||
|
||||
loRaTXinterval = (int)(packetDuration);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
void setupGPS_BMP() {
|
||||
GpsON;
|
||||
delay(100);
|
||||
Wire.begin();
|
||||
bmp.begin();
|
||||
|
||||
Wire.setClock(400000);
|
||||
|
||||
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
|
||||
{
|
||||
SerialUSB.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
|
||||
while (1)
|
||||
;
|
||||
}
|
||||
|
||||
// do not overload the buffer system from the GPS, disable UART output
|
||||
myGPS.setUART1Output(0); //Disable the UART1 port output
|
||||
myGPS.setUART2Output(0); //Disable Set the UART2 port output
|
||||
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
|
||||
|
||||
//myGPS.enableDebugging(); //Enable debug messages over Serial (default)
|
||||
|
||||
myGPS.setNavigationFrequency(navigationFrequencyGPS);//Sadece roket için 10 yapalım. //Set output to 10 times a second
|
||||
byte rate = myGPS.getNavigationFrequency(); //Get the update rate of this module
|
||||
//SerialUSB.print("Current GPS update rate:");
|
||||
//SerialUSB.println(rate);
|
||||
|
||||
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
|
||||
|
||||
}
|
||||
|
||||
|
||||
void setupUBloxDynamicModel() {
|
||||
// If we are going to change the dynamic platform model, let's do it here.
|
||||
// Possible values are:
|
||||
// PORTABLE, STATIONARY, PEDESTRIAN, AUTOMOTIVE, SEA, AIRBORNE1g, AIRBORNE2g, AIRBORNE4g, WRIST, BIKE
|
||||
//DYN_MODEL_AIRBORNE4g model increases ublox max. altitude limit from 12.000 meters to 50.000 meters.
|
||||
if (myGPS.setDynamicModel(DYN_MODEL_AIRBORNE4g) == false) // Set the dynamic model to DYN_MODEL_AIRBORNE4g
|
||||
{
|
||||
SerialUSB.println(F("***!!! Warning: setDynamicModel failed !!!***"));
|
||||
}
|
||||
else
|
||||
{
|
||||
SerialUSB.print(F("Dynamic platform model changed successfully! : "));
|
||||
SerialUSB.println(myGPS.getDynamicModel());
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void freeMem() {
|
||||
#if defined(DEVMODE)
|
||||
SerialUSB.print(F("Free RAM: ")); SerialUSB.print(freeMemory(), DEC); SerialUSB.println(F(" byte"));
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void printGPSData()
|
||||
{
|
||||
// Calling getPVT returns true if there actually is a fresh navigation solution available.
|
||||
SerialUSB.println(F(""));
|
||||
|
||||
byte fixType = myGPS.getFixType();
|
||||
|
||||
SerialUSB.print(F("FixType: "));
|
||||
SerialUSB.print(fixType);
|
||||
|
||||
long latitude = myGPS.getLatitude();
|
||||
float flat = myGPS.getLatitude() / 10000000.f;
|
||||
|
||||
SerialUSB.print(F(" Lat: "));
|
||||
SerialUSB.print(latitude);
|
||||
SerialUSB.print(F(" - "));
|
||||
SerialUSB.print(flat);
|
||||
|
||||
long longitude = myGPS.getLongitude();
|
||||
float flong = myGPS.getLongitude() / 10000000.f;
|
||||
SerialUSB.print(F(" Long: "));
|
||||
SerialUSB.print(longitude);
|
||||
SerialUSB.print(F(" - "));
|
||||
SerialUSB.print(flong);
|
||||
|
||||
float altitude = myGPS.getAltitude() / 1000;
|
||||
SerialUSB.print(F(" Alt: "));
|
||||
SerialUSB.print(altitude);
|
||||
SerialUSB.print(F(" (m)"));
|
||||
|
||||
int SIV = myGPS.getSIV();
|
||||
SerialUSB.print(F(" SIV: "));
|
||||
SerialUSB.print(SIV);
|
||||
|
||||
float speed = myGPS.getGroundSpeed() * 0.0036f;
|
||||
SerialUSB.print(F(" Speed: "));
|
||||
SerialUSB.print(speed);
|
||||
SerialUSB.print(F(" (km/h)"));
|
||||
|
||||
long heading = myGPS.getHeading() / 100000;
|
||||
SerialUSB.print(F(" Heading: "));
|
||||
SerialUSB.print(heading);
|
||||
SerialUSB.print(F(" (degrees )"));
|
||||
|
||||
SerialUSB.print(" ");
|
||||
SerialUSB.print(myGPS.getYear());
|
||||
SerialUSB.print("-");
|
||||
SerialUSB.print(myGPS.getMonth());
|
||||
SerialUSB.print("-");
|
||||
SerialUSB.print(myGPS.getDay());
|
||||
SerialUSB.print(" ");
|
||||
SerialUSB.print(myGPS.getHour());
|
||||
SerialUSB.print(":");
|
||||
SerialUSB.print(myGPS.getMinute());
|
||||
SerialUSB.print(":");
|
||||
SerialUSB.print(myGPS.getSecond());
|
||||
SerialUSB.print(":");
|
||||
SerialUSB.print(myGPS.getMillisecond());
|
||||
|
||||
SerialUSB.println();
|
||||
delay(1000);
|
||||
|
||||
}
|
|
@ -0,0 +1,859 @@
|
|||
#include <basicmac.h>
|
||||
#include <hal/hal.h>
|
||||
#include <Adafruit_BMP085.h>
|
||||
#include "SparkFun_Ublox_Arduino_Library.h"
|
||||
#include <MemoryFree.h>;
|
||||
#include <CayenneLPP.h>
|
||||
#include "SparkFunLIS3DH.h"
|
||||
#include <Adafruit_SSD1306.h>
|
||||
|
||||
// SX1262 has the following connections:
|
||||
#define nssPin 8
|
||||
#define rstPin 9
|
||||
#define dio1Pin 3
|
||||
#define busyPin 2
|
||||
|
||||
#define BattPin A5
|
||||
#define GpsPwr 12
|
||||
#define GpsON digitalWrite(GpsPwr, LOW);
|
||||
#define GpsOFF digitalWrite(GpsPwr, HIGH);
|
||||
|
||||
SFE_UBLOX_GPS myGPS;
|
||||
Adafruit_BMP085 bmp; //temp and pressure sensor
|
||||
LIS3DH myIMU; //accelerometer
|
||||
|
||||
//#define DEVMODE // Development mode. Uncomment to enable for debugging.
|
||||
|
||||
boolean airborne = false; //if you want to put the tracker on an airborne (balloon, drone, plane, etc.) device, set this variable true;
|
||||
uint8_t measurementSystem = 0; //0 for metric (meters, km, Celcius, etc.), 1 for imperial (feet, mile, Fahrenheit,etc.)
|
||||
|
||||
//***************************** UPDATE HERE WITH YOUR DEVICE KEYS **************************************/
|
||||
|
||||
//You should copy device keys from Helium or TTN Console and update following keys. Please check out: https://github.com/lightaprs/LightTracker-1.0/wiki/Adding-Device-on-Helium-Console
|
||||
|
||||
// This EUI must be in little-endian format, so least-significant-byte (lsb)
|
||||
// first. When copying an EUI from Helium Console or ttnctl output, this means to reverse the bytes.
|
||||
|
||||
static const u1_t PROGMEM DEVEUI[8]={0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; //helium or ttn
|
||||
|
||||
// This EUI must be in little-endian format, so least-significant-byte (lsb)
|
||||
// first. When copying an EUI from Helium Console or ttnctl output, this means to reverse the bytes.
|
||||
|
||||
static const u1_t PROGMEM APPEUI[8]={0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; //helium or ttn
|
||||
|
||||
// This key should be in big endian format (or, since it is not really a
|
||||
// number but a block of memory, endianness does not really apply). In practice, a key taken from Helium Console or ttnctl can be copied as-is.
|
||||
|
||||
static const u1_t PROGMEM APPKEY[16] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; //helium or ttn
|
||||
//*****************************************************************************************************/
|
||||
|
||||
|
||||
//************************** LoRaWAN Settings ********************
|
||||
//DO NOT FORGET TO CHANGE YOUR REGION, DEFAULT REGION IS EU. Uncomment your region, but comment other regions
|
||||
uint8_t Lorawan_region_code = REGCODE_EU868;//For EU
|
||||
//uint8_t Lorawan_region_code = REGCODE_US915;//For North America
|
||||
//uint8_t Lorawan_region_code = REGCODE_AS923;//For Asia
|
||||
//uint8_t Lorawan_region_code = REGCODE_AU915;//For South America and Australia
|
||||
//uint8_t Lorawan_region_code = REGCODE_IN865;//For India and Pakistan
|
||||
|
||||
const unsigned TX_INTERVAL = 60000; // Schedule TX every this many miliseconds (might become longer due to duty cycle limitations).
|
||||
boolean gpsFixRequiredforTX = false; //By default GPS fix required for telemetry TX (but not required for OTAA join)
|
||||
|
||||
//Spreading Factor automatically selected by BasicMAC LoRaWAN Library. Keep this "true" if you want to use your tracker in urban areas.
|
||||
//But if you are too far from the the gateways/hotspots then change it to "false"
|
||||
boolean autoSF = true;
|
||||
|
||||
//try to keep telemetry size smaller than 51 bytes if possible. Default telemetry size is 45 bytes.
|
||||
CayenneLPP telemetry(51);
|
||||
|
||||
u1_t os_getRegion (void) { return Lorawan_region_code; } //do not change this.
|
||||
|
||||
uint8_t channelNoFor2ndSubBand = 8; //do not change this. Used for US915 and AU915 / TTN and Helium
|
||||
uint32_t last_packet = 0; //do not change this. Timestamp of last packet sent.
|
||||
|
||||
boolean ev_joined = false;
|
||||
|
||||
//pinmap for SX1262 LoRa module
|
||||
#if !defined(USE_STANDARD_PINMAP)
|
||||
const lmic_pinmap lmic_pins = {
|
||||
.nss = nssPin,
|
||||
.tx = LMIC_UNUSED_PIN,
|
||||
.rx = LMIC_UNUSED_PIN,
|
||||
.rst = rstPin,
|
||||
.dio = {/* DIO0 */ LMIC_UNUSED_PIN, /* DIO1 */ dio1Pin, /* DIO2 */ LMIC_UNUSED_PIN},
|
||||
.busy = busyPin,
|
||||
.tcxo = LMIC_CONTROLLED_BY_DIO3,
|
||||
};
|
||||
#endif // !defined(USE_STANDARD_PINMAP)
|
||||
|
||||
//************************** uBlox GPS Settings ********************
|
||||
|
||||
long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to Ublox module.
|
||||
|
||||
//********************************* Power Settings ******************************
|
||||
|
||||
int battWait=60; //seconds sleep if super capacitors/batteries are below battMin (important if power source is solar panel)
|
||||
float battMin=2.7; // min Volts to TX.
|
||||
|
||||
//********************************* Misc Settings ******************************
|
||||
|
||||
int txCount = 1;
|
||||
float voltage = 0;
|
||||
float tempAltitudeLong = 0;
|
||||
float tempAltitudeShort = 0;
|
||||
float tempSpeed = 0;
|
||||
float tempTemperature = 0;
|
||||
float tempLatitude = 0;
|
||||
float tempLongitude = 0;
|
||||
float tempSats = 0;
|
||||
float tempHeading = 0;
|
||||
float tempPressure = 0;
|
||||
|
||||
static char tempUnit[2] = ""; //C or F
|
||||
static char speedUnit[7] = ""; //km/h or mph (mile per hour)
|
||||
static char altUnit[5] = ""; //meters or feet
|
||||
static char distUnit[5] = ""; //km or mile
|
||||
static char measureSystem[10] = ""; //km or mile
|
||||
static char regionName[6] ="";
|
||||
|
||||
//********** OLED Display Settings ****************//
|
||||
|
||||
#define SCREEN_WIDTH 128 // OLED display width, in pixels
|
||||
#define SCREEN_HEIGHT 64 // OLED display height, in pixels
|
||||
|
||||
// Declaration for an SSD1306 display connected to I2C (SDA, SCL pins)
|
||||
#define OLED_RESET -1 // Reset pin # (or -1 if sharing Arduino reset pin)
|
||||
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);
|
||||
|
||||
int displayPageID = 1;
|
||||
int displayInterval = 7;
|
||||
uint32_t last_display_refreshed = -10000;
|
||||
|
||||
void setup() {
|
||||
|
||||
pinMode(A1,INPUT_PULLUP);
|
||||
if(digitalRead(A1)==LOW) while(1);
|
||||
|
||||
delay(5000); //do not change this
|
||||
|
||||
pinMode(GpsPwr, OUTPUT);
|
||||
|
||||
SerialUSB.begin(115200);
|
||||
|
||||
// Wait up to 5 seconds for serial to be opened, to allow catching
|
||||
// startup messages on native USB boards (that do not reset when
|
||||
// serial is opened).
|
||||
unsigned long start = millis();
|
||||
while (millis() - start < 5000 && !SerialUSB);
|
||||
|
||||
SerialUSB.println();
|
||||
SerialUSB.println(F("Starting"));
|
||||
SerialUSB.println();
|
||||
|
||||
GpsON;
|
||||
delay(1000);
|
||||
|
||||
SerialUSB.println(F("GPS setup"));
|
||||
setupGPS_BMP();
|
||||
delay(2000);
|
||||
|
||||
if(airborne){
|
||||
SerialUSB.println(F("Airborne mode initiated..."));
|
||||
setupUBloxDynamicModel(); // Set the dynamic model to DYN_MODEL_AIRBORNE4g
|
||||
autoSF = false; //override LoRaWAN auto Spreading Factor selection setting
|
||||
}
|
||||
|
||||
SerialUSB.println(F("Searching for GPS fix..."));
|
||||
setupAccel();
|
||||
|
||||
//OLED Display
|
||||
setupDisplay();
|
||||
SerialUSB.println(F("LoRaWAN OTAA Login initiated..."));
|
||||
startJoining();
|
||||
SerialUSB.println(F("LoRaWAN OTAA Login successful..."));
|
||||
printLoRaWANSettings();
|
||||
|
||||
//OLED Display
|
||||
printDisplay(5);
|
||||
delay(1000);
|
||||
|
||||
freeMem();
|
||||
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
voltage = readBatt();
|
||||
|
||||
if (voltage > battMin) {
|
||||
|
||||
// Let LMIC handle LoRaWAN background tasks
|
||||
os_runstep();
|
||||
|
||||
#if defined(DEVMODE)
|
||||
printGPSandSensorData();
|
||||
#endif
|
||||
|
||||
// If TX_INTERVAL passed, *and* our previous packet is not still
|
||||
// pending (which can happen due to duty cycle limitations), send
|
||||
// the next packet.
|
||||
if ((millis() - last_packet > TX_INTERVAL && !(LMIC.opmode & (OP_JOINING|OP_TXRXPEND)))){
|
||||
|
||||
// Calling myGPS.getPVT() returns true if there actually is a fresh navigation solution available.
|
||||
|
||||
if ((myGPS.getPVT() && (myGPS.getFixType() !=0) && (myGPS.getSIV() > 0)) || !gpsFixRequiredforTX) {
|
||||
|
||||
updateTelemetry();
|
||||
|
||||
printDisplay(3);
|
||||
sendLoRaWANPacket();
|
||||
|
||||
SerialUSB.println(F("LoRaWAN packet sent.."));
|
||||
printLoRaWANSettings();
|
||||
freeMem();
|
||||
|
||||
delay(1000);
|
||||
displayPageID=2;
|
||||
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//update display
|
||||
if (millis() - last_display_refreshed > (displayInterval * 1000)) {
|
||||
printDisplay(displayPageID);
|
||||
last_display_refreshed = millis();
|
||||
|
||||
++displayPageID;
|
||||
|
||||
if(displayPageID == 3) {
|
||||
displayPageID = 1;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
} else {
|
||||
|
||||
SerialUSB.println(F("Voltage is too low, please check your battery..."));
|
||||
|
||||
}
|
||||
|
||||
delay(1000);
|
||||
|
||||
}
|
||||
|
||||
void printDisplay(int pageID){
|
||||
|
||||
display.clearDisplay();
|
||||
display.setCursor(0, 0);
|
||||
|
||||
switch(pageID) {
|
||||
|
||||
case 1:
|
||||
static char fixMessage[10] = "";
|
||||
if(myGPS.getFixType() !=0){
|
||||
sprintf(fixMessage, "%s", "Fixed");
|
||||
} else {
|
||||
sprintf(fixMessage, "%s", "Not Fixed");
|
||||
}
|
||||
|
||||
display.print("GPS Fix : ");display.println(fixMessage);
|
||||
display.print("GPS Sats: ");display.println((int)myGPS.getSIV());
|
||||
display.print("Lat : ");display.println(tempLatitude);
|
||||
display.print("Long : ");display.println(tempLongitude);
|
||||
display.print("Altitude: ");display.print((int)tempAltitudeLong);display.println(altUnit);
|
||||
display.print("Speed : ");display.print((int)tempSpeed);display.println(speedUnit);
|
||||
display.print("Battery : ");display.print(voltage); display.println("V");
|
||||
break;
|
||||
|
||||
case 2:
|
||||
display.print("Temp :");display.print(tempTemperature);display.println(tempUnit);
|
||||
display.print("Pressure:");display.print(tempPressure); display.println("hPa");
|
||||
display.print("TX Count:");display.println(txCount-1);
|
||||
display.print("Freq. :");display.print(LMIC.freq/1000000.f);display.println("MHz");
|
||||
display.print("SF&BW :");display.print(F("SF"));display.print(getSf(LMIC.rps) - SF7 + 7);display.print(F("BW"));display.println(125 << (getBw(LMIC.rps) - BW125));
|
||||
display.print("TXPower :");display.println(LMIC.txpow + LMIC.brdTxPowOff);
|
||||
if(txCount >1) {
|
||||
display.print("Last TX :");display.print((millis() - last_packet)/1000); display.println(" secs ago");
|
||||
}
|
||||
break;
|
||||
|
||||
case 3:
|
||||
display.println("");
|
||||
display.println("");
|
||||
display.println("Packet Sending...");
|
||||
display.print("PcktSize: ");display.print(telemetry.getSize());display.println(" bytes");
|
||||
display.println("");
|
||||
break;
|
||||
|
||||
case 4:
|
||||
display.println("");
|
||||
display.println("LoRaWAN OTAA login");
|
||||
display.println("initiated...");
|
||||
display.println("");
|
||||
display.print("Region ");display.println(regionName);
|
||||
|
||||
break;
|
||||
|
||||
case 5:
|
||||
display.println("");
|
||||
display.println("LoRaWAN OTAA login");
|
||||
display.println("successful...");
|
||||
display.println("");
|
||||
display.print("Region ");display.println(regionName);
|
||||
break;
|
||||
|
||||
default:
|
||||
SerialUSB.println("default");
|
||||
break;
|
||||
}
|
||||
|
||||
display.display();
|
||||
|
||||
}
|
||||
|
||||
void setupDisplay(){
|
||||
// SSD1306_SWITCHCAPVCC = generate display voltage from 3.3V internally
|
||||
if(!display.begin(SSD1306_SWITCHCAPVCC, 0x3C)) { // Address 0x3D for 128x64
|
||||
SerialUSB.println(F("SSD1306 allocation failed"));
|
||||
for(;;); // Don't proceed, loop forever
|
||||
}
|
||||
display.clearDisplay();
|
||||
display.setTextSize(1); // Draw 2X-scale text
|
||||
display.setTextColor(SSD1306_WHITE);
|
||||
|
||||
if(measurementSystem == 0){ //Metric
|
||||
//meters
|
||||
sprintf(altUnit, "%s", " m");
|
||||
//km/hour
|
||||
sprintf(speedUnit, "%s", " km/h");
|
||||
//Celsius
|
||||
sprintf(tempUnit, "%s", "C");
|
||||
//km
|
||||
sprintf(distUnit, "%s", " km");
|
||||
//Metric
|
||||
sprintf(measureSystem, "%s", "Metric");
|
||||
|
||||
|
||||
} else { //Imperial
|
||||
|
||||
//feet
|
||||
sprintf(altUnit, "%s", " ft");
|
||||
//mile/hour
|
||||
sprintf(speedUnit, "%s", " mph");
|
||||
//Fahrenheit
|
||||
sprintf(tempUnit, "%s", "F");
|
||||
//mile
|
||||
sprintf(distUnit, "%s", " m");
|
||||
//Imperial
|
||||
sprintf(measureSystem, "%s", "Imperial");
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//to join LoRaWAN network, every region requires different parameters. Please refer to : https://lora-alliance.org/resource_hub/rp2-1-0-3-lorawan-regional-parameters/
|
||||
void startJoining() {
|
||||
|
||||
// LMIC init
|
||||
os_init(nullptr);
|
||||
LMIC_reset();
|
||||
|
||||
// Start join
|
||||
LMIC_startJoining();
|
||||
|
||||
//DO NOT CHANGE following code blocks unless you know what you are doing :)
|
||||
|
||||
//Europe
|
||||
if(Lorawan_region_code == REGCODE_EU868) {
|
||||
|
||||
sprintf(regionName, "%s", "EU868");
|
||||
|
||||
if(!autoSF){
|
||||
//DR2 (SF10 BW125kHz)
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
}
|
||||
|
||||
|
||||
//Japan, Malaysia, Singapore, Brunei, Cambodia, Hong Kong, Indonesia, Laos, Taiwan, Thailand, Vietnam
|
||||
} else if (Lorawan_region_code == REGCODE_AS923) {
|
||||
|
||||
sprintf(regionName, "%s", "AS923");
|
||||
|
||||
if(!autoSF){
|
||||
//DR2 (SF10 BW125kHz)
|
||||
//For AS923, DR2 join only since max payload limit is 11 bytes.
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
}
|
||||
|
||||
|
||||
//North and South America (Except Brazil)
|
||||
} else if (Lorawan_region_code == REGCODE_US915) {
|
||||
|
||||
sprintf(regionName, "%s", "US915");
|
||||
if(!autoSF){
|
||||
//DR0 (SF10 BW125kHz)
|
||||
//For US915, DR0 join only since max payload limit is 11 bytes.
|
||||
LMIC_setDrTxpow(0,KEEP_TXPOWADJ);
|
||||
}
|
||||
|
||||
//TTN and Helium only supports second sub band (channels 8 to 15)
|
||||
//so we should force BasicMAC to initiate a join with second sub band channels.
|
||||
LMIC_selectChannel(8);
|
||||
|
||||
//Australia and New Zeleand
|
||||
} else if (Lorawan_region_code == REGCODE_AU915) {
|
||||
|
||||
sprintf(regionName, "%s", "AU915");
|
||||
|
||||
if(!autoSF){
|
||||
//DR2 (SF10 BW125kHz)
|
||||
//For AU915, DR2 join only since max payload limit is 11 bytes.
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
}
|
||||
|
||||
//TTN and Helium only supports second sub band (channels 8 to 15)
|
||||
//so we should force BasicMAC to initiate a join with second sub band channels.
|
||||
LMIC_selectChannel(8);
|
||||
|
||||
}
|
||||
|
||||
LMIC_setAdrMode(false); //do not enable ADR (Adaptive Data Rate), does not work for every region or gateway
|
||||
LMIC_setLinkCheckMode(0);
|
||||
|
||||
// Make sure the first packet is scheduled ASAP after join completes
|
||||
last_packet = millis() - TX_INTERVAL;
|
||||
|
||||
//OLED Display
|
||||
printDisplay(4);
|
||||
|
||||
// Optionally wait for join to complete (uncomment this is you want
|
||||
// to run the loop while joining).
|
||||
|
||||
while ((LMIC.opmode & (OP_JOINING))) {
|
||||
os_runstep();
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
// Telemetry size is very important, try to keep it lower than 51 bytes. Always lower is better.
|
||||
void sendLoRaWANPacket(){
|
||||
|
||||
//Europa
|
||||
if(Lorawan_region_code == REGCODE_EU868) {
|
||||
|
||||
if(!autoSF){
|
||||
if(telemetry.getSize() < 52) {
|
||||
//DR2 (SF10 BW125kHz) max payload size is 51 bytes.
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
} else if (telemetry.getSize() < 116){
|
||||
//DR3 (SF9 BW125kHz) max payload size is 115 bytes.
|
||||
LMIC_setDrTxpow(3,KEEP_TXPOWADJ);
|
||||
} else {
|
||||
//DR4 (SF8 BW125kHz) max payload size is 222 bytes.
|
||||
LMIC_setDrTxpow(4,KEEP_TXPOWADJ);
|
||||
}
|
||||
}
|
||||
|
||||
//Japan, Malaysia, Singapore, Brunei, Cambodia, Hong Kong, Indonesia, Laos, Taiwan, Thailand, Vietnam
|
||||
} else if (Lorawan_region_code == REGCODE_AS923) {
|
||||
|
||||
if(!autoSF){
|
||||
if(telemetry.getSize() < 54) {
|
||||
//DR3 (SF9 BW125kHz) max payload size is 53 bytes.
|
||||
LMIC_setDrTxpow(3,KEEP_TXPOWADJ);
|
||||
} else if (telemetry.getSize() < 126){
|
||||
//DR4 (SF8 BW125kHz) max payload size is 125 bytes.
|
||||
LMIC_setDrTxpow(4,KEEP_TXPOWADJ);
|
||||
} else {
|
||||
//DR5 (SF7 BW125kHz) max payload size is 222 bytes.
|
||||
LMIC_setDrTxpow(5,KEEP_TXPOWADJ);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
//North and South America (Except Brazil) or Australia and New Zeleand
|
||||
} else if (Lorawan_region_code == REGCODE_US915 || Lorawan_region_code == REGCODE_AU915) {
|
||||
|
||||
if(!autoSF){
|
||||
//North and South America (Except Brazil)
|
||||
if (Lorawan_region_code == REGCODE_US915){
|
||||
if(telemetry.getSize() < 54) {
|
||||
//DR1 (SF9 BW125kHz) max payload size is 53 bytes.
|
||||
LMIC_setDrTxpow(1,KEEP_TXPOWADJ);
|
||||
} else if (telemetry.getSize() < 126){
|
||||
//DR2 (SF8 BW125kHz) max payload size is 125 bytes.
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
} else {
|
||||
//DR3 (SF7 BW125kHz) max payload size is 222 bytes.
|
||||
LMIC_setDrTxpow(3,KEEP_TXPOWADJ);
|
||||
}
|
||||
|
||||
//Australia and New Zeleand
|
||||
} else if (Lorawan_region_code == REGCODE_AU915){
|
||||
if(telemetry.getSize() < 54) {
|
||||
//DR3 (SF9 BW125kHz) max payload size is 53 bytes.
|
||||
LMIC_setDrTxpow(3,KEEP_TXPOWADJ);
|
||||
} else if (telemetry.getSize() < 126){
|
||||
//DR4 (SF8 BW125kHz) max payload size is 125 bytes.
|
||||
LMIC_setDrTxpow(4,KEEP_TXPOWADJ);
|
||||
} else {
|
||||
//DR5 (SF7 BW125kHz) max payload size is 222 bytes.
|
||||
LMIC_setDrTxpow(5,KEEP_TXPOWADJ);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//TTN and Helium only supports second sub band (channels 8 to 15)
|
||||
//so we should force BasicMAC use second sub band channels.
|
||||
LMIC_selectChannel(channelNoFor2ndSubBand);
|
||||
|
||||
++channelNoFor2ndSubBand;
|
||||
if(channelNoFor2ndSubBand > 15) {
|
||||
channelNoFor2ndSubBand = 8;
|
||||
}
|
||||
//India
|
||||
} else if (Lorawan_region_code == REGCODE_IN865) {
|
||||
|
||||
if(!autoSF){
|
||||
if(telemetry.getSize() < 52) {
|
||||
//DR2 (SF10 BW125kHz) max payload size is 51 bytes.
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
} else if (telemetry.getSize() < 116){
|
||||
//DR3 (SF9 BW125kHz) max payload size is 115 bytes.
|
||||
LMIC_setDrTxpow(3,KEEP_TXPOWADJ);
|
||||
} else {
|
||||
//DR4 (SF8 BW125kHz) max payload size is 222 bytes.
|
||||
LMIC_setDrTxpow(4,KEEP_TXPOWADJ);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
LMIC_setAdrMode(false);
|
||||
LMIC_setLinkCheckMode(0);
|
||||
|
||||
LMIC_setTxData2(1, telemetry.getBuffer(), telemetry.getSize(), 0);
|
||||
last_packet = millis();
|
||||
txCount++;
|
||||
SerialUSB.println(F("Packet queued..."));
|
||||
|
||||
}
|
||||
|
||||
void setupAccel() {
|
||||
myIMU.settings.adcEnabled = 1;
|
||||
myIMU.settings.accelSampleRate = 400; //Hz. Can be: 0,1,10,25,50,100,200,400,1600,5000 Hz
|
||||
myIMU.settings.accelRange = 16; //Max G force readable. Can be: 2, 4, 8, 16
|
||||
myIMU.settings.xAccelEnabled = 1;
|
||||
myIMU.settings.yAccelEnabled = 1;
|
||||
myIMU.settings.zAccelEnabled = 1;
|
||||
|
||||
//Call .begin() to configure the IMU
|
||||
myIMU.begin();
|
||||
|
||||
delay(100);
|
||||
|
||||
}
|
||||
|
||||
void setupGPS_BMP() {
|
||||
GpsON;
|
||||
delay(100);
|
||||
Wire.begin();
|
||||
bmp.begin();
|
||||
|
||||
Wire.setClock(400000);
|
||||
|
||||
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
|
||||
{
|
||||
SerialUSB.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
|
||||
while (1)
|
||||
;
|
||||
}
|
||||
|
||||
// do not overload the buffer system from the GPS, disable UART output
|
||||
myGPS.setUART1Output(0); //Disable the UART1 port output
|
||||
myGPS.setUART2Output(0); //Disable Set the UART2 port output
|
||||
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
|
||||
|
||||
//myGPS.enableDebugging(); //Enable debug messages over Serial (default)
|
||||
|
||||
myGPS.setNavigationFrequency(2);//Set output to 2 times a second. Max is 10
|
||||
byte rate = myGPS.getNavigationFrequency(); //Get the update rate of this module
|
||||
SerialUSB.print("Current update rate for GPS: ");
|
||||
SerialUSB.println(rate);
|
||||
|
||||
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
|
||||
|
||||
}
|
||||
|
||||
void printGPSandSensorData()
|
||||
{
|
||||
|
||||
lastTime = millis(); //Update the timer
|
||||
|
||||
byte fixType = myGPS.getFixType();
|
||||
|
||||
SerialUSB.print(F("FixType: "));
|
||||
SerialUSB.print(fixType);
|
||||
|
||||
int SIV = myGPS.getSIV();
|
||||
SerialUSB.print(F(" Sats: "));
|
||||
SerialUSB.print(SIV);
|
||||
|
||||
float flat = myGPS.getLatitude() / 10000000.f;
|
||||
|
||||
SerialUSB.print(F(" Lat: "));
|
||||
SerialUSB.print(flat);
|
||||
|
||||
float flong = myGPS.getLongitude() / 10000000.f;
|
||||
SerialUSB.print(F(" Long: "));
|
||||
SerialUSB.print(flong);
|
||||
|
||||
float altitude = myGPS.getAltitude() / 1000;
|
||||
SerialUSB.print(F(" Alt: "));
|
||||
SerialUSB.print(altitude);
|
||||
SerialUSB.print(F(" (m)"));
|
||||
|
||||
//float speed = myGPS.getGroundSpeed() * 0.0036f;
|
||||
//SerialUSB.print(F(" Speed: "));
|
||||
//SerialUSB.print(speed);
|
||||
//SerialUSB.print(F(" (km/h)"));
|
||||
|
||||
//long heading = myGPS.getHeading() / 100000;
|
||||
//SerialUSB.print(F(" Heading: "));
|
||||
//SerialUSB.print(heading);
|
||||
//SerialUSB.print(F(" (degrees)"));
|
||||
|
||||
SerialUSB.print(" Time: ");
|
||||
SerialUSB.print(myGPS.getYear());
|
||||
SerialUSB.print("-");
|
||||
SerialUSB.print(myGPS.getMonth());
|
||||
SerialUSB.print("-");
|
||||
SerialUSB.print(myGPS.getDay());
|
||||
SerialUSB.print(" ");
|
||||
SerialUSB.print(myGPS.getHour());
|
||||
SerialUSB.print(":");
|
||||
SerialUSB.print(myGPS.getMinute());
|
||||
SerialUSB.print(":");
|
||||
SerialUSB.print(myGPS.getSecond());
|
||||
|
||||
SerialUSB.print(" Temp: ");
|
||||
SerialUSB.print(bmp.readTemperature());
|
||||
SerialUSB.print(" C");
|
||||
|
||||
SerialUSB.print(" Press: ");
|
||||
SerialUSB.print(bmp.readPressure() / 100.0);
|
||||
SerialUSB.print(" hPa");
|
||||
|
||||
//SerialUSB.print(" Accel: ");
|
||||
//SerialUSB.print(myIMU.readFloatAccelX());
|
||||
//SerialUSB.print(",");
|
||||
//SerialUSB.print(myIMU.readFloatAccelY()- 0.98f);
|
||||
//SerialUSB.print(",");
|
||||
//SerialUSB.print(myIMU.readFloatAccelZ());
|
||||
//SerialUSB.print(" ");
|
||||
SerialUSB.println();
|
||||
|
||||
|
||||
}
|
||||
|
||||
void updateTelemetry() {
|
||||
|
||||
tempAltitudeLong = 0; //meters or feet
|
||||
tempAltitudeShort = 0; //km or miles
|
||||
tempSpeed = 0; //km or miles
|
||||
tempTemperature = 0; //Celcius or Fahrenheit
|
||||
|
||||
if(measurementSystem == 0){ //Metric
|
||||
|
||||
tempAltitudeLong = myGPS.getAltitude() / 1000.f; //meters
|
||||
tempAltitudeShort = tempAltitudeLong / 1000.f; //kilometers
|
||||
tempSpeed = myGPS.getGroundSpeed() * 0.0036f; //km/hour
|
||||
tempTemperature = bmp.readTemperature(); //Celsius
|
||||
|
||||
} else { //Imperial
|
||||
|
||||
tempAltitudeLong = (myGPS.getAltitude() * 3.2808399) / 1000.f;//feet
|
||||
tempAltitudeShort = tempAltitudeLong / 5280.f;//miles
|
||||
tempSpeed = myGPS.getGroundSpeed() * 0.00223694f; //mile/hour
|
||||
tempTemperature = (bmp.readTemperature() * 1.8f) + 32; //Fahrenheit
|
||||
}
|
||||
|
||||
tempLatitude = myGPS.getLatitude() / 10000000.f;
|
||||
tempLongitude = myGPS.getLongitude() / 10000000.f;
|
||||
tempSats = myGPS.getSIV();
|
||||
tempHeading = myGPS.getHeading() / 100000;
|
||||
tempPressure = bmp.readPressure() / 100.0f;
|
||||
|
||||
//latitude,longtitude,altitude,speed,course,sattelite,battery,temp,pressure
|
||||
|
||||
telemetry.reset();// clear the buffer
|
||||
telemetry.addGPS(1, tempLatitude, tempLongitude, tempAltitudeLong); // channel 3, coordinates and altitude (meters or feet)
|
||||
telemetry.addTemperature(2, tempTemperature); // Celcius or Fahrenheit
|
||||
telemetry.addAnalogInput(3, voltage); //Battery/Supercaps voltage
|
||||
telemetry.addDigitalInput(4, tempSats); //GPS sattelites in view
|
||||
telemetry.addAnalogInput(5, tempSpeed); //km/h or mile/h
|
||||
telemetry.addDigitalInput(6, tempHeading); //course in degrees
|
||||
telemetry.addBarometricPressure(7, tempPressure); //pressure
|
||||
telemetry.addAccelerometer(8,myIMU.readFloatAccelX(),myIMU.readFloatAccelY(),myIMU.readFloatAccelZ());
|
||||
telemetry.addAnalogInput(9, tempAltitudeShort); //kilometers or miles
|
||||
|
||||
}
|
||||
|
||||
|
||||
float readBatt() {
|
||||
|
||||
float R1 = 560000.0; // 560K
|
||||
float R2 = 100000.0; // 100K
|
||||
float value = 0.0f;
|
||||
|
||||
do {
|
||||
value =analogRead(BattPin);
|
||||
value +=analogRead(BattPin);
|
||||
value +=analogRead(BattPin);
|
||||
value = value / 3.0f;
|
||||
value = (value * 3.3) / 1024.0f;
|
||||
value = value / (R2/(R1+R2));
|
||||
} while (value > 16.0);
|
||||
return value ;
|
||||
|
||||
}
|
||||
|
||||
void freeMem() {
|
||||
#if defined(DEVMODE)
|
||||
SerialUSB.print(F("Free RAM: ")); SerialUSB.print(freeMemory(), DEC); SerialUSB.println(F(" byte"));
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void os_getJoinEui (u1_t* buf) { memcpy_P(buf, APPEUI, 8);}
|
||||
void os_getDevEui (u1_t* buf) { memcpy_P(buf, DEVEUI, 8);}
|
||||
void os_getNwkKey (u1_t* buf) { memcpy_P(buf, APPKEY, 16);}
|
||||
|
||||
void onLmicEvent (ev_t ev) {
|
||||
SerialUSB.print(os_getTime());
|
||||
SerialUSB.print(": ");
|
||||
switch(ev) {
|
||||
case EV_SCAN_TIMEOUT:
|
||||
SerialUSB.println(F("EV_SCAN_TIMEOUT"));
|
||||
break;
|
||||
case EV_BEACON_FOUND:
|
||||
SerialUSB.println(F("EV_BEACON_FOUND"));
|
||||
break;
|
||||
case EV_BEACON_MISSED:
|
||||
SerialUSB.println(F("EV_BEACON_MISSED"));
|
||||
break;
|
||||
case EV_BEACON_TRACKED:
|
||||
SerialUSB.println(F("EV_BEACON_TRACKED"));
|
||||
break;
|
||||
case EV_JOINING:
|
||||
SerialUSB.println(F("EV_JOINING"));
|
||||
break;
|
||||
case EV_JOINED:
|
||||
SerialUSB.println(F("EV_JOINED"));
|
||||
// Disable link check validation (automatically enabled
|
||||
// during join, but not supported by TTN at this time).
|
||||
LMIC_setLinkCheckMode(0);
|
||||
break;
|
||||
case EV_RFU1:
|
||||
SerialUSB.println(F("EV_RFU1"));
|
||||
break;
|
||||
case EV_JOIN_FAILED:
|
||||
SerialUSB.println(F("EV_JOIN_FAILED"));
|
||||
break;
|
||||
case EV_REJOIN_FAILED:
|
||||
SerialUSB.println(F("EV_REJOIN_FAILED"));
|
||||
break;
|
||||
break;
|
||||
case EV_TXCOMPLETE:
|
||||
SerialUSB.println(F("EV_TXCOMPLETE (includes waiting for RX windows)"));
|
||||
if (LMIC.txrxFlags & TXRX_ACK)
|
||||
SerialUSB.println(F("Received ack"));
|
||||
if (LMIC.dataLen) {
|
||||
SerialUSB.print(F("Received "));
|
||||
SerialUSB.print(LMIC.dataLen);
|
||||
SerialUSB.println(F(" bytes of payload"));
|
||||
}
|
||||
break;
|
||||
case EV_LOST_TSYNC:
|
||||
SerialUSB.println(F("EV_LOST_TSYNC"));
|
||||
break;
|
||||
case EV_RESET:
|
||||
SerialUSB.println(F("EV_RESET"));
|
||||
break;
|
||||
case EV_RXCOMPLETE:
|
||||
// data received in ping slot
|
||||
SerialUSB.println(F("EV_RXCOMPLETE"));
|
||||
break;
|
||||
case EV_LINK_DEAD:
|
||||
SerialUSB.println(F("EV_LINK_DEAD"));
|
||||
break;
|
||||
case EV_LINK_ALIVE:
|
||||
SerialUSB.println(F("EV_LINK_ALIVE"));
|
||||
break;
|
||||
case EV_SCAN_FOUND:
|
||||
SerialUSB.println(F("EV_SCAN_FOUND"));
|
||||
break;
|
||||
case EV_TXSTART:
|
||||
SerialUSB.println(F("EV_TXSTART"));
|
||||
break;
|
||||
case EV_TXDONE:
|
||||
SerialUSB.println(F("EV_TXDONE"));
|
||||
break;
|
||||
case EV_DATARATE:
|
||||
SerialUSB.println(F("EV_DATARATE"));
|
||||
break;
|
||||
case EV_START_SCAN:
|
||||
SerialUSB.println(F("EV_START_SCAN"));
|
||||
break;
|
||||
case EV_ADR_BACKOFF:
|
||||
SerialUSB.println(F("EV_ADR_BACKOFF"));
|
||||
break;
|
||||
|
||||
default:
|
||||
SerialUSB.print(F("Unknown event: "));
|
||||
SerialUSB.println(ev);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void printLoRaWANSettings(){
|
||||
|
||||
SerialUSB.println(F("------------------------------------------------------------------------------------"));
|
||||
SerialUSB.print(F("Region: "));
|
||||
SerialUSB.print(regionName);
|
||||
SerialUSB.print(F(", Freq: "));
|
||||
SerialUSB.print(LMIC.freq/1000000.f);
|
||||
SerialUSB.print(F("MHz, SF"));
|
||||
SerialUSB.print(getSf(LMIC.rps) - SF7 + 7);
|
||||
SerialUSB.print(F("BW"));
|
||||
SerialUSB.print(125 << (getBw(LMIC.rps) - BW125));
|
||||
SerialUSB.print(F(", Power: "));
|
||||
SerialUSB.print(LMIC.txpow + LMIC.brdTxPowOff);
|
||||
SerialUSB.print(F("dBm, Payload Size: "));
|
||||
SerialUSB.print(telemetry.getSize());
|
||||
SerialUSB.println(F(" bytes"));
|
||||
SerialUSB.println(F("------------------------------------------------------------------------------------"));
|
||||
|
||||
}
|
||||
|
||||
void setupUBloxDynamicModel() {
|
||||
// If we are going to change the dynamic platform model, let's do it here.
|
||||
// Possible values are:
|
||||
// PORTABLE, STATIONARY, PEDESTRIAN, AUTOMOTIVE, SEA, AIRBORNE1g, AIRBORNE2g, AIRBORNE4g, WRIST, BIKE
|
||||
//DYN_MODEL_AIRBORNE4g model increases ublox max. altitude limit from 12.000 meters to 50.000 meters.
|
||||
if (myGPS.setDynamicModel(DYN_MODEL_AIRBORNE4g) == false) // Set the dynamic model to DYN_MODEL_AIRBORNE4g
|
||||
{
|
||||
SerialUSB.println(F("***!!! Warning: setDynamicModel failed !!!***"));
|
||||
}
|
||||
else
|
||||
{
|
||||
SerialUSB.print(F("Ublox Dynamic platform model changed successfully! : "));
|
||||
SerialUSB.println(myGPS.getDynamicModel());
|
||||
}
|
||||
|
||||
}
|
|
@ -0,0 +1,711 @@
|
|||
#include <basicmac.h>
|
||||
#include <hal/hal.h>
|
||||
#include <Adafruit_BMP085.h>
|
||||
#include <LightTrackerGeofence.h>
|
||||
#include "SparkFun_Ublox_Arduino_Library.h"
|
||||
#include <MemoryFree.h>;
|
||||
#include <CayenneLPP.h>
|
||||
#include "SparkFunLIS3DH.h"
|
||||
|
||||
// SX1262 has the following connections:
|
||||
#define nssPin 8
|
||||
#define rstPin 9
|
||||
#define dio1Pin 3
|
||||
#define busyPin 2
|
||||
|
||||
#define BattPin A5
|
||||
#define GpsPwr 12
|
||||
#define GpsON digitalWrite(GpsPwr, LOW);
|
||||
#define GpsOFF digitalWrite(GpsPwr, HIGH);
|
||||
|
||||
SFE_UBLOX_GPS myGPS;
|
||||
Adafruit_BMP085 bmp; //temp and pressure sensor
|
||||
LIS3DH myIMU; //accelerometer
|
||||
|
||||
|
||||
//#define DEVMODE // Development mode. Uncomment to enable for debugging.
|
||||
|
||||
//***************************** UPDATE HERE WITH YOUR DEVICE KEYS **************************************/
|
||||
|
||||
//You should copy device keys from Helium or TTN Console and update following keys. Please check out: https://github.com/lightaprs/LightTracker-1.0/wiki/Adding-Device-on-Helium-Console
|
||||
|
||||
// This EUI must be in little-endian format, so least-significant-byte (lsb)
|
||||
// first. When copying an EUI from Helium Console or ttnctl output, this means to reverse the bytes.
|
||||
|
||||
static const u1_t PROGMEM DEVEUI[8]={0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; //helium or ttn
|
||||
|
||||
// This EUI must be in little-endian format, so least-significant-byte (lsb)
|
||||
// first. When copying an EUI from Helium Console or ttnctl output, this means to reverse the bytes.
|
||||
|
||||
static const u1_t PROGMEM APPEUI[8]={0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; //helium or ttn
|
||||
|
||||
// This key should be in big endian format (or, since it is not really a
|
||||
// number but a block of memory, endianness does not really apply). In practice, a key taken from Helium Console or ttnctl can be copied as-is.
|
||||
|
||||
static const u1_t PROGMEM APPKEY[16] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; //helium or ttn
|
||||
//*****************************************************************************************************/
|
||||
|
||||
|
||||
//************************** LoRaWAN Settings ********************
|
||||
const unsigned TX_INTERVAL = 60000; // Schedule TX every this many miliseconds (might become longer due to duty cycle limitations).
|
||||
uint8_t measurementSystem = 0; //0 for metric (meters, km, Celcius, etc.), 1 for imperial (feet, mile, Fahrenheit,etc.)
|
||||
|
||||
//try to keep telemetry size smaller than 51 bytes if possible. Default telemetry size is 45 bytes.
|
||||
CayenneLPP telemetry(51);
|
||||
|
||||
// The LoRaWAN region to use, automatically selected based on your location. So GPS fix is necesarry
|
||||
u1_t os_getRegion (void) { return Lorawan_Geofence_region_code; } //do not change this
|
||||
|
||||
// GEOFENCE
|
||||
uint8_t Lorawan_Geofence_no_tx = 0; //do not change this
|
||||
uint8_t Lorawan_Geofence_region_code = _REGCODE_UNDEF; //do not change this
|
||||
uint8_t Lorawan_Geofence_special_region_code = _REGCODE_UNDEF; //do not change this
|
||||
|
||||
uint8_t lastLoRaWANRegion = _REGCODE_UNDEF; //do not change this
|
||||
|
||||
boolean OTAAJoinStatus = false; //do not change this.
|
||||
int channelNoFor2ndSubBand = 8; //do not change this. Used for US915 and AU915 / TTN and Helium
|
||||
uint32_t last_packet = 0; //do not change this. Timestamp of last packet sent.
|
||||
|
||||
//pinmap for SX1262 LoRa module
|
||||
#if !defined(USE_STANDARD_PINMAP)
|
||||
const lmic_pinmap lmic_pins = {
|
||||
.nss = nssPin,
|
||||
.tx = LMIC_UNUSED_PIN,
|
||||
.rx = LMIC_UNUSED_PIN,
|
||||
.rst = rstPin,
|
||||
.dio = {/* DIO0 */ LMIC_UNUSED_PIN, /* DIO1 */ dio1Pin, /* DIO2 */ LMIC_UNUSED_PIN},
|
||||
.busy = busyPin,
|
||||
.tcxo = LMIC_CONTROLLED_BY_DIO3,
|
||||
};
|
||||
#endif // !defined(USE_STANDARD_PINMAP)
|
||||
|
||||
//************************** uBlox GPS Settings ********************
|
||||
long lastTime = 0; //Simple local timer. Limits amount if I2C traffic to Ublox module.
|
||||
boolean gpsFix=false; //do not change this.
|
||||
boolean ublox_high_alt_mode_enabled = false; //do not change this.
|
||||
boolean gpsBMPSetup=false; //do not change this.
|
||||
//********************************* Power Settings ******************************
|
||||
int battWait=60; //seconds sleep if super capacitors/batteries are below battMin (important if power source is solar panel)
|
||||
float battMin=3.5; // min Volts to TX. (Works with 3.3V too but 3.5V is safer)
|
||||
float gpsMinVolt=4.5; //min Volts for GPS to wake up. (important if power source is solar panel) //do not change this
|
||||
//********************************* Misc Settings ******************************
|
||||
int txCount = 1;
|
||||
float voltage = 0;
|
||||
|
||||
void setup() {
|
||||
|
||||
pinMode(A1,INPUT_PULLUP);
|
||||
if(digitalRead(A1)==LOW) while(1);
|
||||
|
||||
delay(5000); //do not change this
|
||||
|
||||
pinMode(GpsPwr, OUTPUT);
|
||||
GpsOFF;
|
||||
|
||||
SerialUSB.begin(115200);
|
||||
|
||||
// Wait up to 5 seconds for serial to be opened, to allow catching
|
||||
// startup messages on native USB boards (that do not reset when
|
||||
// serial is opened).
|
||||
unsigned long start = millis();
|
||||
while (millis() - start < 5000 && !SerialUSB);
|
||||
|
||||
SerialUSB.println();
|
||||
SerialUSB.println(F("Starting"));
|
||||
SerialUSB.println();
|
||||
freeMem();
|
||||
|
||||
}
|
||||
|
||||
void loop() {
|
||||
|
||||
voltage = readBatt();
|
||||
|
||||
if (((voltage > battMin) && gpsFix) || ((voltage > gpsMinVolt) && !gpsFix)) {
|
||||
|
||||
if(!gpsBMPSetup){
|
||||
|
||||
SerialUSB.println(F("GPS setup"));
|
||||
setupGPS_BMP();
|
||||
SerialUSB.println(F("Searching for GPS fix..."));
|
||||
setupAccel();
|
||||
gpsBMPSetup = true;
|
||||
freeMem();
|
||||
|
||||
}
|
||||
|
||||
if(gpsFix) {
|
||||
// Let LMIC handle LoRaWAN background tasks
|
||||
os_runstep();
|
||||
}
|
||||
|
||||
//SerialUSB.println(millis() - lastLoRaPacket);
|
||||
|
||||
// If TX_INTERVAL passed, *and* our previous packet is not still
|
||||
// pending (which can happen due to duty cycle limitations), send
|
||||
// the next packet.
|
||||
if ((millis() - last_packet > TX_INTERVAL && !(LMIC.opmode & (OP_JOINING|OP_TXRXPEND))) || !gpsFix){
|
||||
|
||||
GpsON;
|
||||
delay(500);
|
||||
|
||||
if(!ublox_high_alt_mode_enabled){
|
||||
setupUBloxDynamicModel();
|
||||
}
|
||||
|
||||
// Calling myGPS.getPVT() returns true if there actually is a fresh navigation solution available.
|
||||
|
||||
if (myGPS.getPVT() && (myGPS.getFixType() !=0) && (myGPS.getSIV() > 0)) {
|
||||
gpsFix=true;
|
||||
|
||||
checkRegionByLocation();
|
||||
|
||||
if(lastLoRaWANRegion != Lorawan_Geofence_region_code) {
|
||||
SerialUSB.println(F("Region has changed, force LoRaWAN OTAA Login"));
|
||||
OTAAJoinStatus = false;
|
||||
lastLoRaWANRegion = Lorawan_Geofence_region_code;
|
||||
}
|
||||
|
||||
if(!OTAAJoinStatus && (Lorawan_Geofence_no_tx == 0)){
|
||||
SerialUSB.println(F("LoRaWAN OTAA Login initiated..."));
|
||||
startJoining();
|
||||
SerialUSB.println(F("LoRaWAN OTAA Login success..."));
|
||||
OTAAJoinStatus = true;
|
||||
freeMem();
|
||||
}
|
||||
|
||||
updateTelemetry();
|
||||
#if defined(DEVMODE)
|
||||
SerialUSB.print(F("Telemetry Size: "));
|
||||
SerialUSB.print(telemetry.getSize());
|
||||
SerialUSB.println(F(" bytes"));
|
||||
#endif
|
||||
|
||||
//need to save power
|
||||
if (readBatt() < 4.5) {
|
||||
GpsOFF;
|
||||
ublox_high_alt_mode_enabled = false; //gps sleep mode resets high altitude mode.
|
||||
delay(500);
|
||||
}
|
||||
|
||||
if (Lorawan_Geofence_no_tx == 0) {
|
||||
sendLoRaWANPacket();
|
||||
SerialUSB.println(F("LoRaWAN packet sent.."));
|
||||
}
|
||||
|
||||
freeMem();
|
||||
|
||||
}
|
||||
|
||||
#if defined(DEVMODE)
|
||||
printGPSandSensorData();
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
//this code block protecting serial connected (3V + 3V) super caps from overcharging by powering on GPS module.
|
||||
//GPS module uses too much power while on, so if voltage is too high for supercaps, GPS ON.
|
||||
if (readBatt() > 6.5) {
|
||||
GpsON;
|
||||
delay(500);
|
||||
}
|
||||
|
||||
} else {
|
||||
|
||||
GpsOFF;
|
||||
ublox_high_alt_mode_enabled = false; //gps sleep mode resets high altitude mode.
|
||||
delay(battWait * 1000);
|
||||
|
||||
}
|
||||
|
||||
delay(1000);
|
||||
|
||||
}
|
||||
|
||||
//to join LoRaWAN network, every region requires different parameters. Please refer to : https://lora-alliance.org/resource_hub/rp2-1-0-3-lorawan-regional-parameters/
|
||||
void startJoining() {
|
||||
|
||||
// LMIC init
|
||||
os_init(nullptr);
|
||||
LMIC_reset();
|
||||
|
||||
// Start join
|
||||
LMIC_startJoining();
|
||||
|
||||
//DO NOT CHANGE following code blocks unless you know what you are doing :)
|
||||
|
||||
//Europe
|
||||
if(Lorawan_Geofence_region_code == _REGCODE_EU868) {
|
||||
|
||||
SerialUSB.println(F("Region EU868"));
|
||||
|
||||
//A little hack for Russian region since BasicMAC does not officially support RU864-870. Tested on TTN and worked..
|
||||
if(Lorawan_Geofence_special_region_code == _REGCODE_RU864) {
|
||||
SerialUSB.println(F("Special Region RU864"));
|
||||
LMIC_setupChannel(0, 868900000, DR_RANGE_MAP(0, 2));
|
||||
LMIC_setupChannel(0, 869100000, DR_RANGE_MAP(0, 2));
|
||||
}
|
||||
//DR2 (SF10 BW125kHz)
|
||||
//SF10 is better/optimum spreading factor for high altitude balloons
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
|
||||
//Japan, Malaysia, Singapore, Brunei, Cambodia, Hong Kong, Indonesia, Laos, Taiwan, Thailand, Vietnam
|
||||
} else if (Lorawan_Geofence_region_code == _REGCODE_AS923) {
|
||||
SerialUSB.println(F("Region AS923"));
|
||||
|
||||
//A little hack for Korean region since BasicMAC does not officially support KR920-923. Tested on TTN and worked..
|
||||
if(Lorawan_Geofence_special_region_code == _REGCODE_KR920) {
|
||||
SerialUSB.println(F("Special Region KR920"));
|
||||
LMIC_setupChannel(0, 922100000, DR_RANGE_MAP(0, 2));
|
||||
LMIC_setupChannel(0, 922300000, DR_RANGE_MAP(0, 2));
|
||||
LMIC_setupChannel(0, 922500000, DR_RANGE_MAP(0, 2));
|
||||
}
|
||||
|
||||
//DR2 (SF10 BW125kHz)
|
||||
//For AS923, DR2 join only since max payload limit is 11 bytes.
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
|
||||
//North and South America (Except Brazil)
|
||||
} else if (Lorawan_Geofence_region_code == _REGCODE_US915) {
|
||||
|
||||
SerialUSB.println(F("Region US915"));
|
||||
|
||||
//DR0 (SF10 BW125kHz)
|
||||
//For US915, DR0 join only since max payload limit is 11 bytes.
|
||||
LMIC_setDrTxpow(0,KEEP_TXPOWADJ);
|
||||
//TTN and Helium only supports second sub band (channels 8 to 15)
|
||||
//so we should force BasicMAC to initiate a join with second sub band channels.
|
||||
LMIC_selectChannel(8);
|
||||
|
||||
//Australia and New Zeleand
|
||||
} else if (Lorawan_Geofence_region_code == _REGCODE_AU915) {
|
||||
|
||||
SerialUSB.println(F("Region AU915"));
|
||||
//DR2 (SF10 BW125kHz)
|
||||
//For AU915, DR2 join only since max payload limit is 11 bytes.
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
//TTN and Helium only supports second sub band (channels 8 to 15)
|
||||
//so we should force BasicMAC to initiate a join with second sub band channels.
|
||||
LMIC_selectChannel(8);
|
||||
|
||||
} else {
|
||||
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
|
||||
}
|
||||
|
||||
LMIC_setAdrMode(false);
|
||||
LMIC_setLinkCheckMode(0);
|
||||
|
||||
// Make sure the first packet is scheduled ASAP after join completes
|
||||
last_packet = millis() - TX_INTERVAL;
|
||||
|
||||
|
||||
// Optionally wait for join to complete (uncomment this is you want
|
||||
// to run the loop while joining).
|
||||
while ((LMIC.opmode & (OP_JOINING))) {
|
||||
os_runstep();
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
// Telemetry size is very important, try to keep it lower than 51 bytes. Always lower is better.
|
||||
void sendLoRaWANPacket(){
|
||||
|
||||
//Europa
|
||||
if(Lorawan_Geofence_region_code == _REGCODE_EU868) {
|
||||
|
||||
if(telemetry.getSize() < 52) {
|
||||
//DR2 (SF10 BW125kHz) max payload size is 51 bytes.
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
} else if (telemetry.getSize() < 116){
|
||||
//DR3 (SF9 BW125kHz) max payload size is 115 bytes.
|
||||
LMIC_setDrTxpow(3,KEEP_TXPOWADJ);
|
||||
} else {
|
||||
//DR4 (SF8 BW125kHz) max payload size is 222 bytes.
|
||||
LMIC_setDrTxpow(4,KEEP_TXPOWADJ);
|
||||
|
||||
}
|
||||
//Japan, Malaysia, Singapore, Brunei, Cambodia, Hong Kong, Indonesia, Laos, Taiwan, Thailand, Vietnam
|
||||
} else if (Lorawan_Geofence_region_code == _REGCODE_AS923) {
|
||||
|
||||
if(telemetry.getSize() < 54) {
|
||||
//DR3 (SF9 BW125kHz) max payload size is 53 bytes.
|
||||
LMIC_setDrTxpow(3,KEEP_TXPOWADJ);
|
||||
} else if (telemetry.getSize() < 126){
|
||||
//DR4 (SF8 BW125kHz) max payload size is 125 bytes.
|
||||
LMIC_setDrTxpow(4,KEEP_TXPOWADJ);
|
||||
} else {
|
||||
//DR5 (SF7 BW125kHz) max payload size is 222 bytes.
|
||||
LMIC_setDrTxpow(5,KEEP_TXPOWADJ);
|
||||
|
||||
}
|
||||
|
||||
//North and South America (Except Brazil) or Australia and New Zeleand
|
||||
} else if (Lorawan_Geofence_region_code == _REGCODE_US915 || Lorawan_Geofence_region_code == _REGCODE_AU915) {
|
||||
|
||||
//North and South America (Except Brazil)
|
||||
if (Lorawan_Geofence_region_code == _REGCODE_US915){
|
||||
|
||||
if(telemetry.getSize() < 54) {
|
||||
//DR1 (SF9 BW125kHz) max payload size is 53 bytes.
|
||||
LMIC_setDrTxpow(1,KEEP_TXPOWADJ);
|
||||
} else if (telemetry.getSize() < 126){
|
||||
//DR2 (SF8 BW125kHz) max payload size is 125 bytes.
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
} else {
|
||||
//DR3 (SF7 BW125kHz) max payload size is 222 bytes.
|
||||
LMIC_setDrTxpow(3,KEEP_TXPOWADJ);
|
||||
}
|
||||
|
||||
//Australia and New Zeleand
|
||||
} else if (Lorawan_Geofence_region_code == _REGCODE_AU915){
|
||||
|
||||
if(telemetry.getSize() < 54) {
|
||||
//DR3 (SF9 BW125kHz) max payload size is 53 bytes.
|
||||
LMIC_setDrTxpow(3,KEEP_TXPOWADJ);
|
||||
} else if (telemetry.getSize() < 126){
|
||||
//DR4 (SF8 BW125kHz) max payload size is 125 bytes.
|
||||
LMIC_setDrTxpow(4,KEEP_TXPOWADJ);
|
||||
} else {
|
||||
//DR5 (SF7 BW125kHz) max payload size is 222 bytes.
|
||||
LMIC_setDrTxpow(5,KEEP_TXPOWADJ);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//TTN and Helium only supports second sub band (channels 8 to 15)
|
||||
//so we should force BasicMAC use second sub band channels.
|
||||
LMIC_selectChannel(channelNoFor2ndSubBand);
|
||||
|
||||
++channelNoFor2ndSubBand;
|
||||
if(channelNoFor2ndSubBand > 15) {
|
||||
channelNoFor2ndSubBand = 8;
|
||||
}
|
||||
//India
|
||||
} else if (Lorawan_Geofence_region_code == _REGCODE_IN865) {
|
||||
|
||||
if(telemetry.getSize() < 52) {
|
||||
//DR2 (SF10 BW125kHz) max payload size is 51 bytes.
|
||||
LMIC_setDrTxpow(2,KEEP_TXPOWADJ);
|
||||
} else if (telemetry.getSize() < 116){
|
||||
//DR3 (SF9 BW125kHz) max payload size is 115 bytes.
|
||||
LMIC_setDrTxpow(3,KEEP_TXPOWADJ);
|
||||
} else {
|
||||
//DR4 (SF8 BW125kHz) max payload size is 222 bytes.
|
||||
LMIC_setDrTxpow(4,KEEP_TXPOWADJ);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
LMIC_setAdrMode(false);
|
||||
LMIC_setLinkCheckMode(0);
|
||||
|
||||
LMIC_setTxData2(1, telemetry.getBuffer(), telemetry.getSize(), 0);
|
||||
last_packet = millis();
|
||||
txCount++;
|
||||
SerialUSB.print(F("Packet queued..."));
|
||||
|
||||
}
|
||||
|
||||
void setupAccel() {
|
||||
myIMU.settings.adcEnabled = 1;
|
||||
myIMU.settings.accelSampleRate = 400; //Hz. Can be: 0,1,10,25,50,100,200,400,1600,5000 Hz
|
||||
myIMU.settings.accelRange = 16; //Max G force readable. Can be: 2, 4, 8, 16
|
||||
myIMU.settings.xAccelEnabled = 1;
|
||||
myIMU.settings.yAccelEnabled = 1;
|
||||
myIMU.settings.zAccelEnabled = 1;
|
||||
|
||||
//Call .begin() to configure the IMU
|
||||
myIMU.begin();
|
||||
|
||||
delay(100);
|
||||
|
||||
}
|
||||
|
||||
void setupGPS_BMP() {
|
||||
GpsON;
|
||||
delay(100);
|
||||
Wire.begin();
|
||||
bmp.begin();
|
||||
|
||||
Wire.setClock(400000);
|
||||
|
||||
if (myGPS.begin() == false) //Connect to the Ublox module using Wire port
|
||||
{
|
||||
SerialUSB.println(F("Ublox GPS not detected at default I2C address. Please check wiring. Freezing."));
|
||||
while (1)
|
||||
;
|
||||
}
|
||||
|
||||
// do not overload the buffer system from the GPS, disable UART output
|
||||
myGPS.setUART1Output(0); //Disable the UART1 port output
|
||||
myGPS.setUART2Output(0); //Disable Set the UART2 port output
|
||||
myGPS.setI2COutput(COM_TYPE_UBX); //Set the I2C port to output UBX only (turn off NMEA noise)
|
||||
|
||||
//myGPS.enableDebugging(); //Enable debug messages over Serial (default)
|
||||
|
||||
myGPS.setNavigationFrequency(2);//Set output to 2 times a second. Max is 10
|
||||
byte rate = myGPS.getNavigationFrequency(); //Get the update rate of this module
|
||||
SerialUSB.print("Current update rate for GPS: ");
|
||||
SerialUSB.println(rate);
|
||||
|
||||
myGPS.saveConfiguration(); //Save the current settings to flash and BBR
|
||||
|
||||
}
|
||||
|
||||
void printGPSandSensorData()
|
||||
{
|
||||
|
||||
lastTime = millis(); //Update the timer
|
||||
|
||||
byte fixType = myGPS.getFixType();
|
||||
|
||||
SerialUSB.print(F("FixType: "));
|
||||
SerialUSB.print(fixType);
|
||||
|
||||
int SIV = myGPS.getSIV();
|
||||
SerialUSB.print(F(" Sats: "));
|
||||
SerialUSB.print(SIV);
|
||||
|
||||
float flat = myGPS.getLatitude() / 10000000.f;
|
||||
|
||||
SerialUSB.print(F(" Lat: "));
|
||||
SerialUSB.print(flat);
|
||||
|
||||
float flong = myGPS.getLongitude() / 10000000.f;
|
||||
SerialUSB.print(F(" Long: "));
|
||||
SerialUSB.print(flong);
|
||||
|
||||
float altitude = myGPS.getAltitude() / 1000;
|
||||
SerialUSB.print(F(" Alt: "));
|
||||
SerialUSB.print(altitude);
|
||||
SerialUSB.print(F(" (m)"));
|
||||
|
||||
//float speed = myGPS.getGroundSpeed() * 0.0036f;
|
||||
//SerialUSB.print(F(" Speed: "));
|
||||
//SerialUSB.print(speed);
|
||||
//SerialUSB.print(F(" (km/h)"));
|
||||
|
||||
//long heading = myGPS.getHeading() / 100000;
|
||||
//SerialUSB.print(F(" Heading: "));
|
||||
//SerialUSB.print(heading);
|
||||
//SerialUSB.print(F(" (degrees)"));
|
||||
|
||||
SerialUSB.print(" Time: ");
|
||||
SerialUSB.print(myGPS.getYear());
|
||||
SerialUSB.print("-");
|
||||
SerialUSB.print(myGPS.getMonth());
|
||||
SerialUSB.print("-");
|
||||
SerialUSB.print(myGPS.getDay());
|
||||
SerialUSB.print(" ");
|
||||
SerialUSB.print(myGPS.getHour());
|
||||
SerialUSB.print(":");
|
||||
SerialUSB.print(myGPS.getMinute());
|
||||
SerialUSB.print(":");
|
||||
SerialUSB.print(myGPS.getSecond());
|
||||
|
||||
SerialUSB.print(" Temp: ");
|
||||
SerialUSB.print(bmp.readTemperature());
|
||||
SerialUSB.print(" C");
|
||||
|
||||
SerialUSB.print(" Press: ");
|
||||
SerialUSB.print(bmp.readPressure() / 100.0);
|
||||
SerialUSB.print(" hPa");
|
||||
|
||||
//SerialUSB.print(" Accel: ");
|
||||
//SerialUSB.print(myIMU.readFloatAccelX());
|
||||
//SerialUSB.print(",");
|
||||
//SerialUSB.print(myIMU.readFloatAccelY()- 0.98f);
|
||||
//SerialUSB.print(",");
|
||||
//SerialUSB.print(myIMU.readFloatAccelZ());
|
||||
//SerialUSB.print(" ");
|
||||
SerialUSB.println();
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
void updateTelemetry() {
|
||||
|
||||
float tempAltitudeLong = 0; //meters or feet
|
||||
float tempAltitudeShort = 0; //km or miles
|
||||
float tempSpeed = 0; //km or miles
|
||||
float tempTemperature = 0; //Celcius or Fahrenheit
|
||||
|
||||
if(measurementSystem == 0){ //Metric
|
||||
|
||||
tempAltitudeLong = myGPS.getAltitude() / 1000.f; //meters
|
||||
tempAltitudeShort = tempAltitudeLong / 1000.f; //kilometers
|
||||
tempSpeed = myGPS.getGroundSpeed() * 0.0036f; //km/hour
|
||||
tempTemperature = bmp.readTemperature(); //Celsius
|
||||
|
||||
} else { //Imperial
|
||||
|
||||
tempAltitudeLong = (myGPS.getAltitude() * 3.2808399) / 1000.f;//feet
|
||||
tempAltitudeShort = tempAltitudeLong / 5280.f;//miles
|
||||
tempSpeed = myGPS.getGroundSpeed() * 0.00223694f; //mile/hour
|
||||
tempTemperature = (bmp.readTemperature() * 1.8f) + 32; //Fahrenheit
|
||||
}
|
||||
|
||||
//latitude,longtitude,altitude,speed,course,sattelite,battery,temp,pressure
|
||||
|
||||
telemetry.reset();// clear the buffer
|
||||
telemetry.addGPS(1, myGPS.getLatitude() / 10000000.f, myGPS.getLongitude() / 10000000.f, tempAltitudeLong); // channel 3, coordinates and altitude (meters or feet)
|
||||
telemetry.addTemperature(2, tempTemperature); // Celcius or Fahrenheit
|
||||
telemetry.addAnalogInput(3, voltage); //Battery/Supercaps voltage
|
||||
telemetry.addDigitalInput(4, myGPS.getSIV()); //GPS sattelites in view
|
||||
telemetry.addAnalogInput(5, tempSpeed); //km/h or mile/h
|
||||
telemetry.addDigitalInput(6, myGPS.getHeading() / 100000); //course in degrees
|
||||
telemetry.addBarometricPressure(7, bmp.readPressure() / 100.f); //pressure
|
||||
telemetry.addAccelerometer(8,myIMU.readFloatAccelX(),myIMU.readFloatAccelY()- 0.98f,myIMU.readFloatAccelZ());
|
||||
telemetry.addAnalogInput(9, tempAltitudeShort); //kilometers or miles
|
||||
|
||||
}
|
||||
|
||||
void checkRegionByLocation() {
|
||||
|
||||
float tempLat = myGPS.getLatitude() / 10000000.f;
|
||||
float tempLong = myGPS.getLongitude() / 10000000.f;
|
||||
|
||||
Lorawan_Geofence_position(tempLat,tempLong);
|
||||
|
||||
}
|
||||
|
||||
float readBatt() {
|
||||
|
||||
float R1 = 560000.0; // 560K
|
||||
float R2 = 100000.0; // 100K
|
||||
float value = 0.0f;
|
||||
|
||||
do {
|
||||
value =analogRead(BattPin);
|
||||
value +=analogRead(BattPin);
|
||||
value +=analogRead(BattPin);
|
||||
value = value / 3.0f;
|
||||
value = (value * 3.3) / 1024.0f;
|
||||
value = value / (R2/(R1+R2));
|
||||
} while (value > 16.0);
|
||||
return value ;
|
||||
|
||||
}
|
||||
|
||||
void freeMem() {
|
||||
#if defined(DEVMODE)
|
||||
SerialUSB.print(F("Free RAM: ")); SerialUSB.print(freeMemory(), DEC); SerialUSB.println(F(" byte"));
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void os_getJoinEui (u1_t* buf) { memcpy_P(buf, APPEUI, 8);}
|
||||
void os_getDevEui (u1_t* buf) { memcpy_P(buf, DEVEUI, 8);}
|
||||
void os_getNwkKey (u1_t* buf) { memcpy_P(buf, APPKEY, 16);}
|
||||
|
||||
void onLmicEvent (ev_t ev) {
|
||||
SerialUSB.print(os_getTime());
|
||||
SerialUSB.print(": ");
|
||||
switch(ev) {
|
||||
case EV_SCAN_TIMEOUT:
|
||||
SerialUSB.println(F("EV_SCAN_TIMEOUT"));
|
||||
break;
|
||||
case EV_BEACON_FOUND:
|
||||
SerialUSB.println(F("EV_BEACON_FOUND"));
|
||||
break;
|
||||
case EV_BEACON_MISSED:
|
||||
SerialUSB.println(F("EV_BEACON_MISSED"));
|
||||
break;
|
||||
case EV_BEACON_TRACKED:
|
||||
SerialUSB.println(F("EV_BEACON_TRACKED"));
|
||||
break;
|
||||
case EV_JOINING:
|
||||
SerialUSB.println(F("EV_JOINING"));
|
||||
break;
|
||||
case EV_JOINED:
|
||||
SerialUSB.println(F("EV_JOINED"));
|
||||
|
||||
// Disable link check validation (automatically enabled
|
||||
// during join, but not supported by TTN at this time).
|
||||
LMIC_setLinkCheckMode(0);
|
||||
break;
|
||||
case EV_RFU1:
|
||||
SerialUSB.println(F("EV_RFU1"));
|
||||
break;
|
||||
case EV_JOIN_FAILED:
|
||||
SerialUSB.println(F("EV_JOIN_FAILED"));
|
||||
break;
|
||||
case EV_REJOIN_FAILED:
|
||||
SerialUSB.println(F("EV_REJOIN_FAILED"));
|
||||
break;
|
||||
break;
|
||||
case EV_TXCOMPLETE:
|
||||
SerialUSB.println(F("EV_TXCOMPLETE (includes waiting for RX windows)"));
|
||||
if (LMIC.txrxFlags & TXRX_ACK)
|
||||
SerialUSB.println(F("Received ack"));
|
||||
if (LMIC.dataLen) {
|
||||
SerialUSB.print(F("Received "));
|
||||
SerialUSB.print(LMIC.dataLen);
|
||||
SerialUSB.println(F(" bytes of payload"));
|
||||
}
|
||||
break;
|
||||
case EV_LOST_TSYNC:
|
||||
SerialUSB.println(F("EV_LOST_TSYNC"));
|
||||
break;
|
||||
case EV_RESET:
|
||||
SerialUSB.println(F("EV_RESET"));
|
||||
break;
|
||||
case EV_RXCOMPLETE:
|
||||
// data received in ping slot
|
||||
SerialUSB.println(F("EV_RXCOMPLETE"));
|
||||
break;
|
||||
case EV_LINK_DEAD:
|
||||
SerialUSB.println(F("EV_LINK_DEAD"));
|
||||
break;
|
||||
case EV_LINK_ALIVE:
|
||||
SerialUSB.println(F("EV_LINK_ALIVE"));
|
||||
break;
|
||||
case EV_SCAN_FOUND:
|
||||
SerialUSB.println(F("EV_SCAN_FOUND"));
|
||||
break;
|
||||
case EV_TXSTART:
|
||||
SerialUSB.println(F("EV_TXSTART"));
|
||||
break;
|
||||
case EV_TXDONE:
|
||||
SerialUSB.println(F("EV_TXDONE"));
|
||||
break;
|
||||
case EV_DATARATE:
|
||||
SerialUSB.println(F("EV_DATARATE"));
|
||||
break;
|
||||
case EV_START_SCAN:
|
||||
SerialUSB.println(F("EV_START_SCAN"));
|
||||
break;
|
||||
case EV_ADR_BACKOFF:
|
||||
SerialUSB.println(F("EV_ADR_BACKOFF"));
|
||||
break;
|
||||
|
||||
default:
|
||||
SerialUSB.print(F("Unknown event: "));
|
||||
SerialUSB.println(ev);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void setupUBloxDynamicModel() {
|
||||
// If we are going to change the dynamic platform model, let's do it here.
|
||||
// Possible values are:
|
||||
// PORTABLE, STATIONARY, PEDESTRIAN, AUTOMOTIVE, SEA, AIRBORNE1g, AIRBORNE2g, AIRBORNE4g, WRIST, BIKE
|
||||
//DYN_MODEL_AIRBORNE4g model increases ublox max. altitude limit from 12.000 meters to 50.000 meters.
|
||||
if (myGPS.setDynamicModel(DYN_MODEL_AIRBORNE4g) == false) // Set the dynamic model to DYN_MODEL_AIRBORNE4g
|
||||
{
|
||||
SerialUSB.println(F("***!!! Warning: setDynamicModel failed !!!***"));
|
||||
}
|
||||
else
|
||||
{
|
||||
#if defined(DEVMODE)
|
||||
SerialUSB.print(F("Dynamic platform model changed successfully! : "));
|
||||
SerialUSB.println(myGPS.getDynamicModel());
|
||||
#endif
|
||||
}
|
||||
|
||||
}
|
Ładowanie…
Reference in New Issue