Set of features implemented in code responsible for handling an analogue anemometer

-> timer capture-compare configuration
-> dma configuration to copy timer values into buffer
-> converting impulse times into inter-pulse time
-> debouncing & slew rate limitation of inter-pulse time
-> converting inter-pulse time to windspeed
-> averaging windspeed & looking for maximum vale
-> calculating average wind direction

Missing wind direction sensing using external U/f ic
pull/2/head
Mateusz Lubecki 2020-01-04 14:15:33 +01:00
rodzic 515da4bfa4
commit befdd40e66
15 zmienionych plików z 342 dodań i 38 usunięć

Wyświetl plik

@ -4,7 +4,7 @@
#include "aprs/ax25.h"
#define SW_VER "DE06"
#define SW_DATE "25122019"
#define SW_DATE "05012020"
#define SYSTICK_TICKS_PER_SECONDS 100
#define SYSTICK_TICKS_PERIOD 10
@ -14,6 +14,7 @@ extern uint32_t master_time;
extern int32_t main_wx_sensors_pool_timer;
extern int32_t main_packet_tx_pool_timer;
extern int32_t main_two_second_pool_timer;
extern int32_t main_ten_second_pool_timer;
extern AX25Ctx main_ax25;
extern Afsk main_afsk;
@ -28,13 +29,33 @@ extern char after_tx_lock;
extern unsigned short rx10m, tx10m, digi10m, kiss10m;
uint16_t main_get_adc_sample(void);
void main_wx_decremenet_counter(void);
void main_packets_tx_decremenet_counter(void);
void main_two_second_pool_decrement_counter(void);
//void main_wx_decremenet_counter(void);
//void main_packets_tx_decremenet_counter(void);
//void main_two_second_pool_decrement_counter(void);
inline void main_wait_for_tx_complete(void) {
while(main_afsk.sending == 1);
}
inline void main_wx_decremenet_counter(void) {
if (main_wx_sensors_pool_timer > 0)
main_wx_sensors_pool_timer -= SYSTICK_TICKS_PERIOD;
}
inline void main_packets_tx_decremenet_counter(void) {
if (main_packet_tx_pool_timer > 0)
main_packet_tx_pool_timer -= SYSTICK_TICKS_PERIOD;
}
inline void main_two_second_pool_decrement_counter(void) {
if (main_two_second_pool_timer > 0)
main_two_second_pool_timer -= SYSTICK_TICKS_PERIOD;
}
inline void main_ten_second_pool_decremenet_counter(void) {
if (main_ten_second_pool_timer > 0)
main_ten_second_pool_timer -= SYSTICK_TICKS_PERIOD;
}
#endif

Wyświetl plik

@ -13,6 +13,8 @@
#ifndef RTE_WX_H_
#define RTE_WX_H_
#define WIND_AVERAGE_LEN 18
extern float rte_wx_temperature_dallas, rte_wx_temperature_dallas_valid;
extern float rte_wx_temperature_dalls_slew_rate;
extern float rte_wx_temperature_average_dallas_valid;
@ -21,6 +23,13 @@ extern float rte_wx_temperature_ms, rte_wx_temperature_ms_valid;
extern float rte_wx_pressure, rte_wx_pressure_valid;
extern uint16_t rte_wx_windspeed_pulses;
extern uint16_t rte_wx_windspeed[WIND_AVERAGE_LEN];
extern uint8_t rte_wx_windspeed_it;
extern uint16_t rte_wx_winddirection[WIND_AVERAGE_LEN];
extern uint8_t rte_wx_winddirection_it;
extern uint16_t rte_wx_average_windspeed;
extern uint16_t rte_wx_max_windspeed;
extern int16_t rte_wx_average_winddirection;
extern uint8_t rte_wx_tx20_excessive_slew_rate;
@ -30,5 +39,15 @@ extern DallasQF rte_wx_current_dallas_qf, rte_wx_error_dallas_qf;
DallasAverage_t rte_wx_dallas_average;
extern ms5611_qf_t rte_wx_ms5611_qf;
#ifdef __cplusplus
extern "C"
{
#endif
void rte_wx_init(void);
#ifdef __cplusplus
}
#endif
#endif /* RTE_WX_H_ */

