Skip to content

Commit

Permalink
Rework RTC calendar to use a elapsed seconds offset (BKPx); this way …
Browse files Browse the repository at this point in the history
…RTC once started does not have to be modified

Use a S11 value for subsecond correction throu PPS (BKPx)

Use RTC for millis() over Systick

Add LSE calibration via TCXO for CMWX1ZZABZ (via DIO1)

Add PPS tracking for GNSS to facility RTC phase correction
  • Loading branch information
GrumpyOldPizza committed Jul 6, 2018
1 parent 15b2929 commit aa9037c
Show file tree
Hide file tree
Showing 33 changed files with 1,879 additions and 1,159 deletions.
8 changes: 4 additions & 4 deletions cores/arduino/Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -8,15 +8,15 @@ LD = $(TOOLS)/bin/arm-none-eabi-ld
CFLAGS = -mcpu=cortex-m0plus -mthumb -c -g -Os $(WARNINGS) -std=gnu11 -ffunction-sections -fdata-sections -nostdlib -MMD $(EXTRAS) $(DEFINES) $(INCLUDES)
CXXFLAGS = -mcpu=cortex-m0plus -mthumb -c -g -Os $(WARNINGS) -std=gnu++11 -ffunction-sections -fdata-sections -fno-threadsafe-statics -nostdlib -fno-rtti -fno-exceptions -MMD $(EXTRAS) $(DEFINES) $(INCLUDES)
ASFLAGS = -c -g -x assembler-with-cpp $(EXTRAS) $(DEFINES) $(INCLUDES)
LDFLAGS = -g -Os -mcpu=cortex-m0plus -mthumb -mabi=aapcs -mfloat-abi=soft -Wl,--gc-sections,--no-undefined -T../../variants/STM32L082CZ-Cricket/linker_scripts/STM32L082CZ_FLASH.ld --specs=nano.specs
LDFLAGS = -g -Os -mcpu=cortex-m0plus -mthumb -mabi=aapcs -mfloat-abi=soft -Wl,--gc-sections,--no-undefined -T../../variants/Cricket-L082CZ/linker_scripts/STM32L082CZ_FLASH.ld --specs=nano.specs
WARNINGS = -Wall -Wextra -Wno-unused-parameter
EXTRAS = -DSTM32L082xx -march=armv6-m -mthumb -mabi=aapcs -mfloat-abi=soft
DEFINES = -D_SYSTEM_CORE_CLOCK_=32000000 -DDOSFS_SDCARD=0 -DDOSFS_SFLASH=1 -DARDUINO_MAKEFILE
INCLUDES = \
-I../../system/CMSIS/Include \
-I../../system/CMSIS/Device/ST/STM32L0xx/Include \
-I../../system/STM32L0xx/Include \
-I../../variants/STM32L082CZ-Cricket \
-I../../variants/Cricket-L082CZ \
-I../../libraries/CayenneLPP/src \
-I../../libraries/DOSFS/src \
-I../../libraries/EEPROM/src \
Expand All @@ -40,7 +40,7 @@ SRCS = \
../../libraries/STM32L0/src/STM32L0.cpp \
../../libraries/TimerMillis/src/TimerMillis.cpp \
../../libraries/Wire/src/Wire.cpp \
../../variants/STM32L082CZ-Cricket/variant.cpp \
../../variants/Cricket-L082CZ/variant.cpp \
avr/dtostrf.c \
avr/eeprom.c \
avr/fdevopen.c \
Expand Down Expand Up @@ -86,7 +86,7 @@ OBJS = \
../../libraries/STM32L0/src/STM32L0.o \
../../libraries/TimerMillis/src/TimerMillis.o \
../../libraries/Wire/src/Wire.o \
../../variants/STM32L082CZ-Cricket/variant.o \
../../variants/Cricket-L082CZ/variant.o \
avr/dtostrf.o \
avr/eeprom.o \
avr/fdevopen.o \
Expand Down
11 changes: 8 additions & 3 deletions cores/arduino/delay.c
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,12 @@

