kopia lustrzana https://github.com/SP8EBC/ParaTNC
first sketch of communication with serial port
rodzic
c266446420
commit
1fbcd13d24
|
@ -12,6 +12,7 @@ RM := rm -rf
|
|||
-include system/src/umb_master/subdir.mk
|
||||
-include system/src/stm32l4-hal-driver/subdir.mk
|
||||
-include system/src/modbus_rtu/subdir.mk
|
||||
-include system/src/gsm/subdir.mk
|
||||
-include system/src/drivers/l4/subdir.mk
|
||||
-include system/src/drivers/subdir.mk
|
||||
-include system/src/diag/subdir.mk
|
||||
|
|
|
@ -34,6 +34,7 @@ system/src/davis_vantage \
|
|||
system/src/diag \
|
||||
system/src/drivers \
|
||||
system/src/drivers/l4 \
|
||||
system/src/gsm \
|
||||
system/src/modbus_rtu \
|
||||
system/src/stm32l4-hal-driver \
|
||||
system/src/umb_master \
|
||||
|
|
|
@ -1,5 +1,6 @@
|
|||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<launchConfiguration type="ilg.gnumcueclipse.debug.gdbjtag.openocd.launchConfigurationType">
|
||||
<stringAttribute key="ilg.gnumcueclipse.debug.gdbjtag.PERIPHERALS" value="<?xml version="1.0" encoding="UTF-8" standalone="no"?> <peripherals> <peripheral name="USART3"/> </peripherals> "/>
|
||||
<booleanAttribute key="ilg.gnumcueclipse.debug.gdbjtag.openocd.doContinue" value="true"/>
|
||||
<booleanAttribute key="ilg.gnumcueclipse.debug.gdbjtag.openocd.doDebugInRam" value="false"/>
|
||||
<booleanAttribute key="ilg.gnumcueclipse.debug.gdbjtag.openocd.doFirstReset" value="true"/>
|
||||
|
|
|
@ -48,6 +48,7 @@ extern char main_symbol_s;
|
|||
|
||||
extern srl_context_t* main_kiss_srl_ctx_ptr;
|
||||
extern srl_context_t* main_wx_srl_ctx_ptr;
|
||||
extern srl_context_t* main_gsm_srl_ctx_ptr;
|
||||
|
||||
extern uint8_t main_kiss_enabled;
|
||||
|
||||
|
|
|
@ -149,6 +149,15 @@ void USART2_IRQHandler(void) {
|
|||
srl_irq_handler(main_wx_srl_ctx_ptr);
|
||||
}
|
||||
|
||||
#ifdef STM32L471xx
|
||||
void USART3_IRQHandler() {
|
||||
NVIC_ClearPendingIRQ(USART3_IRQn);
|
||||
srl_irq_handler(main_gsm_srl_ctx_ptr);
|
||||
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void I2C1_EV_IRQHandler(void) {
|
||||
NVIC_ClearPendingIRQ(I2C1_EV_IRQn);
|
||||
|
||||
|
|
67
src/main.c
67
src/main.c
|
@ -14,6 +14,8 @@
|
|||
#include <stm32l4xx_ll_rcc.h>
|
||||
#include <stm32l4xx_ll_gpio.h>
|
||||
#include "cmsis/stm32l4xx/system_stm32l4xx.h"
|
||||
|
||||
#include "gsm/sim800c.h"
|
||||
#endif
|
||||
|
||||
#include <delay.h>
|
||||
|
@ -155,12 +157,20 @@ srl_context_t main_kiss_srl_ctx;
|
|||
// serial context for UART used for comm with wx sensors
|
||||
srl_context_t main_wx_srl_ctx;
|
||||
|
||||
#if defined(PARAMETEO)
|
||||
// serial context for communication with GSM module
|
||||
srl_context_t main_gsm_srl_ctx;
|
||||
#endif
|
||||
|
||||
// a pointer to KISS context
|
||||
srl_context_t* main_kiss_srl_ctx_ptr;
|
||||
|
||||
// a pointer to wx comms context
|
||||
srl_context_t* main_wx_srl_ctx_ptr;
|
||||
|
||||
// a pointer to gsm context
|
||||
srl_context_t* main_gsm_srl_ctx_ptr;
|
||||
|
||||
// target USART1 (kiss) baudrate
|
||||
uint32_t main_target_kiss_baudrate;
|
||||
|
||||
|
@ -206,8 +216,10 @@ char after_tx_lock;
|
|||
|
||||
unsigned short rx10m = 0, tx10m = 0, digi10m = 0, digidrop10m = 0, kiss10m = 0;
|
||||
|
||||
#if defined(STM32L471xx)
|
||||
#if defined(PARAMETEO)
|
||||
LL_GPIO_InitTypeDef GPIO_InitTypeDef;
|
||||
|
||||
gsm_sim800_state_t main_gsm_state;
|
||||
#endif
|
||||
|
||||
static void message_callback(struct AX25Msg *msg) {
|
||||
|
@ -263,7 +275,7 @@ int main(int argc, char* argv[]){
|
|||
BKP->DR6 = 0;
|
||||
#endif
|
||||
|
||||
#if defined(STM32L471xx)
|
||||
#if defined(PARAMETEO)
|
||||
system_clock_update_l4();
|
||||
|
||||
if (system_clock_configure_l4() != 0) {
|
||||
|
@ -278,8 +290,8 @@ int main(int argc, char* argv[]){
|
|||
|
||||
system_clock_configure_rtc_l4();
|
||||
|
||||
RCC->APB1ENR1 |= (RCC_APB1ENR1_TIM2EN | RCC_APB1ENR1_TIM3EN | RCC_APB1ENR1_TIM4EN | RCC_APB1ENR1_TIM5EN | RCC_APB1ENR1_TIM7EN | RCC_APB1ENR1_USART2EN | RCC_APB1ENR1_USART3EN | RCC_APB1ENR1_DAC1EN | RCC_APB1ENR1_I2C1EN);
|
||||
RCC->APB2ENR |= (RCC_APB2ENR_TIM1EN | RCC_APB2ENR_USART1EN);
|
||||
RCC->APB1ENR1 |= (RCC_APB1ENR1_TIM2EN | RCC_APB1ENR1_TIM3EN | RCC_APB1ENR1_TIM4EN | RCC_APB1ENR1_TIM5EN | RCC_APB1ENR1_TIM7EN | RCC_APB1ENR1_USART2EN | RCC_APB1ENR1_USART3EN | RCC_APB1ENR1_DAC1EN | RCC_APB1ENR1_I2C1EN | RCC_APB1ENR1_USART3EN);
|
||||
RCC->APB2ENR |= (RCC_APB2ENR_TIM1EN | RCC_APB2ENR_USART1EN); // RCC_APB1ENR1_USART3EN
|
||||
RCC->AHB1ENR |= (RCC_AHB1ENR_CRCEN | RCC_AHB1ENR_DMA1EN);
|
||||
RCC->AHB2ENR |= (RCC_AHB2ENR_ADCEN | RCC_AHB2ENR_GPIOAEN | RCC_AHB2ENR_GPIOBEN | RCC_AHB2ENR_GPIOCEN | RCC_AHB2ENR_GPIODEN);
|
||||
RCC->BDCR |= RCC_BDCR_RTCEN;
|
||||
|
@ -445,7 +457,7 @@ int main(int argc, char* argv[]){
|
|||
|
||||
#endif
|
||||
|
||||
#if defined(STM32L471xx)
|
||||
#if defined(PARAMETEO)
|
||||
// initialize all powersaving functions
|
||||
pwr_save_init(main_config_data_mode->powersave);
|
||||
#endif
|
||||
|
@ -509,6 +521,23 @@ int main(int argc, char* argv[]){
|
|||
GPIO_InitTypeDef.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
|
||||
LL_GPIO_Init(GPIOA, &GPIO_InitTypeDef); // TX
|
||||
|
||||
// USART3 - GSM
|
||||
GPIO_InitTypeDef.Mode = LL_GPIO_MODE_ALTERNATE;
|
||||
GPIO_InitTypeDef.Pin = LL_GPIO_PIN_10;
|
||||
GPIO_InitTypeDef.Pull = LL_GPIO_PULL_NO;
|
||||
GPIO_InitTypeDef.Speed = LL_GPIO_SPEED_FREQ_VERY_HIGH;
|
||||
GPIO_InitTypeDef.Alternate = LL_GPIO_AF_7;
|
||||
GPIO_InitTypeDef.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
|
||||
LL_GPIO_Init(GPIOB, &GPIO_InitTypeDef); // TX
|
||||
|
||||
GPIO_InitTypeDef.Mode = LL_GPIO_MODE_ALTERNATE;
|
||||
GPIO_InitTypeDef.Pin = LL_GPIO_PIN_11;
|
||||
GPIO_InitTypeDef.Pull = LL_GPIO_PULL_NO;
|
||||
GPIO_InitTypeDef.Speed = LL_GPIO_SPEED_FREQ_VERY_HIGH;
|
||||
GPIO_InitTypeDef.Alternate = LL_GPIO_AF_7;
|
||||
GPIO_InitTypeDef.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
|
||||
LL_GPIO_Init(GPIOB, &GPIO_InitTypeDef); // RX
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(PARATNC_HWREV_A) || defined(PARATNC_HWREV_B)
|
||||
|
@ -538,10 +567,17 @@ int main(int argc, char* argv[]){
|
|||
|
||||
main_kiss_srl_ctx_ptr = &main_kiss_srl_ctx;
|
||||
main_wx_srl_ctx_ptr = &main_wx_srl_ctx;
|
||||
#if defined(PARAMETEO)
|
||||
main_gsm_srl_ctx_ptr = &main_gsm_srl_ctx;
|
||||
#endif
|
||||
|
||||
main_target_kiss_baudrate = 9600u;
|
||||
main_target_wx_baudrate = _SERIAL_BAUDRATE;
|
||||
|
||||
#if defined(PARAMETEO)
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(PARAMETEO)
|
||||
// swtich power to M4. turn on sensors but keep GSM modem turned off
|
||||
pwr_save_switch_mode_to_m4();
|
||||
|
@ -640,6 +676,8 @@ int main(int argc, char* argv[]){
|
|||
#if defined(PARAMETEO)
|
||||
main_wx_srl_ctx_ptr->te_pin = LL_GPIO_PIN_8;
|
||||
main_wx_srl_ctx_ptr->te_port = GPIOA;
|
||||
|
||||
srl_init(main_gsm_srl_ctx_ptr, USART3, srl_usart3_rx_buffer, RX_BUFFER_1_LN, srl_usart3_tx_buffer, TX_BUFFER_1_LN, 115200, 1);
|
||||
#endif
|
||||
|
||||
// initialize APRS path with zeros
|
||||
|
@ -858,6 +896,10 @@ int main(int argc, char* argv[]){
|
|||
|
||||
io_ext_watchdog_service();
|
||||
|
||||
if (main_config_data_mode->gsm == 1) {
|
||||
gsm_sim800_init(&main_gsm_state);
|
||||
}
|
||||
|
||||
if (main_config_data_basic-> beacon_at_bootup == 1) {
|
||||
beacon_send_own();
|
||||
}
|
||||
|
@ -930,6 +972,17 @@ int main(int argc, char* argv[]){
|
|||
rx10m++;
|
||||
}
|
||||
|
||||
// if GSM communication is enabled
|
||||
if (main_config_data_mode->gsm == 1) {
|
||||
|
||||
// if data has been received
|
||||
if (main_gsm_srl_ctx_ptr->srl_rx_state == SRL_RX_DONE || main_kiss_srl_ctx_ptr->srl_rx_state == SRL_RX_ERROR) {
|
||||
|
||||
// receive callback for communicatio with the modem
|
||||
gsm_sim800_rx_done_callback(main_gsm_srl_ctx_ptr, &main_gsm_state);
|
||||
}
|
||||
}
|
||||
|
||||
// if Victron VE.direct client is enabled
|
||||
if (main_config_data_mode->victron == 1) {
|
||||
|
||||
|
@ -1066,6 +1119,10 @@ int main(int argc, char* argv[]){
|
|||
|
||||
digi_pool_viscous();
|
||||
|
||||
#ifdef PARAMETEO
|
||||
gsm_sim800_pool(main_gsm_srl_ctx_ptr, &main_gsm_state);
|
||||
#endif
|
||||
|
||||
if ((main_config_data_mode->wx & WX_ENABLED) == 1) {
|
||||
analog_anemometer_direction_handler();
|
||||
}
|
||||
|
|
|
@ -162,6 +162,11 @@ extern uint8_t srl_usart2_tx_buffer[TX_BUFFER_2_LN];
|
|||
extern uint8_t srl_usart2_rx_buffer[RX_BUFFER_2_LN];
|
||||
#endif
|
||||
|
||||
#ifdef PARAMETEO
|
||||
extern uint8_t srl_usart3_tx_buffer[TX_BUFFER_1_LN];
|
||||
extern uint8_t srl_usart3_rx_buffer[TX_BUFFER_1_LN];
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
|
|
|
@ -0,0 +1,27 @@
|
|||
/*
|
||||
* sim800c.h
|
||||
*
|
||||
* Created on: Jan 18, 2022
|
||||
* Author: mateusz
|
||||
*/
|
||||
|
||||
#ifndef INCLUDE_GSM_SIM800C_H_
|
||||
#define INCLUDE_GSM_SIM800C_H_
|
||||
|
||||
#include "drivers/serial.h"
|
||||
|
||||
typedef enum gsm_sim800_state_t {
|
||||
SIM800_UNKNOWN,
|
||||
SIM800_POWERED_OFF,
|
||||
SIM800_NOT_YET_COMM,
|
||||
SIM800_INITIALIZIG,
|
||||
SIM800_ALIVE,
|
||||
SIM800_GPRS_CONNECTED
|
||||
}gsm_sim800_state_t;
|
||||
|
||||
void gsm_sim800_init(gsm_sim800_state_t * state);
|
||||
|
||||
void gsm_sim800_pool(srl_context_t * srl_context, gsm_sim800_state_t * state);
|
||||
void gsm_sim800_rx_done_callback(srl_context_t * srl_context, gsm_sim800_state_t * state);
|
||||
|
||||
#endif /* INCLUDE_GSM_SIM800C_H_ */
|
|
@ -88,7 +88,7 @@ void srl_init(
|
|||
NVIC_EnableIRQ( USART2_IRQn );
|
||||
}
|
||||
|
||||
port->CR1 |= USART_CR1_UE;
|
||||
port->CR1 |= USART_CR1_UE;
|
||||
port->SR &= (0xFFFFFFFF ^ USART_SR_TC);
|
||||
|
||||
ctx->srl_rx_state = SRL_RX_IDLE;
|
||||
|
|
|
@ -29,6 +29,9 @@ uint8_t srl_usart2_tx_buffer[TX_BUFFER_2_LN] = {'\0'};
|
|||
uint8_t srl_usart2_rx_buffer[RX_BUFFER_2_LN] = {'\0'};
|
||||
#endif
|
||||
|
||||
uint8_t srl_usart3_tx_buffer[TX_BUFFER_1_LN] = {'\0'};
|
||||
uint8_t srl_usart3_rx_buffer[TX_BUFFER_1_LN] = {'\0'};
|
||||
|
||||
|
||||
void srl_init(
|
||||
srl_context_t *ctx,
|
||||
|
@ -84,6 +87,9 @@ void srl_init(
|
|||
else if (port == USART2) {
|
||||
NVIC_EnableIRQ( USART2_IRQn );
|
||||
}
|
||||
else if (port == USART3) {
|
||||
NVIC_EnableIRQ( USART3_IRQn );
|
||||
}
|
||||
|
||||
port->CR1 |= USART_CR1_UE;
|
||||
port->ISR &= (0xFFFFFFFF ^ USART_ISR_TC);
|
||||
|
@ -330,7 +336,7 @@ uint8_t srl_receive_data(srl_context_t *ctx, int num, char start, char stop, cha
|
|||
ctx->srl_stop_trigger = 0;
|
||||
}
|
||||
|
||||
if (ctx->srl_triggered_start == 1 || ctx->srl_triggered_stop == 1) {
|
||||
if (ctx->srl_triggered_start == 1 /*|| ctx->srl_triggered_stop == 1*/) {
|
||||
if (num < 3)
|
||||
return SRL_WRONG_PARAMS_COMBINATION;
|
||||
|
||||
|
@ -392,7 +398,7 @@ uint8_t srl_receive_data_with_instant_timeout(srl_context_t *ctx, int num, char
|
|||
ctx->srl_triggered_stop = 0;
|
||||
}
|
||||
|
||||
if (ctx->srl_triggered_start == 1 || ctx->srl_triggered_stop == 1) {
|
||||
if (ctx->srl_triggered_start == 1 /*|| ctx->srl_triggered_stop == 1*/) {
|
||||
if (num < 3)
|
||||
return SRL_WRONG_PARAMS_COMBINATION;
|
||||
|
||||
|
|
|
@ -0,0 +1,57 @@
|
|||
/*
|
||||
* sim800c.c
|
||||
*
|
||||
* Created on: Jan 18, 2022
|
||||
* Author: mateusz
|
||||
*/
|
||||
|
||||
#include "gsm/sim800c.h"
|
||||
|
||||
#include "main.h"
|
||||
|
||||
#include <string.h>
|
||||
|
||||
static const char * AUTOBAUD_STRING = "AT\r\n\0";
|
||||
static const char * OK = "OK\0";
|
||||
|
||||
uint32_t gsm_time_of_last_command_send_to_module = 0;
|
||||
|
||||
void gsm_sim800_init(gsm_sim800_state_t * state) {
|
||||
|
||||
if (state != 0x00) {
|
||||
*state = SIM800_NOT_YET_COMM;
|
||||
}
|
||||
}
|
||||
|
||||
void gsm_sim800_pool(srl_context_t * srl_context, gsm_sim800_state_t * state) {
|
||||
|
||||
if (*state == SIM800_NOT_YET_COMM) {
|
||||
// send handshake
|
||||
srl_send_data(srl_context, (const uint8_t*) AUTOBAUD_STRING, SRL_MODE_ZERO, strlen(AUTOBAUD_STRING), SRL_INTERNAL);
|
||||
|
||||
// switch the state
|
||||
*state = SIM800_INITIALIZIG;
|
||||
|
||||
// wait for the handshake to transmit
|
||||
srl_wait_for_tx_completion(srl_context);
|
||||
|
||||
// start data reception
|
||||
srl_receive_data(srl_context, 4, 0, '\r', 0, 0, 0);
|
||||
|
||||
// record when the handshake has been sent
|
||||
gsm_time_of_last_command_send_to_module = main_get_master_time();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Callback to be called just after the reception is done
|
||||
*/
|
||||
void gsm_sim800_rx_done_callback(srl_context_t * srl_context, gsm_sim800_state_t * state) {
|
||||
|
||||
int response_compare_res = 123;
|
||||
|
||||
if (state == SIM800_INITIALIZIG) {
|
||||
// compare the response from the module
|
||||
response_compare_res = strcmp(OK, srl_context->srl_rx_buf_pointer);
|
||||
}
|
||||
}
|
Ładowanie…
Reference in New Issue