open collector output support

pull/2/head
Mateusz Lubecki 2020-06-11 20:36:36 +02:00
rodzic 51d2ad8829
commit 9f6baac448
10 zmienionych plików z 164 dodań i 117 usunięć

Wyświetl plik

@ -10,6 +10,7 @@ C_SRCS += \
../src/TimerConfig.c \
../src/_write.c \
../src/delay.c \
../src/io.c \
../src/it_handlers.c \
../src/main.c \
../src/packet_tx_handler.c \
@ -18,17 +19,14 @@ C_SRCS += \
../src/rte_wx.c \
../src/wx_handler.c
CPP_SRCS += \
../src/BlinkLed.cpp
OBJS += \
./src/BlinkLed.o \
./src/KissCommunication.o \
./src/LedConfig.o \
./src/PathConfig.o \
./src/TimerConfig.o \
./src/_write.o \
./src/delay.o \
./src/io.o \
./src/it_handlers.o \
./src/main.o \
./src/packet_tx_handler.o \
@ -44,6 +42,7 @@ C_DEPS += \
./src/TimerConfig.d \
./src/_write.d \
./src/delay.d \
./src/io.d \
./src/it_handlers.d \
./src/main.d \
./src/packet_tx_handler.d \
@ -52,18 +51,8 @@ C_DEPS += \
./src/rte_wx.d \
./src/wx_handler.d
CPP_DEPS += \
./src/BlinkLed.d
# Each subdirectory must supply rules for building sources it contributes
src/%.o: ../src/%.cpp
@echo 'Building file: $<'
@echo 'Invoking: Cross ARM C++ Compiler'
arm-none-eabi-g++ -mcpu=cortex-m3 -mthumb -Og -fmessage-length=0 -fsigned-char -ffunction-sections -fdata-sections -ffreestanding -fno-move-loop-invariants -Wall -Wextra -g3 -DDEBUG -DTRACE -DOS_USE_TRACE_SEMIHOSTING_DEBUG -DSTM32F10X_MD_VL -DUSE_STDPERIPH_DRIVER -DHSE_VALUE=8000000 -I"../include" -I"../system/include/aprs" -I"../system/include" -I"../system/include/cmsis" -I"../system/include/stm32f1-stdperiph" -std=gnu++11 -fabi-version=0 -fno-exceptions -fno-rtti -fno-use-cxa-atexit -fno-threadsafe-statics -MMD -MP -MF"$(@:%.o=%.d)" -MT"$(@)" -c -o "$@" "$<"
@echo 'Finished building: $<'
@echo ' '
src/%.o: ../src/%.c
@echo 'Building file: $<'
@echo 'Invoking: Cross ARM C Compiler'

Wyświetl plik

@ -1,65 +0,0 @@
//
// This file is part of the GNU ARM Eclipse distribution.
// Copyright (c) 2014 Liviu Ionescu.
//
#ifndef BLINKLED_H_
#define BLINKLED_H_
#include "stm32f10x.h"
// ----- LED definitions ------------------------------------------------------
// Adjust these definitions for your own board.
// Olimex STM32-H103 definitions (the GREEN led, C12, active low)
// (SEGGER J-Link device name: STM32F103RB).
// Port numbers: 0=A, 1=B, 2=C, 3=D, 4=E, 5=F, 6=G, ...
#define BLINK_PORT_NUMBER (2)
#define BLINK_PIN_NUMBER (12)
#define BLINK_ACTIVE_LOW (1)
#define BLINK_GPIOx(_N) ((GPIO_TypeDef *)(GPIOA_BASE + (GPIOB_BASE-GPIOA_BASE)*(_N)))
#define BLINK_PIN_MASK(_N) (1 << (_N))
#define BLINK_RCC_MASKx(_N) (RCC_APB2Periph_GPIOA << (_N))
// ----------------------------------------------------------------------------
class BlinkLed
{
public:
BlinkLed() = default;
void
powerUp();
inline void
__attribute__((always_inline))
turnOn()
{
#if (BLINK_ACTIVE_LOW)
GPIO_ResetBits(BLINK_GPIOx(BLINK_PORT_NUMBER),
BLINK_PIN_MASK(BLINK_PIN_NUMBER));
#else
GPIO_SetBits(BLINK_GPIOx(BLINK_PORT_NUMBER),
BLINK_PIN_MASK(BLINK_PIN_NUMBER));
#endif
}
inline void
__attribute__((always_inline))
turnOff()
{
#if (BLINK_ACTIVE_LOW)
GPIO_SetBits(BLINK_GPIOx(BLINK_PORT_NUMBER),
BLINK_PIN_MASK(BLINK_PIN_NUMBER));
#else
GPIO_ResetBits(BLINK_GPIOx(BLINK_PORT_NUMBER),
BLINK_PIN_MASK(BLINK_PIN_NUMBER));
#endif
}
};
// ----------------------------------------------------------------------------
#endif // BLINKLED_H_