unsigned long millis(void)
{
return armv6m_systick_millis();
uint32_t seconds;
uint16_t subseconds;

stm32l0_rtc_get_time(&seconds, &subseconds);

return (seconds * 1000) + ((subseconds * 1000) / 32768);
}

unsigned long micros(void)
Expand Down Expand Up @@ -81,11 +86,11 @@ void delay(uint32_t msec)
while (msec);

} else {
start = armv6m_systick_millis();
start = millis();

do
{
}
while ((armv6m_systick_millis() - start) < msec);
while ((millis() - start) < msec);
}
}
5 changes: 5 additions & 0 deletions drivers/linux/49-nucleo.rules
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
ATTRS{idVendor}=="0483", ATTRS{idProduct}=="374b", ENV{ID_MM_DEVICE_IGNORE}="1"
ATTRS{idVendor}=="0483", ATTRS{idProduct}=="374b", ENV{MTP_NO_PROBE}="1"
ATTRS{idVendor}=="0483", ATTRS{idProduct}=="374b", ENV{UDISKS_AUTO}="0"
SUBSYSTEMS=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="374b", MODE:="0666"
KERNEL=="ttyACM*", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="374b", MODE:="0666"
54 changes: 52 additions & 2 deletions libraries/GNSS/examples/GNSS_periodic/GNSS_periodic.ino
Original file line number Diff line number Diff line change
@@ -1,10 +1,11 @@
#include "GNSS.h"
#include "STM32L0.h"
#include "RTC.h"

bool isPeriodic = false;

unsigned int myAcqTime = 45;
unsigned int myOnTime = 5;
unsigned int myOnTime = 15;
unsigned int myPeriod = 120;

GNSSLocation myLocation;
Expand All @@ -28,6 +29,8 @@ void setup( void )
GNSS.setAntenna(GNSS.ANTENNA_INTERNAL);

while (GNSS.busy()) { }

GNSS.enableWakeup();
}

void loop( void )
Expand All @@ -36,6 +39,9 @@ void loop( void )

if (GNSS.location(myLocation))
{
uint8_t year, month, day, hours, minutes, seconds;
uint32_t subSeconds, milliSeconds;

static const char *fixTypeString[] = {
"NONE",
"TIME",
Expand All @@ -57,14 +63,50 @@ void loop( void )

if (!isPeriodic)
{
if (myLocation.fixType() == GNSSLocation::TYPE_3D)
if ((myLocation.fixType() == GNSSLocation::TYPE_3D) && (myLocation.ehpe() <= 30.0) && myLocation.fullyResolved())
{
isPeriodic = true;

GNSS.setPeriodic(myAcqTime, myOnTime, myPeriod);
}
}

RTC.getDate(day, month, year);
RTC.getTime(hours, minutes, seconds, subSeconds);

milliSeconds = ((subSeconds >> 17) * 1000 + 16384) / 32768;

Serial.print("RTC: ");
Serial.print(2000 + year);
Serial.print("/");
Serial.print(month);
Serial.print("/");
Serial.print(day);
Serial.print(" ");
if (hours <= 9) {
Serial.print("0");
}
Serial.print(hours);
Serial.print(":");
if (minutes <= 9) {
Serial.print("0");
}
Serial.print(minutes);
Serial.print(":");
if (seconds <= 9) {
Serial.print("0");
}
Serial.print(seconds);
Serial.print(".");
if (milliSeconds <= 9) {
Serial.print("0");
}
if (milliSeconds <= 99) {
Serial.print("0");
}
Serial.print(milliSeconds);
Serial.println();

Serial.print("LOCATION: ");
Serial.print(fixTypeString[myLocation.fixType()]);

Expand Down Expand Up @@ -101,6 +143,14 @@ void loop( void )
}
Serial.print(myLocation.millis());

if (myLocation.leapSeconds() != GNSSLocation::LEAP_SECONDS_UNDEFINED) {
Serial.print(" ");
Serial.print(myLocation.leapSeconds());
if (!myLocation.fullyResolved()) {
Serial.print("D");
}
}

if (myLocation.fixType() != GNSSLocation::TYPE_TIME)
{
Serial.print(" LLA=");
Expand Down
79 changes: 73 additions & 6 deletions libraries/GNSS/src/GNSS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ GNSSLocation::GNSSLocation()
_location.time.seconds = 0;
_location.time.millis = 0;
_location.mask = 0;
_location.correction = 0;
_location.correction = -128;
_location.type = 0;
_location.latitude = 0;
_location.longitude = 0;
Expand Down Expand Up @@ -77,6 +77,11 @@ enum GNSSLocation::GNSSfixQuality GNSSLocation::fixQuality(void) const
return (enum GNSSLocation::GNSSfixQuality)_location.quality;
}

bool GNSSLocation::fullyResolved(void) const
{
return !!(_location.mask & GNSS_LOCATION_MASK_RESOLVED);
}

unsigned int GNSSLocation::satellites(void) const
{
return _location.numsv;
Expand Down Expand Up @@ -117,7 +122,7 @@ uint16_t GNSSLocation::millis(void) const
return _location.time.millis;
}

uint8_t GNSSLocation::leapSeconds(void) const
int8_t GNSSLocation::leapSeconds(void) const
{
return _location.correction;
}
Expand Down Expand Up @@ -342,6 +347,11 @@ void GNSSClass::begin(Uart &uart, GNSSmode mode, GNSSrate rate)
}
#endif /* defined(STM32L0_CONFIG_PIN_GNSS_ENABLE) */

