Compare commits

...

10 Commits

19 changed files with 38 additions and 2709 deletions

View File

@ -26,7 +26,7 @@ BINARY = firmware
# which development board is used
# supported are: SYSTEM_BOARD, MAPLE_MINI, BLUE_PILL
BOARD = BLUE_PILL
BOARD = SYSTEM_BOARD
# source files
CSRC = $(wildcard *.c)

View File

@ -14,7 +14,7 @@ More information is available on the [wiki](https://wiki.cuvoodoo.info/doku.php?
board
-----
The development board used for this project is a [blue pill](https://wiki.cuvoodoo.info/doku.php?id=stm32f1xx#blue_pill).
The development board used for this project is a [system board](https://wiki.cuvoodoo.info/doku.php?id=stm32f1xx#system_board).
This offers a [STM32F103C8T6 micro-controller](http://www.st.com/web/en/catalog/mmc/FM141/SC1169/SS1031).
peripherals
@ -30,8 +30,6 @@ LED
- query (yellow): goes on when starting to query the measurement values from all electricity meters, and goes off when it received all values.
- submit (blue): goes on when it start submitting the values to the database (using an HTTP POST on influxDB), and goes off when the submission succeeded.
Note: don't use the onboard LED on PC13 on the blue pill as switching it heavily influences the RTC.
Connections LED (cathode) <-> board (all LED anodes are connected to the +3.3V rail):
- power; GND
@ -64,17 +62,6 @@ Connections DDM100TC <-> board:
- S0+, pin 8; +3.3V or +5V
- S0-, pin 7; PB6, TIM4_CH1 (add pull-down resistor)
PZEM-004T
---------
This 1-phase 2-wire electricity meter provides a UART interface.
For the 3-phase 4-wire power distribution installation I used 3 meters, one per phase.
Because each command includes a device address, they can be connected to the same UART port (one individual addresses have been set).
All meters are periodically (see RTC) sequentially queried for their measurements (voltage, current, power, energy).
The used addresses are hard coded in `main.c`
A timer is used to guarantee a minimum (undocumented in the specification) time between requests in order to improve the response success.
Connections 3xPZEM-004T <-> board:
- 5V, 1; +5V (+3.3V is not sufficient)
@ -101,8 +88,8 @@ Connections 3xSDM120 <-> board:
- VCC; +5V
- GND; ground
- DI; PB10, USART3_TX
- DE; PB1 (shared with RE since one is active low while the other is active high)
- RE; PB1 (shared with DE since one is active low while the other is active high)
- DE; PB12 (shared with RE since one is active low while the other is active high)
- RE; PB12 (shared with DE since one is active low while the other is active high)
- RO; PB11, USART3_RX
ESP8266
@ -125,12 +112,12 @@ The hostname, port, database name, user name, and password are hard coded in `ma
Connections ESP-01 <-> board:
- GND, pin 1; ground
- TX, pin 2; PA10, USART1_RX
- TX, pin 2; PA3, USART2_RX
- GPIO2, pin 3; not connected
- CH_PD, pin 4; pull-up resistor
- GPIO0, pin 5; not connected
- RST, pin 6; pull-up resistor
- RX, pin 7; PA9, USART1_TX
- RX, pin 7; PA2, USART2_TX
- VCC, pin 8; +3.3V (add a large capacitor to cope with power spikes)
code

View File

@ -1,111 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to read/write internal flash (code)
* @file flash_internal.c
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note peripherals used: none
*/
/* standard libraries */
#include <stdint.h> // standard integer types
#include <stdlib.h> // general utilities
/* STM32 (including CM3) libraries */
#include <libopencm3/stm32/desig.h> // device signature utilities
#include <libopencm3/stm32/flash.h> // flash utilities
#include "flash_internal.h" // flash storage library API
#include "global.h" // global definitions
/** the flash page size (medium-density devices have 1KiB page size) */
#define PAGE_SIZE 1024
bool flash_internal_read(uint32_t address, uint8_t *buffer, size_t size)
{
// verify it's in the storage area
if (address<STORAGE_START || (address+size)>STORAGE_END) {
return false;
}
if (buffer==NULL || size==0) {
return false;
}
// copy data byte per byte
// a more efficient way would be to copy words, than the remaining bytes
for (size_t i=0; i<size; i++) {
buffer[i] = *((uint8_t*)address+i);
}
return true;
}
bool flash_internal_write(uint32_t address, uint8_t *buffer, size_t size)
{
// verify it's in the storage area
if (address<STORAGE_START || (address+size)>STORAGE_END) {
return false;
}
if (buffer==NULL || size==0) {
return false;
}
uint8_t page[PAGE_SIZE]; // the complete page to write
flash_unlock(); // unlock flash to be able to write it
// go through memory
while (size) {
uint32_t page_pre = address%PAGE_SIZE; // the beginning data size in the page
address -= page_pre; // go to beginning of the page
storage_read(address, &page[0], page_pre); // copy existing data
if (size>=PAGE_SIZE-page_pre) { // no need to read tailing page data
for (uint16_t i=0; i<PAGE_SIZE-page_pre; i++) { // put buffer in page
page[page_pre+i] = buffer[i];
}
buffer += PAGE_SIZE-page_pre; // adjust remaining buffer
size -= PAGE_SIZE-page_pre; // adjust remaining size
} else { // need read tailing page data
for (uint16_t i=0; i<size; i++) { // put buffer in page
page[page_pre+i] = buffer[i];
}
buffer += size; // adjust remaining buffer
storage_read(address+page_pre+size, &page[page_pre+size], PAGE_SIZE-page_pre-size); // read tailing page data
size = 0; // adjust remaining size
}
// write page
flash_erase_page(address); // erase current page
if (flash_get_status_flags()!=FLASH_SR_EOP) { // operation went wrong
flash_lock(); // lock back flash to protect it
return false;
}
for (uint16_t i=0; i<PAGE_SIZE/2; i++) { // write whole page
flash_program_half_word(address+i*2, *((uint16_t*)page+i));
if (flash_get_status_flags()!=FLASH_SR_EOP) { // operation went wrong
flash_lock(); // lock back flash to protect it
return false;
}
if (*((uint16_t*)address+i)!=*((uint16_t*)page+i)) { // verify the programmed data is right
flash_lock(); // lock back flash to protect it
return false;
}
}
address += PAGE_SIZE; // go to next page
}
flash_lock(); // lock back flash to protect it
return true;
}

View File

@ -1,45 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to read/write internal flash (API)
* @file flash_internal.h
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note peripherals used: none
*/
#pragma once
#include <libopencm3/stm32/desig.h> // device signature utilities
/** how much data (in bytes) should we be able to store (be sure it's available and does not overlap the firmware) */
#define STORAGE_SIZE 2048
/** the end of the flash area where to store data */
#define STORAGE_END FLASH_BASE+DESIG_FLASH_SIZE
/** the start of the flash area where to store data (be sure it's after the firmware data) */
#define STORAGE_START STORAGE_END-STORAGE_SIZE
/** read data from internal flash
* @param[in] address start address of the data to read
* @param[out] buffer where to store the read data
* @param[in] size how much data to read, in bytes
* @return if read succeeded
*/
bool flash_internal_read(uint32_t address, uint8_t *buffer, size_t size);
/** write data to internal flash
* @param[in] address start address where to write data to
* @param[in] buffer data to be written
* @param[in] size how much data to write, in bytes
* @return if write succeeded
*/
bool flash_internal_write(uint32_t address, uint8_t *buffer, size_t size);

View File

@ -1,165 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to drive a WS2812B LED chain (code)
* @file led_ws2812b.c
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note peripherals used: SPI @ref led_ws2812b_spi, timer @ref led_ws2812b_timer, DMA @ref led_ws2812b_dma
*/
/* standard libraries */
#include <stdint.h> // standard integer types
#include <stdlib.h> // general utilities
/* STM32 (including CM3) libraries */
#include <libopencm3/stm32/rcc.h> // real-time control clock library
#include <libopencm3/stm32/gpio.h> // general purpose input output library
#include <libopencm3/stm32/spi.h> // SPI library
#include <libopencm3/stm32/timer.h> // timer library
#include <libopencm3/stm32/dma.h> // DMA library
#include <libopencm3/cm3/nvic.h> // interrupt handler
#include <libopencmsis/core_cm3.h> // Cortex M3 utilities
#include "led_ws2812b.h" // LED WS2812B library API
#include "global.h" // common methods
/** bit template to encode one byte to be shifted out by SPI to the WS2812B LEDs
* @details For each WS2812B bit which needs to be transfered we require to transfer 3 SPI bits.
* The first SPI bit is the high start of the WS2812B bit frame.
* The second SPI bit determines if the WS2812B bit is a 0 or 1.
* The third SPI bit is the last part of the WS2812B bit frame, which is always low.
* The binary pattern is 0b100100100100100100100100
*/
#define LED_WS2812B_SPI_TEMPLATE 0x924924
uint8_t led_ws2812b_data[LED_WS2812B_LEDS*3*3+40*3/8+1] = {0}; /**< data encoded to be shifted out by SPI for the WS2812B, plus the 50us reset (~40 data bits) */
static volatile bool transmit_flag = false; /**< flag set in software when transmission started, clear by interrupt when transmission completed */
void led_ws2812b_set_rgb(uint16_t led, uint8_t red, uint8_t green, uint8_t blue)
{
// verify the led exists
if (led>=LED_WS2812B_LEDS) {
return;
}
// wait for transmission to complete before changing the color
while (transmit_flag) {
__WFI();
}
const uint8_t colors[] = {green, red, blue}; // color order for the WS2812B
const uint8_t pattern_bit[] = {0x02, 0x10, 0x80, 0x04, 0x20, 0x01, 0x08, 0x40}; // which bit to change in the pattern
const uint8_t pattern_byte[] = {2,2,2,1,1,0,0,0}; // in which byte in the pattern to write the pattern bit
for (uint8_t color=0; color<LENGTH(colors); color++) { // colors are encoded similarly
// fill the middle bit (fixed is faster than calculating it)
for (uint8_t bit=0; bit<8; bit++) { // bit from the color to set/clear
if (colors[color]&(1<<bit)) { // setting bit
led_ws2812b_data[led*3*3+color*3+pattern_byte[bit]] |= pattern_bit[bit]; // setting bit is pattern
} else { // clear bit
led_ws2812b_data[led*3*3+color*3+pattern_byte[bit]] &= ~pattern_bit[bit]; // clearing bit is pattern
}
}
}
}
bool led_ws2812b_transmit(void)
{
if (transmit_flag) { // a transmission is already ongoing
return false;
}
transmit_flag = true; // remember transmission started
dma_set_memory_address(LED_WS2812B_DMA, LED_WS2812B_DMA_CH, (uint32_t)led_ws2812b_data);
dma_set_number_of_data(LED_WS2812B_DMA, LED_WS2812B_DMA_CH, LENGTH(led_ws2812b_data)); // set the size of the data to transmit
dma_enable_transfer_complete_interrupt(LED_WS2812B_DMA, LED_WS2812B_DMA_CH); // warm when transfer is complete to stop transmission
dma_enable_channel(LED_WS2812B_DMA, LED_WS2812B_DMA_CH); // enable DMA channel
spi_enable_tx_dma(LED_WS2812B_SPI); // use DMA to provide data stream to be transfered
timer_set_counter(LED_WS2812B_TIMER, 0); // reset timer counter fro clean clock
timer_enable_counter(LED_WS2812B_TIMER); // start timer to generate clock
return true;
}
void led_ws2812b_setup(void)
{
// setup timer to generate clock of (using PWM): 800kHz*3
rcc_periph_clock_enable(LED_WS2812B_CLK_RCC); // enable clock for GPIO peripheral
gpio_set_mode(LED_WS2812B_CLK_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, LED_WS2812B_CLK_PIN); // set pin as output
rcc_periph_clock_enable(RCC_AFIO); // enable clock for alternate function (PWM)
rcc_periph_clock_enable(LED_WS2812B_TIMER_RCC); // enable clock for timer peripheral
timer_reset(LED_WS2812B_TIMER); // reset timer state
timer_set_mode(LED_WS2812B_TIMER, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); // set timer mode, use undivided timer clock, edge alignment (simple count), and count up
timer_set_prescaler(LED_WS2812B_TIMER, 0); // no prescaler to keep most precise timer (72MHz/2^16=1099<800kHz)
timer_set_period(LED_WS2812B_TIMER, rcc_ahb_frequency/800000/3-1); // set the clock frequency to 800kHz*3bit since we need to send 3 bits to output a 800kbps stream
timer_set_oc_value(LED_WS2812B_TIMER, LED_WS2812B_TIMER_OC, rcc_ahb_frequency/800000/3/2); // duty cycle to 50%
timer_set_oc_mode(LED_WS2812B_TIMER, LED_WS2812B_TIMER_OC, TIM_OCM_PWM1); // set timer to generate PWM (used as clock)
timer_enable_oc_output(LED_WS2812B_TIMER, LED_WS2812B_TIMER_OC); // enable output to generate the clock
// setup SPI to transmit data (we are slave and the clock comes from the above PWM): 3 SPI bits for 1 WS2812B bit
rcc_periph_clock_enable(LED_WS2812B_SPI_PORT_RCC); // enable clock for SPI IO peripheral
gpio_set_mode(LED_WS2812B_SPI_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, LED_WS2812B_SPI_CLK); // set clock as input
gpio_set_mode(LED_WS2812B_SPI_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, LED_WS2812B_SPI_DOUT); // set MISO as output
rcc_periph_clock_enable(RCC_AFIO); // enable clock for SPI alternate function
rcc_periph_clock_enable(LED_WS2812B_SPI_RCC); // enable clock for SPI peripheral
spi_reset(LED_WS2812B_SPI); // clear SPI values to default
spi_set_slave_mode(LED_WS2812B_SPI); // set SPI as slave (since we use the clock as input)
spi_set_bidirectional_transmit_only_mode(LED_WS2812B_SPI); // we won't receive data
spi_set_unidirectional_mode(LED_WS2812B_SPI); // we only need to transmit data
spi_set_dff_8bit(LED_WS2812B_SPI); // use 8 bits for simpler encoding (but there will be more interrupts)
spi_set_clock_polarity_1(LED_WS2812B_SPI); // clock is high when idle
spi_set_clock_phase_1(LED_WS2812B_SPI); // output data on second edge (rising)
spi_send_msb_first(LED_WS2812B_SPI); // send least significant bit first
spi_enable_software_slave_management(LED_WS2812B_SPI); // control the slave select in software (since there is no master)
spi_set_nss_low(LED_WS2812B_SPI); // set NSS low so we can output
spi_enable(LED_WS2812B_SPI); // enable SPI
// do not disable SPI or set NSS high since it will put MISO high, breaking the beginning of the next transmission
// configure DMA to provide the pattern to be shifted out from SPI to the WS2812B LEDs
rcc_periph_clock_enable(LED_WS2812B_DMA_RCC); // enable clock for DMA peripheral
dma_channel_reset(LED_WS2812B_DMA, LED_WS2812B_DMA_CH); // start with fresh channel configuration
dma_set_memory_address(LED_WS2812B_DMA, LED_WS2812B_DMA_CH, (uint32_t)led_ws2812b_data); // set bit pattern as source address
dma_set_peripheral_address(LED_WS2812B_DMA, LED_WS2812B_DMA_CH, (uint32_t)&LED_WS2812B_SPI_DR); // set SPI as peripheral destination address
dma_set_read_from_memory(LED_WS2812B_DMA, LED_WS2812B_DMA_CH); // set direction from memory to peripheral
dma_enable_memory_increment_mode(LED_WS2812B_DMA, LED_WS2812B_DMA_CH); // go through bit pattern
dma_set_memory_size(LED_WS2812B_DMA, LED_WS2812B_DMA_CH, DMA_CCR_MSIZE_8BIT); // read 8 bits from memory
dma_set_peripheral_size(LED_WS2812B_DMA, LED_WS2812B_DMA_CH, DMA_CCR_PSIZE_8BIT); // write 8 bits to peripheral
dma_set_priority(LED_WS2812B_DMA, LED_WS2812B_DMA_CH, DMA_CCR_PL_HIGH); // set priority to high since time is crucial for the peripheral
nvic_enable_irq(LED_WS2812B_DMA_IRQ); // enable interrupts for this DMA channel
// fill buffer with bit pattern
for (uint16_t i=0; i<LED_WS2812B_LEDS*3; i++) {
led_ws2812b_data[i*3+0] = (uint8_t)(LED_WS2812B_SPI_TEMPLATE>>16);
led_ws2812b_data[i*3+1] = (uint8_t)(LED_WS2812B_SPI_TEMPLATE>>8);
led_ws2812b_data[i*3+2] = (uint8_t)(LED_WS2812B_SPI_TEMPLATE>>0);
}
// fill remaining with with 0 to encode the reset code
for (uint16_t i=LED_WS2812B_LEDS*3*3; i<LENGTH(led_ws2812b_data); i++) {
led_ws2812b_data[i] = 0;
}
led_ws2812b_transmit(); // set LEDs
}
/** DMA interrupt service routine to stop transmission after it finished */
void LED_WS2812B_DMA_ISR(void)
{
if (dma_get_interrupt_flag(LED_WS2812B_DMA, LED_WS2812B_DMA_CH, DMA_TCIF)) { // transfer completed
dma_clear_interrupt_flags(LED_WS2812B_DMA, LED_WS2812B_DMA_CH, DMA_TCIF); // clear flag
dma_disable_transfer_complete_interrupt(LED_WS2812B_DMA, LED_WS2812B_DMA_CH); // stop warning transfer completed
spi_disable_tx_dma(LED_WS2812B_SPI); // stop SPI asking for more data
while (SPI_SR(LED_WS2812B_SPI) & SPI_SR_BSY); // wait for data to be shifted out
timer_disable_counter(LED_WS2812B_TIMER); // stop clock
dma_disable_channel(LED_WS2812B_DMA, LED_WS2812B_DMA_CH); // stop using DMA
transmit_flag = false; // transmission completed
}
}

View File

@ -1,71 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to drive a WS2812B LED chain (API)
* @file led_ws2812b.h
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note peripherals used: SPI @ref led_ws2812b_spi, timer @ref led_ws2812b_timer, DMA @ref led_ws2812b_dma
*/
#pragma once
/** number of LEDs on the WS2812B strip */
#define LED_WS2812B_LEDS 48
/** peripheral configuration */
/** @defgroup led_ws2812b_spi SPI peripheral used to control the WS2812B LEDs
* @{
*/
#define LED_WS2812B_SPI SPI1 /**< SPI peripheral */
#define LED_WS2812B_SPI_DR SPI1_DR /**< SPI data register for the DMA */
#define LED_WS2812B_SPI_RCC RCC_SPI1 /**< SPI peripheral clock */
#define LED_WS2812B_SPI_PORT_RCC RCC_GPIOA /**< SPI I/O peripheral clock */
#define LED_WS2812B_SPI_PORT GPIOA /**< SPI port */
#define LED_WS2812B_SPI_CLK GPIO_SPI1_SCK /**< SPI clock pin (PA5), connect to PWM output */
#define LED_WS2812B_SPI_DOUT GPIO_SPI1_MISO /**< SPI data pin (PA6), connect to WS2812B DIN */
/** @} */
/** @defgroup led_ws2812b_timer timer peripheral used to generate SPI clock
* @{
*/
#define LED_WS2812B_TIMER TIM3 /**< timer peripheral */
#define LED_WS2812B_TIMER_RCC RCC_TIM3 /**< timer peripheral clock */
#define LED_WS2812B_TIMER_OC TIM_OC3 /**< timer output compare used to set PWM frequency */
#define LED_WS2812B_CLK_RCC RCC_GPIOB /**< timer port peripheral clock */
#define LED_WS2812B_CLK_PORT GPIOB /**< timer port */
#define LED_WS2812B_CLK_PIN GPIO_TIM3_CH3 /**< timer pin to output PWM (PB0), connect to SPI clock input */
/** @} */
/** @defgroup led_ws2812b_dma DMA peripheral used to send the data
* @{
*/
#define LED_WS2812B_DMA DMA1 /**< DMA peripheral to put data for WS2812B LED in SPI queue (only DMA1 supports SPI1_TX interrupt) */
#define LED_WS2812B_DMA_RCC RCC_DMA1 /**< DMA peripheral clock */
#define LED_WS2812B_DMA_CH DMA_CHANNEL3 /**< DMA channel (only DMA1 channel 3 supports SPI1_TX interrupt) */
#define LED_WS2812B_DMA_IRQ NVIC_DMA1_CHANNEL3_IRQ /**< DMA channel interrupt signal */
#define LED_WS2812B_DMA_ISR dma1_channel3_isr /**< DMA channel interrupt service routine */
/** @} */
/** setup WS2812B LED driver */
void led_ws2812b_setup(void);
/** set color of a single LED
* @param[in] led the LED number to set the color
* @param[in] red the red color value to set on the LED
* @param[in] green the green color value to set on the LED
* @param[in] blue the blue color value to set on the LED
* @note transmission needs to be done separately
*/
void led_ws2812b_set_rgb(uint16_t led, uint8_t red, uint8_t green, uint8_t blue);
/** transmit color values to WS2812B LEDs
* @return true if transmission started, false if another transmission is already ongoing
*/
bool led_ws2812b_transmit(void);

View File

@ -38,7 +38,7 @@
/** @defgroup radio_esp8266_usart USART peripheral used for communication with radio
* @{
*/
#define RADIO_ESP8266_USART 1 /**< USART peripheral */
#define RADIO_ESP8266_USART 2 /**< USART peripheral */
/** @} */
/* input and output buffers and used memory */

View File

@ -1,191 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to get time from a DCF77 module (code)
* @file rtc_dcf77.c
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note peripherals used: GPIO @ref rtc_dcf77_gpio, timer @ref rtc_dcf77_timer
*/
/* standard libraries */
#include <stdint.h> // standard integer types
#include <stdlib.h> // general utilities
/* STM32 (including CM3) libraries */
#include <libopencm3/stm32/rcc.h> // real-time control clock library
#include <libopencm3/stm32/gpio.h> // general purpose input output library
#include <libopencm3/stm32/spi.h> // SPI library
#include <libopencm3/stm32/timer.h> // timer library
#include <libopencm3/cm3/nvic.h> // interrupt handler
#include <libopencmsis/core_cm3.h> // Cortex M3 utilities
#include "rtc_dcf77.h" // RTC DCF77 library API
#include "global.h" // common methods
volatile bool rtc_dcf77_time_flag = false;
volatile uint64_t rtc_dcf77_frame = 0; /**< the received DCF77 frame bits */
void rtc_dcf77_setup(void)
{
// setup enable output
rcc_periph_clock_enable(RTC_DCF77_ENABLE_RCC); // enable clock GPIO peripheral
gpio_set_mode(RTC_DCF77_ENABLE_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, RTC_DCF77_ENABLE_PIN); // set pin to output push-pull to be able to enable the module
rtc_dcf77_off(); // disable module at start
// setup signal input
rcc_periph_clock_enable(RTC_DCF77_SIGNAL_RCC); // enable clock for signal input peripheral
gpio_set_mode(RTC_DCF77_SIGNAL_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, RTC_DCF77_SIGNAL_PIN); // set signal pin to input
rcc_periph_clock_enable(RCC_AFIO); // enable alternate function clock for external interrupt
exti_select_source(RTC_DCF77_SIGNAL_EXTI, RTC_DCF77_SIGNAL_PORT); // mask external interrupt of this pin only for this port
exti_set_trigger(RTC_DCF77_SIGNAL_EXTI, EXTI_TRIGGER_BOTH); // trigger on both edges
exti_enable_request(RTC_DCF77_SIGNAL_EXTI); // enable external interrupt
nvic_enable_irq(RTC_DCF77_SIGNAL_IRQ); // enable interrupt
// setup timer to measure pulses
rcc_periph_clock_enable(RTC_DCF77_TIMER_RCC); // enable clock for timer peripheral
timer_reset(RTC_DCF77_TIMER); // reset timer state
timer_set_mode(RTC_DCF77_TIMER, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); // set timer mode, use undivided timer clock, edge alignment (simple count), and count up
timer_set_prescaler(RTC_DCF77_TIMER, RTC_DCF77_TIMER_MAX_TIME*(rcc_ahb_frequency/1000)/(1<<16)); // set prescaler to count up to the maximum time
timer_enable_counter(RTC_DCF77_TIMER); // start timer to measure time
}
void rtc_dcf77_on(void)
{
gpio_clear(RTC_DCF77_ENABLE_PORT, RTC_DCF77_ENABLE_PIN); // enable module by pull pin low
}
void rtc_dcf77_off(void)
{
gpio_set(RTC_DCF77_ENABLE_PORT, RTC_DCF77_ENABLE_PIN); // disable module by pull pin high
}
uint8_t* rtc_dcf77_time(void)
{
static uint8_t to_return[6] = {0}; // arrays with date values to return
uint8_t parity = 0; // to check parity
if (rtc_dcf77_frame==0) { // no time received yet
return NULL;
}
if (!(rtc_dcf77_frame&((uint64_t)1<<20))) { // start of encode time should always be 1
return NULL;
}
// check minute parity
parity = 0;
for (uint8_t bit=21; bit<=28; bit++) {
if (rtc_dcf77_frame&((uint64_t)1<<bit)) {
parity++; // count the set bits
}
}
if (parity%2) { // parity should be even
return NULL;
}
to_return[0] = 1*((rtc_dcf77_frame>>21)&(0x1))+2*((rtc_dcf77_frame>>22)&(0x1))+4*((rtc_dcf77_frame>>23)&(0x1))+8*((rtc_dcf77_frame>>24)&(0x1))+10*((rtc_dcf77_frame>>25)&(0x1))+20*((rtc_dcf77_frame>>26)&(0x1))+40*((rtc_dcf77_frame>>27)&(0x1)); // read minute (00-59)
if (to_return[0]>59) { // minutes should not be more than 59
return NULL;
}
// check hour parity
parity = 0;
for (uint8_t bit=29; bit<=35; bit++) {
if (rtc_dcf77_frame&((uint64_t)1<<bit)) {
parity++; // count the set bits
}
}
if (parity%2) { // parity should be even
return NULL;
}
to_return[1] = 1*((rtc_dcf77_frame>>29)&(0x1))+2*((rtc_dcf77_frame>>30)&(0x1))+4*((rtc_dcf77_frame>>31)&(0x1))+8*((rtc_dcf77_frame>>32)&(0x1))+10*((rtc_dcf77_frame>>33)&(0x1))+20*((rtc_dcf77_frame>>34)&(0x1)); // read hour (00-23)
if (to_return[1]>23) { // hours should not be more than 23
return NULL;
}
// check date parity
parity = 0;
for (uint8_t bit=36; bit<=58; bit++) {
if (rtc_dcf77_frame&((uint64_t)1<<bit)) {
parity++; // count the set bits
}
}
if (parity%2) { // parity should be even
return NULL;
}
to_return[2] = 1*((rtc_dcf77_frame>>36)&(0x1))+2*((rtc_dcf77_frame>>37)&(0x1))+4*((rtc_dcf77_frame>>38)&(0x1))+8*((rtc_dcf77_frame>>39)&(0x1))+10*((rtc_dcf77_frame>>40)&(0x1))+20*((rtc_dcf77_frame>>41)&(0x1)); // read day of the month (01-31)
if (to_return[2]==0 || to_return[2]>31) { // day of the month should be 1-31
return NULL;
}
to_return[3] = 1*((rtc_dcf77_frame>>42)&(0x1))+2*((rtc_dcf77_frame>>43)&(0x1))+4*((rtc_dcf77_frame>>44)&(0x1)); // read day of the week (1=Monday - 7=Sunday)
if (to_return[3]==0 || to_return[3]>7) { // day of the week should be 1-7
return NULL;
}
to_return[4] = 1*((rtc_dcf77_frame>>45)&(0x1))+2*((rtc_dcf77_frame>>46)&(0x1))+4*((rtc_dcf77_frame>>47)&(0x1))+8*((rtc_dcf77_frame>>48)&(0x1))+10*((rtc_dcf77_frame>>49)&(0x1)); // read month of the year (01-12)
if (to_return[4]==0 || to_return[4]>12) { // month of the year should be 1-12
return NULL;
}
to_return[5] = 1*((rtc_dcf77_frame>>50)&(0x1))+2*((rtc_dcf77_frame>>51)&(0x1))+4*((rtc_dcf77_frame>>52)&(0x1))+8*((rtc_dcf77_frame>>53)&(0x1))+10*((rtc_dcf77_frame>>54)&(0x1))+20*((rtc_dcf77_frame>>55)&(0x1))+40*((rtc_dcf77_frame>>56)&(0x1))+80*((rtc_dcf77_frame>>57)&(0x1)); // read year of the century (00-99)
if (to_return[5]>99) { // year should be <100
return NULL;
}
return to_return;
}
/** interrupt service routine called when signal edge is detected, decoding the received DCF77 frame (composed by high pulses) */
void RTC_DCF77_SIGNAL_ISR(void)
{
exti_reset_request(RTC_DCF77_SIGNAL_EXTI); // reset interrupt
static uint16_t old_state = 0; // save last port state to detect difference
static uint8_t pulse = 0; // next pulse number in the DCF77 frame
static uint16_t pulse_edge = 0; // time on when the last pulse (rising edge) has been detected
static uint64_t rtc_dcf77_frame_tmp = 0; // the DCF77 frame bits as they get filled
uint16_t time = timer_get_counter(RTC_DCF77_TIMER); // get timer value
uint16_t new_state = gpio_get(RTC_DCF77_SIGNAL_PORT, RTC_DCF77_SIGNAL_PIN); // save last port state to detect difference
if (old_state!=new_state) { // pulse edge detected
time = (uint32_t)(time-pulse_edge)*RTC_DCF77_TIMER_MAX_TIME/(1<<16); // get time since last rising edge (integer underflow possible)
if (new_state) { // rising edge
if (time < 980) { // glitch
goto end; // ignore glitch
} else if (time < 1030) { // a normal pulse
pulse++; // go to next pulse
if (pulse>58) { // something wrong happened
pulse = 0; // restart
}
} else if (time < 1980) { // glitch
goto end; // ignore glitch
} else if (time < 2130) { // first pulse of a frame
if (pulse==58) { // full frame received
rtc_dcf77_frame = rtc_dcf77_frame_tmp; // save received complete frame
rtc_dcf77_time_flag = true; // notify user
}
pulse = 0;
} else { // something is wrong, restart
pulse = 0;
}
pulse_edge = 0; // save new edge
timer_set_counter(RTC_DCF77_TIMER, 0); // reset timer to count
} else { // falling edge
if (time < 90) { // glitch
goto end; // ignore glitch
} else if (time < 120) { // 0 received
rtc_dcf77_frame_tmp &= ~((uint64_t)1<<pulse); // save 0 bit
} else if (time < 190) { // glitch
goto end; // ignore glitch
} else if (time < 220) { // 1 received
rtc_dcf77_frame_tmp |= ((uint64_t)1<<pulse); // save 1 bit
}
}
}
end:
old_state = new_state; // save new state
}

View File

@ -1,57 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to get time from a DCF77 module (API)
* @file rtc_dcf77.h
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note peripherals used: GPIO @ref rtc_dcf77_gpio, timer @ref rtc_dcf77_timer
*/
#pragma once
/** @defgroup rtc_dcf77_gpio output to enable DCF module and input to capture DCF signal
* @{
*/
#define RTC_DCF77_ENABLE_RCC RCC_GPIOA /**< GPIO peripheral clock to enable the module */
#define RTC_DCF77_ENABLE_PORT GPIOA /**< GPIO port to enable the module */
#define RTC_DCF77_ENABLE_PIN GPIO2 /**< GPIO pinto enable the module */
#define RTC_DCF77_SIGNAL_RCC RCC_GPIOA /**< GPIO peripheral clock to capture the DCF signal */
#define RTC_DCF77_SIGNAL_PORT GPIOA /**< GPIO port to capture the DCF signal */
#define RTC_DCF77_SIGNAL_PIN GPIO3 /**< GPIO pin to capture the DCF signal */
#define RTC_DCF77_SIGNAL_EXTI EXTI3 /**< GPIO external interrupt to capture the DCF signal */
#define RTC_DCF77_SIGNAL_IRQ NVIC_EXTI3_IRQ /**< GPIO line interrupt */
#define RTC_DCF77_SIGNAL_ISR exti3_isr /**< GPIO line interrupt service routine */
/** @} */
/** @defgroup rtc_dcf77_timer timer to measure signal puls
* @{
*/
#define RTC_DCF77_TIMER TIM4 /**< timer peripheral */
#define RTC_DCF77_TIMER_RCC RCC_TIM4 /**< timer peripheral clock */
#define RTC_DCF77_TIMER_MAX_TIME 2200 /**< the maximum time in ms the timer can count. DCF77 have pulses < 2s */
/** @} */
/** set when time information has been received */
extern volatile bool rtc_dcf77_time_flag;
/** setup DCF77 time receiver module */
void rtc_dcf77_setup(void);
/** switch on DCF77 time receiver module */
void rtc_dcf77_on(void);
/** switch off DCF77 time receiver module */
void rtc_dcf77_off(void);
/** get last received DCF77 time
* @return array of {minutes (00-49), hours (00-23), date (01-31), day of the week (1-7=Monday-Sunday), month (01-12), year of the century (00-99)} if received time is valid, NULL else
*/
uint8_t* rtc_dcf77_time(void);

View File

@ -1,457 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to communicate with the Maxim DS1307 I2C RTC IC (code)
* @file rtc_ds1307.c
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note user RAM is not handled
* @note peripherals used: I2C @ref rtc_ds1307_i2c, GPIO & timer @ref rtc_ds1307_square_wave_timer
*/
/* standard libraries */
#include <stdint.h> // standard integer types
#include <stdio.h> // standard I/O facilities
#include <stdlib.h> // general utilities
/* STM32 (including CM3) libraries */
#include <libopencm3/stm32/rcc.h> // real-time control clock library
#include <libopencm3/stm32/gpio.h> // general purpose input output library
#include <libopencm3/stm32/i2c.h> // I2C library
#include <libopencm3/cm3/nvic.h> // interrupt handler
#include <libopencmsis/core_cm3.h> // Cortex M3 utilities
#include <libopencm3/stm32/timer.h> // timer utilities
#include "global.h" // global utilities
#include "rtc_ds1307.h" // RTC header and definitions
#if defined(RTC_DS1307_SQUARE_WAVE_TICKS)
volatile uint32_t rtc_ds1307_ticks = 0;
volatile bool rtc_ds1307_tick_flag = false;
#endif
void rtc_ds1307_setup(void)
{
// configure I2C peripheral (see RM008 26.3.3, I2C master)
rcc_periph_clock_enable(RTC_DS1307_I2C_PORT_RCC); // enable clock for I2C I/O peripheral
gpio_set_mode(RTC_DS1307_I2C_PORT, GPIO_MODE_OUTPUT_10_MHZ, GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN, RTC_DS1307_I2C_PIN_SDA | RTC_DS1307_I2C_PIN_SCL); // setup I2C I/O pins
rcc_periph_clock_enable(RCC_AFIO); // enable clock for alternate function
rcc_periph_clock_enable(RTC_DS1307_I2C_RCC); // enable clock for I2C peripheral
i2c_reset(RTC_DS1307_I2C); // reset configuration
i2c_peripheral_disable(RTC_DS1307_I2C); // I2C needs to be disable to be configured
i2c_set_clock_frequency(RTC_DS1307_I2C, rcc_apb1_frequency/1E6); // configure the peripheral clock to the APB1 freq (where it is connected to)
i2c_set_standard_mode(RTC_DS1307_I2C); // the DS1307 has a maximum I2C SCL freq if 100 kHz (corresponding to the standard mode)
i2c_set_ccr(RTC_DS1307_I2C, rcc_apb1_frequency/(100E3*2)); // set Thigh/Tlow to generate frequency of 100 kHz
i2c_set_trise(RTC_DS1307_I2C, rcc_apb1_frequency/1E6); // max rise time for 100 kHz is 1000 ns (~1 MHz)
i2c_peripheral_enable(RTC_DS1307_I2C); // enable I2C after configuration completed
#if defined(RTC_DS1307_SQUARE_WAVE_TICKS)
// setup timer to generate tick from square wave output
rcc_periph_clock_enable(RTC_DS1307_SQUARE_WAVE_GPIO_RCC); // enable clock for GPIO peripheral
gpio_set_mode(RTC_DS1307_SQUARE_WAVE_GPIO_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, RTC_DS1307_SQUARE_WAVE_GPIO_PIN); // set pin as input
gpio_set(RTC_DS1307_SQUARE_WAVE_GPIO_PORT, RTC_DS1307_SQUARE_WAVE_GPIO_PIN); // enable pull-up
rcc_periph_clock_enable(RTC_DS1307_SQUARE_WAVE_TIMER_RCC); // enable clock for timer peripheral
timer_reset(RTC_DS1307_SQUARE_WAVE_TIMER); // reset timer state
timer_ic_set_input(RTC_DS1307_SQUARE_WAVE_TIMER, RTC_DS1307_SQUARE_WAVE_TIMER_IC, RTC_DS1307_SQUARE_WAVE_TIMER_IN); // configure channel as input capture
timer_ic_set_filter(RTC_DS1307_SQUARE_WAVE_TIMER, RTC_DS1307_SQUARE_WAVE_TIMER_IC, TIM_IC_OFF); // use no input capture filter
timer_ic_set_polarity(RTC_DS1307_SQUARE_WAVE_TIMER, RTC_DS1307_SQUARE_WAVE_TIMER_IC, TIM_IC_FALLING); //capture on falling edge
timer_slave_set_trigger(RTC_DS1307_SQUARE_WAVE_TIMER, RTC_DS1307_SQUARE_WAVE_TIMER_TS); // select trigger
timer_slave_set_mode(RTC_DS1307_SQUARE_WAVE_TIMER, TIM_SMCR_SMS_ECM1); // select external clock more 1 as input
timer_ic_enable(RTC_DS1307_SQUARE_WAVE_TIMER, RTC_DS1307_SQUARE_WAVE_TIMER_IC); // enable input capture
timer_set_mode(RTC_DS1307_SQUARE_WAVE_TIMER, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); // set timer mode, use undivided timer clock, edge alignment (simple count), and count up
timer_set_prescaler(RTC_DS1307_SQUARE_WAVE_TIMER, 0); // no need to prescale
timer_set_period(RTC_DS1307_SQUARE_WAVE_TIMER, RTC_DS1307_SQUARE_WAVE_TICKS-1); // set the tick period
timer_enable_irq(RTC_DS1307_SQUARE_WAVE_TIMER, TIM_DIER_UIE); // enable interrupt for timer
nvic_enable_irq(RTC_DS1307_SQUARE_WAVE_TIMER_IRQ); // allow interrupt for timer
rtc_ds1307_tick_flag = false; // reset RTC tick flag
timer_enable_counter(RTC_DS1307_SQUARE_WAVE_TIMER); // enable timer to count ticks
rtc_ds1307_write_square_wave(RTC_DS1307_SQUARE_WAVE_FREQUENCY); // set square wave output frequency
#endif
}
/** read memory from RTC IC
* @param[in] addr start address for memory to read
* @param[out] data buffer to store read memory
* @param[in] len number of byte to read from the memory
* @return if read succeeded
*/
static bool rtc_ds1307_read_memory(uint8_t addr, uint8_t* data, size_t len)
{
bool to_return = false; // return if read succeeded
if (data==NULL || len==0) { // verify there it data to be read
goto error;
}
i2c_send_start(RTC_DS1307_I2C); // send start condition to start transaction
while (!(I2C_SR1(RTC_DS1307_I2C) & I2C_SR1_SB)); // wait until start condition is transmitted
if (!(I2C_SR2(RTC_DS1307_I2C) & I2C_SR2_MSL)) { // verify if in master mode
goto error;
}
i2c_send_7bit_address(RTC_DS1307_I2C, RTC_DS1307_I2C_ADDR, I2C_WRITE); // select slave
while (!(I2C_SR1(RTC_DS1307_I2C) & I2C_SR1_ADDR)); // wait until address is transmitted
if (!((I2C_SR2(RTC_DS1307_I2C) & I2C_SR2_TRA))) { // verify we are in transmit mode (and read SR2 to clear ADDR)
goto error;
}
i2c_send_data(RTC_DS1307_I2C, addr); // send memory address we want to read
while (!(I2C_SR1(RTC_DS1307_I2C) & I2C_SR1_TxE)); // wait until byte has been transmitted
i2c_send_start(RTC_DS1307_I2C); // send restart condition to switch from write to read mode
while (!(I2C_SR1(RTC_DS1307_I2C) & I2C_SR1_SB)); // wait until start condition is transmitted
i2c_send_7bit_address(RTC_DS1307_I2C, RTC_DS1307_I2C_ADDR, I2C_READ); // select slave
while (!(I2C_SR1(RTC_DS1307_I2C) & I2C_SR1_ADDR)); // wait until address is transmitted
if ((I2C_SR2(RTC_DS1307_I2C) & I2C_SR2_TRA)) { // verify we are in read mode (and read SR2 to clear ADDR)
goto error;
}
for (size_t i=0; i<len; i++) { // read bytes
if (i==len-1) { // prepare to sent NACK for last byte
i2c_disable_ack(RTC_DS1307_I2C); // NACK received to stop slave transmission
i2c_send_stop(RTC_DS1307_I2C); // send STOP after receiving byte
} else {
i2c_enable_ack(RTC_DS1307_I2C); // ACK received byte to continue slave transmission
}
while (!(I2C_SR1(RTC_DS1307_I2C) & I2C_SR1_RxNE)); // wait until byte has been received
data[i] = i2c_get_data(RTC_DS1307_I2C); // read received byte
}
to_return = true;
error:
if (I2C_SR2(RTC_DS1307_I2C) & I2C_SR2_BUSY) { // release bus if busy
i2c_send_stop(RTC_DS1307_I2C); // send stop to release bus
}
while (I2C_SR2(RTC_DS1307_I2C) & I2C_SR2_MSL); // wait until bus released (non master mode)
return to_return;
}
bool rtc_ds1307_oscillator_disabled(void)
{
uint8_t data[1] = {0}; // to read data over I2C
rtc_ds1307_read_memory(0, data, LENGTH(data)); // read a single byte containing CH value
return data[0]&0x80; // return CH bit value to indicate if oscillator is disabled
}
uint16_t rtc_ds1307_read_square_wave(void)
{
uint16_t to_return = 0; // square wave frequency to return (in Hz)
uint8_t data[1] = {0}; // to read data over I2C
const uint16_t rtc_ds1307_rs[] = {1, 4096, 8192, 32768}; // RS1/RS0 values
rtc_ds1307_read_memory(7, data, LENGTH(data)); // read a single byte containing control register
if (data[0]&0x10) { // verify if the square wave is enabled (SQWE)
to_return = rtc_ds1307_rs[data[0]&0x03]; // read RS1/RS0 and get value
} else {
to_return = 0; // square wave output is disabled
}
return to_return;
}
uint8_t rtc_ds1307_read_seconds(void)
{
uint8_t to_return = 0; // seconds to return
uint8_t data[1] = {0}; // to read data over I2C
rtc_ds1307_read_memory(0, data, LENGTH(data)); // read a single byte containing seconds value
to_return = ((data[0]&0x70)>>4)*10+(data[0]&0x0f); // convert BCD coding into seconds
return to_return;
}
uint8_t rtc_ds1307_read_minutes(void)
{
uint8_t to_return = 0; // minutes to return
uint8_t data[1] = {0}; // to read data over I2C
rtc_ds1307_read_memory(1, data, LENGTH(data)); // read a single byte containing minutes value
to_return = (data[0]>>4)*10+(data[0]&0x0f); // convert BCD coding into minutes
return to_return;
}
uint8_t rtc_ds1307_read_hours(void)
{
uint8_t to_return = 0; // hours to return
uint8_t data[1] = {0}; // to read data over I2C
rtc_ds1307_read_memory(2, data, LENGTH(data)); // read a single byte containing hours value
if (data[0]&0x40) { // 12 hour mode
if (data[0]&0x02) { // PM
to_return += 12; // add the 12 hours
}
to_return += ((data[0]&0x10)>>4)*10; // convert BCD coding into hours (first digit)
} else {
to_return = ((data[0]&0x30)>>4)*10; // convert BCD coding into hours (first digit)
}
to_return += (data[0]&0x0f); // convert BCD coding into hours (second digit)
return to_return;
}
uint8_t rtc_ds1307_read_day(void)
{
uint8_t to_return = 0; // day to return
uint8_t data[1] = {0}; // to read data over I2C
rtc_ds1307_read_memory(3, data, LENGTH(data)); // read a single byte containing day value
to_return = (data[0]&0x07); // convert BCD coding into days
return to_return;
}
uint8_t rtc_ds1307_read_date(void)
{
uint8_t to_return = 0; // date to return
uint8_t data[1] = {0}; // to read data over I2C
rtc_ds1307_read_memory(4, data, LENGTH(data)); // read a single byte containing date value
to_return = ((data[0]&0x30)>>4)*10+(data[0]&0x0f); // convert BCD coding into date
return to_return;
}
uint8_t rtc_ds1307_read_month(void)
{
uint8_t to_return = 0; // month to return
uint8_t data[1] = {0}; // to read data over I2C
rtc_ds1307_read_memory(5, data, LENGTH(data)); // read a single byte containing month value
to_return = ((data[0]&0x10)>>4)*10+(data[0]&0x0f); // convert BCD coding into month
return to_return;
}
uint8_t rtc_ds1307_read_year(void)
{
uint8_t data[1] = {0}; // to read data over I2C
rtc_ds1307_read_memory(6, data, LENGTH(data)); // read a single byte containing year value
uint8_t to_return = ((data[0]&0xf0)>>4)*10+(data[0]&0x0f); // convert BCD coding into year
return to_return;
}
uint8_t* rtc_ds1307_read_time(void)
{
static uint8_t time[7] = {0}; // store time {seconds, minutes, hours, day, date, month, year}
uint8_t data[7] = {0}; // to read data over I2C
rtc_ds1307_read_memory(0, data, LENGTH(data)); // read all time bytes
time[0] = ((data[0]&0x70)>>4)*10+(data[0]&0x0f); // convert seconds from BCD
time[1] = (data[1]>>4)*10+(data[1]&0x0f); // convert minutes from BCD
time[2] = 0; // re-initialize hours
if (data[2]&0x40) { // 12 hour mode
if (data[2]&0x02) { // PM
time[2] += 12; // add the 12 hours
}
time[2] += ((data[2]&0x10)>>4)*10; // convert BCD coding into hours (first digit)
} else {
time[2] = ((data[2]&0x30)>>4)*10; // convert BCD coding into hours (first digit)
}
time[2] += (data[2]&0x0f); // convert BCD coding into hours (second digit)
time[3] = (data[3]&0x07); // convert BCD coding into days
time[4] = ((data[4]&0x30)>>4)*10+(data[4]&0x0f); // convert BCD coding into date
time[5] = ((data[5]&0x10)>>4)*10+(data[5]&0x0f); // convert BCD coding into month
time[6] = ((data[6]&0xf0)>>4)*10+(data[6]&0x0f); // convert BCD coding into year
return time;
}
/** write memory into RTC IC
* @param[in] addr start address for memory to be written
* @param[in] data buffer to for memory to be written
* @param[in] len number of byte to write into the memory
* @return if write succeeded
*/
static bool rtc_ds1307_write_memory(uint8_t addr, uint8_t* data, size_t len)
{
bool to_return = false; // return if read succeeded
if (data==NULL || len==0) { // verify there it data to be read
goto error;
}
i2c_send_start(RTC_DS1307_I2C); // send start condition to start transaction
while (!(I2C_SR1(RTC_DS1307_I2C) & I2C_SR1_SB)); // wait until start condition is transmitted
if (!(I2C_SR2(RTC_DS1307_I2C) & I2C_SR2_MSL)) { // verify if in master mode
goto error;
}
i2c_send_7bit_address(RTC_DS1307_I2C, RTC_DS1307_I2C_ADDR, I2C_WRITE); // select slave
while (!(I2C_SR1(RTC_DS1307_I2C) & I2C_SR1_ADDR)); // wait until address is transmitted
if (!((I2C_SR2(RTC_DS1307_I2C) & I2C_SR2_TRA))) { // verify we are in transmit mode (and read SR2 to clear ADDR)
goto error;
}
i2c_send_data(RTC_DS1307_I2C, addr); // send memory address we want to read
while (!(I2C_SR1(RTC_DS1307_I2C) & I2C_SR1_TxE)); // wait until byte has been transmitted
for (size_t i=0; i<len; i++) { // write bytes
i2c_send_data(RTC_DS1307_I2C, data[i]); // send byte to be written in memory
while (!(I2C_SR1(RTC_DS1307_I2C) & I2C_SR1_TxE)); // wait until byte has been transmitted
}
to_return = true;
error:
if (I2C_SR2(RTC_DS1307_I2C) & I2C_SR2_BUSY) { // release bus if busy
i2c_send_stop(RTC_DS1307_I2C); // send stop to release bus
}
while (I2C_SR2(RTC_DS1307_I2C) & I2C_SR2_MSL); // wait until bus released (non master mode)
return to_return;
}
bool rtc_ds1307_oscillator_disable(void)
{
uint8_t data[1] = {0}; // to write CH value data over I2C
rtc_ds1307_read_memory(0, data, LENGTH(data)); // read seconds with CH value
data[0] |= 0x80; // set CH to disable oscillator
return rtc_ds1307_write_memory(0, data, LENGTH(data)); // write current seconds with CH value
}
bool rtc_ds1307_oscillator_enable(void)
{
uint8_t data[1] = {0}; // to write CH value data over I2C
rtc_ds1307_read_memory(0, data, LENGTH(data)); // read seconds with CH value
data[0] &= 0x7f; // clear CH to enable oscillator
return rtc_ds1307_write_memory(0, data, LENGTH(data)); // write current seconds with CH value
}
bool rtc_ds1307_write_square_wave(uint16_t frequency)
{
uint8_t data[1] = {0}; // to write control register value data over I2C
switch (frequency) { // set RS1/RS0 based on frequency
case 0:
data[0] = 0;
break;
case 1:
data[0] = 0|(1<<4);
break;
case 4096:
data[0] = 1|(1<<4);
break;
case 8192:
data[0] = 2|(1<<4);
break;
case 32768:
data[0] = 3|(1<<4);
break;
default: // unspecified frequency
return false;
}
return rtc_ds1307_write_memory(7, data, LENGTH(data)); // write current seconds with CH value
}
bool rtc_ds1307_write_seconds(uint8_t seconds)
{
if (seconds>59) {
return false;
}
uint8_t data[1] = {0}; // to read CH value data and write seconds value over I2C
if (!rtc_ds1307_read_memory(0, data, LENGTH(data))) { // read seconds with CH value
return false;
}
data[0] &= 0x80; // only keep CH flag
data[0] |= (((seconds/10)%6)<<4)+(seconds%10); // encode seconds in BCD format
return rtc_ds1307_write_memory(0, data, LENGTH(data)); // write current seconds with previous CH value
}
bool rtc_ds1307_write_minutes(uint8_t minutes)
{
if (minutes>59) {
return false;
}
uint8_t data[1] = {0}; // to write time value
data[0] = (((minutes/10)%6)<<4)+(minutes%10); // encode minutes in BCD format
return rtc_ds1307_write_memory(1, data, LENGTH(data)); // write time value on RTC
}
bool rtc_ds1307_write_hours(uint8_t hours)
{
if (hours>24) {
return false;
}
uint8_t data[1] = {0}; // to write time value
data[0] = (((hours/10)%3)<<4)+(hours%10); // encode hours in BCD 24h format
return rtc_ds1307_write_memory(2, data, LENGTH(data)); // write time value on RTC
}
bool rtc_ds1307_write_day(uint8_t day)
{
if (day<1 || day>7) {
return false;
}
uint8_t data[1] = {0}; // to write time value
data[0] = (day%8); // encode day in BCD format
return rtc_ds1307_write_memory(3, data, LENGTH(data)); // write time value on RTC
}
bool rtc_ds1307_write_date(uint8_t date)
{
if (date<1 || date>31) {
return false;
}
uint8_t data[1] = {0}; // to write time value
data[0] = (((date/10)%4)<<4)+(date%10); // encode date in BCD format
return rtc_ds1307_write_memory(4, data, LENGTH(data)); // write time value on RTC
}
bool rtc_ds1307_write_month(uint8_t month)
{
if (month<1 || month>12) {
return false;
}
uint8_t data[1] = {0}; // to write time value
data[0] = (((month/10)%2)<<4)+(month%10); // encode month in BCD format
return rtc_ds1307_write_memory(5, data, LENGTH(data)); // write time value on RTC
}
bool rtc_ds1307_write_year(uint8_t year)
{
if (year>99) {
return false;
}
uint8_t data[1] = {0}; // to write time value
data[0] = (((year/10)%10)<<4)+(year%10); // encode year in BCD format
return rtc_ds1307_write_memory(6, data, LENGTH(data)); // write time value on RTC
}
bool rtc_ds1307_write_time(uint8_t seconds, uint8_t minutes, uint8_t hours, uint8_t day, uint8_t date, uint8_t month, uint8_t year)
{
uint8_t data[7] = {0}; // to write all time values
// seconds
if (seconds>59) {
return false;
}
if (!rtc_ds1307_read_memory(0, data, 1)) { // read seconds with CH value
return false;
}
data[0] &= 0x80; // only keep CH flag
data[0] |= (((seconds/10)%6)<<4)+(seconds%10); // encode seconds in BCD format
// minutes
if (minutes>59) {
return false;
}
data[1] = (((minutes/10)%6)<<4)+(minutes%10); // encode minutes in BCD format
// hours
if (hours>24) {
return false;
}
data[2] = (((hours/10)%3)<<4)+(hours%10); // encode hours in BCD 24h format
// day
if (day<1 || day>7) {
return false;
}
data[3] = (day%8); // encode day in BCD format
// date
if (date<1 || date>31) {
return false;
}
data[4] = (((date/10)%4)<<4)+(date%10); // encode date in BCD format
// month
if (month<1 || month>12) {
return false;
}
data[5] = (((month/10)%2)<<4)+(month%10); // encode month in BCD format
// year
if (year>99) {
return false;
}
data[6] = (((year/10)%10)<<4)+(year%10); // encode year in BCD format
return rtc_ds1307_write_memory(0, data, LENGTH(data)); // write time values on RTC
}
#if defined(RTC_DS1307_SQUARE_WAVE_TICKS)
/** timer interrupt service routine called when number of ticks have been received */
void RTC_DS1307_SQUARE_WAVE_TIMER_ISR(void)
{
if (timer_get_flag(RTC_DS1307_SQUARE_WAVE_TIMER, TIM_SR_UIF)) { // overflow even happened
timer_clear_flag(RTC_DS1307_SQUARE_WAVE_TIMER, TIM_SR_UIF); // clear flag
rtc_ds1307_ticks++; // increment count
rtc_ds1307_tick_flag = true; // update flag
}
}
#endif

View File

@ -1,162 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to communicate with the Maxim DS1307 I2C RTC IC (API)
* @file rtc_ds1307.h
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note user RAM is not handled
* @note peripherals used: I2C @ref rtc_ds1307_i2c, GPIO & timer @ref rtc_ds1307_square_wave_timer
*/
#pragma once
/** @defgroup rtc_ds1307_i2c I2C peripheral used to communication with the DS1307 RTC IC
* @{
*/
/** I2C peripheral */
#define RTC_DS1307_I2C I2C1 /**< I2C peripheral */
#define RTC_DS1307_I2C_RCC RCC_I2C1 /**< I2C peripheral clock */
#define RTC_DS1307_I2C_PORT_RCC RCC_GPIOB /**< I2C I/O peripheral clock */
#define RTC_DS1307_I2C_PORT GPIOB /**< I2C I/O peripheral port */
#define RTC_DS1307_I2C_PIN_SDA GPIO_I2C1_SDA /**< I2C peripheral data pin (PB7) */
#define RTC_DS1307_I2C_PIN_SCL GPIO_I2C1_SCL /**< I2C peripheral clock pin (PB6) */
#define RTC_DS1307_I2C_ADDR 0x68 /**< DS1307 I2C address (fixed to 0b1101000) */
/** @} */
/** @defgroup rtc_ds1307_square_wave_timer timer peripheral used to count timer based on RTC IC square wave output
* @note comment out SQUARE_WAVE_TICS to not disable feature
* @{
*/
#define RTC_DS1307_SQUARE_WAVE_TICKS (RTC_DS1307_SQUARE_WAVE_FREQUENCY/256) /**< number of square wave tics before setting rtc_ds1307_tic_flag */
#define RTC_DS1307_SQUARE_WAVE_FREQUENCY 4096 /**< square wave output frequency from the RTC IC */
#define RTC_DS1307_SQUARE_WAVE_TIMER TIM2 /**< timer peripheral */
#define RTC_DS1307_SQUARE_WAVE_TIMER_RCC RCC_TIM2 /**< timer peripheral clock */
#define RTC_DS1307_SQUARE_WAVE_TIMER_IC TIM_IC1 /**< input capture channel (for TIM2_CH1) */
#define RTC_DS1307_SQUARE_WAVE_TIMER_IN TIM_IC_IN_TI1 /**< input capture input source (TIM2_CH1 becomes TI1, then TI1F, then TI1FP1) */
#define RTC_DS1307_SQUARE_WAVE_TIMER_TS TIM_SMCR_TS_IT1FP1 /**< input capture trigger (actually TI1FP1) */
#define RTC_DS1307_SQUARE_WAVE_TIMER_IRQ NVIC_TIM2_IRQ /**< timer interrupt */
#define RTC_DS1307_SQUARE_WAVE_TIMER_ISR tim2_isr /**< timer interrupt service routine */
#define RTC_DS1307_SQUARE_WAVE_GPIO_RCC RCC_GPIOA /**< timer port peripheral clock (TIM2_CH1 on PA0)*/
#define RTC_DS1307_SQUARE_WAVE_GPIO_PORT GPIOA /**< timer port (TIM2_CH1 on PA0) */
#define RTC_DS1307_SQUARE_WAVE_GPIO_PIN GPIO_TIM2_CH1_ETR /**< timer pin input, connect to RTC IC square wave output (TIM2_CH1 on PA0) */
/** @} */
#if defined(RTC_DS1307_SQUARE_WAVE_TICKS)
extern volatile uint32_t rtc_ds1307_ticks; /**< increment on SQUARE_WAVE_TICS square wave ticks */
extern volatile bool rtc_ds1307_tick_flag; /**< set on SQUARE_WAVE_TICS square wave ticks */
#endif
/** setup communication with RTC IC
* configure the I2C port defined in the sources
*/
void rtc_ds1307_setup(void);
/** verify if oscillator is disabled
* @return if oscillator is disabled
*/
bool rtc_ds1307_oscillator_disabled(void);
/** read square wave output frequency (in Hz)
* @return square wave output frequency in Hz, 0 if disabled
*/
uint16_t rtc_ds1307_read_square_wave(void);
/** read seconds from RTC IC
* @return number of seconds (0-59) of the current time
*/
uint8_t rtc_ds1307_read_seconds(void);
/** read minutes from RTC IC
* @return number of minutes (0-59) of the current time
*/
uint8_t rtc_ds1307_read_minutes(void);
/** read hours from RTC IC
* @return number of hours (0-23) of the current time
*/
uint8_t rtc_ds1307_read_hours(void);
/** read day from RTC IC
* @return day of the week (1-7, 1 is Sunday) of the current time, 1 being Sunday
*/
uint8_t rtc_ds1307_read_day(void);
/** read date from RTC IC
* @return day of the month (1-31) of the current time
*/
uint8_t rtc_ds1307_read_date(void);
/** read month from RTC IC
* @return month of the year (1-12) of the current time
*/
uint8_t rtc_ds1307_read_month(void);
/** read year from RTC IC
* @return year of the century (00-99) of the current time
*/
uint8_t rtc_ds1307_read_year(void);
/** read time from RTC IC
* @return array of {seconds, minutes, hours, day, date, month, year} as defined above
*/
uint8_t* rtc_ds1307_read_time(void);
/** disable RTC IC oscillator
* @return if disabling oscillator succeeded
*/
bool rtc_ds1307_oscillator_disable(void);
/** enable RTC IC oscillator
* @return if enabling oscillator succeeded
*/
bool rtc_ds1307_oscillator_enable(void);
/** write square wave output frequency (in Hz)
* @param[in] frequency square wave output frequency in Hz (0 to disable, 1, 4096, 8192, 32768)
* @return if write succeeded
*/
bool rtc_ds1307_write_square_wave(uint16_t frequency);
/** write seconds into RTC IC
* @param[in] seconds number of seconds (0-59)
* @return if write succeeded
*/
bool rtc_ds1307_write_seconds(uint8_t seconds);
/** write minutes into RTC IC
* @param[in] minutes number of minutes (0-59)
* @return if write succeeded
*/
bool rtc_ds1307_write_minutes(uint8_t minutes);
/** write hours into RTC IC
* @param[in] hours number of hours (0-23)
* @return if write succeeded
*/
bool rtc_ds1307_write_hours(uint8_t hours);
/** write day into RTC IC
* @param[in] day day of the week (1-7, 1 is Sunday)
* @return if write succeeded
*/
bool rtc_ds1307_write_day(uint8_t day);
/** write date into RTC IC
* @param[in] date day of the month (1-31)
* @return if write succeeded
*/
bool rtc_ds1307_write_date(uint8_t date);
/** write month into RTC IC
* @param[in] month month of the year (1-12)
* @return if write succeeded
*/
bool rtc_ds1307_write_month(uint8_t month);
/** write year into RTC IC
* @param[in] year year of the century (00-99)
* @return if write succeeded
*/
bool rtc_ds1307_write_year(uint8_t year);
/** write time into RTC IC
* @param[in] seconds number of seconds (0-59)
* @param[in] minutes number of minutes (0-59)
* @param[in] hours number of hours (0-23)
* @param[in] day day of the week (1-7, 1 is Sunday)
* @param[in] date day of the month (1-31)
* @param[in] month month of the year (1-12)
* @param[in] year year of the century (00-99)
* @return if write succeeded
*/
bool rtc_ds1307_write_time(uint8_t seconds, uint8_t minutes, uint8_t hours, uint8_t day, uint8_t date, uint8_t month, uint8_t year);

View File

@ -1,214 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to query measurements from peacefair PZEM-004 and PZEM-004T electricity meter (code)
* @file sensor_pzem.c
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note peripherals used: USART @ref sensor_pzem_usart, timer @ref sensor_pzem_timer
*/
/* standard libraries */
#include <stdint.h> // standard integer types
#include <stdlib.h> // general utilities
/* STM32 (including CM3) libraries */
#include <libopencmsis/core_cm3.h> // Cortex M3 utilities
#include <libopencm3/cm3/nvic.h> // interrupt handler
#include <libopencm3/stm32/rcc.h> // real-time control clock library
#include <libopencm3/stm32/gpio.h> // general purpose input output library
#include <libopencm3/stm32/usart.h> // universal synchronous asynchronous receiver transmitter library
#include <libopencm3/stm32/timer.h> // timer utilities
/* own libraries */
#include "sensor_pzem.h" // PZEM electricity meter header and definitions
#include "global.h" // common methods
/** @defgroup sensor_pzem_usart USART peripheral used for communication with electricity meter
* @{
*/
#define SENSOR_PZEM_USART 2 /**< USART peripheral */
/** @} */
/** @defgroup sensor_pzem_timer timer peripheral used for waiting before sending the next request
* @{
*/
#define SENSOR_PZEM_TIMER 2 /**< timer peripheral */
/** @} */
/* input and output ring buffer, indexes, and available memory */
static uint8_t rx_buffer[7] = {0}; /**< buffer for received response */
static volatile uint8_t rx_i = 0; /**< current position of read received data */
static uint8_t tx_buffer[7] = {0}; /**< buffer for request to transmit */
static volatile uint8_t tx_i = 0; /**< current position of transmitted data */
volatile bool sensor_pzem_measurement_received = false;
void sensor_pzem_setup(void)
{
/* enable USART I/O peripheral */
rcc_periph_clock_enable(RCC_AFIO); // enable pin alternate function (USART)
rcc_periph_clock_enable(USART_PORT_RCC(SENSOR_PZEM_USART)); // enable clock for USART port peripheral
rcc_periph_clock_enable(USART_RCC(SENSOR_PZEM_USART)); // enable clock for USART peripheral
gpio_set_mode(USART_PORT(SENSOR_PZEM_USART), GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, USART_PIN_TX(SENSOR_PZEM_USART)); // setup GPIO pin USART transmit
gpio_set_mode(USART_PORT(SENSOR_PZEM_USART), GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, USART_PIN_RX(SENSOR_PZEM_USART)); // setup GPIO pin USART receive
gpio_set(USART_PORT(SENSOR_PZEM_USART), USART_PIN_RX(SENSOR_PZEM_USART)); // pull up to avoid noise when not connected
/* setup USART parameters for electricity meter: 9600 8N1 */
usart_set_baudrate(USART(SENSOR_PZEM_USART), 9600); // the electricity meter uses a fixed baud rate of 9600 bps
usart_set_databits(USART(SENSOR_PZEM_USART), 8);
usart_set_stopbits(USART(SENSOR_PZEM_USART), USART_STOPBITS_1);
usart_set_mode(USART(SENSOR_PZEM_USART), USART_MODE_TX_RX);
usart_set_parity(USART(SENSOR_PZEM_USART), USART_PARITY_NONE);
usart_set_flow_control(USART(SENSOR_PZEM_USART), USART_FLOWCONTROL_NONE);
nvic_enable_irq(USART_IRQ(SENSOR_PZEM_USART)); // enable the USART interrupt
usart_enable_rx_interrupt(USART(SENSOR_PZEM_USART)); // enable receive interrupt
usart_enable(USART(SENSOR_PZEM_USART)); // enable USART
// setup timer to wait for minimal time before next transmission (after previous transmission or reception)
rcc_periph_clock_enable(RCC_TIM(SENSOR_PZEM_TIMER)); // enable clock for timer block
timer_reset(TIM(SENSOR_PZEM_TIMER)); // reset timer state
timer_set_mode(TIM(SENSOR_PZEM_TIMER), TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); // set timer mode, use undivided timer clock,edge alignment (simple count), and count up
timer_one_shot_mode(TIM(SENSOR_PZEM_TIMER)); // stop counter after update event (we only need to count down once)
timer_set_prescaler(TIM(SENSOR_PZEM_TIMER), 550-1); // set the prescaler so this 16 bits timer allows to wait for maximum 500 ms ( 1/(72E6/550/(2**16))=500.62ms )
timer_set_period(TIM(SENSOR_PZEM_TIMER), 0xffff/2); // the timing is not defined in the specification. I tested until the communication was reliable (all requests get an response)
timer_clear_flag(TIM(SENSOR_PZEM_TIMER), TIM_SR_UIF); // clear flag
timer_enable_irq(TIM(SENSOR_PZEM_TIMER), TIM_DIER_UIE); // enable update interrupt for timer
nvic_enable_irq(NVIC_TIM_IRQ(SENSOR_PZEM_TIMER)); // catch interrupt in service routine
/* reset buffer states */
tx_i = LENGTH(tx_buffer);
rx_i = 0;
sensor_pzem_measurement_received = false;
}
void sensor_pzem_measurement_request(uint32_t address, enum sensor_pzem_measurement_type_t type)
{
if (tx_i<LENGTH(tx_buffer)) { // transmission is ongoing
return;
}
if (type>=SENSOR_PZEM_MAX) { // invalid type
return;
}
tx_buffer[0] = 0xB0+type; // set request nibble and type nibble
tx_buffer[1] = (address>>24)&0xff; // set address
tx_buffer[2] = (address>>16)&0xff; // set address
tx_buffer[3] = (address>>8)&0xff; // set address
tx_buffer[4] = (address>>0)&0xff; // set address
tx_buffer[5] = 0; // only used to set alarm
tx_buffer[6] = 0; // to calculate checksum (sum of all previous bytes)
for (uint8_t i=0; i<LENGTH(tx_buffer)-1; i++) {
tx_buffer[6] += tx_buffer[i]; // calculate buffer
}
tx_i = 0; // remember we have a message to send
if (TIM_CR1(TIM(SENSOR_PZEM_TIMER))&TIM_CR1_CEN) { // timer is already running
// at the end of the timer the transmission will start automatically
} else { // no timer is running
usart_enable_tx_interrupt(USART(SENSOR_PZEM_USART)); // enable interrupt to start sending bytes
//usart_send(USART(SENSOR_PZEM_USART),tx_buffer[tx_i++]); // start transmission
}
sensor_pzem_measurement_received = false; // reset flag
rx_i = 0; // prepare buffer to receive next measurement
}
struct sensor_pzem_measurement_t sensor_pzem_measurement_decode(void)
{
struct sensor_pzem_measurement_t measurement; // decoded measurement to return
measurement.valid = false; // wait until the end to ensure validity
if (rx_i<LENGTH(rx_buffer)) { // buffer is not full, thus no measurement received
return measurement;
}
if ((rx_buffer[0]&0xf0)!=0xa0) { // not a response received
return measurement;
}
if ((rx_buffer[0]&0x0f)>=SENSOR_PZEM_MAX) { // not a valid response type received (actually 4 and 5 are valid, but should not happen when using this code
return measurement;
}
uint8_t checksum = 0; // calculate checksum (sum of all other bytes)
for (uint8_t i=0; i<LENGTH(rx_buffer)-1; i++) {
checksum += rx_buffer[i]; // calculate buffer
}
if (checksum!=rx_buffer[6]) { // checksum does not match
return measurement;
}
measurement.valid = true; // all checks passed
measurement.type = rx_buffer[0]&0x0f; // save type
switch (measurement.type) { // decode value depending on type
case SENSOR_PZEM_VOLTAGE:
measurement.value.voltage = ((uint16_t)rx_buffer[1]<<8)+rx_buffer[2]+rx_buffer[3]*0.1;
break;
case SENSOR_PZEM_CURRENT:
measurement.value.current = rx_buffer[2]+rx_buffer[3]*0.01;
break;
case SENSOR_PZEM_POWER:
measurement.value.power = ((uint16_t)rx_buffer[1]<<8)+rx_buffer[2];
break;
case SENSOR_PZEM_ENERGY:
measurement.value.energy = ((uint32_t)rx_buffer[1]<<16)+((uint16_t)rx_buffer[2]<<8)+rx_buffer[3];
break;
/* not used in this application
case SENSOR_PZEM_ADDRESS:
case SENSOR_PZEM_ALARM:
break; // no value is returned
*/
default:
measurement.valid = false; // unexpected type
}
sensor_pzem_measurement_received = false; // reset flag
rx_i = 0; // prepare buffer to receive next measurement
return measurement;
}
/** USART interrupt service routine called when data has been transmitted or received */
void USART_ISR(SENSOR_PZEM_USART)(void)
{
if (usart_get_interrupt_source(USART(SENSOR_PZEM_USART), USART_SR_TXE)) { // data has been transmitted
if (tx_i<LENGTH(tx_buffer)) { // not all bytes transmitted
usart_send(USART(SENSOR_PZEM_USART),tx_buffer[tx_i++]); // transmit next byte
} else { // request transmitted
usart_disable_tx_interrupt(USART(SENSOR_PZEM_USART)); // disable transmit interrupt
timer_set_counter(TIM(SENSOR_PZEM_TIMER), 0); // reset timer counter to get preset waiting time
timer_enable_counter(TIM(SENSOR_PZEM_TIMER)); // start timer between requests
}
}
if (usart_get_interrupt_source(USART(SENSOR_PZEM_USART), USART_SR_RXNE)) { // data has been received
if (rx_i<LENGTH(rx_buffer)) { // receiving response
rx_buffer[rx_i++] = usart_recv(USART(SENSOR_PZEM_USART)); // put received byte in buffer
if (rx_i>=LENGTH(rx_buffer)) { // buffer full
sensor_pzem_measurement_received = true; // notify used response has been received
}
} else { // previous response not read before receiving the next
usart_recv(USART(SENSOR_PZEM_USART)); // drop received buffer
}
timer_set_counter(TIM(SENSOR_PZEM_TIMER), 0); // reset timer counter to get preset waiting time
timer_enable_counter(TIM(SENSOR_PZEM_TIMER)); // start timer between requests
}
}
/** interrupt service routine called on timeout */
void TIM_ISR(SENSOR_PZEM_TIMER)(void)
{
if (timer_get_flag(TIM(SENSOR_PZEM_TIMER), TIM_SR_UIF)) { // update event happened
timer_clear_flag(TIM(SENSOR_PZEM_TIMER), TIM_SR_UIF); // clear flag
if (tx_i<LENGTH(tx_buffer)) { // bytes are waiting to be sent
usart_enable_tx_interrupt(USART(SENSOR_PZEM_USART)); // enable interrupt to start sending bytes
}
}
}

View File

@ -1,60 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to query measurements from peacefair PZEM-004 and PZEM-004T electricity meter (API)
* @file sensor_pzem.h
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note peripherals used: USART @ref sensor_pzem_usart
*/
#pragma once
/** a measurement response has been received */
extern volatile bool sensor_pzem_measurement_received;
/** measurements (and configurations) offered by electricity meter */
enum sensor_pzem_measurement_type_t {
SENSOR_PZEM_VOLTAGE = 0,
SENSOR_PZEM_CURRENT = 1,
SENSOR_PZEM_POWER = 2,
SENSOR_PZEM_ENERGY = 3,
// SENSOR_PZEM_ADDRESS = 4, // this is a setting, not a measurement
// SENSOR_PZEM_ALARM = 5, // this is a setting, not a measurement
SENSOR_PZEM_MAX
};
/** measurement returned by electricity meter */
struct sensor_pzem_measurement_t {
enum sensor_pzem_measurement_type_t type; /**< measurement type */
bool valid; /**< is the measurement valid (e.g. format and checksum are correct) */
/** possible measurement values */
union measurement_t {
float voltage; /**< measured voltage in volts */
float current; /**< measured current in amperes */
uint16_t power; /**< measured power in watts */
uint32_t energy; /**< measured energy in watts/hour (24 bits) */
} value; /**< measurement value */
};
/** setup peripherals to communicate with electricity meter */
void sensor_pzem_setup(void);
/** request measurement from electricity meter
* @param[in] address electricity meter device address
* @param[in] type measurement type to request
*/
void sensor_pzem_measurement_request(uint32_t address, enum sensor_pzem_measurement_type_t type);
/** decode received measurement
* @return decoded measurement (invalid if no new measurement has been received)
*/
struct sensor_pzem_measurement_t sensor_pzem_measurement_decode(void);

View File

@ -45,7 +45,7 @@
* @{
*/
#define SENSOR_SDM120_REDE_PORT B /**< GPIO port for RS-485 receiver and driver output enable signal */
#define SENSOR_SDM120_REDE_PIN 1 /**< GPIO pin for RS-485 receiver and driver output enable signal */
#define SENSOR_SDM120_REDE_PIN 12 /**< GPIO pin for RS-485 receiver and driver output enable signal */
/** @} */
/** @defgroup sensor_sdm120_timer timer peripheral to enforce waiting time between messages

View File

@ -1,414 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to control up to 4 independent receive and transmit software UART ports (code)
* @file uart_soft.c
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note peripherals used: GPIO @ref uart_soft_gpio, timer @ref uart_soft_timer
*/
/* standard libraries */
#include <stdint.h> // standard integer types
#include <stdlib.h> // general utilities
/* STM32 (including CM3) libraries */
#include <libopencm3/stm32/rcc.h> // real-time control clock library
#include <libopencm3/stm32/gpio.h> // general purpose input output library
#include <libopencm3/stm32/timer.h> // timer library
#include <libopencm3/cm3/nvic.h> // interrupt handler
#include <libopencm3/stm32/exti.h> // external interrupt defines
#include <libopencmsis/core_cm3.h> // Cortex M3 utilities
#include "uart_soft.h" // software UART library API
#include "global.h" // common methods
/** @defgroup uart_soft_gpio GPIO used for the software 4 UART ports
* @note comment if unused
* @warning only one port must be used per line (pin number)
* @{
*/
#define UART_SOFT_RX_PORT0 B /**< port for receive signal for UART port 0 */
#define UART_SOFT_RX_PIN0 9 /**< pin for receive signal for UART port 0 */
//#define UART_SOFT_RX_PORT1 A /**< port for receive signal for UART port 0 */
//#define UART_SOFT_RX_PIN1 0 /**< pin for receive signal for UART port 0 */
//#define UART_SOFT_RX_PORT2 A /**< port for receive signal for UART port 0 */
//#define UART_SOFT_RX_PIN2 0 /**< pin for receive signal for UART port 0 */
//#define UART_SOFT_RX_PORT3 A /**< port for receive signal for UART port 0 */
//#define UART_SOFT_RX_PIN3 0 /**< pin for receive signal for UART port 0 */
#define UART_SOFT_TX_PORT0 B /**< port for transmit signal for UART port 0 */
#define UART_SOFT_TX_PIN0 8 /**< pin for transmit signal for UART port 0 */
//#define UART_SOFT_TX_PORT1 A /**< port for transmit signal for UART port 0 */
//#define UART_SOFT_TX_PIN1 0 /**< pin for transmit signal for UART port 0 */
//#define UART_SOFT_TX_PORT2 A /**< port for transmit signal for UART port 0 */
//#define UART_SOFT_TX_PIN2 0 /**< pin for transmit signal for UART port 0 */
//#define UART_SOFT_TX_PORT3 A /**< port for transmit signal for UART port 0 */
//#define UART_SOFT_TX_PIN3 0 /**< pin for transmit signal for UART port 0 */
/** @} */
/** buffer size for receive and transmit buffers */
#define UART_SOFT_BUFFER 128
/** UART receive state definition */
struct soft_uart_rx_state {
uint32_t port; /**< UART receive port */
uint16_t pin; /**< UART receive pin */
uint32_t rcc; /**< UART receive port peripheral clock */
uint32_t exti; /**< UART receive external interrupt */
uint32_t irq; /**< UART receive interrupt request */
uint32_t baudrate; /**< UART receive baud rate */
volatile uint16_t state; /**< GPIO state for receive pin */
volatile uint8_t bit; /**< next UART frame bit to receive */
volatile uint8_t byte; /**< byte being received */
volatile uint8_t buffer[UART_SOFT_BUFFER]; /**< receive buffer */
volatile uint8_t buffer_i; /**< index of current data to be read out */
volatile uint8_t buffer_used; /**< how much data is available */
volatile bool lock; /**< put lock when changing buffer_i or buffer_used */
volatile uint8_t buffer_byte; /**< to temporary store byte while locked */
volatile bool buffer_byte_used; /**< signal a byte has been stored in temporary buffer */
};
/** UART transmit state definition */
struct soft_uart_tx_state {
uint32_t port; /**< UART receive port */
uint16_t pin; /**< UART receive pin */
uint32_t rcc; /**< UART receive port peripheral clock */
uint32_t baudrate; /**< UART receive baud rate */
volatile uint8_t bit; /**< next UART frame bit to transmit */
volatile uint8_t byte; /**< byte being transmitted */
volatile uint8_t buffer[UART_SOFT_BUFFER]; /**< receive buffer */
volatile uint8_t buffer_i; /**< index of current data to be read out */
volatile uint8_t buffer_used; /**< how much data is available */
volatile bool transmit; /**< flag to know it transmission is ongoing */
};
static struct soft_uart_rx_state* uart_soft_rx_states[4] = {NULL}; /**< states of UART receive ports (up to 4) */
static struct soft_uart_tx_state* uart_soft_tx_states[4] = {NULL}; /**< states of UART transmit ports (up to 4) */
volatile bool uart_soft_received[4] = {false, false, false, false};
/** @defgroup uart_soft_timer timer used to sample UART signals
* @{
*/
#if (defined(UART_SOFT_RX_PORT0) && defined(UART_SOFT_RX_PIN0)) || (defined(UART_SOFT_RX_PORT1) && defined(UART_SOFT_RX_PIN1)) || (defined(UART_SOFT_RX_PORT2) && defined(UART_SOFT_RX_PIN2)) || (defined(UART_SOFT_RX_PORT3) && defined(UART_SOFT_RX_PIN0))
#define UART_SOFT_RX_TIMER 3 /**< timer peripheral for receive signals */
#endif
#if (defined(UART_SOFT_TX_PORT0) && defined(UART_SOFT_TX_PIN0)) || (defined(UART_SOFT_TX_PORT1) && defined(UART_SOFT_TX_PIN1)) || (defined(UART_SOFT_TX_PORT2) && defined(UART_SOFT_TX_PIN2)) || (defined(UART_SOFT_TX_PORT3) && defined(UART_SOFT_TX_PIN0))
#define UART_SOFT_TX_TIMER 4 /**< timer peripheral for transmit signals */
#endif
/** @} */
static const uint32_t timer_flags[4] = {TIM_SR_CC1IF,TIM_SR_CC2IF,TIM_SR_CC3IF,TIM_SR_CC4IF}; /**< the interrupt flags for the compare units */
static const uint32_t timer_interrupt[4] = {TIM_DIER_CC1IE,TIM_DIER_CC2IE,TIM_DIER_CC3IE,TIM_DIER_CC4IE}; /**< the interrupt enable for the compare units */
static const enum tim_oc_id timer_oc[4] = {TIM_OC1,TIM_OC2,TIM_OC3,TIM_OC4}; /**< the output compares for the compare units */
bool uart_soft_setup(uint32_t *rx_baudrates, uint32_t *tx_baudrates)
{
(void)rx_baudrates; // ensure compile does no complain even if no receive port is used
(void)tx_baudrates; // ensure compile does no complain even if no transmit port is used
// save UART receive definition
#if defined(UART_SOFT_RX_PORT0) && defined(UART_SOFT_RX_PIN0)
uart_soft_rx_states[0] = calloc(1,sizeof(struct soft_uart_rx_state)); // create state definition
uart_soft_rx_states[0]->port = GPIO(UART_SOFT_RX_PORT0); // save receive port
uart_soft_rx_states[0]->pin = GPIO(UART_SOFT_RX_PIN0); // save receive pin
uart_soft_rx_states[0]->rcc = RCC_GPIO(UART_SOFT_RX_PORT0); // save receive port peripheral clock
uart_soft_rx_states[0]->exti = EXTI(UART_SOFT_RX_PIN0); // save receive external interrupt
uart_soft_rx_states[0]->irq = NVIC_EXTI_IRQ(UART_SOFT_RX_PIN0); // save receive interrupt request
#endif
// setup UART receive GPIO
for (uint8_t rx=0; rx<4; rx++) {
if (!uart_soft_rx_states[rx]) { // verify is receive UART is defined
continue; // skip configuration if not defined
}
if (!rx_baudrates || rx_baudrates[rx]==0) { // verify if receive baud rate has been defined
return false;
}
uart_soft_rx_states[rx]->baudrate = rx_baudrates[rx]; // save baud rate
rcc_periph_clock_enable(uart_soft_rx_states[rx]->rcc); // enable clock for GPIO peripheral
gpio_set_mode(uart_soft_rx_states[rx]->port, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, uart_soft_rx_states[rx]->pin); // setup GPIO pin UART receive
gpio_set(uart_soft_rx_states[rx]->port, uart_soft_rx_states[rx]->pin); // pull up to avoid noise when not connected
rcc_periph_clock_enable(RCC_AFIO); // enable alternate function clock for external interrupt
exti_select_source(uart_soft_rx_states[rx]->exti, uart_soft_rx_states[rx]->port); // mask external interrupt of this pin only for this port
exti_enable_request(uart_soft_rx_states[rx]->exti); // enable external interrupt
exti_set_trigger(uart_soft_rx_states[rx]->exti, EXTI_TRIGGER_BOTH); // trigger when button is pressed
nvic_enable_irq(uart_soft_rx_states[rx]->irq); // enable interrupt
uart_soft_rx_states[rx]->state = gpio_get(uart_soft_rx_states[rx]->port, uart_soft_rx_states[rx]->pin); // save state of GPIO
uart_soft_rx_states[rx]->bit = 0; // reset bits received
}
// save UART transmit definition
#if defined(UART_SOFT_TX_PORT0) && defined(UART_SOFT_TX_PIN0)
uart_soft_tx_states[0] = calloc(1,sizeof(struct soft_uart_tx_state)); // create state definition
uart_soft_tx_states[0]->port = GPIO(UART_SOFT_TX_PORT0); // save receive port
uart_soft_tx_states[0]->pin = GPIO(UART_SOFT_TX_PIN0); // save receive pin
uart_soft_tx_states[0]->rcc = RCC_GPIO(UART_SOFT_TX_PORT0); // save receive port peripheral clock
#endif
// setup UART transmit GPIO
for (uint8_t tx=0; tx<4; tx++) {
if (!uart_soft_tx_states[tx]) { // verify is transmit UART is defined
continue; // skip configuration if not defined
}
if (!tx_baudrates || tx_baudrates[tx]==0) { // verify if transmit baud rate has been defined
return false;
}
uart_soft_tx_states[tx]->baudrate = tx_baudrates[tx]; // save baud rate
rcc_periph_clock_enable(uart_soft_tx_states[tx]->rcc); // enable clock for GPIO peripheral
gpio_set_mode(uart_soft_tx_states[tx]->port, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, uart_soft_tx_states[tx]->pin); // setup GPIO UART transmit pin
gpio_set(uart_soft_tx_states[tx]->port, uart_soft_tx_states[tx]->pin); // idle high
}
// setup timer
#if defined(UART_SOFT_RX_TIMER)
rcc_periph_clock_enable(RCC_TIM(UART_SOFT_RX_TIMER)); // enable clock for timer peripheral
timer_reset(TIM(UART_SOFT_RX_TIMER)); // reset timer state
timer_set_mode(TIM(UART_SOFT_RX_TIMER), TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); // set timer mode, use undivided timer clock, edge alignment (simple count), and count up
timer_set_prescaler(TIM(UART_SOFT_RX_TIMER), 0); // prescaler to be able to sample 2400-115200 bps (72MHz/2^16=1099<2400bps)
nvic_enable_irq(NVIC_TIM_IRQ(UART_SOFT_RX_TIMER)); // allow interrupt for timer
timer_enable_counter(TIM(UART_SOFT_RX_TIMER)); // start timer to generate interrupts for the receive pins
#endif
#if defined(UART_SOFT_TX_TIMER)
rcc_periph_clock_enable(RCC_TIM(UART_SOFT_TX_TIMER)); // enable clock for timer peripheral
timer_reset(TIM(UART_SOFT_TX_TIMER)); // reset timer state
timer_set_mode(TIM(UART_SOFT_TX_TIMER), TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); // set timer mode, use undivided timer clock, edge alignment (simple count), and count up
timer_set_prescaler(TIM(UART_SOFT_TX_TIMER), 0); // prescaler to be able to output 2400-115200 bps (72MHz/2^16=1099<2400bps)
nvic_enable_irq(NVIC_TIM_IRQ(UART_SOFT_TX_TIMER)); // allow interrupt for timer
timer_enable_counter(TIM(UART_SOFT_TX_TIMER)); // start timer to generate interrupts for the transmit pins
#endif
return true; // setup completed
}
#if defined(UART_SOFT_RX_TIMER)
uint8_t uart_soft_getbyte(uint8_t uart)
{
if (uart>=4 || !uart_soft_rx_states[uart]) { // ensure receive UART port is defined
return 0; // return
}
while (!uart_soft_rx_states[uart]->buffer_used) { // idle until data is available
__WFI(); // sleep until interrupt
}
uart_soft_rx_states[uart]->lock = true; // set lock
uint8_t to_return = uart_soft_rx_states[uart]->buffer[uart_soft_rx_states[uart]->buffer_i]; // get the next available character
uart_soft_rx_states[uart]->buffer_i = (uart_soft_rx_states[uart]->buffer_i+1)%LENGTH(uart_soft_rx_states[uart]->buffer); // update used buffer
uart_soft_rx_states[uart]->buffer_used--; // update used buffer
uart_soft_rx_states[uart]->lock = false; // free lock
if (uart_soft_rx_states[uart]->buffer_byte_used) { // temporary byte has been stored
uart_soft_rx_states[uart]->buffer[(uart_soft_rx_states[uart]->buffer_i+uart_soft_rx_states[uart]->buffer_used)%LENGTH(uart_soft_rx_states[uart]->buffer)] = uart_soft_rx_states[uart]->buffer_byte; // put byte in buffer
uart_soft_rx_states[uart]->buffer_used++; // update used buffer
uart_soft_rx_states[uart]->buffer_byte_used = false; // buffer byte is now in buffer
}
uart_soft_received[uart] = (uart_soft_rx_states[uart]->buffer_used!=0); // notify user if data is available
uart_soft_rx_states[uart]->lock = false; // free lock
return to_return;
}
/** timer interrupt service routine to generate UART transmit signals */
void TIM_ISR(UART_SOFT_RX_TIMER)(void)
{
for (uint8_t rx=0; rx<4; rx++) {
if (timer_interrupt_source(TIM(UART_SOFT_RX_TIMER),timer_flags[rx])) { // got a match on compare for receive pin
timer_clear_flag(TIM(UART_SOFT_RX_TIMER),timer_flags[rx]); // clear flag
if (!uart_soft_rx_states[rx]) { // verify if RX exists
continue; // skip if receive port is not defined it
}
uart_soft_rx_states[rx]->byte += ((gpio_get(uart_soft_rx_states[rx]->port, uart_soft_rx_states[rx]->pin)==0 ? 0 : 1)<<(uart_soft_rx_states[rx]->bit-1)); // save bit value
if (uart_soft_rx_states[rx]->bit<8) { // not the last bit received
timer_set_oc_value(TIM(UART_SOFT_RX_TIMER),timer_oc[rx],timer_get_counter(TIM(UART_SOFT_RX_TIMER))+rcc_ahb_frequency/uart_soft_rx_states[rx]->baudrate); // set timer to next bit
uart_soft_rx_states[rx]->bit++; // wait for next bit
} else { // last bit received
if (uart_soft_rx_states[rx]->lock) { // someone is already reading data
uart_soft_rx_states[rx]->buffer_byte = uart_soft_rx_states[rx]->byte; // save byte
uart_soft_rx_states[rx]->buffer_byte_used = true; // notify reader there is a temporary byte
} else { // buffer can be updated
if (uart_soft_rx_states[rx]->buffer_used>=LENGTH(uart_soft_rx_states[rx]->buffer)) { // buffer is full
uart_soft_rx_states[rx]->buffer_i = (uart_soft_rx_states[rx]->buffer_i+1)%LENGTH(uart_soft_rx_states[rx]->buffer); // drop oldest byte
uart_soft_rx_states[rx]->buffer_used--; // update buffer usage
}
uart_soft_rx_states[rx]->buffer[(uart_soft_rx_states[rx]->buffer_i+uart_soft_rx_states[rx]->buffer_used)%LENGTH(uart_soft_rx_states[rx]->buffer)] = uart_soft_rx_states[rx]->byte; // put byte in buffer
uart_soft_rx_states[rx]->buffer_used++; // update used buffer
uart_soft_received[rx] = true; // notify user data is available
}
timer_disable_irq(TIM(UART_SOFT_RX_TIMER),timer_interrupt[rx]); // stop_interrupting
uart_soft_rx_states[rx]->bit = 0; // next bit should be first bit of next byte
}
}
}
}
#endif
#if defined(UART_SOFT_TX_TIMER)
void uart_soft_flush(uint8_t uart)
{
if (uart>=4 || !uart_soft_tx_states[uart]) { // ensure transmit UART port is defined
return; // return
}
while (uart_soft_tx_states[uart]->buffer_used) { // idle until buffer is empty
__WFI(); // sleep until interrupt
}
while (uart_soft_tx_states[uart]->transmit) { // idle until transmission is complete
__WFI(); // sleep until interrupt
}
}
/** start transmitting a byte from the buffer
* @param[in] uart UART port used for transmission
*/
static void uart_soft_transmit(uint8_t uart) {
if (uart>=4 || !uart_soft_tx_states[uart]) { // ensure transmit UART port is defined
return; // UART transmit port not defined
}
if (uart_soft_tx_states[uart]->transmit) { // already transmitting
return; // transmission is already ongoing
}
if (!uart_soft_tx_states[uart]->buffer_used) { // no buffered data to transmit
return; // nothing to transmit
}
uart_soft_tx_states[uart]->byte = uart_soft_tx_states[uart]->buffer[uart_soft_tx_states[uart]->buffer_i]; // get byte
uart_soft_tx_states[uart]->buffer_i = (uart_soft_tx_states[uart]->buffer_i+1)%LENGTH(uart_soft_tx_states[uart]->buffer); // update index
uart_soft_tx_states[uart]->buffer_used--; // update used buffer
uart_soft_tx_states[uart]->bit = 0; // LSb is transmitted first
uart_soft_tx_states[uart]->transmit = true; // start transmission
gpio_clear(uart_soft_tx_states[uart]->port, uart_soft_tx_states[uart]->pin); // output start bit
timer_set_oc_value(TIM(UART_SOFT_TX_TIMER), timer_oc[uart], timer_get_counter(TIM(UART_SOFT_TX_TIMER))+(rcc_ahb_frequency/uart_soft_tx_states[uart]->baudrate)); // set timer to output UART frame 1 (data bit 0) in 1 bit
timer_clear_flag(TIM(UART_SOFT_TX_TIMER), timer_flags[uart]); // clear flag before enabling interrupt
timer_enable_irq(TIM(UART_SOFT_TX_TIMER), timer_interrupt[uart]);// enable timer IRQ for TX for this UART
}
void uart_soft_putbyte_nonblocking(uint8_t uart, uint8_t byte)
{
if (uart>=4 || !uart_soft_tx_states[uart]) { // ensure transmit UART port is defined
return; // return
}
while (uart_soft_tx_states[uart]->buffer_used>=LENGTH(uart_soft_tx_states[uart]->buffer)) { // idle until there is place in the buffer
__WFI(); // sleep until something happened
}
uart_soft_tx_states[uart]->buffer[(uart_soft_tx_states[uart]->buffer_i+uart_soft_tx_states[uart]->buffer_used)%LENGTH(uart_soft_tx_states[uart]->buffer)] = byte; // save byte to be transmitted
uart_soft_tx_states[uart]->buffer_used++; // update used buffer
uart_soft_transmit(uart); // start transmission
}
void uart_soft_putbyte_blocking(uint8_t uart, uint8_t byte)
{
uart_soft_putbyte_nonblocking(uart, byte); // put byte in queue
uart_soft_flush(uart); // wait for all byte to be transmitted
}
/** timer interrupt service routine to sample UART receive signals */
void TIM_ISR(UART_SOFT_TX_TIMER)(void)
{
for (uint8_t tx=0; tx<4; tx++) {
if (timer_interrupt_source(TIM(UART_SOFT_TX_TIMER),timer_flags[tx])) { // got a match on compare for transmit pin
timer_clear_flag(TIM(UART_SOFT_TX_TIMER),timer_flags[tx]); // clear flag
if (!uart_soft_tx_states[tx]) { // verify if transmit is defined
continue; // skip if transmit port is not defined it
}
if (uart_soft_tx_states[tx]->bit<8) { // there is a data bit to transmit
if ((uart_soft_tx_states[tx]->byte>>uart_soft_tx_states[tx]->bit)&0x01) { // bit to transmit is a 1
gpio_set(uart_soft_tx_states[tx]->port, uart_soft_tx_states[tx]->pin); // set output to high
} else { // bit to transmit is a 0
gpio_clear(uart_soft_tx_states[tx]->port, uart_soft_tx_states[tx]->pin); // set output to low
}
timer_set_oc_value(TIM(UART_SOFT_TX_TIMER), timer_oc[tx], timer_get_counter(TIM(UART_SOFT_TX_TIMER))+(rcc_ahb_frequency/uart_soft_tx_states[tx]->baudrate)); // wait for the next frame bit
uart_soft_tx_states[tx]->bit++; // go to next bit
} else if (uart_soft_tx_states[tx]->bit==8) { // transmit stop bit
gpio_set(uart_soft_tx_states[tx]->port, uart_soft_tx_states[tx]->pin); // go idle high
timer_set_oc_value(TIM(UART_SOFT_TX_TIMER), timer_oc[tx], timer_get_counter(TIM(UART_SOFT_TX_TIMER))+(rcc_ahb_frequency/uart_soft_tx_states[tx]->baudrate)); // wait for 1 stop bit
uart_soft_tx_states[tx]->bit++; // go to next bit
} else { // UART frame is complete
timer_disable_irq(TIM(UART_SOFT_TX_TIMER), timer_interrupt[tx]);// enable timer IRQ for TX for this UART
uart_soft_tx_states[tx]->transmit = false; // transmission finished
uart_soft_transmit(tx); // start next transmission (if there is)
}
} // compare match
} // go through UARTs
}
#endif
/** central function handling receive signal activity */
static void uart_soft_receive_activity(void)
{
for (uint8_t rx=0; rx<4; rx++) {
if (!uart_soft_rx_states[rx]) { // verify if receive port is not configured
continue; // skip if receive port is not defined it
}
if (uart_soft_rx_states[rx]->state!=gpio_get(uart_soft_rx_states[rx]->port, uart_soft_rx_states[rx]->pin)) { // only do something if state changed
uart_soft_rx_states[rx]->state = gpio_get(uart_soft_rx_states[rx]->port, uart_soft_rx_states[rx]->pin); // save new state
if (uart_soft_rx_states[rx]->bit==0) { // start bit edge detected
if (uart_soft_rx_states[rx]->state==0) { // start bit has to be low
timer_set_oc_value(TIM(UART_SOFT_RX_TIMER), timer_oc[rx], timer_get_counter(TIM(UART_SOFT_RX_TIMER))+(rcc_ahb_frequency/uart_soft_rx_states[rx]->baudrate)*1.5); // set timer to sample data bit 0 in 1.5 bits
timer_clear_flag(TIM(UART_SOFT_RX_TIMER), timer_flags[rx]); // clear flag before enabling interrupt
timer_enable_irq(TIM(UART_SOFT_RX_TIMER), timer_interrupt[rx]);// enable timer IRQ for RX for this UART
uart_soft_rx_states[rx]->byte = 0; // reset byte value
uart_soft_rx_states[rx]->bit++; // wait for first bit
}
} else { // data bit detected
timer_set_oc_value(TIM(UART_SOFT_RX_TIMER), timer_oc[rx], timer_get_counter(TIM(UART_SOFT_RX_TIMER))+(rcc_ahb_frequency/uart_soft_rx_states[rx]->baudrate)/2); // resync timer to half a bit (good for drifting transmission, bad if the line is noisy)
}
}
}
}
/** GPIO interrupt service routine to detect UART receive activity */
#if (defined(UART_SOFT_RX_PORT0) && defined(UART_SOFT_RX_PIN0) && UART_SOFT_RX_PIN0==0) || (defined(UART_SOFT_RX_PORT1) && defined(UART_SOFT_RX_PIN1) && UART_SOFT_RX_PIN1==0) || (defined(UART_SOFT_RX_PORT2) && defined(UART_SOFT_RX_PIN2) && UART_SOFT_RX_PIN2==0) || (defined(UART_SOFT_RX_PORT3) && defined(UART_SOFT_RX_PIN3) && UART_SOFT_RX_PIN3==0)
void exti0_isr(void)
{
exti_reset_request(EXTI0); // clear interrupt flag for pin triggers this ISR (pin state will be checked independently)
uart_soft_receive_activity(); // check which GPIO changed
}
#endif
#if (defined(UART_SOFT_RX_PORT0) && defined(UART_SOFT_RX_PIN0) && UART_SOFT_RX_PIN0==1) || (defined(UART_SOFT_RX_PORT1) && defined(UART_SOFT_RX_PIN1) && UART_SOFT_RX_PIN1==1) || (defined(UART_SOFT_RX_PORT2) && defined(UART_SOFT_RX_PIN2) && UART_SOFT_RX_PIN2==1) || (defined(UART_SOFT_RX_PORT3) && defined(UART_SOFT_RX_PIN3) && UART_SOFT_RX_PIN3==1)
void exti1_isr(void)
{
exti_reset_request(EXTI1); // clear interrupt flag for pin triggers this ISR (pin state will be checked independently)
uart_soft_receive_activity(); // check which GPIO changed
}
#endif
#if (defined(UART_SOFT_RX_PORT0) && defined(UART_SOFT_RX_PIN0) && UART_SOFT_RX_PIN0==2) || (defined(UART_SOFT_RX_PORT1) && defined(UART_SOFT_RX_PIN1) && UART_SOFT_RX_PIN1==2) || (defined(UART_SOFT_RX_PORT2) && defined(UART_SOFT_RX_PIN2) && UART_SOFT_RX_PIN2==2) || (defined(UART_SOFT_RX_PORT3) && defined(UART_SOFT_RX_PIN3) && UART_SOFT_RX_PIN3==2)
void exti2_isr(void)
{
exti_reset_request(EXTI2); // clear interrupt flag for pin triggers this ISR (pin state will be checked independently)
uart_soft_receive_activity(); // check which GPIO changed
}
#endif
#if (defined(UART_SOFT_RX_PORT0) && defined(UART_SOFT_RX_PIN0) && UART_SOFT_RX_PIN0==3) || (defined(UART_SOFT_RX_PORT1) && defined(UART_SOFT_RX_PIN1) && UART_SOFT_RX_PIN1==3) || (defined(UART_SOFT_RX_PORT2) && defined(UART_SOFT_RX_PIN2) && UART_SOFT_RX_PIN2==3) || (defined(UART_SOFT_RX_PORT3) && defined(UART_SOFT_RX_PIN3) && UART_SOFT_RX_PIN3==3)
void exti3_isr(void)
{
exti_reset_request(EXTI3); // clear interrupt flag for pin triggers this ISR (pin state will be checked independently)
uart_soft_receive_activity(); // check which GPIO changed
}
#endif
#if (defined(UART_SOFT_RX_PORT0) && defined(UART_SOFT_RX_PIN0) && UART_SOFT_RX_PIN0==4) || (defined(UART_SOFT_RX_PORT1) && defined(UART_SOFT_RX_PIN1) && UART_SOFT_RX_PIN1==4) || (defined(UART_SOFT_RX_PORT2) && defined(UART_SOFT_RX_PIN2) && UART_SOFT_RX_PIN2==4) || (defined(UART_SOFT_RX_PORT3) && defined(UART_SOFT_RX_PIN3) && UART_SOFT_RX_PIN3==4)
void exti4_isr(void)
{
exti_reset_request(EXTI4); // clear interrupt flag for pin triggers this ISR (pin state will be checked independently)
uart_soft_receive_activity(); // check which GPIO changed
}
#endif
#if (defined(UART_SOFT_RX_PORT0) && defined(UART_SOFT_RX_PIN0) && (UART_SOFT_RX_PIN0==5 || UART_SOFT_RX_PIN0==6 || UART_SOFT_RX_PIN0==7 || UART_SOFT_RX_PIN0==8 || UART_SOFT_RX_PIN0==9)) || (defined(UART_SOFT_RX_PORT1) && defined(UART_SOFT_RX_PIN1) && (UART_SOFT_RX_PIN1==5 || UART_SOFT_RX_PIN1==6 || UART_SOFT_RX_PIN1==7 || UART_SOFT_RX_PIN1==8 || UART_SOFT_RX_PIN1==9)) || (defined(UART_SOFT_RX_PORT2) && defined(UART_SOFT_RX_PIN2) && (UART_SOFT_RX_PIN2==5 || UART_SOFT_RX_PIN2==6 || UART_SOFT_RX_PIN2==7 || UART_SOFT_RX_PIN2==8 || UART_SOFT_RX_PIN2==9)) || (defined(UART_SOFT_RX_PORT3) && defined(UART_SOFT_RX_PIN3) && (UART_SOFT_RX_PIN3==5 || UART_SOFT_RX_PIN3==6 || UART_SOFT_RX_PIN3==7 || UART_SOFT_RX_PIN3==8 || UART_SOFT_RX_PIN3==9))
void exti9_5_isr(void)
{
exti_reset_request(EXTI5|EXTI6|EXTI7|EXTI8|EXTI9); // clear interrupt flag for pin triggers this ISR (pin state will be checked independently)
uart_soft_receive_activity(); // check which GPIO changed
}
#endif
#if (defined(UART_SOFT_RX_PORT0) && defined(UART_SOFT_RX_PIN0) && (UART_SOFT_RX_PIN0==10 || UART_SOFT_RX_PIN0==11 || UART_SOFT_RX_PIN0==12 || UART_SOFT_RX_PIN0==13 || UART_SOFT_RX_PIN0==14 || UART_SOFT_RX_PIN0==15)) || (defined(UART_SOFT_RX_PORT1) && defined(UART_SOFT_RX_PIN1) && (UART_SOFT_RX_PIN1==10 || UART_SOFT_RX_PIN1==11 || UART_SOFT_RX_PIN1==12 || UART_SOFT_RX_PIN1==13 || UART_SOFT_RX_PIN1==14 || UART_SOFT_RX_PIN1==15)) || (defined(UART_SOFT_RX_PORT2) && defined(UART_SOFT_RX_PIN2) && (UART_SOFT_RX_PIN2==10 || UART_SOFT_RX_PIN2==11 || UART_SOFT_RX_PIN2==12 || UART_SOFT_RX_PIN2==13 || UART_SOFT_RX_PIN2==14 || UART_SOFT_RX_PIN2==15)) || (defined(UART_SOFT_RX_PORT3) && defined(UART_SOFT_RX_PIN3) && (UART_SOFT_RX_PIN3==10 || UART_SOFT_RX_PIN3==11 || UART_SOFT_RX_PIN3==12 || UART_SOFT_RX_PIN3==13 || UART_SOFT_RX_PIN3==14 || UART_SOFT_RX_PIN3==15))
void exti15_10_isr(void)
{
exti_reset_request(EXTI10|EXTI11|EXTI12|EXTI13|EXTI14|EXTI15); // clear interrupt flag for pin triggers this ISR (pin state will be checked independently)
uart_soft_receive_activity(); // check which GPIO changed
}
#endif

View File

@ -1,52 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to control up to 4 independent receive and transmit software UART ports (API)
* @file uart_soft.h
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note peripherals used: GPIO @ref uart_soft_gpio, timer @ref uart_soft_timer
*/
/** if data has been received from UART port and is available to be read */
extern volatile bool uart_soft_received[4];
/** setup software UART ports
* @param[in] rx_baudrates baud rates of the 4 UART RX ports (0 if unused)
* @param[in] tx_baudrates baud rates of the 4 UART TX ports (0 if unused)
* @return is setup succeeded, else the configuration is wrong
*/
bool uart_soft_setup(uint32_t *rx_baudrates, uint32_t *tx_baudrates);
/** get received byte from UART port
* @param[in] uart UART receive port to read byte from
* @return received byte (0 if no byte is available)
*/
uint8_t uart_soft_getbyte(uint8_t uart);
/** ensure all bytes are transmitted for the UART
* @param[in] uart UART port to flush
*/
void uart_soft_flush(uint8_t uart);
/** put byte in buffer to be transmitted on UART port
* @note blocking if buffer is full
* @param[in] uart UART port to transmit the byte from
* @param[in] byte byte to put in transmit buffer
*/
void uart_soft_putbyte_nonblocking(uint8_t uart, uint8_t byte);
/** transmit byte on UART port
* @note blocks until all buffered byte and this byte are transmitted
* @param[in] uart UART port to transmit the byte from
* @param[in] byte byte to transmit
*/
void uart_soft_putbyte_blocking(uint8_t uart, uint8_t byte);

View File

@ -1,497 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to drive vacuum fluorescent display using supertex HV518 shift register VFD drivers (code)
* @details the current configuration is for a VFD extracted from a Samsung SER-6500 cash register
* @file vfd_hv518.c
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note peripherals used: SPI @ref vfd_hv518_spi , GPIO @ref vfd_hv518_gpio , timer @ref vfd_hv518_timer
*/
/* standard libraries */
#include <stdint.h> // standard integer types
#include <stdlib.h> // general utilities
/* STM32 (including CM3) libraries */
#include <libopencm3/stm32/rcc.h> // real-time control clock library
#include <libopencm3/stm32/gpio.h> // general purpose input output library
#include <libopencm3/stm32/spi.h> // SPI library
#include <libopencm3/stm32/timer.h> // timer library
#include <libopencm3/cm3/nvic.h> // interrupt handler
#include "global.h" // global definitions
#include "vfd_hv518.h" // VFD library API
/** @defgroup vfd_hv518_gpio GPIO to control supertex HV518 VFD drivers
* @{
*/
#define VFD_PORT GPIOA /**< GPIO port */
#define VFD_PORT_RCC RCC_GPIOA /**< GPIO port peripheral clock */
#define VFD_STR GPIO6 /**< strobe pin to enable high voltage output, high voltage is output on low */
#define VFD_NLE GPIO4 /**< latch enable pin, stores the shifted data on low, output the parallel data on high */
/** @} */
/** @defgroup vfd_hv518_spi SPI to send data to supertex HV518 VFD drivers
* @{
*/
#define VFD_SPI_RCC RCC_SPI1 /**< SPI peripheral */
#define VFD_SPI_PORT GPIOA /**< GPIO port */
#define VFD_SPI_PORT_RCC RCC_GPIOA /**< GPIO port peripheral clock */
#define VFD_SPI_IRQ NVIC_SPI1_IRQ /**< SPI peripheral interrupt signal */
#define VFD_SPI_ISR spi1_isr /**< SPI interrupt service routine */
#define VFD_CLK GPIO_SPI1_SCK /**< clock signal */
#define VFD_DIN GPIO_SPI1_MOSI /**< data input, where the data is shifted to */
/** @} */
/** @defgroup vfd_hv518_timer timer for automatic display blocks refresh
* @{
*/
#define VFD_TIMER_RCC RCC_TIM2 /**< timer peripheral clock */
#define VFD_TIMER_IRQ NVIC_TIM2_IRQ /**< timer interrupt signal */
#define VFD_TIMER_ISR tim2_isr /**< timer interrupt service routine */
/** @} */
/** ASCII characters encoded for the 7 segments digit block
* @note starts with space
*/
static const uint8_t ascii_7segments[] = {
0b00000000, // space
0b00110000, // ! (I)
0b00100010, // "
0b01011100, // # (o)
0b01101101, // $ (s)
0b01010010, // % (/)
0b01111101, // & (6)
0b00100000, // '
0b00111001, // ( ([)
0b00001111, // )
0b01110000, // *
0b01000110, // +
0b00010000, // ,
0b01000000, // -
0b00010000, // . (,)
0b01010010, // /
0b00111111, // 0
0b00000110, // 1
0b01011011, // 2
0b01001111, // 3
0b01100110, // 4
0b01101101, // 5
0b01111101, // 6
0b00000111, // 7
0b01111111, // 8
0b01101111, // 9
0b01001000, // : (=)
0b01001000, // ; (=)
0b01011000, // <
0b01001000, // =
0b01001100, // >
0b01010011, // ?
0b01111011, // @
0b01110111, // A
0b01111111, // B
0b00111001, // C
0b01011110, // D
0b01111001, // E
0b01110001, // F
0b00111101, // G
0b01110110, // H
0b00110000, // I
0b00011110, // J
0b01110110, // K
0b00111000, // L
0b00110111, // M
0b00110111, // N
0b00111111, // O
0b01110011, // P
0b01101011, // Q
0b00110011, // R
0b01101101, // S
0b01111000, // T
0b00111110, // U
0b00111110, // V (U)
0b00111110, // W (U)
0b01110110, // X (H)
0b01101110, // Y
0b01011011, // Z
0b00111001, // [
0b01100100, // '\'
0b00001111, // /
0b00100011, // ^
0b00001000, // _
0b00000010, // `
0b01011111, // a
0b01111100, // b
0b01011000, // c
0b01011110, // d
0b01111011, // e
0b01110001, // f
0b01101111, // g
0b01110100, // h
0b00010000, // i
0b00001100, // j
0b01110110, // k
0b00110000, // l
0b01010100, // m
0b01010100, // n
0b01011100, // o
0b01110011, // p
0b01100111, // q
0b01010000, // r
0b01101101, // s
0b01111000, // t
0b00011100, // u
0b00011100, // v (u)
0b00011100, // w (u)
0b01110110, // x
0b01101110, // y
0b01011011, // z
0b00111001, // { ([)
0b00110000, // |
0b00001111, // } ([)
0b01000000, // ~
};
/** font for the 5x7 dot matrix block
* @details first value is left-most line, LSB is top dot, MSB is not used
* @note from http://sunge.awardspace.com/glcd-sd/node4.html
*/
static const uint8_t font5x7[][5] = {
{0x00, 0x00, 0x00, 0x00, 0x00}, // (space)
{0x00, 0x00, 0x5F, 0x00, 0x00}, // !
{0x00, 0x07, 0x00, 0x07, 0x00}, // "
{0x14, 0x7F, 0x14, 0x7F, 0x14}, // #
{0x24, 0x2A, 0x7F, 0x2A, 0x12}, // $
{0x23, 0x13, 0x08, 0x64, 0x62}, // %
{0x36, 0x49, 0x55, 0x22, 0x50}, // &
{0x00, 0x05, 0x03, 0x00, 0x00}, // '
{0x00, 0x1C, 0x22, 0x41, 0x00}, // (
{0x00, 0x41, 0x22, 0x1C, 0x00}, // )
{0x08, 0x2A, 0x1C, 0x2A, 0x08}, // *
{0x08, 0x08, 0x3E, 0x08, 0x08}, // +
{0x00, 0x50, 0x30, 0x00, 0x00}, // ,
{0x08, 0x08, 0x08, 0x08, 0x08}, // -
{0x00, 0x60, 0x60, 0x00, 0x00}, // .
{0x20, 0x10, 0x08, 0x04, 0x02}, // /
{0x3E, 0x51, 0x49, 0x45, 0x3E}, // 0
{0x00, 0x42, 0x7F, 0x40, 0x00}, // 1
{0x42, 0x61, 0x51, 0x49, 0x46}, // 2
{0x21, 0x41, 0x45, 0x4B, 0x31}, // 3
{0x18, 0x14, 0x12, 0x7F, 0x10}, // 4
{0x27, 0x45, 0x45, 0x45, 0x39}, // 5
{0x3C, 0x4A, 0x49, 0x49, 0x30}, // 6
{0x01, 0x71, 0x09, 0x05, 0x03}, // 7
{0x36, 0x49, 0x49, 0x49, 0x36}, // 8
{0x06, 0x49, 0x49, 0x29, 0x1E}, // 9
{0x00, 0x36, 0x36, 0x00, 0x00}, // :
{0x00, 0x56, 0x36, 0x00, 0x00}, // ;
{0x00, 0x08, 0x14, 0x22, 0x41}, // <
{0x14, 0x14, 0x14, 0x14, 0x14}, // =
{0x41, 0x22, 0x14, 0x08, 0x00}, // >
{0x02, 0x01, 0x51, 0x09, 0x06}, // ?
{0x32, 0x49, 0x79, 0x41, 0x3E}, // @
{0x7E, 0x11, 0x11, 0x11, 0x7E}, // A
{0x7F, 0x49, 0x49, 0x49, 0x36}, // B
{0x3E, 0x41, 0x41, 0x41, 0x22}, // C
{0x7F, 0x41, 0x41, 0x22, 0x1C}, // D
{0x7F, 0x49, 0x49, 0x49, 0x41}, // E
{0x7F, 0x09, 0x09, 0x01, 0x01}, // F
{0x3E, 0x41, 0x41, 0x51, 0x32}, // G
{0x7F, 0x08, 0x08, 0x08, 0x7F}, // H
{0x00, 0x41, 0x7F, 0x41, 0x00}, // I
{0x20, 0x40, 0x41, 0x3F, 0x01}, // J
{0x7F, 0x08, 0x14, 0x22, 0x41}, // K
{0x7F, 0x40, 0x40, 0x40, 0x40}, // L
{0x7F, 0x02, 0x04, 0x02, 0x7F}, // M
{0x7F, 0x04, 0x08, 0x10, 0x7F}, // N
{0x3E, 0x41, 0x41, 0x41, 0x3E}, // O
{0x7F, 0x09, 0x09, 0x09, 0x06}, // P
{0x3E, 0x41, 0x51, 0x21, 0x5E}, // Q
{0x7F, 0x09, 0x19, 0x29, 0x46}, // R
{0x46, 0x49, 0x49, 0x49, 0x31}, // S
{0x01, 0x01, 0x7F, 0x01, 0x01}, // T
{0x3F, 0x40, 0x40, 0x40, 0x3F}, // U
{0x1F, 0x20, 0x40, 0x20, 0x1F}, // V
{0x7F, 0x20, 0x18, 0x20, 0x7F}, // W
{0x63, 0x14, 0x08, 0x14, 0x63}, // X
{0x03, 0x04, 0x78, 0x04, 0x03}, // Y
{0x61, 0x51, 0x49, 0x45, 0x43}, // Z
{0x00, 0x00, 0x7F, 0x41, 0x41}, // [
{0x02, 0x04, 0x08, 0x10, 0x20}, // '\'
{0x41, 0x41, 0x7F, 0x00, 0x00}, // ]
{0x04, 0x02, 0x01, 0x02, 0x04}, // ^
{0x40, 0x40, 0x40, 0x40, 0x40}, // _
{0x00, 0x01, 0x02, 0x04, 0x00}, // `
{0x20, 0x54, 0x54, 0x54, 0x78}, // a
{0x7F, 0x48, 0x44, 0x44, 0x38}, // b
{0x38, 0x44, 0x44, 0x44, 0x20}, // c
{0x38, 0x44, 0x44, 0x48, 0x7F}, // d
{0x38, 0x54, 0x54, 0x54, 0x18}, // e
{0x08, 0x7E, 0x09, 0x01, 0x02}, // f
{0x08, 0x14, 0x54, 0x54, 0x3C}, // g
{0x7F, 0x08, 0x04, 0x04, 0x78}, // h
{0x00, 0x44, 0x7D, 0x40, 0x00}, // i
{0x20, 0x40, 0x44, 0x3D, 0x00}, // j
{0x00, 0x7F, 0x10, 0x28, 0x44}, // k
{0x00, 0x41, 0x7F, 0x40, 0x00}, // l
{0x7C, 0x04, 0x18, 0x04, 0x78}, // m
{0x7C, 0x08, 0x04, 0x04, 0x78}, // n
{0x38, 0x44, 0x44, 0x44, 0x38}, // o
{0x7C, 0x14, 0x14, 0x14, 0x08}, // p
{0x08, 0x14, 0x14, 0x18, 0x7C}, // q
{0x7C, 0x08, 0x04, 0x04, 0x08}, // r
{0x48, 0x54, 0x54, 0x54, 0x20}, // s
{0x04, 0x3F, 0x44, 0x40, 0x20}, // t
{0x3C, 0x40, 0x40, 0x20, 0x7C}, // u
{0x1C, 0x20, 0x40, 0x20, 0x1C}, // v
{0x3C, 0x40, 0x30, 0x40, 0x3C}, // w
{0x44, 0x28, 0x10, 0x28, 0x44}, // x
{0x0C, 0x50, 0x50, 0x50, 0x3C}, // y
{0x44, 0x64, 0x54, 0x4C, 0x44}, // z
{0x00, 0x08, 0x36, 0x41, 0x00}, // {
{0x00, 0x00, 0x7F, 0x00, 0x00}, // |
{0x00, 0x41, 0x36, 0x08, 0x00}, // }
{0b00001000, 0b00000100, 0b00001100, 0b00001000, 0b00000100} // ~
};
/** pictures for the 5x7 dot matrix block
* @details first value is left-most line, LSB is top dot, MSB is not used
*/
static const uint8_t pict5x7[][5] = {
{0x08, 0x08, 0x2A, 0x1C, 0x08}, // ->
{0x08, 0x1C, 0x2A, 0x08, 0x08}, // <-
{0b01110000, 0b01110000, 0b01111010, 0b01111100, 0b01011000}, // bunny side 1
{0b00100000, 0b01110000, 0b01110010, 0b01111100, 0b01011000}, // bunny side 2
{0b00111110, 0b01001001, 0b01010110, 0b01001001, 0b00111110}, // bunny face 1
{0b00111110, 0b01010001, 0b01100110, 0b01010001, 0b00111110}, // bunny face 2
{0b00111000, 0b01010111, 0b01100100, 0b01010111, 0b00111000}, // bunny face 3
{0b00111000, 0b01001111, 0b01010100, 0b01001111, 0b00111000}, // bunny face 4
{0b00111000, 0b01011110, 0b01101000, 0b01011110, 0b00111000}, // bunny face 5
{0b01000001, 0b00110110, 0b00001000, 0b00110110, 0b01000001}, // cross 1
{~0b01000001, ~0b00110110, ~0b00001000, ~0b00110110, ~0b01000001}, // cross 1 negated
{0b00100010, 0b00010100, 0b00001000, 0b00010100, 0b00100010}, // cross 2
{~0b00100010, ~0b00010100, ~0b00001000, ~0b00010100, ~0b00100010}, // cross 2 negated
{0x00, 0x00, 0x00, 0x00, 0x00} // nothing
};
/** the 32 bits values to be shifted out to the VFD driver
* @note split into 16 bit for SPI transfer
* @note since the bits for digits and matrix are independent, they can be combined
* @note we have more matrix (12) than digits (10)
*/
static uint16_t driver_data[VFD_MATRIX][VFD_DRIVERS*2] = {0};
/** which driver data is being transmitted */
static volatile uint8_t spi_i = 0;
/** which grid/part to activate
* @note digits and matrix can be combined
*/
static volatile uint8_t vfd_grid = 0;
/** the bits used for selecting then digit and 7 segment anodes
* @note for the second driver
*/
static const uint32_t digit_mask = 0x00fffff0;
void vfd_digit(uint8_t nb, char c)
{
if (!(nb<VFD_DIGITS)) { // check the digit exists
return;
}
uint32_t digit_data = 0; // the data to be shifted out for the driver (for the second driver)
digit_data = 1<<(4+(9-nb)); // select digit
/* encode segment
* here the bit order (classic 7 segment + underline and dot)
* 3_
* 8|9_|4
* 7|6_|5.1
* 0_2,
* */
if (false) { // add the underline (not encoded)
digit_data |= (1<<(14));
}
if (c&0x80) { // add the dot (encoded in the 8th bit)
digit_data |= (1<<(15));
}
if (false) { // add the comma (not encoded)
digit_data |= (1<<(16));
}
c &= 0x7f; // only take the ASCII part
if (c>=' ') { // only take printable characters
uint8_t i = c-' '; // get index for character
if (i<LENGTH(ascii_7segments)) {
digit_data |= (ascii_7segments[i]<<(17)); // add encoded segments to memory
}
}
digit_data &= digit_mask; // be sure only the bits for the digit are used
digit_data |= (driver_data[nb][2]+(driver_data[nb][3]<<16))&~digit_mask; // get the existing data and add the bits for the digit
driver_data[nb][2] = digit_data; // write back data (least significant half)
driver_data[nb][3] = (digit_data>>16); // write back data (most significant half)
}
void vfd_matrix(uint8_t nb, char c)
{
// check the matrix exists
if (!(nb<VFD_MATRIX)) {
return;
}
uint32_t matrix_data[VFD_DRIVERS] = {0}; // the data to be shifted out for the driver
// select matrix
if (nb<4) {
matrix_data[1] = 1<<(3-nb);
} else {
matrix_data[0] = 1<<(35-nb);
}
if ((c<0x80) && (c>=' ')) { // only take printable characters
uint8_t i = c-' '; // get index for character
if (i<LENGTH(font5x7)) {
matrix_data[1] |= font5x7[i][0]<<24;
matrix_data[2] |= font5x7[i][1]<<0;
matrix_data[2] |= font5x7[i][2]<<8;
matrix_data[2] |= font5x7[i][3]<<16;
matrix_data[2] |= font5x7[i][4]<<24;
}
} else if (c>0x7f) { // the non ASCII character are used for pictures
uint8_t i = c-0x80; // get index for character
if (i<LENGTH(pict5x7)) {
matrix_data[1] |= pict5x7[i][0]<<24;
matrix_data[2] |= pict5x7[i][1]<<0;
matrix_data[2] |= pict5x7[i][2]<<8;
matrix_data[2] |= pict5x7[i][3]<<16;
matrix_data[2] |= pict5x7[i][4]<<24;
}
}
matrix_data[1] &= ~digit_mask; // be sure only the bits for the matrix are used
matrix_data[1] |= (driver_data[nb][2]+(driver_data[nb][3]<<16))&digit_mask; // get the existing data for the digit
// prepare the data for SPI to shift it out
for (uint8_t i=0; i<LENGTH(matrix_data); i++) {
driver_data[nb][i*2] = matrix_data[i];
driver_data[nb][i*2+1] = matrix_data[i]>>16;
}
}
void vfd_clear(void)
{
for (uint8_t i=0; i<LENGTH(driver_data); i++) {
for (uint8_t j=0; j<LENGTH(driver_data[0]); j++) {
driver_data[i][j] = 0;
}
}
}
void vfd_test(void)
{
for (uint8_t i=0; i<LENGTH(driver_data); i++) {
for (uint8_t j=0; j<LENGTH(driver_data[0]); j++) {
driver_data[i][j] = ~0;
}
}
}
void vfd_on(void)
{
gpio_clear(VFD_PORT, VFD_STR); // enable HV output
timer_enable_counter(VFD_TIMER); // start timer to periodically output that to the parts
}
void vfd_off(void)
{
gpio_set(VFD_PORT, VFD_STR); // disable HV output
timer_disable_counter(VFD_TIMER); // stop timer to periodically output that to the parts
}
void vfd_setup(void)
{
/* setup GPIO to control the VFD */
rcc_periph_clock_enable(VFD_PORT_RCC); // enable clock for VFD GPIO
gpio_set_mode(VFD_PORT, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, VFD_STR); // set VFD pin to output push-pull
gpio_set_mode(VFD_PORT, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, VFD_NLE); // set VFD pin to output push-pull
gpio_set(VFD_PORT, VFD_STR); // disable HV output
gpio_clear(VFD_PORT, VFD_NLE); // do not output latched data
/* setup SPI to transmit data */
rcc_periph_clock_enable(VFD_SPI_RCC); // enable SPI clock
rcc_periph_clock_enable(VFD_SPI_PORT_RCC); // enable clock for VFD SPI GPIO
gpio_set_mode(VFD_SPI_PORT, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, VFD_CLK); // set VFD pin to alternative function push-pull
gpio_set_mode(VFD_SPI_PORT, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, VFD_DIN); // set VFD pin to alternative function push-pull
spi_reset(VFD_SPI); // clear SPI values
/* set SPI:
* - use VFD_SPI port
* - divide clock by 8 for generating the baudrate (F_PCLK1 is 36MHz, max HV518 is 6MHz)
* - clock idle high polarity
* - data is valid on rising edge (second clock phase)
* - send 16 bits at a time
* - send least significant bit first (that's how I coded the data)
*/
spi_init_master(VFD_SPI, SPI_CR1_BAUDRATE_FPCLK_DIV_8, SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE, SPI_CR1_CPHA_CLK_TRANSITION_2, SPI_CR1_DFF_16BIT, SPI_CR1_LSBFIRST);
//spi_set_bidirectional_transmit_only_mode(VFD_SPI); // only use MOSI to transmit
spi_set_unidirectional_mode(VFD_SPI); // MISO is unused
/* set NSS high to enable transmission
* the NSS in STM32 can not be used as hardware slave select
* RM0008 reference manual 25.3.1 is misleading
* when hardware NSS is used and output is enabled NSS never goes up after transmission, even if SPI is disabled
* when software NSS is used, NSS can not be set high again, even when writing to the register
* the slave select must be done manually using GPIO */
spi_enable_software_slave_management(VFD_SPI);
spi_set_nss_high(VFD_SPI); // set NSS high
nvic_enable_irq(VFD_SPI_IRQ); // enable SPI interrupt
spi_enable(VFD_SPI); // enable SPI (the tx empty interrupt will trigger)
/* setup timer to refresh display */
rcc_periph_clock_enable(VFD_TIMER_RCC); // enable clock for timer block
timer_reset(VFD_TIMER); // reset timer state
timer_set_mode(VFD_TIMER, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); // set timer mode, use undivided timer clock,edge alignment (simple count), and count up
timer_set_prescaler(VFD_TIMER, (SYSTEM_CLOCK_FREQ/(1<<16))-1); // set the prescaler so this 16 bits timer overflows at 1Hz
timer_set_period(VFD_TIMER, 0xffff/LENGTH(driver_data)/100); // set the refresh frequency
timer_enable_irq(VFD_TIMER, TIM_DIER_UIE); // enable interrupt for timer
nvic_enable_irq(VFD_TIMER_IRQ); // allow interrupt for timer
vfd_clear(); // initialize values
}
/** SPI interrupt service routine called when data has been transmitted */
void VFD_SPI_ISR(void)
{
if (SPI_SR(VFD_SPI) & SPI_SR_TXE) { // transmission buffer empty
if (spi_i<LENGTH(driver_data[0])) { // check if data is available
gpio_clear(VFD_PORT, VFD_NLE); // slave select to latch data
spi_send(VFD_SPI, driver_data[vfd_grid][spi_i++]); // send next data
} else { // all data transmitted
spi_disable_tx_buffer_empty_interrupt(VFD_SPI); // no need to wait for new data
while (SPI_SR(VFD_SPI) & SPI_SR_BSY); // wait for data to be shifted out
spi_disable_tx_buffer_empty_interrupt(VFD_SPI); // no need to wait for new data
gpio_set(VFD_PORT, VFD_NLE); // output latched data
}
}
}
/** timer interrupt service routine called time passed */
void VFD_TIMER_ISR(void)
{
if (timer_get_flag(VFD_TIMER, TIM_SR_UIF)) { // overflow even happened
timer_clear_flag(VFD_TIMER, TIM_SR_UIF); // clear flag
spi_i = 0; // set the register to shift out
spi_enable_tx_buffer_empty_interrupt(VFD_SPI); // enable TX empty interrupt
vfd_grid = (vfd_grid+1)%LENGTH(driver_data); // got to next segment
}
}

View File

@ -1,51 +0,0 @@
/* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/** library to drive vacuum fluorescent display using supertex HV518 shift register VFD drivers (API)
* @details the current configuration is for a VFD extracted from a Samsung SER-6500 cash register
* @file vfd_hv518.h
* @author King Kévin <kingkevin@cuvoodoo.info>
* @date 2016
* @note peripherals used: USART @ref usart
*/
/** number HV518 VFD drivers */
#define VFD_DRIVERS 3
/** number of digits blocks on SER-6500 VFD */
#define VFD_DIGITS 10
/** number of dot matrix blocks on SER-6500 VFD */
#define VFD_MATRIX 12
/** set character to digit block
* @param[in] nb digit block to set
* @param[in] c ASCII character to set
* @note use the MSB of @p nb to enable the dot
*/
void vfd_digit(uint8_t nb, char c);
/** set character to matrix block
* @param[in] nb matrix block to set
* @param[in] c ASCII character to set
* @note on ASCII characters are used for pictures
*/
void vfd_matrix(uint8_t nb, char c);
/** clear VFD display */
void vfd_clear(void);
/** test VFD display (light up all segments) */
void vfd_test(void);
/** switch VFD on */
void vfd_on(void);
/** switch VFD display off */
void vfd_off(void);
/** setup VFD */
void vfd_setup(void);

171
main.c
View File

@ -42,9 +42,8 @@
/* own libraries */
#include "global.h" // board definitions
//#include "usart.h" // USART utilities
#include "usart.h" // USART utilities
#include "usb_cdcacm.h" // USB CDC ACM utilities
#include "sensor_pzem.h" // PZEM electricity meter utilities
#include "sensor_sdm120.h" // SDM120 electricity meter utilities
#include "radio_esp8266.h" // ESP8266 WiFi SoC utilities
@ -75,6 +74,7 @@ volatile bool rtc_internal_tick_flag = false; /**< flag set when internal RTC ti
#define DDM100TC_TIMER 4 /**< timer to measure time between pulses **/
#define DDM100TC_PORT B /**< timer ipnut capture port (TIM4_CH1=PB6) **/
#define DDM100TC_CAPTURE TIM4_CH1 /**< time input capture used to detect pulse **/
#define DDM100TC_RATE 1600 /**< number of impulse/kWh */
volatile uint32_t ddm100tc_interval = 0; /**< last time interval between pulses **/
/** @} */
@ -97,8 +97,8 @@ int _write(int file, char *ptr, int len)
for (i = 0; i < len; i++) {
if (ptr[i] == '\r' || ptr[i] == '\n') { // send CR+LF newline for most carriage return and line feed combination
if (newline==0 || (newline==ptr[i])) { // newline has already been detected
//usart_putchar_nonblocking('\r'); // send newline over USART
//usart_putchar_nonblocking('\n'); // send newline over USART
usart_putchar_nonblocking('\r'); // send newline over USART
usart_putchar_nonblocking('\n'); // send newline over USART
cdcacm_putchar('\r'); // send newline over USB
cdcacm_putchar('\n'); // send newline over USB
newline = ptr[i]; // remember the newline
@ -107,7 +107,7 @@ int _write(int file, char *ptr, int len)
newline = 0; // clear new line
}
} else { // non-newline character
//usart_putchar_nonblocking(ptr[i]); // send byte over USART
usart_putchar_nonblocking(ptr[i]); // send byte over USART
cdcacm_putchar(ptr[i]); // send byte over USB
newline = 0; // clear new line
}
@ -136,8 +136,8 @@ static void process_command(char* str)
// parse command
if (0==strcmp(word,"help")) {
printf("available commands:\n");
printf("led [on|off|toggle]\n");
printf("time [HH:MM:SS]\n");
printf("led on|off|toggle\n");
printf("energy <Wh>\n");
} else if (0==strcmp(word,"led")) {
word = strtok(NULL,delimiter);
if (!word) {
@ -154,15 +154,17 @@ static void process_command(char* str)
} else {
goto error;
}
} else if (0==strcmp(word,"time")) {
} else if (0==strcmp(word,"energy")) {
word = strtok(NULL,delimiter);
if (!word) {
printf("current time: %02lu:%02lu:%02lu\n", rtc_get_counter_val()/(60*60), (rtc_get_counter_val()%(60*60))/60, (rtc_get_counter_val()%60)); // get and print time from internal RTC
} else if (strlen(word)!=8 || word[0]<'0' || word[0]>'2' || word[1]<'0' || word[1]>'9' || word[3]<'0' || word[3]>'5' || word[4]<'0' || word[4]>'9' || word[6]<'0' || word[6]>'5' || word[7]<'0' || word[7]>'9') { // time format is incorrect
goto error;
} else {
rtc_set_counter_val(((word[0]-'0')*10+(word[1]-'0')*1)*(60*60)+((word[3]-'0')*10+(word[4]-'0')*1)*60+((word[6]-'0')*10+(word[7]-'0')*1)); // set time in internal RTC counter
printf("time set\n");
if (!word) { // value required but not provided
goto error;
} else { // save energy value
uint64_t energy = (atol(word)*DDM100TC_RATE)/1000; // get value to save
pwr_disable_backup_domain_write_protect(); // enable backup register write
BKP_DR1 = (energy>>16); // set high 16 bits
BKP_DR2 = (energy&0xffff); // set low 16 bits
pwr_enable_backup_domain_write_protect(); // protect backup register from write
printf("energy value set\n"); // notify user
}
} else {
goto error;
@ -273,9 +275,10 @@ void main(void)
// setup board
board_setup();
led_on();
// setup USART and USB for user communication
//usart_setup(); // setup USART (for printing)
usart_setup(); // setup USART (for printing)
cdcacm_setup(); // setup USB CDC ACM (for printing)
setbuf(stdout, NULL); // set standard out buffer to NULL to immediately print
setbuf(stderr, NULL); // set standard error buffer to NULL to immediately print
@ -284,7 +287,7 @@ void main(void)
printf("welcome to the spark abacus electricity monitoring system\n"); // print welcome message
#if !(DEBUG)
printf("watchdog set to %.2fs\n",WATCHDOG_PERIOD/1000.0);
printf("watchdog set to %.2fs\n",WATCHDOG_PERIOD/1000.0);
if (FLASH_OBR&FLASH_OBR_OPTERR) {
printf("option bytes not set in flash: software wachtdog used (not started at reset)\n");
} else if (FLASH_OBR&FLASH_OBR_WDG_SW) {
@ -348,11 +351,6 @@ void main(void)
timer_enable_counter(TIM(DDM100TC_TIMER)); // enable timer
printf("OK\n");
// setup PZEM electricity meter
printf("setup PZEM-004 electricity meter: ");
sensor_pzem_setup(); // setup PZEM electricity meter
printf("OK\n");
// setup SDM120 electricity meter
printf("setup SDM120 electricity meter: ");
sensor_sdm120_setup(9600); // setup SDM120 electricity meter (get baud rate by scrolling through the menu on the device)
@ -371,11 +369,6 @@ void main(void)
bool char_flag = false; // a new character has been received
led_on(); // indicate setup is complete
// variables for PZEM-004T meter measurements
struct sensor_pzem_measurement_t pzem_measurements[3][SENSOR_PZEM_MAX]; // PZEM-004T measurements (2 meters, all measurements)
uint8_t pzem_meter = 0; // PZEM-004T meter index (add to prefix)
uint8_t pzem_measurement = 0; // PZEM-004T measurement index (matches the type)
// variables for SDM120 meter measurements
float sdm120_measurements[3][SENSOR_SDM120_MEASUREMENT_MAX]; // SDM120 measurements (2 meters, all measurements)
uint8_t sdm120_meter = 0; // SDM120 meter index (add to 1 to get ID)
@ -387,6 +380,12 @@ void main(void)
while (true) { // infinite loop
iwdg_reset(); // kick the dog
while (usart_received) { // data received over UART
action = true; // action has been performed
led_toggle(); // toggle LED
c = usart_getchar(); // store receive character
char_flag = true; // notify character has been received
}
while (cdcacm_received) { // data received over USB
action = true; // action has been performed
c = cdcacm_getchar(); // store receive character
@ -409,59 +408,6 @@ void main(void)
}
}
}
while (sensor_pzem_measurement_received) { // measurement from electricity meter received
sensor_pzem_measurement_received = false; // clear flag
struct sensor_pzem_measurement_t measurement = sensor_pzem_measurement_decode(); // decode measurement
if (measurement.type>=SENSOR_PZEM_MAX) {
fprintf(stderr,"unknown measurement type: %u\n", measurement.type);
while (true); // unhandled error
}
if (measurement.valid) { // only show valid measurement
printf("PZEM-004T meter %u ", pzem_meter);
switch (measurement.type) {
case SENSOR_PZEM_VOLTAGE:
printf("voltage: %.01f V\n", measurement.value.voltage); // display measurement
break;
case SENSOR_PZEM_CURRENT:
printf("current: %.02f A\n", measurement.value.current);
break;
case SENSOR_PZEM_POWER:
printf("power: %u W\n", measurement.value.power);
break;
case SENSOR_PZEM_ENERGY:
printf("energy: %lu Wh\n", measurement.value.energy);
break;
/* not used for this application
case SENSOR_PZEM_ADDRESS:
printf("address set\n");
break;
case SENSOR_PZEM_ALARM:
printf("alarm threshold set\n");
break;
*/
default:
break;
}
if (measurement.type!=pzem_measurement) {
fprintf(stderr, "PZEM-004T measurement mismatch: expected %u, got %u\n", pzem_measurement, measurement.type);
sensor_pzem_measurement_request(0xc0a80100+pzem_meter, pzem_measurement); // request same measurement
} else if (pzem_measurement<SENSOR_PZEM_MAX-1) { // not all measurement types requested
pzem_measurements[pzem_meter][pzem_measurement] = measurement; // save measurement (the type matches the index)
pzem_measurement++; // go to next measurement
sensor_pzem_measurement_request(0xc0a80100+pzem_meter, pzem_measurement); // request next measurement
} else { // all measurement types requested
pzem_measurements[pzem_meter][pzem_measurement] = measurement; // save measurement (the type matches the index)
pzem_meter++; // got to next meter
pzem_measurement = 0; // restart measurements
if (pzem_meter<LENGTH(pzem_measurements)) { // ensure next meter exists
sensor_pzem_measurement_request(0xc0a80100+pzem_meter, pzem_measurement); // request measurement for next meter
}
}
} else { // measurement not valid
fprintf(stderr, "PZEM-004T measurement invalid\n");
sensor_pzem_measurement_request(0xc0a80100+pzem_meter, pzem_measurement); // request same measurement
}
}
while (sensor_sdm120_measurement_received) { // measurement from electricity meter received
float measurement = sensor_sdm120_measurement_decode(); // decode measurement
if (isnan(measurement)) {
@ -530,6 +476,7 @@ void main(void)
}
while (rtc_internal_tick_flag) { // the internal RTC ticked
rtc_internal_tick_flag = false; // reset flag
led_toggle(); // toggle LED to indicate if main function is stuck
gpio_toggle(GPIO(LED_HEARTBEAT_PORT), GPIO(LED_HEARTBEAT_PIN)); // toggle heart beat LED to indicate if main function is stuck (do not toggle onboard the LED on PC13 on the blue pill board since this heavily influences the RTC)
ticks_time = rtc_get_counter_val(); // copy time from internal RTC for processing
action = true; // action has been performed
@ -540,17 +487,13 @@ void main(void)
printf("query meter measurements (%lu.%02lu:%02lu:%02lu)\n", ticks_time/(60*60*24), (ticks_time/(60*60))%24, (ticks_time%(60*60))/60, (ticks_time%60));
gpio_clear(GPIO(LED_QUERY_PORT), GPIO(LED_QUERY_PIN)); // switch on query LED
// start getting all PZEM-004T measurements from all meters
pzem_meter = 0; // reset PZEM meter number
pzem_measurement = 0; // reset PZEM measurement index
sensor_pzem_measurement_request(0xc0a80100+pzem_meter, pzem_measurement); // request first measurement
// start getting all SDM120 measurements from all meters
sdm120_meter = 0; // reset SDM120 meter number
sdm120_measurement = 0; // reset SDM120 measurement index
sensor_sdm120_measurement_request(1+sdm120_meter, sdm120_measurement); // request first measurement
// calculate and show DDM100TC measurements (base on number of pulses and interval)
ddm100tc_value_energy = (uint32_t)((((BKP_DR1<<16)+BKP_DR2)*(uint64_t)1000)/1600); // the meter has 1600 impulses/kWh (use 64-bit calculation to not overflow after 2684354 Wh)
ddm100tc_value_energy = (uint32_t)((((BKP_DR1<<16)+BKP_DR2)*(uint64_t)1000)/DDM100TC_RATE); // the meter has 1600 impulses/kWh (use 64-bit calculation to not overflow after 2684354 Wh)
if (ddm100tc_interval==0) { // no measurements received yet
ddm100tc_value_power = 0;
} else {
@ -560,17 +503,11 @@ void main(void)
printf("DDM100TC meter power: %lu W\n", ddm100tc_value_power);
}
}
while (pzem_meter>=LENGTH(pzem_measurements) && sdm120_meter>=LENGTH(sdm120_measurements)) { // all measurements received for all meter
while (sdm120_meter>=LENGTH(sdm120_measurements)) { // all measurements received for all meter
action = true; // action has been performed
printf("saving measurements to database: ");
gpio_set(GPIO(LED_QUERY_PORT), GPIO(LED_QUERY_PIN)); // switch off query LED
gpio_clear(GPIO(LED_SUBMIT_PORT), GPIO(LED_SUBMIT_PIN)); // switch off submit LED
const char* pzem_strings[SENSOR_PZEM_MAX] = {
"voltage,meter=PZEM-004T,phase=%u value=%.1f\n",
"current,meter=PZEM-004T,phase=%u value=%.2f\n",
"power,meter=PZEM-004T,phase=%u value=%u\n",
"energy,meter=PZEM-004T,phase=%u value=%lu\n"
};
const char* sdm120_strings[SENSOR_SDM120_MEASUREMENT_MAX] = {
"voltage,meter=SDM120,phase=%u value=%.3f\n",
"current,meter=SDM120,phase=%u value=%.3f\n",
@ -592,29 +529,6 @@ void main(void)
// calculate length for text to POST
char line[256] = {0}; // measurement line to send
size_t data_length = 0; /**< length of the data string to send */
for (pzem_meter = 0; pzem_meter<LENGTH(pzem_measurements); pzem_meter++) {
for (pzem_measurement = 0; pzem_measurement<SENSOR_PZEM_MAX; pzem_measurement++) {
struct sensor_pzem_measurement_t measurement = pzem_measurements[pzem_meter][pzem_measurement]; // get measurement
if (measurement.valid) { // only use valid measurements
switch (measurement.type) { // get the size (hope no error is occurring)
case SENSOR_PZEM_VOLTAGE:
data_length += snprintf(line, LENGTH(line), pzem_strings[pzem_measurement], pzem_meter, measurement.value.voltage);
break;
case SENSOR_PZEM_CURRENT:
data_length += snprintf(line, LENGTH(line), pzem_strings[pzem_measurement], pzem_meter, measurement.value.current);
break;
case SENSOR_PZEM_POWER:
data_length += snprintf(line, LENGTH(line), pzem_strings[pzem_measurement], pzem_meter, measurement.value.power);
break;
case SENSOR_PZEM_ENERGY:
data_length += snprintf(line, LENGTH(line), pzem_strings[pzem_measurement], pzem_meter, measurement.value.energy);
break;
default:
break;
}
}
}
}
for (sdm120_meter = 0; sdm120_meter<LENGTH(sdm120_measurements); sdm120_meter++) {
for (sdm120_measurement = 0; sdm120_measurement<SENSOR_SDM120_MEASUREMENT_MAX; sdm120_measurement++) {
if (sdm120_measurement<SENSOR_SDM120_ENERGY_ACTIVE_IMPORT) {
@ -631,31 +545,6 @@ void main(void)
if (!http_post_header(DATABASE_HOST, DATABASE_PORT, data_length)) { // send header
fprintf(stderr,"could not sent HTTP POST header\n");
} else {
// send PZEM-004T values
for (pzem_meter = 0; pzem_meter<LENGTH(pzem_measurements); pzem_meter++) {
for (pzem_measurement = 0; pzem_measurement<SENSOR_PZEM_MAX; pzem_measurement++) {
struct sensor_pzem_measurement_t measurement = pzem_measurements[pzem_meter][pzem_measurement]; // get measurement
if (measurement.valid) { // only use valid measurements
switch (measurement.type) { // make line (hope no error is occurring)
case SENSOR_PZEM_VOLTAGE:
snprintf(line, LENGTH(line), pzem_strings[pzem_measurement], pzem_meter, measurement.value.voltage);
break;
case SENSOR_PZEM_CURRENT:
snprintf(line, LENGTH(line), pzem_strings[pzem_measurement], pzem_meter, measurement.value.current);
break;
case SENSOR_PZEM_POWER:
snprintf(line, LENGTH(line), pzem_strings[pzem_measurement], pzem_meter, measurement.value.power);
break;
case SENSOR_PZEM_ENERGY:
snprintf(line, LENGTH(line), pzem_strings[pzem_measurement], pzem_meter, measurement.value.energy);
break;
default:
break;
}
http_send((uint8_t*)line, 0); // don't care about the result
}
}
}
// send SDM120 values
for (sdm120_meter = 0; sdm120_meter<LENGTH(sdm120_measurements); sdm120_meter++) {
for (sdm120_measurement = 0; sdm120_measurement<SENSOR_SDM120_MEASUREMENT_MAX; sdm120_measurement++) {
@ -670,6 +559,7 @@ void main(void)
}
}
}
// send DM100TC values
if (snprintf(line, LENGTH(line), ddm100tc_string_energy, ddm100tc_value_energy)>0) {
http_send((uint8_t*)line, 0); // don't care about the result
}
@ -681,7 +571,6 @@ void main(void)
printf("OK\n");
}
pzem_meter = 0; // reset meter
sdm120_meter = 0; // reset meter
}