Wyświetl plik

@ -4,8 +4,8 @@
#include "aprs/ax25.h"
#include "drivers/serial.h"
#define SW_VER "DF00"
#define SW_DATE "06062020"
#define SW_VER "DF01"
#define SW_DATE "11062020"
#define SYSTICK_TICKS_PER_SECONDS 100
#define SYSTICK_TICKS_PERIOD 10

Wyświetl plik

@ -16,7 +16,8 @@ extern uint32_t wx_last_good_wind_time;
typedef enum wx_pwr_state_t {
WX_PWR_OFF,
WX_PWR_ON,
WX_PWR_UNDER_RESET
WX_PWR_UNDER_RESET,
WX_PWR_DISABLED
}wx_pwr_state_t;
void wx_get_all_measurements(void);
@ -24,5 +25,10 @@ void wx_pool_dht22(void);
void wx_pool_anemometer(void);
void wx_pwr_init(void);
void wx_pwr_periodic_handle(void);
void wx_pwr_disable_12v_sw(void);
void wx_pwr_disable_5v_isol(void);
void wx_pwr_enable_12v_sw(void);
void wx_pwr_enable_5v_isol(void);
#endif /* WX_HANDLER_H_ */

Wyświetl plik

@ -1,28 +0,0 @@
//
// This file is part of the GNU ARM Eclipse distribution.
// Copyright (c) 2014 Liviu Ionescu.
//
#include "BlinkLed.h"
// ----------------------------------------------------------------------------
void
BlinkLed::powerUp()
{
// Enable GPIO Peripheral clock
RCC_APB2PeriphClockCmd(BLINK_RCC_MASKx(BLINK_PORT_NUMBER), ENABLE);
GPIO_InitTypeDef GPIO_InitStructure;
// Configure pin in output push/pull mode
GPIO_InitStructure.GPIO_Pin = BLINK_PIN_MASK(BLINK_PIN_NUMBER);
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
GPIO_Init(BLINK_GPIOx(BLINK_PORT_NUMBER), &GPIO_InitStructure);
// Start with led turned off
turnOff();
}
// ----------------------------------------------------------------------------

38
src/io.c 100644
Wyświetl plik

@ -0,0 +1,38 @@
/*
* io.c
*
* Created on: 11.06.2020
* Author: mateusz
*/
#include "io.h"
#include <stm32f10x.h>
#include "station_config.h"
void io_oc_init(void) {
#if (defined PARATNC_HWREV_C)
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
GPIO_Init(GPIOA, &GPIO_InitStructure);
#endif
}
void io_oc_output_low(void) {
#if (defined PARATNC_HWREV_C)
GPIO_SetBits(GPIOA, GPIO_Pin_11);
#endif
}
void io_oc_output_hiz(void) {
#if (defined PARATNC_HWREV_C)
GPIO_ResetBits(GPIOA, GPIO_Pin_11);
#endif
}

17
src/io.h 100644
Wyświetl plik

