optimized
This commit is contained in:
parent
1b11b44336
commit
0adeb9a7b1
12
Makefile
12
Makefile
|
@ -22,7 +22,6 @@ CFLAGS?=-Datmega328p\
|
||||||
-fdata-sections\
|
-fdata-sections\
|
||||||
-MMD\
|
-MMD\
|
||||||
-flto\
|
-flto\
|
||||||
-std=c++11\
|
|
||||||
-fno-fat-lto-objects\
|
-fno-fat-lto-objects\
|
||||||
-fuse-linker-plugin\
|
-fuse-linker-plugin\
|
||||||
-Wall
|
-Wall
|
||||||
|
@ -45,7 +44,8 @@ CXXFLAGS?=-Datmega328p\
|
||||||
-fuse-linker-plugin\
|
-fuse-linker-plugin\
|
||||||
-Wall
|
-Wall
|
||||||
|
|
||||||
INC_DIRS?=-I./$(ARDUINO_DIR)/libraries/SPI/src\
|
INC_DIRS?=-I./\
|
||||||
|
-I./$(ARDUINO_DIR)/libraries/SPI/src\
|
||||||
-I./$(ARDUINO_DIR)/cores/arduino\
|
-I./$(ARDUINO_DIR)/cores/arduino\
|
||||||
-I./$(ARDUINO_DIR)/variants/eightanaloginputs\
|
-I./$(ARDUINO_DIR)/variants/eightanaloginputs\
|
||||||
-I./libraries/TinyGPSPlus/src\
|
-I./libraries/TinyGPSPlus/src\
|
||||||
|
@ -56,7 +56,8 @@ INC_DIRS?=-I./$(ARDUINO_DIR)/libraries/SPI/src\
|
||||||
-I./libraries/arduino-lmic/src/\
|
-I./libraries/arduino-lmic/src/\
|
||||||
-I./libraries/arduino-lmic/src/hal/\
|
-I./libraries/arduino-lmic/src/hal/\
|
||||||
-I./libraries/arduino-lmic/src/lmic/\
|
-I./libraries/arduino-lmic/src/lmic/\
|
||||||
-I./libraries/arduino-lmic/src/aes/
|
-I./libraries/arduino-lmic/src/aes/\
|
||||||
|
-I./libraries/AltSoftSerial/
|
||||||
|
|
||||||
SRC_FILES?=./$(ARDUINO_DIR)/cores/arduino/main.cpp\
|
SRC_FILES?=./$(ARDUINO_DIR)/cores/arduino/main.cpp\
|
||||||
./$(ARDUINO_DIR)/cores/arduino/wiring_digital.c\
|
./$(ARDUINO_DIR)/cores/arduino/wiring_digital.c\
|
||||||
|
@ -98,7 +99,8 @@ SRC_FILES?=./$(ARDUINO_DIR)/cores/arduino/main.cpp\
|
||||||
./libraries/arduino-lmic/src/lmic/radio.c\
|
./libraries/arduino-lmic/src/lmic/radio.c\
|
||||||
./libraries/arduino-lmic/src/lmic/lmic_in866.c\
|
./libraries/arduino-lmic/src/lmic/lmic_in866.c\
|
||||||
./libraries/arduino-lmic/src/aes/lmic.c\
|
./libraries/arduino-lmic/src/aes/lmic.c\
|
||||||
./libraries/arduino-lmic/src/aes/other.c
|
./libraries/arduino-lmic/src/aes/other.c\
|
||||||
|
./libraries/AltSoftSerial/AltSoftSerial.cpp
|
||||||
|
|
||||||
|
|
||||||
SRC_FILES_COMMON?=\
|
SRC_FILES_COMMON?=\
|
||||||
|
@ -125,7 +127,7 @@ $(OUT)$(NAME): $(OUT)$(NAME).elf
|
||||||
$(OUT)eep.hex: $(OUT)$(NAME).elf
|
$(OUT)eep.hex: $(OUT)$(NAME).elf
|
||||||
$(OBJCOPY) -j .eeprom --change-section-lma .eeprom=0 -O ihex $(OUT)$(NAME).elf $(OUT)eep.hex
|
$(OBJCOPY) -j .eeprom --change-section-lma .eeprom=0 -O ihex $(OUT)$(NAME).elf $(OUT)eep.hex
|
||||||
$(OUT)$(NAME).elf: protobufg bin $(OBJDIRS) $(OBJS)
|
$(OUT)$(NAME).elf: protobufg bin $(OBJDIRS) $(OBJS)
|
||||||
$(CC) $(CFLAGS) -o $(OUT)$(NAME).elf collar.cpp $(INC_DIRS) $(OBJS)
|
$(CC) $(CXXFLAGS) -o $(OUT)$(NAME).elf collar.cpp $(INC_DIRS) $(OBJS)
|
||||||
|
|
||||||
test:
|
test:
|
||||||
g++ -o $(OUT)test test.c $(INC_DIRS) $(SRC_FILES_COMMON)
|
g++ -o $(OUT)test test.c $(INC_DIRS) $(SRC_FILES_COMMON)
|
||||||
|
|
388
collar.cpp
388
collar.cpp
|
@ -21,39 +21,15 @@
|
||||||
*******************************************************************************/
|
*******************************************************************************/
|
||||||
#include <lmic.h>
|
#include <lmic.h>
|
||||||
#include <hal/hal.h>
|
#include <hal/hal.h>
|
||||||
#include <SPI.h>
|
|
||||||
#include <TinyGPS++.h>
|
#include <TinyGPS++.h>
|
||||||
#include <SoftwareSerial.h>
|
|
||||||
|
|
||||||
#include "Base64.h"
|
#include <AltSoftSerial.h>
|
||||||
#include "gateway/message.pb.h"
|
|
||||||
|
|
||||||
#include "pb_common.h"
|
|
||||||
#include "pb.h"
|
|
||||||
#include "pb_encode.h"
|
|
||||||
#include "pb_decode.h"
|
|
||||||
|
|
||||||
#include "gateway/message.pb.h"
|
|
||||||
|
|
||||||
// DHT digital pin and sensor type
|
// DHT digital pin and sensor type
|
||||||
#define DHTPIN 60
|
#define DHTPIN 60
|
||||||
#define DHTTYPE DHT22
|
#define DHTTYPE DHT22
|
||||||
|
|
||||||
//
|
|
||||||
// For normal use, we require that you edit the sketch to replace FILLMEIN
|
|
||||||
// with values assigned by the TTN console. However, for regression tests,
|
|
||||||
// we want to be able to compile these scripts. The regression tests define
|
|
||||||
// COMPILE_REGRESSION_TEST, and in that case we define FILLMEIN to a non-
|
|
||||||
// working but innocuous value.
|
|
||||||
//
|
|
||||||
/*
|
|
||||||
#ifdef COMPILE_REGRESSION_TEST
|
|
||||||
# define FILLMEIN 0
|
|
||||||
#else
|
|
||||||
# warning "You must replace the values marked FILLMEIN with real values from the TTN control panel!"
|
|
||||||
# define FILLMEIN (#dont edit this, edit the lines that use FILLMEIN)
|
|
||||||
#endif
|
|
||||||
*/
|
|
||||||
// LoRaWAN NwkSKey, network session key
|
// LoRaWAN NwkSKey, network session key
|
||||||
static const PROGMEM u1_t NWKSKEY[16] = { 0x52, 0x92, 0xC0, 0x72, 0x2D, 0x3C, 0x55, 0x5E, 0xE4, 0xB9, 0x9E, 0x9B, 0x88, 0x66, 0x47, 0xF1 };
|
static const PROGMEM u1_t NWKSKEY[16] = { 0x52, 0x92, 0xC0, 0x72, 0x2D, 0x3C, 0x55, 0x5E, 0xE4, 0xB9, 0x9E, 0x9B, 0x88, 0x66, 0x47, 0xF1 };
|
||||||
|
|
||||||
|
@ -77,16 +53,13 @@ void os_getArtEui (u1_t* buf) { }
|
||||||
void os_getDevEui (u1_t* buf) { }
|
void os_getDevEui (u1_t* buf) { }
|
||||||
void os_getDevKey (u1_t* buf) { }
|
void os_getDevKey (u1_t* buf) { }
|
||||||
|
|
||||||
// payload to send to TTN gateway
|
|
||||||
//static uint8_t payload[] = "Hello, world!";
|
|
||||||
|
|
||||||
// Data Packet to Send to TTN
|
// Data Packet to Send to TTN
|
||||||
u1_t loraData[Fenceless_CollarResponse_size+1] = {0};
|
|
||||||
static osjob_t sendjob;
|
static osjob_t sendjob;
|
||||||
|
|
||||||
// Schedule TX every this many seconds (might become longer due to duty
|
// Schedule TX every this many seconds (might become longer due to duty
|
||||||
// cycle limitations).
|
// cycle limitations).
|
||||||
const unsigned TX_INTERVAL = 10;
|
const unsigned TX_INTERVAL = 10;
|
||||||
|
const unsigned GPS_INTERVAL = 1;
|
||||||
|
|
||||||
// Pin mapping for Adafruit Feather M0 LoRa
|
// Pin mapping for Adafruit Feather M0 LoRa
|
||||||
const lmic_pinmap lmic_pins = {
|
const lmic_pinmap lmic_pins = {
|
||||||
|
@ -103,10 +76,8 @@ const lmic_pinmap lmic_pins = {
|
||||||
* Arduino drivers
|
* Arduino drivers
|
||||||
* - LoRaWAN
|
* - LoRaWAN
|
||||||
* - GPS
|
* - GPS
|
||||||
* - Software Serial
|
|
||||||
***************************************************/
|
***************************************************/
|
||||||
TinyGPSPlus gps;
|
TinyGPSPlus gps;
|
||||||
// SoftwareSerial ss(6, 7);
|
|
||||||
|
|
||||||
/****************************************************
|
/****************************************************
|
||||||
* Track each pair of X and Y coordinates
|
* Track each pair of X and Y coordinates
|
||||||
|
@ -121,7 +92,7 @@ int n_poly=0;
|
||||||
* Add a coordinate to the arrays
|
* Add a coordinate to the arrays
|
||||||
* - stores a total of N_POLY_MAX pairs
|
* - stores a total of N_POLY_MAX pairs
|
||||||
***************************************************/
|
***************************************************/
|
||||||
int push_vert(float x, float y) {
|
const int push_vert(const float x, const float y) {
|
||||||
if(n_poly>N_POLY_MAX)
|
if(n_poly>N_POLY_MAX)
|
||||||
return 0;
|
return 0;
|
||||||
polyx[n_poly]=x;
|
polyx[n_poly]=x;
|
||||||
|
@ -129,6 +100,7 @@ int push_vert(float x, float y) {
|
||||||
n_poly++;
|
n_poly++;
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
/****************************************************
|
/****************************************************
|
||||||
* 'Clear' pairs of coordinates
|
* 'Clear' pairs of coordinates
|
||||||
***************************************************/
|
***************************************************/
|
||||||
|
@ -141,8 +113,8 @@ void clear_verts() {
|
||||||
* of vertices
|
* of vertices
|
||||||
* - https://wrf.ecse.rpi.edu//Research/Short_Notes/pnpoly.html
|
* - https://wrf.ecse.rpi.edu//Research/Short_Notes/pnpoly.html
|
||||||
***************************************************/
|
***************************************************/
|
||||||
int pnpoly(int nvert, float *vertx, float *verty, float testx, float testy)
|
const int pnpoly(int nvert, const float *vertx, const float *verty, const float testx, const float testy)
|
||||||
{
|
{
|
||||||
int i, j, c = 0;
|
int i, j, c = 0;
|
||||||
for (i = 0, j = nvert-1; i < nvert; j = i++) {
|
for (i = 0, j = nvert-1; i < nvert; j = i++) {
|
||||||
if ( ((verty[i]>testy) != (verty[j]>testy)) &&
|
if ( ((verty[i]>testy) != (verty[j]>testy)) &&
|
||||||
|
@ -151,221 +123,67 @@ int pnpoly(int nvert, float *vertx, float *verty, float testx, float testy)
|
||||||
}
|
}
|
||||||
return c;
|
return c;
|
||||||
}
|
}
|
||||||
|
|
||||||
/****************************************************
|
/****************************************************
|
||||||
* Test a coordinate against all vertices
|
* Test a coordinate against all vertices
|
||||||
* - takes current GPS coordinates
|
* - takes current GPS coordinates
|
||||||
* - return 1 if in bounds
|
* - return 1 if in bounds
|
||||||
***************************************************/
|
***************************************************/
|
||||||
int check_bounds(float x, float y) {
|
const int check_bounds(const float x, const float y) {
|
||||||
return pnpoly(n_poly, polyx, polyy, x, y);
|
return pnpoly(n_poly, polyx, polyy, x, y);
|
||||||
}
|
}
|
||||||
|
|
||||||
/****************************************************
|
/****************************************************
|
||||||
* Load coordinates from protobuff stream
|
* Load coordinates from protobuff stream
|
||||||
* - currently a maximum of 10 coordinates
|
* - currently a maximum of 10 coordinates
|
||||||
* - loading arrays in nanopb does not appear
|
* - loading arrays in nanopb does not appear
|
||||||
* to work.
|
* to work.
|
||||||
***************************************************/
|
***************************************************/
|
||||||
void import_protobuf(uint8_t *protobuffer, uint32_t size) {
|
void import_protobuf(const uint8_t *protobuffer, const uint32_t size) {
|
||||||
|
|
||||||
#define TYPE_STRING 0x0A
|
|
||||||
#define TYPE_VARIANT 0x10
|
|
||||||
#define PROTO_LEN 0x0A
|
|
||||||
#define FIELD_ONE_FLOAT 0x0D
|
|
||||||
#define FIELD_TWO_FLOAT 0x15
|
|
||||||
#define FIELD_TWO_VARIANT 0x10
|
|
||||||
#define FIELD_ONE_VARIANT 0x08
|
|
||||||
#define FIELD_TWO_STRING 0x12
|
|
||||||
#define FIELD_THREE_STRING 0x1A
|
|
||||||
#define FIELD_FOUR_STRING 0x22
|
|
||||||
#define FIELD_FIVE_STRING 0x2A
|
|
||||||
#define FIELD_SIX_STRING 0x32
|
|
||||||
#define FIELD_SEVEN_STRING 0x3A
|
|
||||||
#define FIELD_EIGHT_STRING 0x42
|
|
||||||
#define FIELD_NINE_STRING 0x4A
|
|
||||||
#define FIELD_TEN_STRING 0x52
|
|
||||||
#define FIELD_ELEVEN_STRING 0x5A
|
|
||||||
|
|
||||||
/*uint8_t buffer0[] {
|
|
||||||
FIELD_ONE_VARIANT, 0x01,
|
|
||||||
FIELD_TWO_STRING, 0x0A,
|
|
||||||
FIELD_ONE_FLOAT, 0x1B, 0x91, 0xF6, 0xC2,
|
|
||||||
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
|
||||||
FIELD_THREE_STRING, 0x0A,
|
|
||||||
FIELD_ONE_FLOAT, 0xB5, 0x3B, 0x32, 0x42,
|
|
||||||
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
|
||||||
FIELD_FOUR_STRING, 0x0A,
|
|
||||||
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
|
||||||
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
|
||||||
FIELD_FIVE_STRING, 0x0A,
|
|
||||||
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
|
||||||
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
|
||||||
FIELD_SIX_STRING, 0x0A,
|
|
||||||
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
|
||||||
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
|
||||||
FIELD_SEVEN_STRING, 0x0A,
|
|
||||||
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
|
||||||
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
|
||||||
FIELD_EIGHT_STRING, 0x0A,
|
|
||||||
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
|
||||||
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
|
||||||
FIELD_NINE_STRING, 0x0A,
|
|
||||||
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
|
||||||
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
|
||||||
FIELD_TEN_STRING, 0x0A,
|
|
||||||
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
|
||||||
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
|
||||||
FIELD_ELEVEN_STRING, 0x0A,
|
|
||||||
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
|
||||||
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40
|
|
||||||
};*/
|
|
||||||
|
|
||||||
Serial.println("DECODE FUNCTION");
|
|
||||||
if(size != 122) {
|
if(size != 122) {
|
||||||
Serial.println("Failed to decode");
|
Serial.println("Failed to decode");
|
||||||
Serial.print("Size:");
|
|
||||||
Serial.println(size);
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
/*
|
|
||||||
* this stuff does not work yet
|
Serial.println("Recieved valid protobuf data?");
|
||||||
*/
|
|
||||||
|
|
||||||
uint32_t isr;
|
uint32_t isr;
|
||||||
isr = 0;
|
isr = 0;
|
||||||
isr = protobuffer[1];
|
isr = protobuffer[1];
|
||||||
|
|
||||||
Serial.print("Isr: ");
|
|
||||||
Serial.println(isr);
|
|
||||||
|
|
||||||
if(isr>N_POLY_MAX) isr = N_POLY_MAX;
|
if(isr>N_POLY_MAX) isr = N_POLY_MAX;
|
||||||
|
|
||||||
Serial.println("Recieved valid protobuf data?");
|
|
||||||
|
|
||||||
clear_verts();
|
clear_verts();
|
||||||
|
|
||||||
uint8_t *ptr = protobuffer+5;
|
const uint8_t *ptr = protobuffer + 5;
|
||||||
for(uint32_t i=0;i<isr;i++) {
|
for(uint32_t i=0;i<isr;i++) {
|
||||||
if(i%5==0)
|
|
||||||
Serial.println();
|
|
||||||
|
|
||||||
float x,y;
|
float x,y;
|
||||||
memcpy(&x, ptr + i*12, 4);
|
memcpy(&x, ptr + i*12, 4);
|
||||||
memcpy(&y, ptr + i*12+5, 4);
|
memcpy(&y, ptr + i*12+5, 4);
|
||||||
|
|
||||||
Serial.print('(');
|
|
||||||
Serial.print(x);
|
|
||||||
Serial.print(',');
|
|
||||||
Serial.print(y);
|
|
||||||
Serial.print(')');
|
|
||||||
Serial.print(' ');
|
|
||||||
|
|
||||||
push_vert(x, y);
|
push_vert(x, y);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void do_send(osjob_t* j);
|
uint8_t is_sending = 0;
|
||||||
void onEvent (ev_t ev) {
|
void onEvent (ev_t ev) {
|
||||||
Serial.print(os_getTime());
|
// Serial.print(os_getTime());
|
||||||
Serial.print(": ");
|
// Serial.print(": ");
|
||||||
switch(ev) {
|
|
||||||
case EV_SCAN_TIMEOUT:
|
|
||||||
Serial.println(F("EV_SCAN_TIMEOUT"));
|
|
||||||
break;
|
|
||||||
case EV_BEACON_FOUND:
|
|
||||||
Serial.println(F("EV_BEACON_FOUND"));
|
|
||||||
break;
|
|
||||||
case EV_BEACON_MISSED:
|
|
||||||
Serial.println(F("EV_BEACON_MISSED"));
|
|
||||||
break;
|
|
||||||
case EV_BEACON_TRACKED:
|
|
||||||
Serial.println(F("EV_BEACON_TRACKED"));
|
|
||||||
break;
|
|
||||||
case EV_JOINING:
|
|
||||||
Serial.println(F("EV_JOINING"));
|
|
||||||
break;
|
|
||||||
case EV_JOINED:
|
|
||||||
Serial.println(F("EV_JOINED"));
|
|
||||||
break;
|
|
||||||
/*
|
|
||||||
|| This event is defined but not used in the code. No
|
|
||||||
|| point in wasting codespace on it.
|
|
||||||
||
|
|
||||||
|| case EV_RFU1:
|
|
||||||
|| Serial.println(F("EV_RFU1"));
|
|
||||||
|| break;
|
|
||||||
*/
|
|
||||||
case EV_JOIN_FAILED:
|
|
||||||
Serial.println(F("EV_JOIN_FAILED"));
|
|
||||||
break;
|
|
||||||
case EV_REJOIN_FAILED:
|
|
||||||
Serial.println(F("EV_REJOIN_FAILED"));
|
|
||||||
break;
|
|
||||||
case EV_TXCOMPLETE:
|
|
||||||
Serial.println(F("EV_TXCOMPLETE (includes waiting for RX windows)"));
|
|
||||||
|
|
||||||
if (LMIC.txrxFlags & TXRX_ACK)
|
if(ev == EV_TXCOMPLETE) {
|
||||||
Serial.println(F("Received ack"));
|
Serial.println("EV_TXCOMPLETE (includes waiting for RX windows)");
|
||||||
if (LMIC.dataLen) {
|
|
||||||
Serial.println(F("Received "));
|
|
||||||
Serial.println(LMIC.dataLen);
|
|
||||||
|
|
||||||
// Serial.println(F(" bytes of payload"));
|
if (LMIC.dataLen) {
|
||||||
|
Serial.println(F("Received "));
|
||||||
// for(int i=0;i<LMIC.dataLen;i++) {
|
import_protobuf(LMIC.frame + LMIC.dataBeg, LMIC.dataLen);
|
||||||
// Serial.print(LMIC.frame[LMIC.dataBeg + i], HEX);
|
}
|
||||||
// Serial.print(' ');
|
is_sending = 0;
|
||||||
// Serial.print('-');
|
}
|
||||||
// Serial.print(' ');
|
else if(ev == EV_TXSTART) {
|
||||||
// if(i%10==0)
|
Serial.println(F("EV_TXSTART"));
|
||||||
// Serial.println();
|
}
|
||||||
// }
|
else {
|
||||||
// Serial.println();
|
Serial.print(F("Unknown event: "));
|
||||||
|
|
||||||
import_protobuf(LMIC.frame + LMIC.dataBeg, LMIC.dataLen);
|
|
||||||
}
|
|
||||||
|
|
||||||
os_setTimedCallback(&sendjob, os_getTime()+sec2osticks(TX_INTERVAL), do_send);
|
|
||||||
break;
|
|
||||||
case EV_LOST_TSYNC:
|
|
||||||
Serial.println(F("EV_LOST_TSYNC"));
|
|
||||||
break;
|
|
||||||
case EV_RESET:
|
|
||||||
Serial.println(F("EV_RESET"));
|
|
||||||
break;
|
|
||||||
case EV_RXCOMPLETE:
|
|
||||||
// data received in ping slot
|
|
||||||
Serial.println(F("EV_RXCOMPLETE"));
|
|
||||||
break;
|
|
||||||
case EV_LINK_DEAD:
|
|
||||||
Serial.println(F("EV_LINK_DEAD"));
|
|
||||||
break;
|
|
||||||
case EV_LINK_ALIVE:
|
|
||||||
Serial.println(F("EV_LINK_ALIVE"));
|
|
||||||
break;
|
|
||||||
/*
|
|
||||||
|| This event is defined but not used in the code. No
|
|
||||||
|| point in wasting codespace on it.
|
|
||||||
||
|
|
||||||
|| case EV_SCAN_FOUND:
|
|
||||||
|| Serial.println(F("EV_SCAN_FOUND"));
|
|
||||||
|| break;
|
|
||||||
*/
|
|
||||||
case EV_TXSTART:
|
|
||||||
Serial.println(F("EV_TXSTART"));
|
|
||||||
break;
|
|
||||||
case EV_TXCANCELED:
|
|
||||||
Serial.println(F("EV_TXCANCELED"));
|
|
||||||
break;
|
|
||||||
case EV_RXSTART:
|
|
||||||
/* do not print anything -- it wrecks timing */
|
|
||||||
break;
|
|
||||||
case EV_JOIN_TXCOMPLETE:
|
|
||||||
Serial.println(F("EV_JOIN_TXCOMPLETE: no JoinAccept"));
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
Serial.print(F("Unknown event: "));
|
|
||||||
Serial.println((unsigned) ev);
|
|
||||||
break;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -376,16 +194,16 @@ void onEvent (ev_t ev) {
|
||||||
#define FIELD_TWO_FLOAT 0x15
|
#define FIELD_TWO_FLOAT 0x15
|
||||||
#define FIELD_TWO_VARIANT 0x10
|
#define FIELD_TWO_VARIANT 0x10
|
||||||
|
|
||||||
|
|
||||||
uint8_t buffer[] = {
|
uint8_t buffer[] = {
|
||||||
TYPE_STRING,
|
TYPE_STRING,
|
||||||
PROTO_LEN,
|
PROTO_LEN,
|
||||||
FIELD_ONE_FLOAT, 0x00, 0x00, 0x48, 0x43,
|
FIELD_ONE_FLOAT, 0x00, 0x00, 0x48, 0x43,
|
||||||
FIELD_TWO_FLOAT, 0x00, 0x00, 0xc8, 0x42,
|
FIELD_TWO_FLOAT, 0x00, 0x00, 0xc8, 0x42,
|
||||||
FIELD_TWO_VARIANT, 0};
|
FIELD_TWO_VARIANT, 0};
|
||||||
|
|
||||||
void do_send(osjob_t* j){
|
void do_send(osjob_t* j){
|
||||||
// Check if there is not a current TX/RX job running
|
// Check if there is not a current TX/RX job running
|
||||||
|
is_sending = 1;
|
||||||
if (LMIC.opmode & OP_TXRXPEND) {
|
if (LMIC.opmode & OP_TXRXPEND) {
|
||||||
Serial.println(F("OP_TXRXPEND, not sending"));
|
Serial.println(F("OP_TXRXPEND, not sending"));
|
||||||
} else {
|
} else {
|
||||||
|
@ -393,9 +211,9 @@ void do_send(osjob_t* j){
|
||||||
// transmit on port 1 (the first parameter); you can use any value from 1 to 223 (others are reserved).
|
// transmit on port 1 (the first parameter); you can use any value from 1 to 223 (others are reserved).
|
||||||
// don't request an ack (the last parameter, if not zero, requests an ack from the network).
|
// don't request an ack (the last parameter, if not zero, requests an ack from the network).
|
||||||
// Remember, acks consume a lot of network resources; don't ask for an ack unless you really need it.
|
// Remember, acks consume a lot of network resources; don't ask for an ack unless you really need it.
|
||||||
float latitude = gps.location.lat();
|
const float latitude = gps.location.lat();
|
||||||
float longitude = gps.location.lng();
|
const float longitude = gps.location.lng();
|
||||||
int oob = check_bounds(latitude, longitude);
|
const int oob = check_bounds(latitude, longitude);
|
||||||
|
|
||||||
memcpy(buffer+3, (void*)&latitude, 4);
|
memcpy(buffer+3, (void*)&latitude, 4);
|
||||||
memcpy(buffer+8, (void*)&longitude, 4);
|
memcpy(buffer+8, (void*)&longitude, 4);
|
||||||
|
@ -403,19 +221,25 @@ void do_send(osjob_t* j){
|
||||||
|
|
||||||
LMIC_setTxData2(1, buffer, sizeof(buffer), 0);
|
LMIC_setTxData2(1, buffer, sizeof(buffer), 0);
|
||||||
}
|
}
|
||||||
// Next TX is scheduled after TX_COMPLETE event.
|
}
|
||||||
|
|
||||||
|
void do_gps(osjob_t* j){
|
||||||
|
while(softserial_available()>0) {
|
||||||
|
gps.encode(softserial_read());
|
||||||
|
}
|
||||||
|
if(!is_sending && gps.location.isValid()) {
|
||||||
|
do_send(&sendjob);
|
||||||
|
}
|
||||||
|
os_setTimedCallback(&sendjob, os_getTime()+sec2osticks(GPS_INTERVAL), do_gps);
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
delay(1000);
|
|
||||||
Serial.begin(4800);
|
Serial.begin(4800);
|
||||||
// ss.begin(4800);
|
softserial_init();
|
||||||
|
|
||||||
delay(100);
|
delay(100);
|
||||||
Serial.println(F("Starting"));
|
Serial.println(F("Starting"));
|
||||||
|
|
||||||
pinMode(LED_BUILTIN, OUTPUT);
|
|
||||||
|
|
||||||
// LMIC init
|
// LMIC init
|
||||||
os_init();
|
os_init();
|
||||||
// Reset the MAC state. Session and pending data transfers will be discarded.
|
// Reset the MAC state. Session and pending data transfers will be discarded.
|
||||||
|
@ -430,18 +254,8 @@ void setup() {
|
||||||
uint8_t nwkskey[sizeof(NWKSKEY)];
|
uint8_t nwkskey[sizeof(NWKSKEY)];
|
||||||
memcpy_P(appskey, APPSKEY, sizeof(APPSKEY));
|
memcpy_P(appskey, APPSKEY, sizeof(APPSKEY));
|
||||||
memcpy_P(nwkskey, NWKSKEY, sizeof(NWKSKEY));
|
memcpy_P(nwkskey, NWKSKEY, sizeof(NWKSKEY));
|
||||||
|
|
||||||
LMIC_setSession (0x13, DEVADDR, nwkskey, appskey);
|
LMIC_setSession (0x13, DEVADDR, nwkskey, appskey);
|
||||||
|
|
||||||
/*
|
|
||||||
// We'll disable all 72 channels used by TTN
|
|
||||||
for (int c = 0; c < 72; c++){
|
|
||||||
LMIC_disableChannel(c);
|
|
||||||
}
|
|
||||||
|
|
||||||
// We'll only enable Channel 16 (905.5Mhz) since we're transmitting on a single-channel
|
|
||||||
LMIC_enableChannel(16);
|
|
||||||
*/
|
|
||||||
|
|
||||||
LMIC_selectSubBand(1);
|
LMIC_selectSubBand(1);
|
||||||
|
|
||||||
// Disable link check validation
|
// Disable link check validation
|
||||||
|
@ -453,109 +267,9 @@ void setup() {
|
||||||
// Set data rate and transmit power for uplink
|
// Set data rate and transmit power for uplink
|
||||||
LMIC_setDrTxpow(DR_SF7,14);
|
LMIC_setDrTxpow(DR_SF7,14);
|
||||||
|
|
||||||
delay(2000);
|
os_setTimedCallback(&sendjob, os_getTime()+sec2osticks(GPS_INTERVAL), do_gps);
|
||||||
// Start job
|
|
||||||
// do_send(&sendjob);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/****************************************************
|
|
||||||
* Read a byte from GPS over software serial
|
|
||||||
***************************************************/
|
|
||||||
int read_gps() {
|
|
||||||
int ret = 0;
|
|
||||||
// int timeout = 0;
|
|
||||||
while(Serial.available()>0) {// || timeout < 20) {
|
|
||||||
gps.encode(Serial.read());
|
|
||||||
ret = 1;
|
|
||||||
//timeout++;
|
|
||||||
}
|
|
||||||
return ret;
|
|
||||||
}
|
|
||||||
/****************************************************
|
|
||||||
* Set cursor to beginning of line and clear it
|
|
||||||
***************************************************/
|
|
||||||
const int16_t PROGRESS_BAR_COUNT = 50;
|
|
||||||
const int16_t START_OF_LINE = 13;
|
|
||||||
|
|
||||||
int led_on = 0;
|
|
||||||
void clear_line() {
|
|
||||||
Serial.write(START_OF_LINE);
|
|
||||||
for(int i=0;i<PROGRESS_BAR_COUNT;i++)
|
|
||||||
Serial.write(' ');
|
|
||||||
Serial.write(START_OF_LINE);
|
|
||||||
|
|
||||||
digitalWrite(LED_BUILTIN, led_on);
|
|
||||||
led_on = !led_on;
|
|
||||||
}
|
|
||||||
|
|
||||||
/****************************************************
|
|
||||||
* State variables
|
|
||||||
* - track events of main loop
|
|
||||||
***************************************************/
|
|
||||||
enum STATE_ {
|
|
||||||
START_GPS,
|
|
||||||
WAITING_GPS,
|
|
||||||
VERIFYING_GPS,
|
|
||||||
SENDING_LORA,
|
|
||||||
WAITING_LORA,
|
|
||||||
LORA_DONE
|
|
||||||
};
|
|
||||||
int state = START_GPS;
|
|
||||||
int loopCounter = 0;
|
|
||||||
int startTime = 0;
|
|
||||||
uint32_t got_data = 0;
|
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
switch(state) {
|
os_runloop_once();
|
||||||
case START_GPS:
|
|
||||||
Serial.println("Waiting for GPS");
|
|
||||||
state = WAITING_GPS;
|
|
||||||
break;
|
|
||||||
case WAITING_GPS:
|
|
||||||
got_data =
|
|
||||||
read_gps();
|
|
||||||
/****************************************************
|
|
||||||
* loading bar animation
|
|
||||||
***************************************************/
|
|
||||||
if(got_data) {
|
|
||||||
if(loopCounter%100==0)
|
|
||||||
Serial.write('.');
|
|
||||||
if(loopCounter>PROGRESS_BAR_COUNT*100) {
|
|
||||||
clear_line();
|
|
||||||
loopCounter=0;
|
|
||||||
|
|
||||||
state = VERIFYING_GPS;
|
|
||||||
}
|
|
||||||
loopCounter++;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
case VERIFYING_GPS:
|
|
||||||
/****************************************************
|
|
||||||
* if no data has been received from the gps in 5 seconds
|
|
||||||
* then the GPS is probably not connected properly
|
|
||||||
***************************************************/
|
|
||||||
if (millis() > 5000 && gps.charsProcessed() < 10)
|
|
||||||
{
|
|
||||||
Serial.println(F("No GPS detected: check wiring."));
|
|
||||||
while(true);
|
|
||||||
}
|
|
||||||
/****************************************************
|
|
||||||
* only send to LoRaWAN if valid GPS coordinates are
|
|
||||||
* available
|
|
||||||
***************************************************/
|
|
||||||
if(gps.location.isValid())
|
|
||||||
state = SENDING_LORA;
|
|
||||||
else
|
|
||||||
state = WAITING_GPS;
|
|
||||||
break;
|
|
||||||
case SENDING_LORA:
|
|
||||||
do_send(&sendjob);
|
|
||||||
|
|
||||||
digitalWrite(LED_BUILTIN, 0);
|
|
||||||
state = LORA_DONE;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
os_runloop_once();
|
|
||||||
}
|
}
|
||||||
|
|
200
libraries/AltSoftSerial/AltSoftSerial.cpp
Normal file
200
libraries/AltSoftSerial/AltSoftSerial.cpp
Normal file
|
@ -0,0 +1,200 @@
|
||||||
|
/* An Alternative Software Serial Library
|
||||||
|
* http://www.pjrc.com/teensy/td_libs_AltSoftSerial.html
|
||||||
|
* Copyright (c) 2014 PJRC.COM, LLC, Paul Stoffregen, paul@pjrc.com
|
||||||
|
*
|
||||||
|
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
* of this software and associated documentation files (the "Software"), to deal
|
||||||
|
* in the Software without restriction, including without limitation the rights
|
||||||
|
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
* copies of the Software, and to permit persons to whom the Software is
|
||||||
|
* furnished to do so, subject to the following conditions:
|
||||||
|
*
|
||||||
|
* The above copyright notice and this permission notice shall be included in
|
||||||
|
* all copies or substantial portions of the Software.
|
||||||
|
*
|
||||||
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||||
|
* THE SOFTWARE.
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Revisions are now tracked on GitHub
|
||||||
|
// https://github.com/PaulStoffregen/AltSoftSerial
|
||||||
|
//
|
||||||
|
// Version 1.2: Support Teensy 3.x
|
||||||
|
//
|
||||||
|
// Version 1.1: Improve performance in receiver code
|
||||||
|
//
|
||||||
|
// Version 1.0: Initial Release
|
||||||
|
|
||||||
|
|
||||||
|
#include "AltSoftSerial.h"
|
||||||
|
#include "config/AltSoftSerial_Boards.h"
|
||||||
|
#include "config/AltSoftSerial_Timers.h"
|
||||||
|
|
||||||
|
/****************************************/
|
||||||
|
/** Initialization **/
|
||||||
|
/****************************************/
|
||||||
|
|
||||||
|
bool timing_error=false;
|
||||||
|
|
||||||
|
static uint8_t rx_state;
|
||||||
|
static uint8_t rx_byte;
|
||||||
|
static uint8_t rx_bit = 0;
|
||||||
|
static uint16_t rx_target;
|
||||||
|
static volatile uint8_t rx_buffer_head;
|
||||||
|
static volatile uint8_t rx_buffer_tail;
|
||||||
|
#define RX_BUFFER_SIZE 80
|
||||||
|
static volatile uint8_t rx_buffer[RX_BUFFER_SIZE];
|
||||||
|
|
||||||
|
const uint32_t cycles_per_bit = (ALTSS_BASE_FREQ + 4800 / 2) / 4800;
|
||||||
|
const uint16_t rx_stop_ticks= cycles_per_bit * 37 / 4;
|
||||||
|
|
||||||
|
#ifndef INPUT_PULLUP
|
||||||
|
#define INPUT_PULLUP INPUT
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define MAX_COUNTS_PER_BIT 6241 // 65536 / 10.5
|
||||||
|
|
||||||
|
void softserial_init()
|
||||||
|
{
|
||||||
|
// rx_stop_ticks = cycles_per_bit * 37 / 4;
|
||||||
|
pinMode(INPUT_CAPTURE_PIN, INPUT_PULLUP);
|
||||||
|
digitalWrite(OUTPUT_COMPARE_A_PIN, HIGH);
|
||||||
|
pinMode(OUTPUT_COMPARE_A_PIN, OUTPUT);
|
||||||
|
rx_state = 0;
|
||||||
|
rx_buffer_head = 0;
|
||||||
|
rx_buffer_tail = 0;
|
||||||
|
ENABLE_INT_INPUT_CAPTURE();
|
||||||
|
}
|
||||||
|
|
||||||
|
void softserial_end(void)
|
||||||
|
{
|
||||||
|
DISABLE_INT_COMPARE_B();
|
||||||
|
DISABLE_INT_INPUT_CAPTURE();
|
||||||
|
softserial_flush();
|
||||||
|
DISABLE_INT_COMPARE_A();
|
||||||
|
// TODO: restore timer to original settings?
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t state, bit, head, tail, out;
|
||||||
|
ISR(COMPARE_A_INTERRUPT)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
/****************************************/
|
||||||
|
/** Reception **/
|
||||||
|
/****************************************/
|
||||||
|
ISR(CAPTURE_INTERRUPT)
|
||||||
|
{
|
||||||
|
uint16_t capture, target;
|
||||||
|
uint16_t offset, offset_overflow;
|
||||||
|
|
||||||
|
capture = GET_INPUT_CAPTURE();
|
||||||
|
bit = rx_bit;
|
||||||
|
if (bit) {
|
||||||
|
CONFIG_CAPTURE_FALLING_EDGE();
|
||||||
|
rx_bit = 0;
|
||||||
|
} else {
|
||||||
|
CONFIG_CAPTURE_RISING_EDGE();
|
||||||
|
rx_bit = 0x80;
|
||||||
|
}
|
||||||
|
state = rx_state;
|
||||||
|
if (state == 0) {
|
||||||
|
if (!bit) {
|
||||||
|
uint16_t end = capture + rx_stop_ticks;
|
||||||
|
SET_COMPARE_B(end);
|
||||||
|
ENABLE_INT_COMPARE_B();
|
||||||
|
rx_target = capture + cycles_per_bit + cycles_per_bit/2;
|
||||||
|
rx_state = 1;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
target = rx_target;
|
||||||
|
offset_overflow = 65535 - cycles_per_bit;
|
||||||
|
while (1) {
|
||||||
|
offset = capture - target;
|
||||||
|
if (offset > offset_overflow) break;
|
||||||
|
rx_byte = (rx_byte >> 1) | rx_bit;
|
||||||
|
target += cycles_per_bit;
|
||||||
|
state++;
|
||||||
|
if (state >= 9) {
|
||||||
|
DISABLE_INT_COMPARE_B();
|
||||||
|
head = rx_buffer_head + 1;
|
||||||
|
if (head >= RX_BUFFER_SIZE) head = 0;
|
||||||
|
if (head != rx_buffer_tail) {
|
||||||
|
rx_buffer[head] = rx_byte;
|
||||||
|
rx_buffer_head = head;
|
||||||
|
}
|
||||||
|
CONFIG_CAPTURE_FALLING_EDGE();
|
||||||
|
rx_bit = 0;
|
||||||
|
rx_state = 0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
rx_target = target;
|
||||||
|
rx_state = state;
|
||||||
|
}
|
||||||
|
//if (GET_TIMER_COUNT() - capture > cycles_per_bit) AltSoftSerial::timing_error = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
ISR(COMPARE_B_INTERRUPT)
|
||||||
|
{
|
||||||
|
DISABLE_INT_COMPARE_B();
|
||||||
|
CONFIG_CAPTURE_FALLING_EDGE();
|
||||||
|
state = rx_state;
|
||||||
|
bit = rx_bit ^ 0x80;
|
||||||
|
while (state < 9) {
|
||||||
|
rx_byte = (rx_byte >> 1) | bit;
|
||||||
|
state++;
|
||||||
|
}
|
||||||
|
head = rx_buffer_head + 1;
|
||||||
|
if (head >= RX_BUFFER_SIZE) head = 0;
|
||||||
|
if (head != rx_buffer_tail) {
|
||||||
|
rx_buffer[head] = rx_byte;
|
||||||
|
rx_buffer_head = head;
|
||||||
|
}
|
||||||
|
rx_state = 0;
|
||||||
|
CONFIG_CAPTURE_FALLING_EDGE();
|
||||||
|
rx_bit = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
const int softserial_read()
|
||||||
|
{
|
||||||
|
|
||||||
|
head = rx_buffer_head;
|
||||||
|
tail = rx_buffer_tail;
|
||||||
|
if (head == tail) return -1;
|
||||||
|
if (++tail >= RX_BUFFER_SIZE) tail = 0;
|
||||||
|
out = rx_buffer[tail];
|
||||||
|
rx_buffer_tail = tail;
|
||||||
|
return out;
|
||||||
|
}
|
||||||
|
|
||||||
|
const int softserial_available()
|
||||||
|
{
|
||||||
|
head = rx_buffer_head;
|
||||||
|
tail = rx_buffer_tail;
|
||||||
|
if (head >= tail) return head - tail;
|
||||||
|
return RX_BUFFER_SIZE + head - tail;
|
||||||
|
}
|
||||||
|
|
||||||
|
void softserial_flush()
|
||||||
|
{
|
||||||
|
rx_buffer_head = rx_buffer_tail;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef ALTSS_USE_FTM0
|
||||||
|
void ftm0_isr(void)
|
||||||
|
{
|
||||||
|
uint32_t flags = FTM0_STATUS;
|
||||||
|
FTM0_STATUS = 0;
|
||||||
|
if (flags & (1<<0) && (FTM0_C0SC & 0x40)) altss_compare_b_interrupt();
|
||||||
|
if (flags & (1<<5)) altss_capture_interrupt();
|
||||||
|
if (flags & (1<<6) && (FTM0_C6SC & 0x40)) altss_compare_a_interrupt();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
42
libraries/AltSoftSerial/AltSoftSerial.h
Normal file
42
libraries/AltSoftSerial/AltSoftSerial.h
Normal file
|
@ -0,0 +1,42 @@
|
||||||
|
/* An Alternative Software Serial Library
|
||||||
|
* http://www.pjrc.com/teensy/td_libs_AltSoftSerial.html
|
||||||
|
* Copyright (c) 2014 PJRC.COM, LLC, Paul Stoffregen, paul@pjrc.com
|
||||||
|
*
|
||||||
|
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
* of this software and associated documentation files (the "Software"), to deal
|
||||||
|
* in the Software without restriction, including without limitation the rights
|
||||||
|
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
* copies of the Software, and to permit persons to whom the Software is
|
||||||
|
* furnished to do so, subject to the following conditions:
|
||||||
|
*
|
||||||
|
* The above copyright notice and this permission notice shall be included in
|
||||||
|
* all copies or substantial portions of the Software.
|
||||||
|
*
|
||||||
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||||
|
* THE SOFTWARE.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef AltSoftSerial_h
|
||||||
|
#define AltSoftSerial_h
|
||||||
|
|
||||||
|
#include <inttypes.h>
|
||||||
|
|
||||||
|
#include "Arduino.h"
|
||||||
|
|
||||||
|
#if defined(__arm__) && defined(CORE_TEENSY)
|
||||||
|
#define ALTSS_BASE_FREQ F_BUS
|
||||||
|
#else
|
||||||
|
#define ALTSS_BASE_FREQ F_CPU
|
||||||
|
#endif
|
||||||
|
|
||||||
|
const int softserial_available();
|
||||||
|
const int softserial_read();
|
||||||
|
void softserial_flush();
|
||||||
|
void softserial_init();
|
||||||
|
|
||||||
|
#endif
|
11
libraries/AltSoftSerial/README.md
Normal file
11
libraries/AltSoftSerial/README.md
Normal file
|
@ -0,0 +1,11 @@
|
||||||
|
# AltSoftSerial Library
|
||||||
|
|
||||||
|
Improved software emulated serial, using hardware timers for precise signal
|
||||||
|
timing and availability of CPU time for other libraries to respond to interrupts
|
||||||
|
during data AltSoftSerial data transmission and reception.
|
||||||
|
|
||||||
|
http://www.pjrc.com/teensy/td_libs_AltSoftSerial.html
|
||||||
|
|
||||||
|
![AltSoftSerial on Teensy 2.0](http://www.pjrc.com/teensy/td_libs_AltSoftSerial_2.jpg)
|
||||||
|
|
||||||
|
If you need very low baud rates, check out [SlowSoftSerial](https://forum.pjrc.com/threads/58604-SlowSoftSerial-library-for-slow-baud-rates?p=222991#post222991) by Paul Williamson.
|
147
libraries/AltSoftSerial/config/AltSoftSerial_Boards.h
Normal file
147
libraries/AltSoftSerial/config/AltSoftSerial_Boards.h
Normal file
|
@ -0,0 +1,147 @@
|
||||||
|
/* An Alternative Software Serial Library
|
||||||
|
* http://www.pjrc.com/teensy/td_libs_AltSoftSerial.html
|
||||||
|
* Copyright (c) 2014 PJRC.COM, LLC, Paul Stoffregen, paul@pjrc.com
|
||||||
|
*
|
||||||
|
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
* of this software and associated documentation files (the "Software"), to deal
|
||||||
|
* in the Software without restriction, including without limitation the rights
|
||||||
|
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
* copies of the Software, and to permit persons to whom the Software is
|
||||||
|
* furnished to do so, subject to the following conditions:
|
||||||
|
*
|
||||||
|
* The above copyright notice and this permission notice shall be included in
|
||||||
|
* all copies or substantial portions of the Software.
|
||||||
|
*
|
||||||
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||||
|
* THE SOFTWARE.
|
||||||
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
// Teensy 2.0
|
||||||
|
//
|
||||||
|
#if defined(__AVR_ATmega32U4__) && defined(CORE_TEENSY)
|
||||||
|
|
||||||
|
//#define ALTSS_USE_TIMER1
|
||||||
|
//#define INPUT_CAPTURE_PIN 22 // receive
|
||||||
|
//#define OUTPUT_COMPARE_A_PIN 14 // transmit
|
||||||
|
//#define OUTPUT_COMPARE_B_PIN 15 // unusable PWM
|
||||||
|
//#define OUTPUT_COMPARE_C_PIN 4 // unusable PWM
|
||||||
|
|
||||||
|
#define ALTSS_USE_TIMER3
|
||||||
|
#define INPUT_CAPTURE_PIN 10 // receive
|
||||||
|
#define OUTPUT_COMPARE_A_PIN 9 // transmit
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// Teensy++ 2.0
|
||||||
|
//
|
||||||
|
#elif defined(__AVR_AT90USB1286__) && defined(CORE_TEENSY)
|
||||||
|
|
||||||
|
#define ALTSS_USE_TIMER1
|
||||||
|
#define INPUT_CAPTURE_PIN 4 // receive
|
||||||
|
#define OUTPUT_COMPARE_A_PIN 25 // transmit
|
||||||
|
#define OUTPUT_COMPARE_B_PIN 26 // unusable PWM
|
||||||
|
#define OUTPUT_COMPARE_C_PIN 27 // unusable PWM
|
||||||
|
|
||||||
|
//#define ALTSS_USE_TIMER3
|
||||||
|
//#define INPUT_CAPTURE_PIN 17 // receive
|
||||||
|
//#define OUTPUT_COMPARE_A_PIN 16 // transmit
|
||||||
|
//#define OUTPUT_COMPARE_B_PIN 15 // unusable PWM
|
||||||
|
//#define OUTPUT_COMPARE_C_PIN 14 // unusable PWM
|
||||||
|
|
||||||
|
|
||||||
|
// Teensy 3.x
|
||||||
|
//
|
||||||
|
#elif defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MK64FX512__) || defined(__MK66FX1M0__)
|
||||||
|
#define ALTSS_USE_FTM0
|
||||||
|
#define INPUT_CAPTURE_PIN 20 // receive (FTM0_CH5)
|
||||||
|
#define OUTPUT_COMPARE_A_PIN 21 // transmit (FTM0_CH6)
|
||||||
|
#define OUTPUT_COMPARE_B_PIN 22 // unusable PWM (FTM0_CH0)
|
||||||
|
#define OUTPUT_COMPARE_C_PIN 23 // PWM usable fixed freq
|
||||||
|
#define OUTPUT_COMPARE_D_PIN 5 // PWM usable fixed freq
|
||||||
|
#define OUTPUT_COMPARE_E_PIN 6 // PWM usable fixed freq
|
||||||
|
#define OUTPUT_COMPARE_F_PIN 9 // PWM usable fixed freq
|
||||||
|
#define OUTPUT_COMPARE_G_PIN 10 // PWM usable fixed freq
|
||||||
|
|
||||||
|
|
||||||
|
// Wiring-S
|
||||||
|
//
|
||||||
|
#elif defined(__AVR_ATmega644P__) && defined(WIRING)
|
||||||
|
|
||||||
|
#define ALTSS_USE_TIMER1
|
||||||
|
#define INPUT_CAPTURE_PIN 6 // receive
|
||||||
|
#define OUTPUT_COMPARE_A_PIN 5 // transmit
|
||||||
|
#define OUTPUT_COMPARE_B_PIN 4 // unusable PWM
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// Arduino Uno, Duemilanove, LilyPad, etc
|
||||||
|
//
|
||||||
|
#elif defined(__AVR_ATmega168__) || defined(__AVR_ATmega328P__)
|
||||||
|
|
||||||
|
#define ALTSS_USE_TIMER1
|
||||||
|
#define INPUT_CAPTURE_PIN 8 // receive
|
||||||
|
#define OUTPUT_COMPARE_A_PIN 9 // transmit
|
||||||
|
#define OUTPUT_COMPARE_B_PIN 10 // unusable PWM
|
||||||
|
|
||||||
|
|
||||||
|
// Arduino Leonardo & Yun (from Cristian Maglie)
|
||||||
|
//
|
||||||
|
#elif defined(ARDUINO_AVR_YUN) || defined(ARDUINO_AVR_LEONARDO) || defined(__AVR_ATmega32U4__)
|
||||||
|
|
||||||
|
//#define ALTSS_USE_TIMER1
|
||||||
|
//#define INPUT_CAPTURE_PIN 4 // receive
|
||||||
|
//#define OUTPUT_COMPARE_A_PIN 9 // transmit
|
||||||
|
//#define OUTPUT_COMPARE_B_PIN 10 // unusable PWM
|
||||||
|
//#define OUTPUT_COMPARE_C_PIN 11 // unusable PWM
|
||||||
|
|
||||||
|
#define ALTSS_USE_TIMER3
|
||||||
|
#define INPUT_CAPTURE_PIN 13 // receive
|
||||||
|
#define OUTPUT_COMPARE_A_PIN 5 // transmit
|
||||||
|
|
||||||
|
|
||||||
|
// Arduino Mega
|
||||||
|
//
|
||||||
|
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||||
|
|
||||||
|
//#define ALTSS_USE_TIMER4
|
||||||
|
//#define INPUT_CAPTURE_PIN 49 // receive
|
||||||
|
//#define OUTPUT_COMPARE_A_PIN 6 // transmit
|
||||||
|
//#define OUTPUT_COMPARE_B_PIN 7 // unusable PWM
|
||||||
|
//#define OUTPUT_COMPARE_C_PIN 8 // unusable PWM
|
||||||
|
|
||||||
|
#define ALTSS_USE_TIMER5
|
||||||
|
#define INPUT_CAPTURE_PIN 48 // receive
|
||||||
|
#define OUTPUT_COMPARE_A_PIN 46 // transmit
|
||||||
|
#define OUTPUT_COMPARE_B_PIN 45 // unusable PWM
|
||||||
|
#define OUTPUT_COMPARE_C_PIN 44 // unusable PWM
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// EnviroDIY Mayfly, Sodaq Mbili
|
||||||
|
#elif defined ARDUINO_AVR_ENVIRODIY_MAYFLY || defined ARDUINO_AVR_SODAQ_MBILI
|
||||||
|
#define ALTSS_USE_TIMER1
|
||||||
|
#define INPUT_CAPTURE_PIN 6 // receive
|
||||||
|
#define OUTPUT_COMPARE_A_PIN 5 // transmit
|
||||||
|
#define OUTPUT_COMPARE_B_PIN 4 // unusable PWM
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// Sanguino, Mighty 1284
|
||||||
|
#elif defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega1284__)
|
||||||
|
#define ALTSS_USE_TIMER1
|
||||||
|
#define INPUT_CAPTURE_PIN 14 // receive
|
||||||
|
#define OUTPUT_COMPARE_A_PIN 13 // transmit
|
||||||
|
#define OUTPUT_COMPARE_B_PIN 12 // unusable PWM
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// Unknown board
|
||||||
|
#else
|
||||||
|
#error "Please define your board timer and pins"
|
||||||
|
#endif
|
187
libraries/AltSoftSerial/config/AltSoftSerial_Timers.h
Normal file
187
libraries/AltSoftSerial/config/AltSoftSerial_Timers.h
Normal file
|
@ -0,0 +1,187 @@
|
||||||
|
/* An Alternative Software Serial Library
|
||||||
|
* http://www.pjrc.com/teensy/td_libs_AltSoftSerial.html
|
||||||
|
* Copyright (c) 2014 PJRC.COM, LLC, Paul Stoffregen, paul@pjrc.com
|
||||||
|
*
|
||||||
|
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
* of this software and associated documentation files (the "Software"), to deal
|
||||||
|
* in the Software without restriction, including without limitation the rights
|
||||||
|
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
* copies of the Software, and to permit persons to whom the Software is
|
||||||
|
* furnished to do so, subject to the following conditions:
|
||||||
|
*
|
||||||
|
* The above copyright notice and this permission notice shall be included in
|
||||||
|
* all copies or substantial portions of the Software.
|
||||||
|
*
|
||||||
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||||
|
* THE SOFTWARE.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if defined(ALTSS_USE_TIMER1)
|
||||||
|
#define CONFIG_TIMER_NOPRESCALE() (TIMSK1 = 0, TCCR1A = 0, TCCR1B = (1<<ICNC1) | (1<<CS10))
|
||||||
|
#define CONFIG_TIMER_PRESCALE_8() (TIMSK1 = 0, TCCR1A = 0, TCCR1B = (1<<ICNC1) | (1<<CS11))
|
||||||
|
#define CONFIG_TIMER_PRESCALE_256() (TIMSK1 = 0, TCCR1A = 0, TCCR1B = (1<<ICNC1) | (1<<CS12))
|
||||||
|
#define CONFIG_MATCH_NORMAL() (TCCR1A = TCCR1A & ~((1<<COM1A1) | (1<<COM1A0)))
|
||||||
|
#define CONFIG_MATCH_TOGGLE() (TCCR1A = (TCCR1A & ~(1<<COM1A1)) | (1<<COM1A0))
|
||||||
|
#define CONFIG_MATCH_CLEAR() (TCCR1A = (TCCR1A | (1<<COM1A1)) & ~(1<<COM1A0))
|
||||||
|
#define CONFIG_MATCH_SET() (TCCR1A = TCCR1A | ((1<<COM1A1) | (1<<COM1A0)))
|
||||||
|
#define CONFIG_CAPTURE_FALLING_EDGE() (TCCR1B &= ~(1<<ICES1))
|
||||||
|
#define CONFIG_CAPTURE_RISING_EDGE() (TCCR1B |= (1<<ICES1))
|
||||||
|
#define ENABLE_INT_INPUT_CAPTURE() (TIFR1 = (1<<ICF1), TIMSK1 = (1<<ICIE1))
|
||||||
|
#define ENABLE_INT_COMPARE_A() (TIFR1 = (1<<OCF1A), TIMSK1 |= (1<<OCIE1A))
|
||||||
|
#define ENABLE_INT_COMPARE_B() (TIFR1 = (1<<OCF1B), TIMSK1 |= (1<<OCIE1B))
|
||||||
|
#define DISABLE_INT_INPUT_CAPTURE() (TIMSK1 &= ~(1<<ICIE1))
|
||||||
|
#define DISABLE_INT_COMPARE_A() (TIMSK1 &= ~(1<<OCIE1A))
|
||||||
|
#define DISABLE_INT_COMPARE_B() (TIMSK1 &= ~(1<<OCIE1B))
|
||||||
|
#define GET_TIMER_COUNT() (TCNT1)
|
||||||
|
#define GET_INPUT_CAPTURE() (ICR1)
|
||||||
|
#define GET_COMPARE_A() (OCR1A)
|
||||||
|
#define GET_COMPARE_B() (OCR1B)
|
||||||
|
#define SET_COMPARE_A(val) (OCR1A = (val))
|
||||||
|
#define SET_COMPARE_B(val) (OCR1B = (val))
|
||||||
|
#define CAPTURE_INTERRUPT TIMER1_CAPT_vect
|
||||||
|
#define COMPARE_A_INTERRUPT TIMER1_COMPA_vect
|
||||||
|
#define COMPARE_B_INTERRUPT TIMER1_COMPB_vect
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined(ALTSS_USE_TIMER3)
|
||||||
|
#define CONFIG_TIMER_NOPRESCALE() (TIMSK3 = 0, TCCR3A = 0, TCCR3B = (1<<ICNC3) | (1<<CS30))
|
||||||
|
#define CONFIG_TIMER_PRESCALE_8() (TIMSK3 = 0, TCCR3A = 0, TCCR3B = (1<<ICNC3) | (1<<CS31))
|
||||||
|
#define CONFIG_TIMER_PRESCALE_256() (TIMSK3 = 0, TCCR3A = 0, TCCR3B = (1<<ICNC3) | (1<<CS32))
|
||||||
|
#define CONFIG_MATCH_NORMAL() (TCCR3A = TCCR3A & ~((1<<COM3A1) | (1<<COM3A0)))
|
||||||
|
#define CONFIG_MATCH_TOGGLE() (TCCR3A = (TCCR3A & ~(1<<COM3A1)) | (1<<COM3A0))
|
||||||
|
#define CONFIG_MATCH_CLEAR() (TCCR3A = (TCCR3A | (1<<COM3A1)) & ~(1<<COM3A0))
|
||||||
|
#define CONFIG_MATCH_SET() (TCCR3A = TCCR3A | ((1<<COM3A1) | (1<<COM3A0)))
|
||||||
|
#define CONFIG_CAPTURE_FALLING_EDGE() (TCCR3B &= ~(1<<ICES3))
|
||||||
|
#define CONFIG_CAPTURE_RISING_EDGE() (TCCR3B |= (1<<ICES3))
|
||||||
|
#define ENABLE_INT_INPUT_CAPTURE() (TIFR3 = (1<<ICF3), TIMSK3 = (1<<ICIE3))
|
||||||
|
#define ENABLE_INT_COMPARE_A() (TIFR3 = (1<<OCF3A), TIMSK3 |= (1<<OCIE3A))
|
||||||
|
#define ENABLE_INT_COMPARE_B() (TIFR3 = (1<<OCF3B), TIMSK3 |= (1<<OCIE3B))
|
||||||
|
#define DISABLE_INT_INPUT_CAPTURE() (TIMSK3 &= ~(1<<ICIE3))
|
||||||
|
#define DISABLE_INT_COMPARE_A() (TIMSK3 &= ~(1<<OCIE3A))
|
||||||
|
#define DISABLE_INT_COMPARE_B() (TIMSK3 &= ~(1<<OCIE3B))
|
||||||
|
#define GET_TIMER_COUNT() (TCNT3)
|
||||||
|
#define GET_INPUT_CAPTURE() (ICR3)
|
||||||
|
#define GET_COMPARE_A() (OCR3A)
|
||||||
|
#define GET_COMPARE_B() (OCR3B)
|
||||||
|
#define SET_COMPARE_A(val) (OCR3A = (val))
|
||||||
|
#define SET_COMPARE_B(val) (OCR3B = (val))
|
||||||
|
#define CAPTURE_INTERRUPT TIMER3_CAPT_vect
|
||||||
|
#define COMPARE_A_INTERRUPT TIMER3_COMPA_vect
|
||||||
|
#define COMPARE_B_INTERRUPT TIMER3_COMPB_vect
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined(ALTSS_USE_TIMER4)
|
||||||
|
#define CONFIG_TIMER_NOPRESCALE() (TIMSK4 = 0, TCCR4A = 0, TCCR4B = (1<<ICNC4) | (1<<CS40))
|
||||||
|
#define CONFIG_TIMER_PRESCALE_8() (TIMSK4 = 0, TCCR4A = 0, TCCR4B = (1<<ICNC4) | (1<<CS41))
|
||||||
|
#define CONFIG_TIMER_PRESCALE_256() (TIMSK4 = 0, TCCR4A = 0, TCCR4B = (1<<ICNC4) | (1<<CS42))
|
||||||
|
#define CONFIG_MATCH_NORMAL() (TCCR4A = TCCR4A & ~((1<<COM4A1) | (1<<COM4A0)))
|
||||||
|
#define CONFIG_MATCH_TOGGLE() (TCCR4A = (TCCR4A & ~(1<<COM4A1)) | (1<<COM4A0))
|
||||||
|
#define CONFIG_MATCH_CLEAR() (TCCR4A = (TCCR4A | (1<<COM4A1)) & ~(1<<COM4A0))
|
||||||
|
#define CONFIG_MATCH_SET() (TCCR4A = TCCR4A | ((1<<COM4A1) | (1<<COM4A0)))
|
||||||
|
#define CONFIG_CAPTURE_FALLING_EDGE() (TCCR4B &= ~(1<<ICES4))
|
||||||
|
#define CONFIG_CAPTURE_RISING_EDGE() (TCCR4B |= (1<<ICES4))
|
||||||
|
#define ENABLE_INT_INPUT_CAPTURE() (TIFR4 = (1<<ICF4), TIMSK4 = (1<<ICIE4))
|
||||||
|
#define ENABLE_INT_COMPARE_A() (TIFR4 = (1<<OCF4A), TIMSK4 |= (1<<OCIE4A))
|
||||||
|
#define ENABLE_INT_COMPARE_B() (TIFR4 = (1<<OCF4B), TIMSK4 |= (1<<OCIE4B))
|
||||||
|
#define DISABLE_INT_INPUT_CAPTURE() (TIMSK4 &= ~(1<<ICIE4))
|
||||||
|
#define DISABLE_INT_COMPARE_A() (TIMSK4 &= ~(1<<OCIE4A))
|
||||||
|
#define DISABLE_INT_COMPARE_B() (TIMSK4 &= ~(1<<OCIE4B))
|
||||||
|
#define GET_TIMER_COUNT() (TCNT4)
|
||||||
|
#define GET_INPUT_CAPTURE() (ICR4)
|
||||||
|
#define GET_COMPARE_A() (OCR4A)
|
||||||
|
#define GET_COMPARE_B() (OCR4B)
|
||||||
|
#define SET_COMPARE_A(val) (OCR4A = (val))
|
||||||
|
#define SET_COMPARE_B(val) (OCR4B = (val))
|
||||||
|
#define CAPTURE_INTERRUPT TIMER4_CAPT_vect
|
||||||
|
#define COMPARE_A_INTERRUPT TIMER4_COMPA_vect
|
||||||
|
#define COMPARE_B_INTERRUPT TIMER4_COMPB_vect
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined(ALTSS_USE_TIMER5)
|
||||||
|
#define CONFIG_TIMER_NOPRESCALE() (TIMSK5 = 0, TCCR5A = 0, TCCR5B = (1<<ICNC5) | (1<<CS50))
|
||||||
|
#define CONFIG_TIMER_PRESCALE_8() (TIMSK5 = 0, TCCR5A = 0, TCCR5B = (1<<ICNC5) | (1<<CS51))
|
||||||
|
#define CONFIG_TIMER_PRESCALE_256() (TIMSK5 = 0, TCCR5A = 0, TCCR5B = (1<<ICNC5) | (1<<CS52))
|
||||||
|
#define CONFIG_MATCH_NORMAL() (TCCR5A = TCCR5A & ~((1<<COM5A1) | (1<<COM5A0)))
|
||||||
|
#define CONFIG_MATCH_TOGGLE() (TCCR5A = (TCCR5A & ~(1<<COM5A1)) | (1<<COM5A0))
|
||||||
|
#define CONFIG_MATCH_CLEAR() (TCCR5A = (TCCR5A | (1<<COM5A1)) & ~(1<<COM5A0))
|
||||||
|
#define CONFIG_MATCH_SET() (TCCR5A = TCCR5A | ((1<<COM5A1) | (1<<COM5A0)))
|
||||||
|
#define CONFIG_CAPTURE_FALLING_EDGE() (TCCR5B &= ~(1<<ICES5))
|
||||||
|
#define CONFIG_CAPTURE_RISING_EDGE() (TCCR5B |= (1<<ICES5))
|
||||||
|
#define ENABLE_INT_INPUT_CAPTURE() (TIFR5 = (1<<ICF5), TIMSK5 = (1<<ICIE5))
|
||||||
|
#define ENABLE_INT_COMPARE_A() (TIFR5 = (1<<OCF5A), TIMSK5 |= (1<<OCIE5A))
|
||||||
|
#define ENABLE_INT_COMPARE_B() (TIFR5 = (1<<OCF5B), TIMSK5 |= (1<<OCIE5B))
|
||||||
|
#define DISABLE_INT_INPUT_CAPTURE() (TIMSK5 &= ~(1<<ICIE5))
|
||||||
|
#define DISABLE_INT_COMPARE_A() (TIMSK5 &= ~(1<<OCIE5A))
|
||||||
|
#define DISABLE_INT_COMPARE_B() (TIMSK5 &= ~(1<<OCIE5B))
|
||||||
|
#define GET_TIMER_COUNT() (TCNT5)
|
||||||
|
#define GET_INPUT_CAPTURE() (ICR5)
|
||||||
|
#define GET_COMPARE_A() (OCR5A)
|
||||||
|
#define GET_COMPARE_B() (OCR5B)
|
||||||
|
#define SET_COMPARE_A(val) (OCR5A = (val))
|
||||||
|
#define SET_COMPARE_B(val) (OCR5B = (val))
|
||||||
|
#define CAPTURE_INTERRUPT TIMER5_CAPT_vect
|
||||||
|
#define COMPARE_A_INTERRUPT TIMER5_COMPA_vect
|
||||||
|
#define COMPARE_B_INTERRUPT TIMER5_COMPB_vect
|
||||||
|
|
||||||
|
|
||||||
|
#elif defined(ALTSS_USE_FTM0)
|
||||||
|
// CH5 = input capture (input, pin 20)
|
||||||
|
// CH6 = compare a (output, pin 21)
|
||||||
|
// CH0 = compare b (input timeout)
|
||||||
|
#define CONFIG_TIMER_NOPRESCALE() FTM0_SC = 0; FTM0_CNT = 0; FTM0_MOD = 0xFFFF; \
|
||||||
|
FTM0_SC = FTM_SC_CLKS(1) | FTM_SC_PS(0); \
|
||||||
|
digitalWriteFast(21, HIGH); \
|
||||||
|
NVIC_SET_PRIORITY(IRQ_FTM0, 48); \
|
||||||
|
FTM0_C0SC = 0x18; \
|
||||||
|
NVIC_ENABLE_IRQ(IRQ_FTM0);
|
||||||
|
#define CONFIG_TIMER_PRESCALE_8() FTM0_SC = 0; FTM0_CNT = 0; FTM0_MOD = 0xFFFF; \
|
||||||
|
FTM0_SC = FTM_SC_CLKS(1) | FTM_SC_PS(3); \
|
||||||
|
digitalWriteFast(21, HIGH); \
|
||||||
|
NVIC_SET_PRIORITY(IRQ_FTM0, 48); \
|
||||||
|
FTM0_C0SC = 0x18; \
|
||||||
|
NVIC_ENABLE_IRQ(IRQ_FTM0);
|
||||||
|
#define CONFIG_TIMER_PRESCALE_128() FTM0_SC = 0; FTM0_CNT = 0; FTM0_MOD = 0xFFFF; \
|
||||||
|
FTM0_SC = FTM_SC_CLKS(1) | FTM_SC_PS(7); \
|
||||||
|
digitalWriteFast(21, HIGH); \
|
||||||
|
NVIC_SET_PRIORITY(IRQ_FTM0, 48); \
|
||||||
|
FTM0_C0SC = 0x18; \
|
||||||
|
NVIC_ENABLE_IRQ(IRQ_FTM0);
|
||||||
|
#define CONFIG_MATCH_NORMAL() (FTM0_C6SC = 0)
|
||||||
|
#define CONFIG_MATCH_TOGGLE() (FTM0_C6SC = (FTM0_C6SC & 0xC3) | 0x14)
|
||||||
|
#define CONFIG_MATCH_CLEAR() (FTM0_C6SC = (FTM0_C6SC & 0xC3) | 0x18)
|
||||||
|
#define CONFIG_MATCH_SET() (FTM0_C6SC = (FTM0_C6SC & 0xC3) | 0x1C)
|
||||||
|
#define CONFIG_CAPTURE_FALLING_EDGE() (FTM0_C5SC = (FTM0_C5SC & 0xC3) | 0x08)
|
||||||
|
#define CONFIG_CAPTURE_RISING_EDGE() (FTM0_C5SC = (FTM0_C5SC & 0xC3) | 0x04)
|
||||||
|
#define ENABLE_INT_INPUT_CAPTURE() FTM0_C5SC = 0x48; \
|
||||||
|
CORE_PIN20_CONFIG = PORT_PCR_MUX(4)|PORT_PCR_PE|PORT_PCR_PS
|
||||||
|
#define ENABLE_INT_COMPARE_A() FTM0_C6SC |= 0x40; \
|
||||||
|
CORE_PIN21_CONFIG = PORT_PCR_MUX(4)|PORT_PCR_DSE|PORT_PCR_SRE
|
||||||
|
#define ENABLE_INT_COMPARE_B() (FTM0_C0SC = 0x58)
|
||||||
|
#define DISABLE_INT_INPUT_CAPTURE() FTM0_C5SC &= ~0x40; \
|
||||||
|
CORE_PIN20_CONFIG = PORT_PCR_MUX(1)|PORT_PCR_PE|PORT_PCR_PS
|
||||||
|
#define DISABLE_INT_COMPARE_A() FTM0_C6SC &= ~0x40; \
|
||||||
|
CORE_PIN21_CONFIG = PORT_PCR_MUX(1)|PORT_PCR_DSE|PORT_PCR_SRE; \
|
||||||
|
digitalWriteFast(21, HIGH)
|
||||||
|
#define DISABLE_INT_COMPARE_B() (FTM0_C0SC &= ~0x40)
|
||||||
|
#define GET_TIMER_COUNT() (FTM0_CNT)
|
||||||
|
#define GET_INPUT_CAPTURE() (FTM0_C5V)
|
||||||
|
#define GET_COMPARE_A() (FTM0_C6V)
|
||||||
|
#define GET_COMPARE_B() (FTM0_C0V)
|
||||||
|
#define SET_COMPARE_A(val) (FTM0_C6V = val)
|
||||||
|
#define SET_COMPARE_B(val) if (FTM0_C0SC & FTM_CSC_CHF) FTM0_C0SC = 0x18; \
|
||||||
|
do { FTM0_C0V = (val); } while (FTM0_C0V != (val));
|
||||||
|
#define CAPTURE_INTERRUPT altss_capture_interrupt
|
||||||
|
#define COMPARE_A_INTERRUPT altss_compare_a_interrupt
|
||||||
|
#define COMPARE_B_INTERRUPT altss_compare_b_interrupt
|
||||||
|
#ifdef ISR
|
||||||
|
#undef ISR
|
||||||
|
#endif
|
||||||
|
#define ISR(f) static void f (void)
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
64
libraries/AltSoftSerial/docs/issue_template.md
Normal file
64
libraries/AltSoftSerial/docs/issue_template.md
Normal file
|
@ -0,0 +1,64 @@
|
||||||
|
Please use this form only to report code defects or bugs.
|
||||||
|
|
||||||
|
For any question, even questions directly pertaining to this code, post your question on the forums related to the board you are using.
|
||||||
|
|
||||||
|
Arduino: forum.arduino.cc
|
||||||
|
Teensy: forum.pjrc.com
|
||||||
|
ESP8266: www.esp8266.com
|
||||||
|
ESP32: www.esp32.com
|
||||||
|
Adafruit Feather/Metro/Trinket: forums.adafruit.com
|
||||||
|
Particle Photon: community.particle.io
|
||||||
|
|
||||||
|
If you are experiencing trouble but not certain of the cause, or need help using this code, ask on the appropriate forum. This is not the place to ask for support or help, even directly related to this code. Only use this form you are certain you have discovered a defect in this code!
|
||||||
|
|
||||||
|
Please verify the problem occurs when using the very latest version, using the newest version of Arduino and any other related software.
|
||||||
|
|
||||||
|
|
||||||
|
----------------------------- Remove above -----------------------------
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
### Description
|
||||||
|
|
||||||
|
Describe your problem.
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
### Steps To Reproduce Problem
|
||||||
|
|
||||||
|
Please give detailed instructions needed for anyone to attempt to reproduce the problem.
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
### Hardware & Software
|
||||||
|
|
||||||
|
Board
|
||||||
|
Shields / modules used
|
||||||
|
Arduino IDE version
|
||||||
|
Teensyduino version (if using Teensy)
|
||||||
|
Version info & package name (from Tools > Boards > Board Manager)
|
||||||
|
Operating system & version
|
||||||
|
Any other software or hardware?
|
||||||
|
|
||||||
|
|
||||||
|
### Arduino Sketch
|
||||||
|
|
||||||
|
```cpp
|
||||||
|
// Change the code below by your sketch (please try to give the smallest code which demonstrates the problem)
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
// libraries: give links/details so anyone can compile your code for the same result
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
}
|
||||||
|
```
|
||||||
|
|
||||||
|
|
||||||
|
### Errors or Incorrect Output
|
||||||
|
|
||||||
|
If you see any errors or incorrect output, please show it here. Please use copy & paste to give an exact copy of the message. Details matter, so please show (not merely describe) the actual message or error exactly as it appears.
|
||||||
|
|
||||||
|
|
40
libraries/AltSoftSerial/examples/Echo/Echo.ino
Normal file
40
libraries/AltSoftSerial/examples/Echo/Echo.ino
Normal file
|
@ -0,0 +1,40 @@
|
||||||
|
#include <AltSoftSerial.h>
|
||||||
|
|
||||||
|
// AltSoftSerial always uses these pins:
|
||||||
|
//
|
||||||
|
// Board Transmit Receive PWM Unusable
|
||||||
|
// ----- -------- ------- ------------
|
||||||
|
// Teensy 3.0 & 3.1 21 20 22
|
||||||
|
// Teensy 2.0 9 10 (none)
|
||||||
|
// Teensy++ 2.0 25 4 26, 27
|
||||||
|
// Arduino Uno 9 8 10
|
||||||
|
// Arduino Leonardo 5 13 (none)
|
||||||
|
// Arduino Mega 46 48 44, 45
|
||||||
|
// Wiring-S 5 6 4
|
||||||
|
// Sanguino 13 14 12
|
||||||
|
|
||||||
|
// This example code is in the public domain.
|
||||||
|
|
||||||
|
AltSoftSerial altSerial;
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Serial.begin(9600);
|
||||||
|
while (!Serial) ; // wait for Arduino Serial Monitor to open
|
||||||
|
Serial.println("AltSoftSerial Test Begin");
|
||||||
|
altSerial.begin(9600);
|
||||||
|
altSerial.println("Hello World");
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
char c;
|
||||||
|
|
||||||
|
if (Serial.available()) {
|
||||||
|
c = Serial.read();
|
||||||
|
altSerial.print(c);
|
||||||
|
}
|
||||||
|
if (altSerial.available()) {
|
||||||
|
c = altSerial.read();
|
||||||
|
Serial.print(c);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
52
libraries/AltSoftSerial/examples/ReceiveTest/ReceiveTest.ino
Normal file
52
libraries/AltSoftSerial/examples/ReceiveTest/ReceiveTest.ino
Normal file
|
@ -0,0 +1,52 @@
|
||||||
|
// AltSoftSerial Receive Test
|
||||||
|
//
|
||||||
|
// Transmit data with Serial1 and try to receive
|
||||||
|
// it with AltSoftSerial. You must connect a wire
|
||||||
|
// from Serial1 TX to AltSoftSerial RX.
|
||||||
|
|
||||||
|
#include <AltSoftSerial.h>
|
||||||
|
|
||||||
|
AltSoftSerial altser;
|
||||||
|
const int mybaud = 9600;
|
||||||
|
|
||||||
|
// Board Serial1 TX AltSoftSerial RX
|
||||||
|
// ----- ---------- ----------------
|
||||||
|
// Teensy 3.x 1 20
|
||||||
|
// Teensy 2.0 8 (D3) 10 (C7)
|
||||||
|
// Teensy++ 2.0 3 (D3) 4 (D4)
|
||||||
|
// Arduino Leonardo 1 13
|
||||||
|
// Arduino Mega 18 48
|
||||||
|
|
||||||
|
// Serial1 on AVR @ 16 MHz minimum baud is 245
|
||||||
|
// Serial1 on Teensy 3.2 @ 96 MHz minimum baud is 733
|
||||||
|
|
||||||
|
// This example code is in the public domain.
|
||||||
|
|
||||||
|
byte sentbyte;
|
||||||
|
unsigned long prevmillis;
|
||||||
|
byte testbyte=0xF0;
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
delay(200);
|
||||||
|
Serial.begin(9600);
|
||||||
|
while (!Serial) ; // wait for Arduino Serial Monitor
|
||||||
|
Serial1.begin(mybaud); // connect a wire from TX1
|
||||||
|
altser.begin(mybaud); // to AltSoftSerial RX
|
||||||
|
Serial.println("AltSoftSerial Receive Test");
|
||||||
|
prevmillis = millis();
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
// transmit a test byte on Serial 1
|
||||||
|
if (millis() - prevmillis > 250) {
|
||||||
|
sentbyte = testbyte++;
|
||||||
|
Serial1.write(sentbyte);
|
||||||
|
prevmillis = millis();
|
||||||
|
}
|
||||||
|
// attempt to receive it by AltSoftSerial
|
||||||
|
if (altser.available() > 0) {
|
||||||
|
byte b = altser.read();
|
||||||
|
Serial.println(b);
|
||||||
|
if (b != sentbyte) Serial.println("***** ERROR *****");
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1,97 @@
|
||||||
|
#include <AltSoftSerial.h>
|
||||||
|
|
||||||
|
// AltSoftSerial show configuration example
|
||||||
|
// Will print library configuration to default serial port
|
||||||
|
// Open your serial monitor to see config for your board
|
||||||
|
// Printout would repeat every 10sec (just in case you missed it somehow)
|
||||||
|
|
||||||
|
// Print Configuration
|
||||||
|
// -----------------------
|
||||||
|
|
||||||
|
// Direct include AltSoftSerial internals to obtaion PIN setup (you do not need this in regular code)
|
||||||
|
|
||||||
|
// This example code is in the public domain.
|
||||||
|
|
||||||
|
#include <config/AltSoftSerial_Boards.h>
|
||||||
|
|
||||||
|
void printAltSoftSerialSetup(Stream &port)
|
||||||
|
{
|
||||||
|
#define PRINT_PFX "AltSoftSerial:"
|
||||||
|
#define PRINT_PIN_NAME(pin,name) { char buffer[128+1]; sprintf(buffer, PRINT_PFX "PIN:%2d %s", (int)pin, (const char*)name); port.println(buffer); }
|
||||||
|
|
||||||
|
port.println(PRINT_PFX "Setup info: begin");
|
||||||
|
|
||||||
|
#if defined(ALTSS_USE_FTM0)
|
||||||
|
port.println(PRINT_PFX "USE FTM0");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(ALTSS_USE_TIMER1)
|
||||||
|
port.println(PRINT_PFX "USE TIMER1");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(ALTSS_USE_TIMER2)
|
||||||
|
port.println(PRINT_PFX "USE TIMER2");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(ALTSS_USE_TIMER3)
|
||||||
|
port.println(PRINT_PFX "USE TIMER3");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(ALTSS_USE_TIMER4)
|
||||||
|
port.println(PRINT_PFX "USE TIMER4");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(ALTSS_USE_TIMER5)
|
||||||
|
port.println(PRINT_PFX "USE TIMER5");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(INPUT_CAPTURE_PIN)
|
||||||
|
PRINT_PIN_NAME(INPUT_CAPTURE_PIN,"RX");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(OUTPUT_COMPARE_A_PIN)
|
||||||
|
PRINT_PIN_NAME(OUTPUT_COMPARE_A_PIN,"TX");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(OUTPUT_COMPARE_B_PIN)
|
||||||
|
PRINT_PIN_NAME(OUTPUT_COMPARE_B_PIN,"(unused PWM)");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(OUTPUT_COMPARE_C_PIN)
|
||||||
|
PRINT_PIN_NAME(OUTPUT_COMPARE_C_PIN,"(unused PWM)");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(OUTPUT_COMPARE_D_PIN)
|
||||||
|
PRINT_PIN_NAME(OUTPUT_COMPARE_D_PIN,"(unused PWM)");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(OUTPUT_COMPARE_E_PIN)
|
||||||
|
PRINT_PIN_NAME(OUTPUT_COMPARE_E_PIN,"(unused PWM)");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(OUTPUT_COMPARE_F_PIN)
|
||||||
|
PRINT_PIN_NAME(OUTPUT_COMPARE_F_PIN,"(unused PWM)");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
port.println(PRINT_PFX "Setup info: end");
|
||||||
|
|
||||||
|
#undef PRINT_PIN_NAME
|
||||||
|
#undef PRINT_PFX
|
||||||
|
}
|
||||||
|
|
||||||
|
void setup()
|
||||||
|
{
|
||||||
|
// Open default serial to dump config to
|
||||||
|
Serial.begin(9600);
|
||||||
|
while (!Serial) ; // wait for serial monitor
|
||||||
|
printAltSoftSerialSetup(Serial);
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop()
|
||||||
|
{
|
||||||
|
// Repeat every 10 sec (just in case)
|
||||||
|
delay(10000);
|
||||||
|
Serial.println("");
|
||||||
|
printAltSoftSerialSetup(Serial);
|
||||||
|
}
|
||||||
|
|
4
libraries/AltSoftSerial/keywords.txt
Normal file
4
libraries/AltSoftSerial/keywords.txt
Normal file
|
@ -0,0 +1,4 @@
|
||||||
|
AltSoftSerial KEYWORD1
|
||||||
|
active KEYWORD2
|
||||||
|
overflow KEYWORD2
|
||||||
|
library_version KEYWORD2
|
18
libraries/AltSoftSerial/library.json
Normal file
18
libraries/AltSoftSerial/library.json
Normal file
|
@ -0,0 +1,18 @@
|
||||||
|
{
|
||||||
|
"name": "AltSoftSerial",
|
||||||
|
"frameworks": "Arduino",
|
||||||
|
"keywords": "serial",
|
||||||
|
"description": "Alternate Software Serial",
|
||||||
|
"url": "http://www.pjrc.com/teensy/td_libs_AltSoftSerial.html",
|
||||||
|
"authors":
|
||||||
|
{
|
||||||
|
"name": "Paul Stoffregen",
|
||||||
|
"maintainer": true
|
||||||
|
},
|
||||||
|
"repository":
|
||||||
|
{
|
||||||
|
"type": "git",
|
||||||
|
"url": "https://github.com/PaulStoffregen/AltSoftSerial"
|
||||||
|
},
|
||||||
|
"version": "1.4"
|
||||||
|
}
|
9
libraries/AltSoftSerial/library.properties
Normal file
9
libraries/AltSoftSerial/library.properties
Normal file
|
@ -0,0 +1,9 @@
|
||||||
|
name=AltSoftSerial
|
||||||
|
version=1.4
|
||||||
|
author=Paul Stoffregen
|
||||||
|
maintainer=Paul Stoffregen
|
||||||
|
sentence=Software emulated serial using hardware timers for improved compatibility
|
||||||
|
paragraph=Improved software emulated serial, using hardware timers for precise signal timing and improved compatibility with other interrupt-based libraries.
|
||||||
|
category=Communication
|
||||||
|
url=http://www.pjrc.com/teensy/td_libs_AltSoftSerial.html
|
||||||
|
architectures=avr
|
|
@ -139,5 +139,59 @@ int main() {
|
||||||
//stream0 = pb_istream_from_buffer(buffer, stream.bytes_written);
|
//stream0 = pb_istream_from_buffer(buffer, stream.bytes_written);
|
||||||
//err = pb_decode(&stream0, Fenceless_Coordinates_fields, &coords0);
|
//err = pb_decode(&stream0, Fenceless_Coordinates_fields, &coords0);
|
||||||
//assert(err);
|
//assert(err);
|
||||||
|
|
||||||
|
|
||||||
|
/* Reference Protobuff data
|
||||||
|
#define TYPE_STRING 0x0A
|
||||||
|
#define TYPE_VARIANT 0x10
|
||||||
|
#define PROTO_LEN 0x0A
|
||||||
|
#define FIELD_ONE_FLOAT 0x0D
|
||||||
|
#define FIELD_TWO_FLOAT 0x15
|
||||||
|
#define FIELD_TWO_VARIANT 0x10
|
||||||
|
#define FIELD_ONE_VARIANT 0x08
|
||||||
|
#define FIELD_TWO_STRING 0x12
|
||||||
|
#define FIELD_THREE_STRING 0x1A
|
||||||
|
#define FIELD_FOUR_STRING 0x22
|
||||||
|
#define FIELD_FIVE_STRING 0x2A
|
||||||
|
#define FIELD_SIX_STRING 0x32
|
||||||
|
#define FIELD_SEVEN_STRING 0x3A
|
||||||
|
#define FIELD_EIGHT_STRING 0x42
|
||||||
|
#define FIELD_NINE_STRING 0x4A
|
||||||
|
#define FIELD_TEN_STRING 0x52
|
||||||
|
#define FIELD_ELEVEN_STRING 0x5A
|
||||||
|
uint8_t buffer0[] {
|
||||||
|
FIELD_ONE_VARIANT, 0x01,
|
||||||
|
FIELD_TWO_STRING, 0x0A,
|
||||||
|
FIELD_ONE_FLOAT, 0x1B, 0x91, 0xF6, 0xC2,
|
||||||
|
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
||||||
|
FIELD_THREE_STRING, 0x0A,
|
||||||
|
FIELD_ONE_FLOAT, 0xB5, 0x3B, 0x32, 0x42,
|
||||||
|
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
||||||
|
FIELD_FOUR_STRING, 0x0A,
|
||||||
|
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
||||||
|
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
||||||
|
FIELD_FIVE_STRING, 0x0A,
|
||||||
|
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
||||||
|
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
||||||
|
FIELD_SIX_STRING, 0x0A,
|
||||||
|
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
||||||
|
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
||||||
|
FIELD_SEVEN_STRING, 0x0A,
|
||||||
|
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
||||||
|
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
||||||
|
FIELD_EIGHT_STRING, 0x0A,
|
||||||
|
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
||||||
|
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
||||||
|
FIELD_NINE_STRING, 0x0A,
|
||||||
|
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
||||||
|
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
||||||
|
FIELD_TEN_STRING, 0x0A,
|
||||||
|
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
||||||
|
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40,
|
||||||
|
FIELD_ELEVEN_STRING, 0x0A,
|
||||||
|
FIELD_ONE_FLOAT, 0x00, 0x00, 0x80, 0x3F,
|
||||||
|
FIELD_TWO_FLOAT, 0x00, 0x00, 0x00, 0x40
|
||||||
|
};*/
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue
Block a user