#if defined(STM32L0_CONFIG_PIN_GNSS_PPS)
stm32l0_gpio_pin_configure(STM32L0_CONFIG_PIN_GNSS_PPS, (STM32L0_GPIO_PARK_NONE | STM32L0_GPIO_PUPD_PULLDOWN | STM32L0_GPIO_OSPEED_HIGH | STM32L0_GPIO_OTYPE_PUSHPULL | STM32L0_GPIO_MODE_INPUT));
stm32l0_exti_attach(STM32L0_CONFIG_PIN_GNSS_PPS, STM32L0_EXTI_CONTROL_EDGE_FALLING, (stm32l0_exti_callback_t)ppsCallback, (void*)this);
#endif

_uart = &uart;

_uart->begin(9600);
Expand Down Expand Up @@ -412,14 +422,34 @@ bool GNSSClass::setPeriodic(unsigned int acqTime, unsigned int onTime, unsigned
return (_uart && gnss_set_periodic(acqTime, onTime, period));
}

bool GNSSClass::sleep()
bool GNSSClass::suspend()
{
return (_uart && gnss_sleep());
if (!(_uart && gnss_suspend()))
{
return false;
}

#if defined(STM32L0_CONFIG_PIN_GNSS_PPS)
stm32l0_exti_detach(STM32L0_CONFIG_PIN_GNSS_PPS);
stm32l0_gpio_pin_configure(STM32L0_CONFIG_PIN_GNSS_PPS, (STM32L0_GPIO_PARK_NONE | STM32L0_GPIO_MODE_ANALOG));
#endif

return true;
}

bool GNSSClass::wakeup()
bool GNSSClass::resume()
{
return (_uart && gnss_wakeup());
if (!(_uart && gnss_resume()))
{
return false;
}

#if defined(STM32L0_CONFIG_PIN_GNSS_PPS)
stm32l0_gpio_pin_configure(STM32L0_CONFIG_PIN_GNSS_PPS, (STM32L0_GPIO_PARK_NONE | STM32L0_GPIO_PUPD_PULLDOWN | STM32L0_GPIO_OSPEED_HIGH | STM32L0_GPIO_OTYPE_PUSHPULL | STM32L0_GPIO_MODE_INPUT));
stm32l0_exti_attach(STM32L0_CONFIG_PIN_GNSS_PPS, STM32L0_EXTI_CONTROL_EDGE_FALLING, (stm32l0_exti_callback_t)ppsCallback, (void*)this);
#endif

return true;
}

bool GNSSClass::busy()
Expand Down Expand Up @@ -462,6 +492,16 @@ bool GNSSClass::satellites(GNSSSatellites &satellites)
return true;
}

void GNSSClass::enableWakeup()
{
_wakeup = true;
}

void GNSSClass::disableWakeup()
{
_wakeup = false;
}