@ -0,0 +1,17 @@
/*
* io.h
*
* Created on: 11.06.2020
* Author: mateusz
*/
#ifndef IO_H_
#define IO_H_
void io_oc_init(void);
void io_oc_output_low(void);
void io_oc_output_hiz(void);
#endif /* IO_H_ */

Wyświetl plik

@ -15,6 +15,7 @@
#include "afsk_pr.h"
#include "TimerConfig.h"
#include "PathConfig.h"
#include "io.h"
#include "it_handlers.h"
@ -214,6 +215,12 @@ int main(int argc, char* argv[]){
#endif
// initialize sensor power control and switch off supply voltage
wx_pwr_init();
// call periodic handle to wait for 1 second and then switch on voltage
wx_pwr_periodic_handle();
// Configure I/O pins for USART1 (Kiss modem)
Configure_GPIO(GPIOA,10,PUD_INPUT); // RX
Configure_GPIO(GPIOA,9,AFPP_OUTPUT_2MHZ); // TX
@ -283,6 +290,9 @@ int main(int argc, char* argv[]){
// initialize GPIO pins leds are connecting to
led_init();
// initalizing separated Open Collector output
io_oc_init();
// initialize AX25 & APRS stuff
AFSK_Init(&main_afsk);
ax25_init(&main_ax25, &main_afsk, 0, 0x00);
@ -295,11 +305,6 @@ int main(int argc, char* argv[]){
rte_wx_init();
#ifdef _METEO
// initialize sensor power control and switch off supply voltage
wx_pwr_init();
// call periodic handle to wait for 1 second and then switch on voltage
wx_pwr_periodic_handle();
// initialize humidity sensor
dht22_init();
@ -418,6 +423,7 @@ int main(int argc, char* argv[]){
srl_receive_data(main_kiss_srl_ctx_ptr, 100, FEND, FEND, 0, 0, 0);
#endif
io_oc_output_low();
GPIO_ResetBits(GPIOC, GPIO_Pin_8 | GPIO_Pin_9);
// configuting system timers

Wyświetl plik

@ -8,8 +8,8 @@
#include "wx_handler.h"
#include <rte_wx.h>
#include <stm32f10x.h>
#include <math.h>
#include <stm32f10x.h>
#include "drivers/_dht22.h"
#include "drivers/ms5611.h"
#include "drivers/analog_anemometer.h"
@ -301,16 +301,34 @@ void wx_pool_anemometer(void) {
}
void wx_pwr_init(void) {
// RELAY_CNTRL
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
#if (defined PARATNC_HWREV_A || defined PARATNC_HWREV_B)
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
#elif (defined PARATNC_HWREV_C)
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
#else
#error ("Hardware Revision not chosen.")
#endif
GPIO_Init(GPIOB, &GPIO_InitStructure);
#if (defined PARATNC_HWREV_C)
// +12V PWR_CNTRL
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
GPIO_Init(GPIOA, &GPIO_InitStructure);
#endif
wx_pwr_state = WX_PWR_OFF;
GPIO_ResetBits(GPIOB, GPIO_Pin_8);
#if (defined PARATNC_HWREV_C)
// +12V_SW PWR_CNTRL
GPIO_ResetBits(GPIOA, GPIO_Pin_6);
#endif
}
void wx_pwr_periodic_handle(void) {
@ -322,7 +340,7 @@ void wx_pwr_periodic_handle(void) {
// if timeout watchod expired there is a time to reset the supply voltage
wx_pwr_state = WX_PWR_UNDER_RESET;
// pulling the output down to switch the relay
// pulling the output down to switch the relay and disable +5V_ISOL (VDD_SW)
GPIO_ResetBits(GPIOB, GPIO_Pin_8);
// setting the last_good timers to current value to prevent reset loop
@ -339,6 +357,14 @@ void wx_pwr_periodic_handle(void) {
// one second delay
delay_fixed(2000);
#if (defined PARATNC_HWREV_C)
// Turn on the +12V_SW voltage
GPIO_SetBits(GPIOA, GPIO_Pin_6);
#endif
delay_fixed(100);
// Turn on the +5V_ISOL (VDD_SW) voltage
GPIO_SetBits(GPIOB, GPIO_Pin_8);
// power is off after power-up and needs to be powered on
@ -348,10 +374,54 @@ void wx_pwr_periodic_handle(void) {
break;
case WX_PWR_UNDER_RESET:
// Turn on the +5V_ISOL (VDD_SW) voltage
GPIO_SetBits(GPIOB, GPIO_Pin_8);
wx_pwr_state = WX_PWR_ON;
break;
case WX_PWR_DISABLED:
break;
}
}
void wx_pwr_disable_12v_sw(void) {
#if (defined PARATNC_HWREV_C)
wx_pwr_state = WX_PWR_DISABLED;
GPIO_ResetBits(GPIOA, GPIO_Pin_6);
#endif
}
void wx_pwr_disable_5v_isol(void) {
wx_pwr_state = WX_PWR_DISABLED;
GPIO_ResetBits(GPIOB, GPIO_Pin_8);
}
void wx_pwr_enable_12v_sw(void) {
#if (defined PARATNC_HWREV_C)
wx_pwr_state = WX_PWR_OFF;
// setting last good measurements timers to inhibit relay clicking
// just after the power is applied
wx_last_good_temperature_time = master_time;
wx_last_good_wind_time = master_time;
#endif
}
void wx_pwr_enable_5v_isol(void) {
#if (defined PARATNC_HWREV_C)
wx_pwr_state = WX_PWR_OFF;
// setting last good measurements timers to inhibit relay clicking
// just after the power is applied
wx_last_good_temperature_time = master_time;
wx_last_good_wind_time = master_time;
#endif
}

Wyświetl plik

@ -9,6 +9,8 @@
#ifdef _ANEMOMETER_ANALOGUE
#define WIND_DEBUG
#include "drivers/analog_anemometer.h"
#include <stdint.h>
@ -33,6 +35,11 @@ uint16_t analog_anemometer_windspeed_pulses_time[ANALOG_ANEMOMETER_SPEED_PULSES_
// an array with calculated times between pulses
uint16_t analog_anemometer_time_between_pulses[ANALOG_ANEMOMETER_SPEED_PULSES_N];
#ifdef WIND_DEBUG
uint16_t analog_anemometer_direction_timer_values[ANALOG_ANEMOMETER_SPEED_PULSES_N];
uint8_t analog_anemometer_direction_timer_values_it = 0;
#endif
// a static copy of impulse-meters/second constant. This value expresses
// how many pulses in 10 seconds measurement time gives 1 m/s.
// Value of ten means that if within 10 second period 10 pulses were detected it gives
@ -84,6 +91,9 @@ void analog_anemometer_init(uint16_t pulses_per_meter_second, uint8_t anemometer
// initializing arrays;
memset(analog_anemometer_windspeed_pulses_time, 0x00, ANALOG_ANEMOMETER_SPEED_PULSES_N);
memset(analog_anemometer_time_between_pulses, 0x00, ANALOG_ANEMOMETER_SPEED_PULSES_N);
#ifdef WIND_DEBUG
memset(analog_anemometer_direction_timer_values, 0x00, ANALOG_ANEMOMETER_SPEED_PULSES_N);
#endif
// enabling the clock for TIM17
RCC->APB2ENR |= RCC_APB2ENR_TIM17EN;
@ -361,6 +371,10 @@ int16_t analog_anemometer_direction_handler(void) {
// getting current counter value
uint16_t current_value = TIM_GetCounter(TIM3);
#ifdef WIND_DEBUG
analog_anemometer_direction_timer_values[(analog_anemometer_direction_timer_values_it++) % ANALOG_ANEMOMETER_SPEED_PULSES_N] = current_value;
#endif
// if the value is greater than maximum one just ignore
if (current_value > UF_MAXIMUM_FREQUENCY) {