Add a bunch of stuff: Add baudrate reconfig command to shell and move the uart to separate C file
This commit is contained in:
		@@ -324,7 +324,6 @@ void __attribute__((noreturn)) Reset_Handler(void) {
 | 
				
			|||||||
	/* Move the stack and the stack pointer to CCMRAM
 | 
						/* Move the stack and the stack pointer to CCMRAM
 | 
				
			||||||
	 * This allows us to perform a RAM test on the main RAM.
 | 
						 * This allows us to perform a RAM test on the main RAM.
 | 
				
			||||||
	 */
 | 
						 */
 | 
				
			||||||
	/* R2 holds the amount of bytes / words on the stack. */
 | 
					 | 
				
			||||||
	__asm__ __volatile__ (
 | 
						__asm__ __volatile__ (
 | 
				
			||||||
			"mov r2, sp\n" /* Move stack pointer to register 2 */
 | 
								"mov r2, sp\n" /* Move stack pointer to register 2 */
 | 
				
			||||||
			"sub r2, %[stacktop], r2\n" /* Subtract stackpointer from top of ram => byte usage */
 | 
								"sub r2, %[stacktop], r2\n" /* Subtract stackpointer from top of ram => byte usage */
 | 
				
			||||||
 
 | 
				
			|||||||
@@ -91,7 +91,6 @@ static int parse_value(struct config_parser_entry *entry, char *value_start_toke
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
	if (value_start_token[0] != '-') {
 | 
						if (value_start_token[0] != '-') {
 | 
				
			||||||
		/* Try parsing as ul */
 | 
							/* Try parsing as ul */
 | 
				
			||||||
		/* Try parsing as int */
 | 
					 | 
				
			||||||
		entry->value.uint_val = strtoul(value_start_token, &endptr, 0);
 | 
							entry->value.uint_val = strtoul(value_start_token, &endptr, 0);
 | 
				
			||||||
		if (endptr == value_start_token) {
 | 
							if (endptr == value_start_token) {
 | 
				
			||||||
			return -1;
 | 
								return -1;
 | 
				
			||||||
 
 | 
				
			|||||||
@@ -25,9 +25,11 @@
 | 
				
			|||||||
#endif
 | 
					#endif
 | 
				
			||||||
 | 
					
 | 
				
			||||||
/* UART_DIV is 45.5625 => 115200 @ 84 MHz */
 | 
					/* UART_DIV is 45.5625 => 115200 @ 84 MHz */
 | 
				
			||||||
#define SHELL_UART_DIV_FRACTION 9U /* Equals 9/16 = 0.5625 */
 | 
					#define SHELL_UART_DEFAULT_DIV_FRACTION 9U /* Equals 9/16 = 0.5625 */
 | 
				
			||||||
#define SHELL_UART_DIV_MANTISSA 45U /* Equals 45 */
 | 
					#define SHELL_UART_DEFAULT_DIV_MANTISSA 45U /* Equals 45 */
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#define SHELL_UART_BRR_REG_VALUE ((SHELL_UART_DIV_MANTISSA<<4) | SHELL_UART_DIV_FRACTION);
 | 
					#define SHELL_UART_DEFAULT_BRR_REG_VALUE ((SHELL_UART_DEFAULT_DIV_MANTISSA<<4) | SHELL_UART_DEFAULT_DIV_FRACTION);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#define SHELL_UART_PERIPHERAL_CLOCK (84000000UL)
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#endif /* __SHELL_UART_CONFIG_H__ */
 | 
					#endif /* __SHELL_UART_CONFIG_H__ */
 | 
				
			||||||
 
 | 
				
			|||||||
@@ -25,7 +25,8 @@
 | 
				
			|||||||
 * @brief Convert PT1000 resistance to temperature in degrees celsius
 | 
					 * @brief Convert PT1000 resistance to temperature in degrees celsius
 | 
				
			||||||
 * @param resistance PT1000 resistance value
 | 
					 * @param resistance PT1000 resistance value
 | 
				
			||||||
 * @param[out] temp_out Temperature output
 | 
					 * @param[out] temp_out Temperature output
 | 
				
			||||||
 * @return 0 if ok, -1 if value is below conversion range, 1 if value is above conversion range,-1000 in case of pointer error
 | 
					 * @return 0 if ok, -1 if value is below conversion range, 1 if value is above conversion range,
 | 
				
			||||||
 | 
					 * -1000 in case of pointer error
 | 
				
			||||||
 */
 | 
					 */
 | 
				
			||||||
int temp_converter_convert_resistance_to_temp(float resistance, float *temp_out);
 | 
					int temp_converter_convert_resistance_to_temp(float resistance, float *temp_out);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 
 | 
				
			|||||||
							
								
								
									
										51
									
								
								stm-firmware/include/reflow-controller/ui/shell-uart.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										51
									
								
								stm-firmware/include/reflow-controller/ui/shell-uart.h
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,51 @@
 | 
				
			|||||||
 | 
					/* Reflow Oven Controller
 | 
				
			||||||
 | 
					*
 | 
				
			||||||
 | 
					* Copyright (C) 2021  Mario Hüttel <mario.huettel@gmx.net>
 | 
				
			||||||
 | 
					*
 | 
				
			||||||
 | 
					* This file is part of the Reflow Oven Controller Project.
 | 
				
			||||||
 | 
					*
 | 
				
			||||||
 | 
					* The reflow oven controller is free software: you can redistribute it and/or modify
 | 
				
			||||||
 | 
					* it under the terms of the GNU General Public License version 2 as
 | 
				
			||||||
 | 
					* published by the Free Software Foundation.
 | 
				
			||||||
 | 
					*
 | 
				
			||||||
 | 
					* The Reflow Oven Control Firmware 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 the reflow oven controller project.
 | 
				
			||||||
 | 
					* If not, see <http://www.gnu.org/licenses/>.
 | 
				
			||||||
 | 
					*/
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#ifndef __SHELL_UART_H__
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#include <shellmatta.h>
 | 
				
			||||||
 | 
					#include <stddef.h>
 | 
				
			||||||
 | 
					#include <stdint.h>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					/**
 | 
				
			||||||
 | 
					 * @brief Configure the UART for the shellmatta shell.
 | 
				
			||||||
 | 
					 *
 | 
				
			||||||
 | 
					 * This will configure the UART for use with a DMA ring buffer.
 | 
				
			||||||
 | 
					 * @param uart
 | 
				
			||||||
 | 
					 */
 | 
				
			||||||
 | 
					void shell_uart_setup(void);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					shellmatta_retCode_t shell_uart_write_callback(const char *data, uint32_t len);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					int shell_uart_receive_data_with_dma(const char **data, size_t *len);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					/**
 | 
				
			||||||
 | 
					 * @brief Configure a new connection speed.
 | 
				
			||||||
 | 
					 * @param new_baud Baudrate. E.g: 115200
 | 
				
			||||||
 | 
					 * @return Error in permille (1/1000). A return value of 2 means a baudrate error of: 0.002 or 0.2%.
 | 
				
			||||||
 | 
					 * Return value is negative in case of a hard error.
 | 
				
			||||||
 | 
					 */
 | 
				
			||||||
 | 
					int32_t shell_uart_reconfig_baud(uint32_t new_baud);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					uint32_t shell_uart_get_current_baudrate(void);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#define __SHELL_UART_H__
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#endif /* __SHELL_UART_H__ */
 | 
				
			||||||
@@ -50,6 +50,8 @@ int uart_init(struct stm_uart *uart);
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
void uart_change_brr(struct stm_uart *uart, uint32_t brr);
 | 
					void uart_change_brr(struct stm_uart *uart, uint32_t brr);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					uint32_t uart_get_brr(struct stm_uart *uart);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
void uart_disable(struct stm_uart *uart);
 | 
					void uart_disable(struct stm_uart *uart);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
void uart_send_char(struct stm_uart *uart, char c);
 | 
					void uart_send_char(struct stm_uart *uart, char c);
 | 
				
			||||||
 
 | 
				
			|||||||
@@ -31,7 +31,6 @@
 | 
				
			|||||||
#include <setup/system_stm32f4xx.h>
 | 
					#include <setup/system_stm32f4xx.h>
 | 
				
			||||||
#include <reflow-controller/systick.h>
 | 
					#include <reflow-controller/systick.h>
 | 
				
			||||||
#include <reflow-controller/adc-meas.h>
 | 
					#include <reflow-controller/adc-meas.h>
 | 
				
			||||||
#include <reflow-controller/shell.h>
 | 
					 | 
				
			||||||
#include <reflow-controller/digio.h>
 | 
					#include <reflow-controller/digio.h>
 | 
				
			||||||
#include "fatfs/shimatta_sdio_driver/shimatta_sdio.h"
 | 
					#include "fatfs/shimatta_sdio_driver/shimatta_sdio.h"
 | 
				
			||||||
#include <stm-periph/stm32-gpio-macros.h>
 | 
					#include <stm-periph/stm32-gpio-macros.h>
 | 
				
			||||||
@@ -41,6 +40,8 @@
 | 
				
			|||||||
#include <reflow-controller/oven-driver.h>
 | 
					#include <reflow-controller/oven-driver.h>
 | 
				
			||||||
#include <fatfs/ff.h>
 | 
					#include <fatfs/ff.h>
 | 
				
			||||||
#include <reflow-controller/ui/gui.h>
 | 
					#include <reflow-controller/ui/gui.h>
 | 
				
			||||||
 | 
					#include <reflow-controller/ui/shell.h>
 | 
				
			||||||
 | 
					#include <reflow-controller/ui/shell-uart.h>
 | 
				
			||||||
#include <reflow-controller/safety/safety-controller.h>
 | 
					#include <reflow-controller/safety/safety-controller.h>
 | 
				
			||||||
#include <reflow-controller/settings/settings.h>
 | 
					#include <reflow-controller/settings/settings.h>
 | 
				
			||||||
#include <reflow-controller/safety/safety-memory.h>
 | 
					#include <reflow-controller/safety/safety-memory.h>
 | 
				
			||||||
@@ -87,55 +88,6 @@ static inline void uart_gpio_config(void)
 | 
				
			|||||||
#endif
 | 
					#endif
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
/**
 | 
					 | 
				
			||||||
 * @brief TX buffer for the shell's uart
 | 
					 | 
				
			||||||
 */
 | 
					 | 
				
			||||||
static char shell_uart_tx_buff[256];
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
/**
 | 
					 | 
				
			||||||
 * @brief RX buffer for the shell's uart
 | 
					 | 
				
			||||||
 */
 | 
					 | 
				
			||||||
static char shell_uart_rx_buff[48];
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
/**
 | 
					 | 
				
			||||||
 * @brief The uart instance handling the shellmatta shell.
 | 
					 | 
				
			||||||
 */
 | 
					 | 
				
			||||||
struct stm_uart shell_uart;
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
static shellmatta_retCode_t write_shell_callback(const char *data, uint32_t len)
 | 
					 | 
				
			||||||
{
 | 
					 | 
				
			||||||
	uart_send_array_with_dma(&shell_uart, data, len);
 | 
					 | 
				
			||||||
	return SHELLMATTA_OK;
 | 
					 | 
				
			||||||
}
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
/**
 | 
					 | 
				
			||||||
 * @brief Configure the UART for the shellmatta shell.
 | 
					 | 
				
			||||||
 *
 | 
					 | 
				
			||||||
 * This will configure the UART for use with a DMA ring buffer.
 | 
					 | 
				
			||||||
 * @param uart
 | 
					 | 
				
			||||||
 */
 | 
					 | 
				
			||||||
static inline void setup_shell_uart(struct stm_uart *uart)
 | 
					 | 
				
			||||||
{
 | 
					 | 
				
			||||||
	uart->rx = 1;
 | 
					 | 
				
			||||||
	uart->tx = 1;
 | 
					 | 
				
			||||||
	uart->brr_val = SHELL_UART_BRR_REG_VALUE;
 | 
					 | 
				
			||||||
	uart->rcc_reg = &SHELL_UART_RCC_REG;
 | 
					 | 
				
			||||||
	uart->rcc_bit_no = BITMASK_TO_BITNO(SHELL_UART_RCC_MASK);
 | 
					 | 
				
			||||||
	uart->uart_dev = SHELL_UART_PERIPH;
 | 
					 | 
				
			||||||
	uart->dma_rx_buff = shell_uart_rx_buff;
 | 
					 | 
				
			||||||
	uart->dma_tx_buff = shell_uart_tx_buff;
 | 
					 | 
				
			||||||
	uart->rx_buff_count = sizeof(shell_uart_rx_buff);
 | 
					 | 
				
			||||||
	uart->tx_buff_count = sizeof(shell_uart_tx_buff);
 | 
					 | 
				
			||||||
	uart->base_dma_num = 2;
 | 
					 | 
				
			||||||
	uart->dma_rx_stream = SHELL_UART_RECEIVE_DMA_STREAM;
 | 
					 | 
				
			||||||
	uart->dma_tx_stream = SHELL_UART_SEND_DMA_STREAM;
 | 
					 | 
				
			||||||
	uart->dma_rx_trigger_channel = SHELL_UART_RX_DMA_TRIGGER;
 | 
					 | 
				
			||||||
	uart->dma_tx_trigger_channel = SHELL_UART_TX_DMA_TRIGGER;
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
	uart_init(uart);
 | 
					 | 
				
			||||||
	NVIC_EnableIRQ(DMA2_Stream7_IRQn);
 | 
					 | 
				
			||||||
}
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
/**
 | 
					/**
 | 
				
			||||||
 * @brief Mount the SD card if available and not already mounted
 | 
					 * @brief Mount the SD card if available and not already mounted
 | 
				
			||||||
 * @param mounted The current mounting state of the SD card
 | 
					 * @param mounted The current mounting state of the SD card
 | 
				
			||||||
@@ -293,7 +245,7 @@ static inline void setup_system(void)
 | 
				
			|||||||
	handle_boot_status();
 | 
						handle_boot_status();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
	/** - Initialize the shell UART */
 | 
						/** - Initialize the shell UART */
 | 
				
			||||||
	setup_shell_uart(&shell_uart);
 | 
						shell_uart_setup();
 | 
				
			||||||
 | 
					
 | 
				
			||||||
	/** - Enable the ADC for PT1000 measurement */
 | 
						/** - Enable the ADC for PT1000 measurement */
 | 
				
			||||||
	adc_pt1000_setup_meas();
 | 
						adc_pt1000_setup_meas();
 | 
				
			||||||
@@ -314,7 +266,7 @@ static void handle_shell_uart_input(shellmatta_handle_t shell_handle)
 | 
				
			|||||||
	size_t uart_input_len;
 | 
						size_t uart_input_len;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
	/* Handle UART input for shell */
 | 
						/* Handle UART input for shell */
 | 
				
			||||||
	uart_receive_status = uart_receive_data_with_dma(&shell_uart, &uart_input, &uart_input_len);
 | 
						uart_receive_status = shell_uart_receive_data_with_dma(&uart_input, &uart_input_len);
 | 
				
			||||||
	if (uart_receive_status >= 0)
 | 
						if (uart_receive_status >= 0)
 | 
				
			||||||
		shell_handle_input(shell_handle, uart_input, uart_input_len);
 | 
							shell_handle_input(shell_handle, uart_input, uart_input_len);
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
@@ -344,7 +296,7 @@ int main(void)
 | 
				
			|||||||
		adc_pt1000_set_resistance_calibration(offset, sens, true);
 | 
							adc_pt1000_set_resistance_calibration(offset, sens, true);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
	/** - Initialize the shellmatta shell */
 | 
						/** - Initialize the shellmatta shell */
 | 
				
			||||||
	shell_handle = shell_init(write_shell_callback);
 | 
						shell_handle = shell_init(shell_uart_write_callback);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
	/** - Print motd to shell */
 | 
						/** - Print motd to shell */
 | 
				
			||||||
	shell_print_motd(shell_handle);
 | 
						shell_print_motd(shell_handle);
 | 
				
			||||||
@@ -421,16 +373,3 @@ void sdio_wait_ms(uint32_t ms)
 | 
				
			|||||||
{
 | 
					{
 | 
				
			||||||
	systick_wait_ms(ms);
 | 
						systick_wait_ms(ms);
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					 | 
				
			||||||
/**
 | 
					 | 
				
			||||||
 * @brief Handles the TX of UART1 (Shellmatta)
 | 
					 | 
				
			||||||
 */
 | 
					 | 
				
			||||||
void DMA2_Stream7_IRQHandler(void)
 | 
					 | 
				
			||||||
{
 | 
					 | 
				
			||||||
	uint32_t hisr = DMA2->HISR & (0x3F << 22);
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
	DMA2->HIFCR = hisr;
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
	if (hisr & DMA_HISR_TCIF7)
 | 
					 | 
				
			||||||
		uart_tx_dma_complete_int_callback(&shell_uart);
 | 
					 | 
				
			||||||
}
 | 
					 | 
				
			||||||
 
 | 
				
			|||||||
@@ -67,6 +67,13 @@ int watchdog_setup(uint8_t prescaler)
 | 
				
			|||||||
	else
 | 
						else
 | 
				
			||||||
		prescaler_reg_val = 6UL;
 | 
							prescaler_reg_val = 6UL;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						/** - (De)activate the watchdog during debug access according to @ref WATCHDOG_HALT_DEBUG */
 | 
				
			||||||
 | 
						if (WATCHDOG_HALT_DEBUG) {
 | 
				
			||||||
 | 
							DBGMCU->APB1FZ |= DBGMCU_APB1_FZ_DBG_IWDG_STOP;
 | 
				
			||||||
 | 
						} else {
 | 
				
			||||||
 | 
							DBGMCU->APB1FZ &= ~DBGMCU_APB1_FZ_DBG_IWDG_STOP;
 | 
				
			||||||
 | 
						}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
	/** - Unlock registers */
 | 
						/** - Unlock registers */
 | 
				
			||||||
	IWDG->KR = STM32_WATCHDOG_REGISTER_ACCESS_KEY;
 | 
						IWDG->KR = STM32_WATCHDOG_REGISTER_ACCESS_KEY;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 
 | 
				
			|||||||
@@ -95,6 +95,14 @@ void uart_change_brr(struct stm_uart *uart, uint32_t brr)
 | 
				
			|||||||
	uart->uart_dev->BRR = brr;
 | 
						uart->uart_dev->BRR = brr;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					uint32_t uart_get_brr(struct stm_uart *uart)
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
						if (!uart || !uart->uart_dev)
 | 
				
			||||||
 | 
							return 0;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						return uart->brr_val;
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
void uart_disable(struct stm_uart *uart)
 | 
					void uart_disable(struct stm_uart *uart)
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
	if (!uart)
 | 
						if (!uart)
 | 
				
			||||||
 
 | 
				
			|||||||
							
								
								
									
										130
									
								
								stm-firmware/ui/shell-uart.c
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										130
									
								
								stm-firmware/ui/shell-uart.c
									
									
									
									
									
										Normal file
									
								
							@@ -0,0 +1,130 @@
 | 
				
			|||||||
 | 
					/* Reflow Oven Controller
 | 
				
			||||||
 | 
					*
 | 
				
			||||||
 | 
					* Copyright (C) 2021  Mario Hüttel <mario.huettel@gmx.net>
 | 
				
			||||||
 | 
					*
 | 
				
			||||||
 | 
					* This file is part of the Reflow Oven Controller Project.
 | 
				
			||||||
 | 
					*
 | 
				
			||||||
 | 
					* The reflow oven controller is free software: you can redistribute it and/or modify
 | 
				
			||||||
 | 
					* it under the terms of the GNU General Public License version 2 as
 | 
				
			||||||
 | 
					* published by the Free Software Foundation.
 | 
				
			||||||
 | 
					*
 | 
				
			||||||
 | 
					* The Reflow Oven Control Firmware 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 the reflow oven controller project.
 | 
				
			||||||
 | 
					* If not, see <http://www.gnu.org/licenses/>.
 | 
				
			||||||
 | 
					*/
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					#include <reflow-controller/ui/shell-uart.h>
 | 
				
			||||||
 | 
					#include <reflow-controller/periph-config/shell-uart-config.h>
 | 
				
			||||||
 | 
					#include <stm-periph/stm32-gpio-macros.h>
 | 
				
			||||||
 | 
					#include <stm-periph/uart.h>
 | 
				
			||||||
 | 
					#include <helper-macros/helper-macros.h>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					/**
 | 
				
			||||||
 | 
					 * @brief TX buffer for the shell's uart
 | 
				
			||||||
 | 
					 */
 | 
				
			||||||
 | 
					static char shell_uart_tx_buff[4096];
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					/**
 | 
				
			||||||
 | 
					 * @brief RX buffer for the shell's uart
 | 
				
			||||||
 | 
					 */
 | 
				
			||||||
 | 
					static char shell_uart_rx_buff[128];
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					/**
 | 
				
			||||||
 | 
					 * @brief The uart instance handling the shellmatta shell.
 | 
				
			||||||
 | 
					 */
 | 
				
			||||||
 | 
					struct stm_uart shell_uart;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					void shell_uart_setup(void)
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
						struct stm_uart *uart = &shell_uart;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						uart->rx = 1;
 | 
				
			||||||
 | 
						uart->tx = 1;
 | 
				
			||||||
 | 
						uart->brr_val = SHELL_UART_DEFAULT_BRR_REG_VALUE;
 | 
				
			||||||
 | 
						uart->rcc_reg = &SHELL_UART_RCC_REG;
 | 
				
			||||||
 | 
						uart->rcc_bit_no = BITMASK_TO_BITNO(SHELL_UART_RCC_MASK);
 | 
				
			||||||
 | 
						uart->uart_dev = SHELL_UART_PERIPH;
 | 
				
			||||||
 | 
						uart->dma_rx_buff = shell_uart_rx_buff;
 | 
				
			||||||
 | 
						uart->dma_tx_buff = shell_uart_tx_buff;
 | 
				
			||||||
 | 
						uart->rx_buff_count = sizeof(shell_uart_rx_buff);
 | 
				
			||||||
 | 
						uart->tx_buff_count = sizeof(shell_uart_tx_buff);
 | 
				
			||||||
 | 
						uart->base_dma_num = 2;
 | 
				
			||||||
 | 
						uart->dma_rx_stream = SHELL_UART_RECEIVE_DMA_STREAM;
 | 
				
			||||||
 | 
						uart->dma_tx_stream = SHELL_UART_SEND_DMA_STREAM;
 | 
				
			||||||
 | 
						uart->dma_rx_trigger_channel = SHELL_UART_RX_DMA_TRIGGER;
 | 
				
			||||||
 | 
						uart->dma_tx_trigger_channel = SHELL_UART_TX_DMA_TRIGGER;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						uart_init(uart);
 | 
				
			||||||
 | 
						NVIC_EnableIRQ(DMA2_Stream7_IRQn);
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					shellmatta_retCode_t shell_uart_write_callback(const char *data, uint32_t len)
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
						uart_send_array_with_dma(&shell_uart, data, len);
 | 
				
			||||||
 | 
						return SHELLMATTA_OK;
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					int shell_uart_receive_data_with_dma(const char **data, size_t *len)
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
						return uart_receive_data_with_dma(&shell_uart, data, len);
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					int32_t shell_uart_reconfig_baud(uint32_t new_baud)
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
						uint32_t brr_val_floor;
 | 
				
			||||||
 | 
						uint32_t brr_val_remainder;
 | 
				
			||||||
 | 
						uint32_t error_permille;
 | 
				
			||||||
 | 
						int64_t actual_baud;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						/* Calculate the new BRR register value */
 | 
				
			||||||
 | 
						brr_val_floor = SHELL_UART_PERIPHERAL_CLOCK / new_baud;
 | 
				
			||||||
 | 
						brr_val_remainder =  SHELL_UART_PERIPHERAL_CLOCK % new_baud;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						/* Round to the nearest value */
 | 
				
			||||||
 | 
						if (brr_val_remainder > (new_baud / 2u)) {
 | 
				
			||||||
 | 
							brr_val_floor++;
 | 
				
			||||||
 | 
							brr_val_remainder = new_baud - brr_val_remainder;
 | 
				
			||||||
 | 
						}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						actual_baud = (1000U *(int64_t)SHELL_UART_PERIPHERAL_CLOCK) / brr_val_floor;
 | 
				
			||||||
 | 
						error_permille = (ABS(actual_baud - 1000U * (int64_t)new_baud)) / (int64_t)new_baud;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						if (error_permille < 20u) {
 | 
				
			||||||
 | 
							uart_change_brr(&shell_uart, brr_val_floor);
 | 
				
			||||||
 | 
						} else {
 | 
				
			||||||
 | 
							return -1;
 | 
				
			||||||
 | 
						}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						return (int32_t)error_permille;
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					uint32_t shell_uart_get_current_baudrate(void)
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
						uint32_t brr;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						brr = uart_get_brr(&shell_uart);
 | 
				
			||||||
 | 
						if (brr == 0)
 | 
				
			||||||
 | 
							return 0;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						return (SHELL_UART_PERIPHERAL_CLOCK) / brr;
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					/**
 | 
				
			||||||
 | 
					 * @brief Handles the TX of UART1 (Shellmatta)
 | 
				
			||||||
 | 
					 */
 | 
				
			||||||
 | 
					void DMA2_Stream7_IRQHandler(void)
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
						uint32_t hisr = DMA2->HISR & (0x3F << 22);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						DMA2->HIFCR = hisr;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						if (hisr & DMA_HISR_TCIF7)
 | 
				
			||||||
 | 
							uart_tx_dma_complete_int_callback(&shell_uart);
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
@@ -20,7 +20,7 @@
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
#include <stm32/stm32f4xx.h>
 | 
					#include <stm32/stm32f4xx.h>
 | 
				
			||||||
#include <cmsis/core_cm4.h>
 | 
					#include <cmsis/core_cm4.h>
 | 
				
			||||||
#include <reflow-controller/shell.h>
 | 
					#include <reflow-controller/ui/shell.h>
 | 
				
			||||||
#include <stm-periph/uart.h>
 | 
					#include <stm-periph/uart.h>
 | 
				
			||||||
#include <string.h>
 | 
					#include <string.h>
 | 
				
			||||||
#include <reflow-controller/adc-meas.h>
 | 
					#include <reflow-controller/adc-meas.h>
 | 
				
			||||||
@@ -47,6 +47,7 @@
 | 
				
			|||||||
#include <reflow-controller/main-cycle-counter.h>
 | 
					#include <reflow-controller/main-cycle-counter.h>
 | 
				
			||||||
#include <stm-periph/option-bytes.h>
 | 
					#include <stm-periph/option-bytes.h>
 | 
				
			||||||
#include <reflow-controller/ui/gui.h>
 | 
					#include <reflow-controller/ui/gui.h>
 | 
				
			||||||
 | 
					#include <reflow-controller/ui/shell-uart.h>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#include <stdio.h>
 | 
					#include <stdio.h>
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@@ -946,6 +947,56 @@ shellmatta_retCode_t shell_cmd_print_opt_bytes(const shellmatta_handle_t handle,
 | 
				
			|||||||
	return SHELLMATTA_OK;
 | 
						return SHELLMATTA_OK;
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
					shellmatta_retCode_t shell_cmd_set_baud(const shellmatta_handle_t handle, const char *args, uint32_t len)
 | 
				
			||||||
 | 
					{
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						shellmatta_retCode_t opt_stat;
 | 
				
			||||||
 | 
						char option;
 | 
				
			||||||
 | 
						char *argument;
 | 
				
			||||||
 | 
						uint32_t arg_len;
 | 
				
			||||||
 | 
						char *baud_string = NULL;
 | 
				
			||||||
 | 
						uint32_t baud;
 | 
				
			||||||
 | 
						(void)len;
 | 
				
			||||||
 | 
						(void)args;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						const shellmatta_opt_long_t options[] = {
 | 
				
			||||||
 | 
							{NULL, '\0', SHELLMATTA_OPT_ARG_NONE},
 | 
				
			||||||
 | 
						};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						while (1) {
 | 
				
			||||||
 | 
							opt_stat = shellmatta_opt_long(handle, options, &option, &argument, &arg_len);
 | 
				
			||||||
 | 
							if (opt_stat != SHELLMATTA_OK)
 | 
				
			||||||
 | 
								break;
 | 
				
			||||||
 | 
							switch (option) {
 | 
				
			||||||
 | 
							case '\0':
 | 
				
			||||||
 | 
								baud_string = argument;
 | 
				
			||||||
 | 
								break;
 | 
				
			||||||
 | 
							default:
 | 
				
			||||||
 | 
								break;
 | 
				
			||||||
 | 
							}
 | 
				
			||||||
 | 
						}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						shellmatta_printf(handle, "Current baudrate: %u\r\n", (unsigned int)shell_uart_get_current_baudrate());
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						if (!baud_string) {
 | 
				
			||||||
 | 
							shellmatta_printf(handle, "Please specify a baudrate\r\n");
 | 
				
			||||||
 | 
							return SHELLMATTA_OK;
 | 
				
			||||||
 | 
						}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						baud = strtoul(baud_string, NULL, 0);
 | 
				
			||||||
 | 
						if (baud < 38400) {
 | 
				
			||||||
 | 
							shellmatta_printf(handle, "38400 is the minimum recommended baudrate!\r\n");
 | 
				
			||||||
 | 
						}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						shellmatta_printf(handle, "Setting baud to: %u\r\n", (unsigned int)baud);
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						if (shell_uart_reconfig_baud(baud) < 0) {
 | 
				
			||||||
 | 
							shellmatta_printf(handle,"Setting baudrate not possible. Error greater than 2%%\r\n");
 | 
				
			||||||
 | 
						}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
						return SHELLMATTA_OK;
 | 
				
			||||||
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
//typedef struct shellmatta_cmd
 | 
					//typedef struct shellmatta_cmd
 | 
				
			||||||
//{
 | 
					//{
 | 
				
			||||||
//    char                    *cmd;       /**< command name                           */
 | 
					//    char                    *cmd;       /**< command name                           */
 | 
				
			||||||
@@ -955,7 +1006,7 @@ shellmatta_retCode_t shell_cmd_print_opt_bytes(const shellmatta_handle_t handle,
 | 
				
			|||||||
//    shellmatta_cmdFct_t     cmdFct;     /**< pointer to the cmd callack function    */
 | 
					//    shellmatta_cmdFct_t     cmdFct;     /**< pointer to the cmd callack function    */
 | 
				
			||||||
//    struct shellmatta_cmd   *next;      /**< pointer to next command or NULL        */
 | 
					//    struct shellmatta_cmd   *next;      /**< pointer to next command or NULL        */
 | 
				
			||||||
//} shellmatta_cmd_t;
 | 
					//} shellmatta_cmd_t;
 | 
				
			||||||
static shellmatta_cmd_t cmd[24] = {
 | 
					static shellmatta_cmd_t cmd[25] = {
 | 
				
			||||||
	{
 | 
						{
 | 
				
			||||||
		.cmd = "version",
 | 
							.cmd = "version",
 | 
				
			||||||
		.cmdAlias = "ver",
 | 
							.cmdAlias = "ver",
 | 
				
			||||||
@@ -1147,8 +1198,17 @@ static shellmatta_cmd_t cmd[24] = {
 | 
				
			|||||||
		.helpText = "Print the currently set option bytes of the STM32",
 | 
							.helpText = "Print the currently set option bytes of the STM32",
 | 
				
			||||||
		.usageText = "",
 | 
							.usageText = "",
 | 
				
			||||||
		.cmdFct = shell_cmd_print_opt_bytes,
 | 
							.cmdFct = shell_cmd_print_opt_bytes,
 | 
				
			||||||
 | 
							.next = &cmd[24],
 | 
				
			||||||
 | 
						},
 | 
				
			||||||
 | 
						{
 | 
				
			||||||
 | 
							.cmd = "baudrate",
 | 
				
			||||||
 | 
							.cmdAlias = "opt-bytes",
 | 
				
			||||||
 | 
							.helpText = "Set a new temporary baudrate for the UART",
 | 
				
			||||||
 | 
							.usageText = "baudrate <new baud>",
 | 
				
			||||||
 | 
							.cmdFct = shell_cmd_set_baud,
 | 
				
			||||||
		.next = NULL,
 | 
							.next = NULL,
 | 
				
			||||||
	}
 | 
						},
 | 
				
			||||||
 | 
					
 | 
				
			||||||
};
 | 
					};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
shellmatta_handle_t shell_init(shellmatta_write_t write_func)
 | 
					shellmatta_handle_t shell_init(shellmatta_write_t write_func)
 | 
				
			||||||
@@ -6,7 +6,7 @@
 | 
				
			|||||||
void uart_init(void)
 | 
					void uart_init(void)
 | 
				
			||||||
{
 | 
					{
 | 
				
			||||||
	SHELL_UART_RCC_REG |= SHELL_UART_RCC_MASK;
 | 
						SHELL_UART_RCC_REG |= SHELL_UART_RCC_MASK;
 | 
				
			||||||
	SHELL_UART_PERIPH->BRR = SHELL_UART_BRR_REG_VALUE;
 | 
						SHELL_UART_PERIPH->BRR = SHELL_UART_DEFAULT_BRR_REG_VALUE;
 | 
				
			||||||
	SHELL_UART_PERIPH->CR2 = 0;
 | 
						SHELL_UART_PERIPH->CR2 = 0;
 | 
				
			||||||
	SHELL_UART_PERIPH->CR3 = 0;
 | 
						SHELL_UART_PERIPH->CR3 = 0;
 | 
				
			||||||
	SHELL_UART_PERIPH->CR1 = USART_CR1_TE | USART_CR1_UE;
 | 
						SHELL_UART_PERIPH->CR1 = USART_CR1_TE | USART_CR1_UE;
 | 
				
			||||||
 
 | 
				
			|||||||
		Reference in New Issue
	
	Block a user