void GNSSClass::onLocation(void(*callback)(void))
{
_locationCallback = Callback(callback);
Expand All @@ -482,6 +522,16 @@ void GNSSClass::onSatellites(Callback callback)
_satellitesCallback = callback;
}

void GNSSClass::attachInterrupt(void(*callback)(void))
{
_ppsCallback = callback;
}

void GNSSClass::detachInterrupt()
{
_ppsCallback = NULL;
}

void GNSSClass::receiveCallback(void)
{
uint8_t rx_data[16];
Expand Down Expand Up @@ -540,6 +590,10 @@ void GNSSClass::disableCallback(class GNSSClass *self)

void GNSSClass::locationCallback(class GNSSClass *self, const gnss_location_t *location)
{
if (self->_wakeup) {
stm32l0_system_wakeup();
}

self->_location_data = *location;
self->_location_pending = true;

Expand All @@ -548,10 +602,23 @@ void GNSSClass::locationCallback(class GNSSClass *self, const gnss_location_t *l

void GNSSClass::satellitesCallback(class GNSSClass *self, const gnss_satellites_t *satellites)
{
if (self->_wakeup) {
stm32l0_system_wakeup();
}

self->_satellites_data = *satellites;
self->_satellites_pending = true;

self->_satellitesCallback.queue();
}

void GNSSClass::ppsCallback(class GNSSClass *self)
{
gnss_pps_callback();

if (self->_ppsCallback) {
(*self->_ppsCallback)();
}
}

GNSSClass GNSS;
21 changes: 17 additions & 4 deletions libraries/GNSS/src/GNSS.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,13 +53,16 @@ class GNSSLocation {
QUALITY_SIMULATION,
};

static const int LEAP_SECONDS_UNDEFINED = -128;

GNSSLocation(const gnss_location_t *location);
GNSSLocation();

operator bool() const;

enum GNSSfixType fixType(void) const;
enum GNSSfixQuality fixQuality(void) const;
bool fullyResolved(void) const;
unsigned int satellites(void) const;

uint16_t year(void) const;
Expand All @@ -69,7 +72,7 @@ class GNSSLocation {
uint8_t minutes(void) const;
uint8_t seconds(void) const;
uint16_t millis(void) const;
uint8_t leapSeconds(void) const;
int8_t leapSeconds(void) const;

double latitude(void) const; // WGS84
double longitude(void) const; // WGS84
Expand Down Expand Up @@ -167,21 +170,28 @@ class GNSSClass {
bool setAutonomous(bool enable);
bool setPlatform(GNSSplatform platform);
bool setPeriodic(unsigned int acqTime, unsigned int onTime, unsigned int period);
bool sleep();
bool wakeup();
bool suspend();
bool resume();
bool busy();

bool location(GNSSLocation &location);
bool satellites(GNSSSatellites &satellites);

void enableWakeup();
void disableWakeup();

void onLocation(void(*callback)(void));
void onLocation(Callback callback);
void onSatellites(void(*callback)(void));
void onSatellites(Callback callback);

void attachInterrupt(void(*callback)(void));
void detachInterrupt();

private:
Uart *_uart;
uint32_t _baudrate;
bool _wakeup;
gnss_location_t _location_data;
volatile uint32_t _location_pending;
gnss_satellites_t _satellites_data;
Expand All @@ -190,15 +200,18 @@ class GNSSClass {
Callback _locationCallback;
Callback _satellitesCallback;

void (*_ppsCallback)(void);
void (*_doneCallback)(void);

void receiveCallback(void);
void completionCallback(void);

void (*_doneCallback)(void);
static void sendRoutine(class GNSSClass*, const uint8_t*, uint32_t, gnss_send_callback_t);
static void enableCallback(class GNSSClass*);
static void disableCallback(class GNSSClass*);
static void locationCallback(class GNSSClass*, const gnss_location_t*);
static void satellitesCallback(class GNSSClass*, const gnss_satellites_t*);
static void ppsCallback(class GNSSClass*);
};

extern GNSSClass GNSS;
Expand Down
Loading

0 comments on commit aa9037c

Please sign in to comment.