Wyświetl plik

@ -21,6 +21,7 @@ typedef enum wx_pwr_state_t {
void wx_get_all_measurements(void);
void wx_pool_dht22(void);
void wx_pool_analog_anemometer(void);
void wx_pwr_init(void);
void wx_pwr_periodic_handle(void);

116
memory_metrics.txt 100644
Wyświetl plik

@ -0,0 +1,116 @@
#define SW_VER "DE06"
#define SW_DATE "05012020"
---
MEMORY USAGE METRICS:
14:11:23 **** Incremental Build of configuration Debug for project ParaTNC ****
make all
Invoking: Cross ARM GNU Print Size
arm-none-eabi-size --format=berkeley "ParaTNC.elf"
text data bss dec hex filename
52110 588 5440 58138 e31a ParaTNC.elf
Finished building: ParaTNC.siz
14:11:24 Build Finished (took 422ms)
---
CONFIGURATION USED DURING COMPILATION:
#ifndef STATION_CONFIG_H_
#define STATION_CONFIG_H_
/* ------------------ */
/* MODES OF OPERATION */
#define _METEO // Enable meteo station
#define _DIGI // Enable WIDE1-1 digipeater
//#define _DIGI_ONLY_789 // Limit digipeater to handle only -7, -8 and -9 SSIDs
//#define _VICTRON // Enable support for Victron VE.Direct protocol
/* MODES OF OPERATION */
/* ------------------ */
#define PARATNC_HWREV_A
//#define PARATNC_HWREV_B
/* ---------------------------- */
/* WEATHER/METEO CONFIGURATION */
//#define _DALLAS_AS_TELEM // Use Dallas one-wire thermometer as a 5th telemetry channel
// May be used even if _METEO is not enabled
#define _DALLAS_SPLIT_PIN
//#define _ANEMOMETER_TX20
#define _ANEMOMETER_ANALOGUE
#define _ANEMOMETER_PULSES_IN_10SEC_PER_ONE_MS_OF_WINDSPEED 10
#define _ANEMOMETER_DIRECTION_ASCENDING_WITH_VOLTAGE
#define _ANEMOMETER_VOLTAGE_FOR_1DEG_DIRECTION
#define _ANEMOMETER_VOLTAGE_FOR_359DEG_DIRECTION
/* WEATHER/METEO CONFIGURATION */
/* ---------------------------- */
======================================================================
#define SW_VER "DE06"
#define SW_DATE "05012020"
---
MEMORY USAGE METRICS:
Invoking: Cross ARM GNU Create Flash Image
arm-none-eabi-objcopy -O ihex "ParaTNC.elf" "ParaTNC.hex"
Finished building: ParaTNC.hex
Invoking: Cross ARM GNU Print Size
arm-none-eabi-size --format=berkeley "ParaTNC.elf"
text data bss dec hex filename
51574 588 5796 57958 e266 ParaTNC.elf
Finished building: ParaTNC.siz
12:15:35 Build Finished (took 8s.439ms)
---
CONFIGURATION USED DURING COMPILATION:
#ifndef STATION_CONFIG_H_
#define STATION_CONFIG_H_
/* ------------------ */
/* MODES OF OPERATION */
#define _METEO // Enable meteo station
#define _DIGI // Enable WIDE1-1 digipeater
//#define _DIGI_ONLY_789 // Limit digipeater to handle only -7, -8 and -9 SSIDs
//#define _VICTRON // Enable support for Victron VE.Direct protocol
/* MODES OF OPERATION */
/* ------------------ */
#define PARATNC_HWREV_A
//#define PARATNC_HWREV_B
/* ---------------------------- */
/* WEATHER/METEO CONFIGURATION */
//#define _DALLAS_AS_TELEM // Use Dallas one-wire thermometer as a 5th telemetry channel
// May be used even if _METEO is not enabled
#define _DALLAS_SPLIT_PIN
#define _ANEMOMETER_TX20
//#define _ANEMOMETER_ANALOGUE
#define _ANEMOMETER_PULSES_IN_10SEC_PER_ONE_MS_OF_WINDSPEED 10
#define _ANEMOMETER_DIRECTION_ASCENDING_WITH_VOLTAGE
#define _ANEMOMETER_VOLTAGE_FOR_1DEG_DIRECTION
#define _ANEMOMETER_VOLTAGE_FOR_359DEG_DIRECTION
/* WEATHER/METEO CONFIGURATION */
/* ---------------------------- */

Wyświetl plik

@ -8,7 +8,7 @@
#include <stm32f10x.h>
void LedConfig(void) {
void led_init(void) {
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;

Wyświetl plik

@ -76,6 +76,8 @@ void SysTick_Handler(void) {
main_two_second_pool_decrement_counter();
main_ten_second_pool_decremenet_counter();
srl_keep_timeout();
i2cKeepTimeout();

Wyświetl plik

@ -86,6 +86,9 @@ int32_t main_packet_tx_pool_timer = 60000;
// two second pool interval
int32_t main_two_second_pool_timer = 2000;
// ten second pool interval
int32_t main_ten_second_pool_timer = 10000;
// global variables represending the AX25/APRS stack
AX25Ctx main_ax25;
Afsk main_afsk;
@ -183,13 +186,22 @@ main(int argc, char* argv[])
main_own_path_ln = ConfigPath(main_own_path);
#ifdef _METEO
// initialize i2c controller
i2cConfigure();
#endif
LedConfig();
// initialize GPIO pins leds are connecting to
led_init();
// initialize AX25 & APRS stuff
AFSK_Init(&main_afsk);
ax25_init(&main_ax25, &main_afsk, 0, 0x00);
DA_Init();
// initialize variables & arrays in rte_wx
rte_wx_init();
#ifdef _METEO
// initialize sensor power control and switch off supply voltage
wx_pwr_init();
@ -326,8 +338,14 @@ main(int argc, char* argv[])
//telemetry_send_values(rx10m, tx10m, digi10m, kiss10m, rte_wx_temperature_dallas_valid, rte_wx_dallas_qf, rte_wx_ms5611_qf, rte_wx_dht.qf);
SendOwnBeacon();
#else
#ifdef _ANEMOMETER_TX20
SendWXFrame(&VNAME, rte_wx_temperature_dallas_valid, rte_wx_pressure_valid);
#endif
#else
SendWXFrame(rte_wx_average_windspeed, rte_wx_max_windspeed, rte_wx_average_winddirection, rte_wx_temperature_dallas_valid, rte_wx_pressure_valid);
#endif // #ifdef _ANEMOMETER_TX20
#endif // #ifndef _METEO
}
button_inhibit = 1;
@ -423,6 +441,13 @@ main(int argc, char* argv[])
main_two_second_pool_timer = 2000;
}
if (main_ten_second_pool_timer < 10) {
wx_pool_analog_anemometer();
main_ten_second_pool_timer = 10000;
}
#ifdef _METEO
// dht22 sensor communication pooling
wx_pool_dht22();
@ -435,20 +460,7 @@ uint16_t main_get_adc_sample(void) {
return (uint16_t) ADC1->DR;
}
void main_wx_decremenet_counter(void) {
if (main_wx_sensors_pool_timer > 0)
main_wx_sensors_pool_timer -= SYSTICK_TICKS_PERIOD;
}
void main_packets_tx_decremenet_counter(void) {
if (main_packet_tx_pool_timer > 0)
main_packet_tx_pool_timer -= SYSTICK_TICKS_PERIOD;
}
void main_two_second_pool_decrement_counter(void) {
if (main_two_second_pool_timer > 0)
main_two_second_pool_timer -= SYSTICK_TICKS_PERIOD;
}
#pragma GCC diagnostic pop

Wyświetl plik

@ -59,8 +59,15 @@ void packet_tx_handler(void) {
// _DALLAS_AS_TELEM wil be set during compilation wx packets will be filled by temperature from MS5611 sensor
SendWXFrame(&VNAME, rte_wx_temperature_valid, rte_wx_pressure_valid);
#else
SendWXFrame(&VNAME, rte_wx_temperature_average_dallas_valid, rte_wx_pressure_valid);
#ifdef _ANEMOMETER_TX20
SendWXFrame(&VNAME, rte_wx_temperature_average_dallas_valid, rte_wx_pressure_valid);
#else
SendWXFrame(rte_wx_average_windspeed, rte_wx_max_windspeed, rte_wx_average_winddirection, rte_wx_temperature_dallas_valid, rte_wx_pressure_valid);
#endif // #ifdef _ANEMOMETER_TX20
#endif
main_wait_for_tx_complete();
packet_tx_meteo_counter = 0;
@ -70,14 +77,18 @@ void packet_tx_handler(void) {
srl_wait_for_tx_completion();
#ifdef _ANEMOMETER_TX20
SendWXFrameToBuffer(&VNAME, rte_wx_temperature_dallas_valid, rte_wx_pressure_valid, srl_tx_buffer, TX_BUFFER_LN, &ln);
#else
SendWXFrameToBuffer(rte_wx_average_windspeed, rte_wx_max_windspeed, rte_wx_average_winddirection, rte_wx_temperature_dallas_valid, rte_wx_pressure_valid, srl_tx_buffer, TX_BUFFER_LN, &ln);
#endif
srl_start_tx(ln);
packet_tx_meteo_kiss_counter = 0;
}
#endif
#endif // #ifdef _METEO
if (packet_tx_telemetry_counter >= packet_tx_telemetry_interval) {

Wyświetl plik

@ -16,6 +16,13 @@ float rte_wx_temperature_ms = 0.0f, rte_wx_temperature_ms_valid = 0.0f;
float rte_wx_pressure = 0.0f, rte_wx_pressure_valid = 0.0f;
uint16_t rte_wx_windspeed_pulses = 0;
uint16_t rte_wx_windspeed[WIND_AVERAGE_LEN];
uint8_t rte_wx_windspeed_it = 0;
uint16_t rte_wx_winddirection[WIND_AVERAGE_LEN];
uint8_t rte_wx_winddirection_it = 0;
uint16_t rte_wx_average_windspeed = 0;
uint16_t rte_wx_max_windspeed = 0;
int16_t rte_wx_average_winddirection = 0;
uint8_t rte_wx_tx20_excessive_slew_rate = 0;
@ -24,4 +31,11 @@ DallasQF rte_wx_current_dallas_qf, rte_wx_error_dallas_qf = DALLAS_QF_UNKNOWN;
DallasAverage_t rte_wx_dallas_average;
ms5611_qf_t rte_wx_ms5611_qf;
void rte_wx_init(void) {
int i = 0;
for (; i < WIND_AVERAGE_LEN; i++) {
rte_wx_windspeed[i] = 0;
rte_wx_winddirection[i] = 0;
}
}

Wyświetl plik

@ -9,8 +9,10 @@
#include <rte_wx.h>
#include <stm32f10x.h>
#include <math.h>
#include "drivers/_dht22.h"
#include "drivers/ms5611.h"
#include "drivers/analog_anemometer.h"
#include "station_config.h"
@ -147,6 +149,73 @@ void wx_pool_dht22(void) {
}
void wx_pool_analog_anemometer(void) {
// locals
uint32_t average_windspeed = 0;
uint32_t wind_direction_x_avg = 0;
uint32_t wind_direction_y_avg = 0;
uint16_t wind_direction_x = 0;
uint16_t wind_direction_y = 0;
short i = 0;
// this windspeed is scaled * 10. Example: 0.2 meters per second is stored as 2
uint16_t scaled_windspeed = analog_anemometer_get_ms_from_pulse(rte_wx_windspeed_pulses);
// putting the wind speed into circular buffer
rte_wx_windspeed[rte_wx_windspeed_it] = scaled_windspeed;
// increasing the iterator to the windspeed buffer
rte_wx_windspeed_it++;
// checking if iterator reached an end of the buffer
if (rte_wx_windspeed_it >= WIND_AVERAGE_LEN)
rte_wx_windspeed_it = 0;
// calculating the average windspeed
for (i = 0; i < WIND_AVERAGE_LEN; i++)
average_windspeed += rte_wx_windspeed[i];
average_windspeed /= WIND_AVERAGE_LEN;
// store the value in rte
rte_wx_average_windspeed = average_windspeed;
// reuse the local variable to find maximum value
average_windspeed = 0;
// looking for gusts
for (i = 0; i < WIND_AVERAGE_LEN; i++) {
if (average_windspeed < rte_wx_windspeed[i])
average_windspeed = rte_wx_windspeed[i];
}
// storing wind gusts value in rte
rte_wx_max_windspeed = average_windspeed;
// calculating average wind direction
for (i = 0; i < WIND_AVERAGE_LEN; i++) {
// split the wind direction into x and y component
wind_direction_x = (uint16_t)(100.0f * cosf((float)rte_wx_winddirection[i] * M_PI/180.0f));
wind_direction_y = (uint16_t)(100.0f * sinf((float)rte_wx_winddirection[i] * M_PI/180.0f));
// adding components to calculate average
wind_direction_x_avg += wind_direction_x;
wind_direction_y_avg += wind_direction_y;
}
// dividing to get average of x and y componen
wind_direction_x_avg /= WIND_AVERAGE_LEN;
wind_direction_y_avg /= WIND_AVERAGE_LEN;
// converting x & y component of wind direction back to an angle
rte_wx_average_winddirection = (uint16_t)(atan2f(wind_direction_y_avg , wind_direction_x_avg) * 180.0f/M_PI);
if (rte_wx_average_winddirection < 0)
rte_wx_average_winddirection += 360;
}
void wx_pwr_init(void) {
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8;

Wyświetl plik

@ -9,10 +9,18 @@
#define INCLUDE_APRS_WX_H_
#include "drivers/tx20.h"
#include "station_config.h"
#include <stdint.h>
#ifdef _ANEMOMETER_TX20
void SendWXFrame(Anemometer* input, float temperatura, float cisnienie);
void SendWXFrameToBuffer(Anemometer* input, float temperatura, float cisnienie, uint8_t* buffer, uint16_t buffer_ln, uint16_t* output_ln);
#else
void SendWXFrame(uint16_t windspeed, uint16_t windgusts, uint16_t winddirection, float temperatura, float cisnienie);
void SendWXFrameToBuffer(uint16_t windspeed, uint16_t windgusts, uint16_t winddirection, float temperatura, float cisnienie, uint8_t* buffer, uint16_t buffer_ln, uint16_t* output_ln);
#endif
#endif /* INCLUDE_APRS_WX_H_ */

Wyświetl plik

@ -1,6 +1,10 @@
#ifndef __TX20_H
#define __TX20_H
#include "station_config.h"
#ifdef _ANEMOMETER_TX20
#define VNAME TX20 // nazwa tworzonej zmiennej strukturalnej
typedef struct {
@ -71,4 +75,6 @@ void TX20DataParse(void);
extern Anemometer VNAME;
#endif
#endif // #ifdef _ANEMOMETER_TX20
#endif // #ifndef __TX20_H

Wyświetl plik

@ -12,15 +12,13 @@
#include "station_config.h"
#include <stdio.h>
void SendOwnBeacon(void) {
// BcnLng = sprintf(BcnInfoField, "=%07.2f%c%c%08.2f%c%c %s", this->Settings.Lat, this->Settings.LatNS, this->Settings.BcnSymbolF, this->Settings.Lon, this->Settings.LonWE, this->Settings.BcnSymbolS, this->Settings.Comment);
main_own_aprs_msg_len = sprintf(main_own_aprs_msg, "=%07.2f%c%c%08.2f%c%c %s\0", (float)_LAT, _LATNS, _SYMBOL_F, (float)_LON, _LONWE, _SYMBOL_S, _COMMENT);
main_own_aprs_msg[main_own_aprs_msg_len] = 0;
// fifo_flush(&a.tx_fifo);
ax25_sendVia(&main_ax25, main_own_path, main_own_path_ln, main_own_aprs_msg, main_own_aprs_msg_len);
after_tx_lock = 1;
// for(jj = 0; jj <= 0xFBFFF; jj++);
// while(ax25.dcd == true);
afsk_txStart(&main_afsk);
}
@ -29,7 +27,5 @@ void SendStartup(void) {
main_own_aprs_msg[main_own_aprs_msg_len] = 0;
ax25_sendVia(&main_ax25, main_own_path, main_own_path_ln, main_own_aprs_msg, main_own_aprs_msg_len);
after_tx_lock = 1;
// for(jj = 0; jj <= 0xFBFFF; jj++);
// while(ax25.dcd == true);
afsk_txStart(&main_afsk);
}

Wyświetl plik

@ -13,14 +13,27 @@
#include "station_config.h"
#ifdef _ANEMOMETER_TX20
void SendWXFrame(Anemometer* input, float temperatura, float cisnienie) {
#else
void SendWXFrame(uint16_t windspeed, uint16_t windgusts, uint16_t winddirection, float temperatura, float cisnienie) {
#endif
float max_wind_speed = 0.0f, temp = 0.0f;
unsigned char wind_speed_mph = 0, wind_gusts_mph = 0, d = 0;
unsigned pressure = 0;
uint8_t wind_speed_mph = 0, wind_gusts_mph = 0, d = 0;
uint32_t pressure = 0;
uint16_t direction = 0;
#ifdef _ANEMOMETER_TX20
for(d = 1; d <= TX20_BUFF_LN - 1 ; d++)
if (VNAME.HistoryAVG[d].WindSpeed > max_wind_speed)
max_wind_speed = VNAME.HistoryAVG[d].WindSpeed; // Wyszukiwane najwiekszej wartosci
temp = input->HistoryAVG[0].WindSpeed;
#else
#endif
temp /= 0.45; // Konwersja na mile na godzine
max_wind_speed /= 0.45;
if ((temp - (short)temp) >= 0.5) // Zaokraglanie wartosci
@ -44,7 +57,7 @@ void SendWXFrame(Anemometer* input, float temperatura, float cisnienie) {
pressure = (unsigned)(cisnienie * 10);
main_own_aprs_msg_len = sprintf(main_own_aprs_msg, "!%07.2f%c%c%08.2f%c%c%03d/%03dg%03dt%03dr...p...P...b%05d", _LAT, _LATNS, '/', _LON, _LONWE, '_', /* kierunek */(short)(input->HistoryAVG[0].WindDirX), /* predkosc*/(int)wind_speed_mph, /* porywy */(short)(wind_gusts_mph), /*temperatura */(short)(temperatura*1.8+32), pressure);
main_own_aprs_msg_len = sprintf(main_own_aprs_msg, "!%07.2f%c%c%08.2f%c%c%03d/%03dg%03dt%03dr...p...P...b%05d", _LAT, _LATNS, '/', _LON, _LONWE, '_', /* kierunek */direction, /* predkosc*/(int)wind_speed_mph, /* porywy */(short)(wind_gusts_mph), /*temperatura */(short)(temperatura*1.8+32), pressure);
main_own_aprs_msg[main_own_aprs_msg_len] = 0;
ax25_sendVia(&main_ax25, main_own_path, main_own_path_ln, main_own_aprs_msg, main_own_aprs_msg_len);
after_tx_lock = 1;
@ -54,16 +67,29 @@ void SendWXFrame(Anemometer* input, float temperatura, float cisnienie) {
}
#ifdef _ANEMOMETER_TX20
void SendWXFrameToBuffer(Anemometer* input, float temperatura, float cisnienie, uint8_t* buffer, uint16_t buffer_ln, uint16_t* output_ln) {
#else
void SendWXFrameToBuffer(uint16_t windspeed, uint16_t windgusts, uint16_t winddirection, float temperatura, float cisnienie, uint8_t* buffer, uint16_t buffer_ln, uint16_t* output_ln) {
#endif
uint16_t output_frame_ln = 0;
float max_wind_speed = 0.0f, temp = 0.0f;
unsigned char wind_speed_mph = 0, wind_gusts_mph = 0, d = 0;
unsigned pressure = 0;
uint8_t wind_speed_mph = 0, wind_gusts_mph = 0, d = 0;
uint32_t pressure = 0;
uint16_t direction = 0;
#ifdef _ANEMOMETER_TX20
for(d = 1; d <= TX20_BUFF_LN - 1 ; d++)
if (VNAME.HistoryAVG[d].WindSpeed > max_wind_speed)
max_wind_speed = VNAME.HistoryAVG[d].WindSpeed; // Wyszukiwane najwiekszej wartosci
temp = input->HistoryAVG[0].WindSpeed;
#else
#endif
temp /= 0.45; // Konwersja na mile na godzine
max_wind_speed /= 0.45;
if ((temp - (short)temp) >= 0.5) // Zaokraglanie wartosci
@ -82,7 +108,7 @@ void SendWXFrameToBuffer(Anemometer* input, float temperatura, float cisnienie,
pressure = (unsigned)(cisnienie * 10);
main_own_aprs_msg_len = sprintf(main_own_aprs_msg, "!%07.2f%c%c%08.2f%c%c%03d/%03dg%03dt%03dr...p...P...b%05d", _LAT, _LATNS, '/', _LON, _LONWE, '_', /* kierunek */(short)(input->HistoryAVG[0].WindDirX), /* predkosc*/(int)wind_speed_mph, /* porywy */(short)(wind_gusts_mph), /*temperatura */(short)(temperatura*1.8+32), pressure);
main_own_aprs_msg_len = sprintf(main_own_aprs_msg, "!%07.2f%c%c%08.2f%c%c%03d/%03dg%03dt%03dr...p...P...b%05d", _LAT, _LATNS, '/', _LON, _LONWE, '_', /* kierunek */direction, /* predkosc*/(int)wind_speed_mph, /* porywy */(short)(wind_gusts_mph), /*temperatura */(short)(temperatura*1.8+32), pressure);
// aprs_msg_len = sprintf(aprs_msg, "%s%03d/%03dg%03dt%03dr%03dp%03dP%03db%04d ~", "!5001.45N/02159.66E_", /* kierunek */90, /* predkosc*/(int)(2.1 * 2.23698), /* porywy */(short)(5.7 * 2.23698), /*temperatura */(short)(23 * 1.8 + 32), 0, 0, 0, 10130);
main_own_aprs_msg[main_own_aprs_msg_len] = 0;

Wyświetl plik

@ -1,4 +1,7 @@
#include "drivers/tx20.h"
#ifdef _ANEMOMETER_TX20
#include <stdlib.h>
//#define STM32F10X_MD_VL
#include <stm32f10x.h>
@ -9,8 +12,6 @@
#include "main.h"
#include "wx_handler.h"
#include "station_config.h"
#define BS VNAME.BitSampler
#define BQ VNAME.BitQueue
#define QL VNAME.QueueLenght
@ -38,7 +39,7 @@ void inline TX20BlinkLed(void) {
#endif
void TX20Init(void) {
char i;
int i;
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
@ -296,3 +297,5 @@ void TIM4_IRQHandler( void ) {
#endif
#endif // #define _ANEMOMETER_TX20