Skip to content
Snippets Groups Projects
Commit 688bc361 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Initial commit of the firmware.

parents
No related branches found
No related tags found
No related merge requests found
Showing with 2796 additions and 0 deletions
Makefile 0 → 100755
# setup
# modified by zerom for WinARM 8/2010
STM32_HAL_PATH=$(HOME)/humanoids/stm32_hal
STM32_LIBRARIES_PATH=$(HOME)/humanoids/stm32_libraries
PROJECT_NAME=ir_feet
TARGET_FILES=src/main.c
TARGET_FILES+=src/eeprom.c
TARGET_FILES+=src/ir_feet_dyn_slave.c
TARGET_FILES+=src/ir_feet_time.c
TARGET_FILES+=src/ram.c
TARGET_FILES+=src/scheduler.c
TARGET_FILES+=src/stm32f1xx_hal_msp.c
TARGET_FILES+=src/gpio.c
TARGET_FILES+=src/adc_dma.c
TARGET_PROCESSOR=STM32F103CB
HAL_PATH=$(STM32_HAL_PATH)/f1
include $(HAL_PATH)/select_processor.mk
STM32_STARTUP_FILES_PATH = $(HAL_PATH)/startup_code/
STM32_LINKER_SCRIPTS_PATH = ./linker_script
UTILS_PATH=$(STM32_LIBRARIES_PATH)/utils
COMM_PATH=$(STM32_LIBRARIES_PATH)/comm
MEMORY_PATH=$(STM32_LIBRARIES_PATH)/memory
USART_PATH=$(STM32_LIBRARIES_PATH)/f1/usart
DYNAMIXEL_PATH=$(STM32_LIBRARIES_PATH)/dynamixel_base
BUILD_PATH=build
COMPILE_OPTS = -mlittle-endian -mcpu=cortex-m3 -mthumb # -mthumb-interwork
COMPILE_OPTS += -Wall -O2 -fno-common -msoft-float -DUSE_HAL_DRIVER
#COMPILE_OPTS += -Wall -g -fno-common -msoft-float -DUSE_HAL_DRIVER
COMPILE_OPTS += -ffreestanding -nostdlib -D$(PROCESSOR_MACRO) -DHSE_VALUE=8000000
INCLUDE_DIRS = -I$(HAL_PATH)/include -I$(HAL_PATH)/include/core -I$(HAL_PATH)/include/devices -I$(HAL_PATH)/include/legacy
INCLUDE_DIRS += -I$(UTILS_PATH)/include -I$(COMM_PATH)/include -I$(DYNAMIXEL_PATH)/include -I$(MEMORY_PATH)/include -I$(USART_PATH)/include -I./include
TCHAIN_PREFIX=arm-none-eabi-
CC = $(TCHAIN_PREFIX)gcc
CFLAGS = $(COMPILE_OPTS) $(INCLUDE_DIRS)
AS = $(TCHAIN_PREFIX)gcc
ASFLAGS = $(COMPILE_OPTS) -c
LD = $(TCHAIN_PREFIX)gcc
LDFLAGS = -mthumb -mcpu=cortex-m3 -Wl,-Map=$@.map,-cref $(INCLUDE_DIRS) -T $(STM32_LINKER_SCRIPTS_PATH)/ir_feet.ld --specs=nosys.specs
EXT_LIB = $(COMM_PATH)/lib/comm_m3.a $(UTILS_PATH)/lib/utils_m3.a $(DYNAMIXEL_PATH)/lib/dynamixel_m3.a $(MEMORY_PATH)/lib/memory_m3.a
OBJCP = $(TCHAIN_PREFIX)objcopy
OBJCPFLAGS_HEX = -O ihex
OBJCPFLAGS_BIN = -O binary
OBJDUMP = $(TCHAIN_PREFIX)objdump
OBJDUMPFLAGS = -h -S -C -D
MAIN_OUT_ELF = $(BUILD_PATH)/$(PROJECT_NAME).elf
MAIN_OUT_HEX = $(BUILD_PATH)/$(PROJECT_NAME).hex
MAIN_OUT_BIN = $(BUILD_PATH)/$(PROJECT_NAME).bin
MAIN_OUT_LSS = $(BUILD_PATH)/$(PROJECT_NAME).lss
# add STM32 src files
TARGET_FILES+=$(HAL_PATH)/src/devices/system_stm32f1xx.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_gpio.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_cortex.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_rcc.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_rcc_ex.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_pwr.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_tim.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_tim_ex.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_flash.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_flash_ex.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_uart.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_dma.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_adc.c
TARGET_FILES+=$(HAL_PATH)/src/stm32f1xx_hal_adc_ex.c
TARGET_FILES+=$(USART_PATH)/src/usart1_remap.c
IR_FEET_OBJS_TMP = $(notdir $(TARGET_FILES:.c=.o))
IR_FEET_OBJS = $(patsubst %,$(BUILD_PATH)/%,$(IR_FEET_OBJS_TMP))
all: $(MAIN_OUT_ELF) $(MAIN_OUT_HEX) $(MAIN_OUT_BIN) $(MAIN_OUT_LSS)
mkdir_build:
mkdir -p $(BUILD_PATH)
$(BUILD_PATH)/%.o: src/%.c
$(CC) -c $(CFLAGS) -o $@ $<
$(BUILD_PATH)/%.o: $(HAL_PATH)/src/devices/%.c
$(CC) -c $(CFLAGS) -o $@ $<
$(BUILD_PATH)/%.o: $(HAL_PATH)/src/%.c
$(CC) -c $(CFLAGS) -o $@ $<
$(BUILD_PATH)/%.o: $(USART_PATH)/src/%.c
$(CC) -c $(CFLAGS) -o $@ $<
$(MAIN_OUT_ELF): mkdir_build $(IR_FEET_OBJS) $(BUID_PATH)/$(STARTUP_FILE:.s=.o)
$(LD) $(LDFLAGS) $(IR_FEET_OBJS) $(BUILD_PATH)/$(STARTUP_FILE:.s=.o) $(EXT_LIB) --output $@
$(MAIN_OUT_HEX): $(MAIN_OUT_ELF)
$(OBJCP) $(OBJCPFLAGS_HEX) $< $@
$(MAIN_OUT_BIN): $(MAIN_OUT_ELF)
$(OBJCP) $(OBJCPFLAGS_BIN) $< $@
$(MAIN_OUT_LSS): $(MAIN_OUT_ELF)
$(OBJDUMP) $(OBJDUMPFLAGS) $< > $@
$(BUID_PATH)/$(STARTUP_FILE:.s=.o): $(STM32_STARTUP_FILES_PATH)/$(STARTUP_FILE)
$(AS) $(ASFLAGS) -o $(BUILD_PATH)/$(STARTUP_FILE:.s=.o) $(STM32_STARTUP_FILES_PATH)/$(STARTUP_FILE) > $(BUILD_PATH)/$(STARTUP_FILE:.s=.lst)
clean:
-rm -rf $(BUILD_PATH)
#ifndef _ADC_DMA_H
#define _ADC_DMA_H
#include "stm32f1xx.h"
#define ADC_NUM_CHANNELS 10
typedef enum {ADC_CH1=0,ADC_CH2,ADC_CH3,ADC_CH4,ADC_CH5,ADC_CH6,ADC_CH7,ADC_CH8,ADC_CH9,ADC_CH10} adc_dma_ch_t;
float adc_get_voltage(adc_dma_ch_t channel_id);
inline float adc_get_temperature(void);
#endif
#ifndef _ADC_DMA_REGISTERS_H
#define _ADC_DMA_REGISTERS_H
#include "ir_feet_conf.h"
#ifndef RAM_ADC_DMA_BASE_ADDRESS
#define RAM_ADC_DMA_BASE_ADDRESS ((unsigned short int)0x0000)
#endif
#ifndef EEPROM_ADC_DMA_BASE_ADDRESS
#define EEPROM_ADC_DMA_BASE_ADDRESS ((unsigned short int)0x0000)
#endif
#define RAM_ADC_DMA_LENGTH 22
#define ADC_CH1_VOLTAGE RAM_ADC_DMA_BASE_ADDRESS
#define ADC_CH2_VOLTAGE (RAM_ADC_DMA_BASE_ADDRESS+2)
#define ADC_CH3_VOLTAGE (RAM_ADC_DMA_BASE_ADDRESS+4)
#define ADC_CH4_VOLTAGE (RAM_ADC_DMA_BASE_ADDRESS+6)
#define ADC_CH5_VOLTAGE (RAM_ADC_DMA_BASE_ADDRESS+8)
#define ADC_CH6_VOLTAGE (RAM_ADC_DMA_BASE_ADDRESS+10)
#define ADC_CH7_VOLTAGE (RAM_ADC_DMA_BASE_ADDRESS+12)
#define ADC_CH8_VOLTAGE (RAM_ADC_DMA_BASE_ADDRESS+14)
#define ADC_CH9_VOLTAGE (RAM_ADC_DMA_BASE_ADDRESS+16)
#define ADC_CH10_VOLTAGE (RAM_ADC_DMA_BASE_ADDRESS+18)
#define ADC_TEMPERATURE (RAM_ADC_DMA_BASE_ADDRESS+20)
#endif
/**
******************************************************************************
* @file EEPROM_Emulation/inc/eeprom.h
* @author MCD Application Team
* @version V1.0.0
* @date 17-December-2014
* @brief This file contains all the functions prototypes for the EEPROM
* emulation firmware library.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __EEPROM_H
#define __EEPROM_H
/* Includes ------------------------------------------------------------------*/
#include "stm32f1xx.h"
/* Exported constants --------------------------------------------------------*/
/* Define the size of the sectors to be used */
#define PAGE_SIZE (uint32_t)FLASH_PAGE_SIZE /* Page size */
/* EEPROM start address in Flash */
#define EEPROM_START_ADDRESS ((uint32_t)0x08000400) /* EEPROM emulation start address */
/* Pages 0 and 1 base and end addresses */
#define PAGE0_BASE_ADDRESS ((uint32_t)(EEPROM_START_ADDRESS + 0x0000))
#define PAGE0_END_ADDRESS ((uint32_t)(EEPROM_START_ADDRESS + (PAGE_SIZE - 1)))
#define PAGE0_ID 0x08000800
#define PAGE1_BASE_ADDRESS ((uint32_t)(EEPROM_START_ADDRESS + 0x0400))
#define PAGE1_END_ADDRESS ((uint32_t)(EEPROM_START_ADDRESS + 2*PAGE_SIZE - 1))
#define PAGE1_ID 0x08001000
/* Used Flash pages for EEPROM emulation */
#define PAGE0 ((uint16_t)0x0000)
#define PAGE1 ((uint16_t)0x0001)
/* No valid page define */
#define NO_VALID_PAGE ((uint16_t)0x00AB)
/* Page status definitions */
#define ERASED ((uint16_t)0xFFFF) /* Page is empty */
#define RECEIVE_DATA ((uint16_t)0xEEEE) /* Page is marked to receive data */
#define VALID_PAGE ((uint16_t)0x0000) /* Page containing valid data */
/* Valid pages in read and write defines */
#define READ_FROM_VALID_PAGE ((uint8_t)0x00)
#define WRITE_IN_VALID_PAGE ((uint8_t)0x01)
/* Page full define */
#define PAGE_FULL ((uint8_t)0x80)
/* Exported types ------------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
uint16_t EE_Init(void);
uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data);
uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data);
#endif /* __EEPROM_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
#ifndef _GPIO_H
#define _GPIO_H
#include "stm32f1xx_hal.h"
typedef enum {FRONT_LEFT,FRONT_RIGHT,DOWN_LEFT_FRONT,DOWN_LEFT_MIDDLE,DOWN_LEFT_REAR,DOWN_RIGHT_FRONT,DOWN_RIGHT_MIDDLE,DOWN_RIGHT_REAR} exp_led_t;
void gpio_init(void);
/* output functions */
void gpio_set_led(exp_led_t led_id);
void gpio_clear_led(exp_led_t led_id);
#endif
#ifndef _IR_FEET_CONF_H
#define _IR_FEET_CONF_H
/* dynamixel slave registers base addresses */
#define EEPROM_DYN_SLAVE_BASE_ADDRESS1 ((unsigned short int)0x0000)
#define EEPROM_DYN_SLAVE_BASE_ADDRESS2 ((unsigned short int)0x0010)
/* ADC registers base address */
#define RAM_ADC_DMA_BASE_ADDRESS ((unsigned short int)0x004a)
#define EEPROM_NUM_VAR 32
#define DEFAULT_DEVICE_MODEL 0x000c
#define DEFAULT_FIRMWARE_VERSION 0x01
#define DEFAULT_DEVICE_ID 0x03
#define DEFAULT_BAUDRATE 0x10
#define DEFAULT_RETURN_DELAY 0x00
#define DEFAULT_RETURN_LEVEL 0x02
#endif
#ifndef _IR_FEET_DYN_SLAVE_H
#define _IR_FEET_DYN_SLAVE_H
#include "stm32f1xx.h"
#include "dynamixel_slave.h"
#include "memory.h"
uint8_t ir_feet_dyn_slave_init(TMemory *memory);
void ir_feet_dyn_slave_start(void);
void ir_feet_dyn_slave_stop(void);
#endif
#ifndef _IR_FEET_DYN_SLAVE_REGISTERS_H
#define _IR_FEET_DYN_SLAVE_REGISTERS_H
#include "ir_feet_conf.h"
#ifndef EEPROM_DYN_SLAVE_BASE_ADDRESS1
#define EEPROM_DYN_SLAVE_BASE_ADDRESS1 ((unsigned short int)0x0000)
#endif
#define EEPROM_DYN_SLAVE_LENGTH1 6
#ifndef EEPROM_DYN_SLAVE_BASE_ADDRESS2
#define EEPROM_DYN_SLAVE_BASE_ADDRESS2 ((unsigned short int)0x0000)
#endif
#define EEPROM_DYN_SLAVE_LENGTH2 1
#define DEVICE_MODEL (EEPROM_DYN_SLAVE_BASE_ADDRESS1)
#define FIRMWARE_VERSION (EEPROM_DYN_SLAVE_BASE_ADDRESS1+2)
#define DEVICE_ID (EEPROM_DYN_SLAVE_BASE_ADDRESS1+3)
#define BAUDRATE (EEPROM_DYN_SLAVE_BASE_ADDRESS1+4)
#define RETURN_DELAY (EEPROM_DYN_SLAVE_BASE_ADDRESS1+5)
#define RETURN_LEVEL (EEPROM_DYN_SLAVE_BASE_ADDRESS2)
#ifndef DEFAULT_DEVICE_MODEL
#define DEFAULT_DEVICE_MODEL 0x7300
#endif
#ifndef DEFAULT_FIRMWARE_VERSION
#define DEFAULT_FIRMWARE_VERSION 0x0001
#endif
#ifndef DEFAULT_DEVICE_ID
#define DEFAULT_DEVICE_ID 0x0001
#endif
#ifndef DEFAULT_BAUDRATE
#define DEFAULT_BAUDRATE 0x0010
#endif
#ifndef DEFAULT_RETURN_DELAY
#define DEFAULT_RETURN_DELAY 0x0000
#endif
#ifndef DEFAULT_RETURN_LEVEL
#define DEFAULT_RETURN_LEVEL 0x0002
#endif
#endif
#ifndef _IR_FEET_TIME_H
#define _IR_FEET_TIME_H
#include "stm32f1xx.h"
void ir_feet_time_init(void);
unsigned long long int ir_feet_time_get_counts(void);
unsigned int ir_feet_time_get_counts_per_us(void);
#endif
#ifndef _RAM_H
#define _RAM_H
#ifdef __cplusplus
extern "C" {
#endif
#include "stm32f1xx.h"
#include "memory.h"
#define RAM_SUCCESS 0
#define RAM_BAD_ADDRESS -1
#define RAM_WRITE_ERROR -2
#define RAM_BAD_BIT -3
#define RAM_BAD_ACCESS -4
extern uint8_t ram_data[RAM_SIZE];
uint8_t ram_init(TMemory *memory);
inline void ram_read_byte(uint16_t address, uint8_t *data);
inline void ram_read_word(uint16_t address, uint16_t *data);
uint8_t ram_read_table(uint16_t address, uint16_t length,uint8_t *data);
uint8_t ram_set_bit(uint16_t address, uint8_t bit);
uint8_t ram_clear_bit(uint16_t address, uint8_t bit);
uint8_t ram_write_byte(uint16_t address, uint8_t data);
uint8_t ram_write_word(uint16_t address, uint16_t data);
uint8_t ram_write_table(uint16_t address, uint16_t length,uint8_t *data);
inline uint8_t ram_in_range(uint16_t reg,uint16_t address,uint16_t length);
uint8_t ram_in_window(uint16_t start_reg,uint16_t reg_length,uint16_t start_address,uint16_t address_length);
#ifdef __cplusplus
}
#endif
#endif
#ifndef _SCHEDULER_H
#define _SCHEDULER_H
#include "stm32f1xx_hal.h"
typedef struct{
void (*function)(void);
unsigned char period_ms;
unsigned short int pulse;
unsigned char enabled;
}TSchedInfo;
typedef enum {SCHED_CH1=0,SCHED_CH2=1,SCHED_CH3=2,SCHED_CH4=3} sched_channel_t;
void scheduler_init(void);
void scheduler_set_channel(sched_channel_t channel_id, void (*function)(void), unsigned char period_ms);
void scheduler_enable_channel(sched_channel_t channel_id);
void scheduler_change_period(sched_channel_t channel_id,unsigned char period_ms);
void scheduler_disable_channel(sched_channel_t channel_id);
#endif
/**
******************************************************************************
* @file stm32f1xx_hal_conf.h
* @author MCD Application Team
* @version V1.0.4
* @date 29-April-2016
* @brief HAL configuration template file.
* This file should be copied to the application folder and renamed
* to stm32f1xx_hal_conf.h.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F1xx_HAL_CONF_H
#define __STM32F1xx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
#define HAL_ADC_MODULE_ENABLED
//#define HAL_CAN_MODULE_ENABLED
//#define HAL_CEC_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
//#define HAL_CRC_MODULE_ENABLED
//#define HAL_DAC_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
//#define HAL_ETH_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_GPIO_MODULE_ENABLED
//#define HAL_HCD_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
//#define HAL_I2S_MODULE_ENABLED
//#define HAL_IRDA_MODULE_ENABLED
//#define HAL_IWDG_MODULE_ENABLED
//#define HAL_NAND_MODULE_ENABLED
//#define HAL_NOR_MODULE_ENABLED
//#define HAL_PCCARD_MODULE_ENABLED
//#define HAL_PCD_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
//#define HAL_RTC_MODULE_ENABLED
//#define HAL_SD_MODULE_ENABLED
//#define HAL_SMARTCARD_MODULE_ENABLED
//#define HAL_SPI_MODULE_ENABLED
//#define HAL_SRAM_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
//#define HAL_WWDG_MODULE_ENABLED
/* ########################## Oscillator Values adaptation ####################*/
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#if defined(USE_STM3210C_EVAL)
#define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */
#else
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
#endif
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief External Low Speed oscillator (LSE) value.
* This value is used by the UART, RTC HAL module to compute the system frequency
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/
#endif /* LSE_VALUE */
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/* Tip: To avoid modifying this file each time you need to use different HSE,
=== you can define the HSE value in your toolchain compiler preprocessor. */
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)0x000F) /*!< tick interrupt priority */
#define USE_RTOS 0
#define PREFETCH_ENABLE 1
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/*#define USE_FULL_ASSERT 1*/
/* ################## Ethernet peripheral configuration ##################### */
/* Section 1 : Ethernet peripheral configuration */
/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
#define MAC_ADDR0 2
#define MAC_ADDR1 0
#define MAC_ADDR2 0
#define MAC_ADDR3 0
#define MAC_ADDR4 0
#define MAC_ADDR5 0
/* Definition of the Ethernet driver buffers size and count */
#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
#define ETH_RXBUFNB ((uint32_t)8) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
#define ETH_TXBUFNB ((uint32_t)4) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
/* Section 2: PHY configuration section */
/* DP83848 PHY Address*/
#define DP83848_PHY_ADDRESS 0x01
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
#define PHY_RESET_DELAY ((uint32_t)0x000000FF)
/* PHY Configuration delay */
#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFF)
#define PHY_READ_TO ((uint32_t)0x0000FFFF)
#define PHY_WRITE_TO ((uint32_t)0x0000FFFF)
/* Section 3: Common PHY Registers */
#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */
#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */
#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */
#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */
#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */
#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */
#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */
#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */
#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */
#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */
#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */
#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */
#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */
#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */
#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */
/* Section 4: Extended PHY Registers */
#define PHY_SR ((uint16_t)0x10) /*!< PHY status register Offset */
#define PHY_MICR ((uint16_t)0x11) /*!< MII Interrupt Control Register */
#define PHY_MISR ((uint16_t)0x12) /*!< MII Interrupt Status and Misc. Control Register */
#define PHY_LINK_STATUS ((uint16_t)0x0001) /*!< PHY Link mask */
#define PHY_SPEED_STATUS ((uint16_t)0x0002) /*!< PHY Speed mask */
#define PHY_DUPLEX_STATUS ((uint16_t)0x0004) /*!< PHY Duplex mask */
#define PHY_MICR_INT_EN ((uint16_t)0x0002) /*!< PHY Enable interrupts */
#define PHY_MICR_INT_OE ((uint16_t)0x0001) /*!< PHY Enable output interrupt events */
#define PHY_MISR_LINK_INT_EN ((uint16_t)0x0020) /*!< Enable Interrupt on change of link status */
#define PHY_LINK_INTERRUPT ((uint16_t)0x2000) /*!< PHY link status interrupt mask */
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32f1xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32f1xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32f1xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_ETH_MODULE_ENABLED
#include "stm32f1xx_hal_eth.h"
#endif /* HAL_ETH_MODULE_ENABLED */
#ifdef HAL_CAN_MODULE_ENABLED
#include "stm32f1xx_hal_can.h"
#endif /* HAL_CAN_MODULE_ENABLED */
#ifdef HAL_CEC_MODULE_ENABLED
#include "stm32f1xx_hal_cec.h"
#endif /* HAL_CEC_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32f1xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32f1xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32f1xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32f1xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32f1xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32f1xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
#ifdef HAL_NOR_MODULE_ENABLED
#include "stm32f1xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32f1xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32f1xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32f1xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32f1xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32f1xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_PCCARD_MODULE_ENABLED
#include "stm32f1xx_hal_pccard.h"
#endif /* HAL_PCCARD_MODULE_ENABLED */
#ifdef HAL_SD_MODULE_ENABLED
#include "stm32f1xx_hal_sd.h"
#endif /* HAL_SD_MODULE_ENABLED */
#ifdef HAL_NAND_MODULE_ENABLED
#include "stm32f1xx_hal_nand.h"
#endif /* HAL_NAND_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32f1xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32f1xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32f1xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32f1xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32f1xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32f1xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32f1xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32f1xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_HCD_MODULE_ENABLED
#include "stm32f1xx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr: If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif
#endif /* __STM32F1xx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
/*
*****************************************************************************
**
*****************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/* Highest address of the user mode stack */
_estack = 0x20004FFF; /* end of RAM */
/* Generate a link error if heap and stack don't fit into RAM */
_Min_Heap_Size = 0; /* required amount of heap */
_Min_Stack_Size = 0x400; /* required amount of stack */
/* Specify the memory areas */
MEMORY
{
ISR (rx) : ORIGIN = 0x08000000, LENGTH = 1K
EEPROM (rw) : ORIGIN = 0x08000400, LENGTH = 2K
FLASH (rx) : ORIGIN = 0x08000C00, LENGTH = 125K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K
}
/* Define output sections */
SECTIONS
{
/* The startup code goes first into FLASH */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >ISR
.eeprom :
{
. = ALIGN(4);
*(.eeprom)
. = ALIGN(4);
} >EEPROM
/* The program code and other data goes into FLASH */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >FLASH
/* Constant data goes into FLASH */
.rodata :
{
. = ALIGN(4);
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
. = ALIGN(4);
} >FLASH
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
.ARM : {
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} >FLASH
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
} >FLASH
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
} >FLASH
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
} >FLASH
/* used by the startup to initialize data */
_sidata = LOADADDR(.data);
/* Initialized data sections goes into RAM, load LMA copy after code */
.data :
{
. = ALIGN(4);
_sdata = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT> FLASH
/* Uninitialized data section */
. = ALIGN(4);
.bss :
{
/* This is used by the startup in order to initialize the .bss secion */
_sbss = .; /* define a global symbol at bss start */
__bss_start__ = _sbss;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM
/* User_heap_stack section, used to check that there is enough RAM left */
._user_heap_stack :
{
. = ALIGN(4);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(4);
} >RAM
/* Remove information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}
#include "adc_dma.h"
#include "adc_dma_registers.h"
#include "ram.h"
#define ADC1_CH1 ADC_CHANNEL_4
#define ADC1_CH2 ADC_CHANNEL_6
#define ADC1_CH3 ADC_CHANNEL_TEMPSENSOR
#define ADC2_CH1 ADC_CHANNEL_5
#define ADC2_CH2 ADC_CHANNEL_7
#define ADC2_CH3 ADC_CHANNEL_8
#define ADC1_CH1_PIN GPIO_PIN_4
#define ADC1_CH1_PORT GPIOA
#define ADC1_CH1_ENABLE_PORT_CLK __GPIOA_CLK_ENABLE()
#define ADC1_CH2_PIN GPIO_PIN_6
#define ADC1_CH2_PORT GPIOA
#define ADC1_CH2_ENABLE_PORT_CLK __GPIOA_CLK_ENABLE()
#define ADC2_CH1_PIN GPIO_PIN_5
#define ADC2_CH1_PORT GPIOA
#define ADC2_CH1_ENABLE_PORT_CLK __GPIOA_CLK_ENABLE()
#define ADC2_CH2_PIN GPIO_PIN_7
#define ADC2_CH2_PORT GPIOA
#define ADC2_CH2_ENABLE_PORT_CLK __GPIOA_CLK_ENABLE()
#define ADC2_CH3_PIN GPIO_PIN_0
#define ADC2_CH3_PORT GPIOB
#define ADC2_CH3_ENABLE_PORT_CLK __GPIOB_CLK_ENABLE()
#define ADC1_ENABLE_CLK __ADC1_CLK_ENABLE()
#define ADC2_ENABLE_CLK __ADC2_CLK_ENABLE()
#define ADC_DMA DMA1
#define ADC_ENABLE_DMA_CLK __DMA1_CLK_ENABLE()
#define ADC_DMA_CHANNEL DMA1_Channel1
#define ADC_DMA_IRQn DMA1_Channel1_IRQn
#define ADC_DMA_IRQHandler DMA1_Channel1_IRQHandler
// temperature conversion functions
#define TEMP_V25 1.43// ADC voltage at 25 degrees in V
#define TEMP_INV_SLOPE 232.558// ADC slope in degree/mV
// general voltage conversion
#define VOLTAGE_DELTA 0.805664
#define MOTOR_VOLTAGE_GAIN 16.0
// private variables
ADC_HandleTypeDef hadc1;
ADC_HandleTypeDef hadc2;
DMA_HandleTypeDef hdma_adc1;
float adc_temperature;
float adc_voltages[4];
uint32_t adc_data[3];// temporal buffer to store ADC data before conversion
/* memory module */
TMemModule adc_mem_module;
void adc_convert_temperature(uint16_t value)
{
uint16_t ram_value;
adc_temperature=((((float)value)*VOLTAGE_DELTA/1000.0)-TEMP_V25)*TEMP_INV_SLOPE+25.0;
ram_value=(uint16_t)(adc_temperature*1024.0);
ram_data[ADC_TEMPERATURE]=ram_value%256;
ram_data[ADC_TEMPERATURE+1]=ram_value/256;
}
void adc_convert_voltage(adc_dma_ch_t channel_id,uint16_t value)
{
uint16_t ram_value;
switch(channel_id)
{
case ADC_CH1: adc_voltages[0]=((float)value)*VOLTAGE_DELTA/adc_gains[0];
ram_value=(uint16_t)adc_voltages[0];
ram_data[ADC_CH1_VOLTAGE]=ram_value%256;
ram_data[ADC_CH1_VOLTAGE+1]=ram_value/256;
break;
case ADC_CH2: adc_voltages[1]=((float)value)*VOLTAGE_DELTA/adc_gains[1];
ram_value=(uint16_t)adc_voltages[1];
ram_data[ADC_CH2_VOLTAGE]=ram_value%256;
ram_data[ADC_CH2_VOLTAGE+1]=ram_value/256;
break;
case ADC_CH3: adc_voltages[2]=((float)value)*VOLTAGE_DELTA/adc_gains[2];
ram_value=(uint16_t)adc_voltages[2];
ram_data[ADC_CH3_VOLTAGE]=ram_value%256;
ram_data[ADC_CH3_VOLTAGE+1]=ram_value/256;
break;
case ADC_CH4: adc_voltages[3]=((float)value)*VOLTAGE_DELTA/adc_gains[3];
ram_value=(uint16_t)adc_voltages[3];
ram_data[ADC_CH4_VOLTAGE]=ram_value%256;
ram_data[ADC_CH4_VOLTAGE+1]=ram_value/256;
break;
case ADC_CH6: adc_motor_voltage=((float)value)*VOLTAGE_DELTA*MOTOR_VOLTAGE_GAIN;
ram_value=(uint16_t)adc_motor_voltage;
ram_data[ADC_MOTOR_VOLTAGE]=ram_value%256;
ram_data[ADC_MOTOR_VOLTAGE+1]=ram_value/256;
break;
default: break;
}
}
void adc_write_cmd(unsigned short int address,unsigned short int length,unsigned char *data)
{
}
void adc_read_cmd(unsigned short int address,unsigned short int length,unsigned char *data)
{
ram_read_table(address,length,data);
}
/* interrupt handlers */
void ADC_DMA_IRQHandler(void)
{
if(__HAL_DMA_GET_FLAG(&hdma_adc1, __HAL_DMA_GET_TE_FLAG_INDEX(&hdma_adc1)) != RESET)
if(__HAL_DMA_GET_IT_SOURCE(&hdma_adc1, DMA_IT_TE) != RESET)
__HAL_DMA_CLEAR_FLAG(&hdma_adc1, __HAL_DMA_GET_TE_FLAG_INDEX(&hdma_adc1));
if(__HAL_DMA_GET_FLAG(&hdma_adc1, __HAL_DMA_GET_HT_FLAG_INDEX(&hdma_adc1)) != RESET)
if(__HAL_DMA_GET_IT_SOURCE(&hdma_adc1, DMA_IT_HT) != RESET)
__HAL_DMA_CLEAR_FLAG(&hdma_adc1, __HAL_DMA_GET_HT_FLAG_INDEX(&hdma_adc1));
if(__HAL_DMA_GET_FLAG(&hdma_adc1, __HAL_DMA_GET_TC_FLAG_INDEX(&hdma_adc1)) != RESET)
if(__HAL_DMA_GET_IT_SOURCE(&hdma_adc1, DMA_IT_TC) != RESET)
{
__HAL_DMA_CLEAR_FLAG(&hdma_adc1, __HAL_DMA_GET_TC_FLAG_INDEX(&hdma_adc1));
HAL_ADC_Stop(&hadc2);
adc_convert_voltage(ADC_CH1,adc_data[0]&0x0000FFFF);
adc_convert_voltage(ADC_CH2,(adc_data[0]>>16)&0x0000FFFF);
adc_convert_voltage(ADC_CH3,adc_data[1]&0x0000FFFF);
adc_convert_voltage(ADC_CH4,(adc_data[1]>>16)&0x0000FFFF);
adc_convert_temperature(adc_data[2]&0x0000FFFF);
adc_convert_voltage(ADC_CH6,(adc_data[2]>>16)&0x0000FFFF);
}
}
// public functions
uint8_t adc_init(TMemory *memory)
{
GPIO_InitTypeDef GPIO_InitStruct;
ADC_MultiModeTypeDef multimode;
ADC_ChannelConfTypeDef sConfig;
/* enable clocks */
ADC1_CH1_ENABLE_PORT_CLK;
ADC1_CH2_ENABLE_PORT_CLK;
ADC2_CH1_ENABLE_PORT_CLK;
ADC2_CH2_ENABLE_PORT_CLK;
ADC2_CH3_ENABLE_PORT_CLK;
ADC1_ENABLE_CLK;
ADC2_ENABLE_CLK;
// configure GPIO
GPIO_InitStruct.Pin = ADC1_CH1_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(ADC1_CH1_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = ADC1_CH2_PIN;
HAL_GPIO_Init(ADC1_CH2_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = ADC2_CH1_PIN;
HAL_GPIO_Init(ADC2_CH1_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = ADC2_CH2_PIN;
HAL_GPIO_Init(ADC2_CH2_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = ADC2_CH3_PIN;
HAL_GPIO_Init(ADC2_CH3_PORT, &GPIO_InitStruct);
ADC_ENABLE_DMA_CLK;
//initialize DMA
hdma_adc1.Instance = ADC_DMA_CHANNEL;
hdma_adc1.Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_adc1.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_adc1.Init.MemInc = DMA_MINC_ENABLE;
hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD;
hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_WORD;
hdma_adc1.Init.Mode = DMA_CIRCULAR;
hdma_adc1.Init.Priority = DMA_PRIORITY_LOW;
HAL_DMA_Init(&hdma_adc1);
__HAL_LINKDMA(&hadc1,DMA_Handle,hdma_adc1);
HAL_NVIC_SetPriority(ADC_DMA_IRQn, 2, 0);
HAL_NVIC_EnableIRQ(ADC_DMA_IRQn);
// configure ADC1
hadc1.Instance = ADC1;
hadc1.Init.ScanConvMode = ADC_SCAN_ENABLE;
hadc1.Init.ContinuousConvMode = DISABLE;
hadc1.Init.DiscontinuousConvMode = DISABLE;
hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START;
hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT;
hadc1.Init.NbrOfConversion = 3;
HAL_ADC_Init(&hadc1);
multimode.Mode = ADC_DUALMODE_REGSIMULT;
HAL_ADCEx_MultiModeConfigChannel(&hadc1, &multimode);
// configure ADC1 channels
sConfig.Channel = ADC1_CH1;
sConfig.Rank = 1;
sConfig.SamplingTime = ADC_SAMPLETIME_239CYCLES_5;
HAL_ADC_ConfigChannel(&hadc1, &sConfig);
sConfig.Channel = ADC1_CH2;
sConfig.Rank = 2;
HAL_ADC_ConfigChannel(&hadc1, &sConfig);
sConfig.Channel = ADC1_CH3;
sConfig.Rank = 3;
HAL_ADC_ConfigChannel(&hadc1, &sConfig);
// configure ADC2
hadc2.Instance = ADC2;
hadc2.Init.ScanConvMode = ADC_SCAN_ENABLE;
hadc2.Init.ContinuousConvMode = DISABLE;
hadc2.Init.DiscontinuousConvMode = DISABLE;
hadc2.Init.ExternalTrigConv = ADC_SOFTWARE_START;
hadc2.Init.DataAlign = ADC_DATAALIGN_RIGHT;
hadc2.Init.NbrOfConversion = 3;
HAL_ADC_Init(&hadc2);
multimode.Mode = ADC_DUALMODE_REGSIMULT;
HAL_ADCEx_MultiModeConfigChannel(&hadc2, &multimode);
// configure ADC1 channels
sConfig.Channel = ADC2_CH1;
sConfig.Rank = 1;
sConfig.SamplingTime = ADC_SAMPLETIME_239CYCLES_5;
HAL_ADC_ConfigChannel(&hadc2, &sConfig);
sConfig.Channel = ADC2_CH2;
sConfig.Rank = 2;
HAL_ADC_ConfigChannel(&hadc2, &sConfig);
sConfig.Channel = ADC2_CH3;
sConfig.Rank = 3;
HAL_ADC_ConfigChannel(&hadc2, &sConfig);
/* calibrate ADC1 */
HAL_ADCEx_Calibration_Start(&hadc1);
HAL_ADCEx_Calibration_Start(&hadc2);
/* initialize the digital potentiometer modules */
digital_pot_init(&pot1,0x58,POT_20k);
digital_pot_init(&pot2,0x5A,POT_20k);
/* initialize memory module */
mem_module_init(&adc_mem_module);
adc_mem_module.write_cmd=adc_write_cmd;
adc_mem_module.read_cmd=adc_read_cmd;
if(!mem_module_add_ram_segment(&adc_mem_module,RAM_ADC_DMA_BASE_ADDRESS,RAM_ADC_DMA_LENGTH))
return 0x00;
if(!mem_module_add_eeprom_segment(&adc_mem_module,EEPROM_ADC_DMA_BASE_ADDRESS,EEPROM_ADC_DMA_LENGTH))
return 0x00;
if(!mem_add_module(memory,&adc_mem_module))
return 0x00;
return 0x01;
}
void adc_start_conversion(void)
{
HAL_ADC_Start(&hadc2);
HAL_ADCEx_MultiModeStart_DMA(&hadc1,adc_data,3);
}
float adc_get_voltage(adc_dma_ch_t channel_id)
{
switch(channel_id)
{
case ADC_CH1: return adc_voltages[0];
case ADC_CH2: return adc_voltages[1];
case ADC_CH3: return adc_voltages[2];
case ADC_CH4: return adc_voltages[3];
default: return 0.0;
}
}
inline float adc_get_temperature(void)
{
return adc_temperature;
}
/**
******************************************************************************
* @file EEPROM_Emulation/src/eeprom.c
* @author MCD Application Team
* @version V1.0.0
* @date 17-December-2014
* @brief This file provides all the EEPROM emulation firmware functions.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/** @addtogroup EEPROM_Emulation
* @{
*/
/* Includes ------------------------------------------------------------------*/
#include "eeprom.h"
#include "ir_feet_conf.h"
#ifndef EEPROM_NUM_VAR
#define EEPROM_NUM_VAR 0
#endif
uint16_t eeprom_data[] __attribute__ ((section (".eeprom")))={VALID_PAGE, 0xFFFF};
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Global variable used to store variable value in read sequence */
uint16_t DataVar = 0;
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
static HAL_StatusTypeDef EE_Format(void);
static uint16_t EE_FindValidPage(uint8_t Operation);
static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data);
static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data);
static uint16_t EE_VerifyPageFullyErased(uint32_t Address);
/**
* @brief Restore the pages to a known good state in case of page's status
* corruption after a power loss.
* @param None.
* @retval - Flash error code: on write Flash error
* - FLASH_COMPLETE: on success
*/
uint16_t EE_Init(void)
{
uint16_t pagestatus0 = 6, pagestatus1 = 6;
uint16_t varidx = 0;
uint16_t eepromstatus = 0, readstatus = 0;
int16_t x = -1;
HAL_StatusTypeDef flashstatus;
uint32_t page_error = 0;
FLASH_EraseInitTypeDef s_eraseinit;
/* Unlock the Flash Program Erase controller */
HAL_FLASH_Unlock();
/* Get Page0 status */
pagestatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS);
/* Get Page1 status */
pagestatus1 = (*(__IO uint16_t*)PAGE1_BASE_ADDRESS);
/* Fill EraseInit structure*/
s_eraseinit.TypeErase = TYPEERASE_PAGES;
s_eraseinit.PageAddress = PAGE0_ID;
s_eraseinit.NbPages = 1;
/* Check for invalid header states and repair if necessary */
switch (pagestatus0)
{
case ERASED:
if (pagestatus1 == VALID_PAGE) /* Page0 erased, Page1 valid */
{
/* Erase Page0 */
if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS))
{
flashstatus = HAL_FLASHEx_Erase(&s_eraseinit, &page_error);
/* If erase operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
}
else if (pagestatus1 == RECEIVE_DATA) /* Page0 erased, Page1 receive */
{
/* Erase Page0 */
if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS))
{
flashstatus = HAL_FLASHEx_Erase(&s_eraseinit, &page_error);
/* If erase operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
/* Mark Page1 as valid */
flashstatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE1_BASE_ADDRESS, VALID_PAGE);
/* If program operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
else /* First EEPROM access (Page0&1 are erased) or invalid state -> format EEPROM */
{
/* Erase both Page0 and Page1 and set Page0 as valid page */
flashstatus = EE_Format();
/* If erase/program operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
break;
case RECEIVE_DATA:
if (pagestatus1 == VALID_PAGE) /* Page0 receive, Page1 valid */
{
/* Transfer data from Page1 to Page0 */
for (varidx = 0; varidx < EEPROM_NUM_VAR; varidx++)
{
if (( *(__IO uint16_t*)(PAGE0_BASE_ADDRESS + 6)) == eeprom_data[varidx])
{
x = varidx;
}
if (varidx != x)
{
/* Read the last variables' updates */
readstatus = EE_ReadVariable(eeprom_data[varidx], &DataVar);
/* In case variable corresponding to the virtual address was found */
if (readstatus != 0x1)
{
/* Transfer the variable to the Page0 */
eepromstatus = EE_VerifyPageFullWriteVariable(eeprom_data[varidx], DataVar);
/* If program operation was failed, a Flash error code is returned */
if (eepromstatus != HAL_OK)
{
return eepromstatus;
}
}
}
}
/* Mark Page0 as valid */
flashstatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE);
/* If program operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
s_eraseinit.TypeErase = TYPEERASE_PAGES;
s_eraseinit.PageAddress = PAGE1_ID;
s_eraseinit.NbPages = 1;
/* Erase Page1 */
if(!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS))
{
flashstatus = HAL_FLASHEx_Erase(&s_eraseinit, &page_error);
/* If erase operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
}
else if (pagestatus1 == ERASED) /* Page0 receive, Page1 erased */
{
s_eraseinit.TypeErase = TYPEERASE_PAGES;
s_eraseinit.PageAddress = PAGE1_ID;
s_eraseinit.NbPages = 1;
/* Erase Page1 */
if(!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS))
{
flashstatus = HAL_FLASHEx_Erase(&s_eraseinit, &page_error);
/* If erase operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
/* Mark Page0 as valid */
flashstatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE);
/* If program operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
else /* Invalid state -> format eeprom */
{
/* Erase both Page0 and Page1 and set Page0 as valid page */
flashstatus = EE_Format();
/* If erase/program operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
break;
case VALID_PAGE:
if (pagestatus1 == VALID_PAGE) /* Invalid state -> format eeprom */
{
/* Erase both Page0 and Page1 and set Page0 as valid page */
flashstatus = EE_Format();
/* If erase/program operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
else if (pagestatus1 == ERASED) /* Page0 valid, Page1 erased */
{
s_eraseinit.TypeErase = TYPEERASE_PAGES;
s_eraseinit.PageAddress = PAGE1_ID;
s_eraseinit.NbPages = 1;
/* Erase Page1 */
if(!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS))
{
flashstatus = HAL_FLASHEx_Erase(&s_eraseinit, &page_error);
/* If erase operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
}
else /* Page0 valid, Page1 receive */
{
/* Transfer data from Page0 to Page1 */
for (varidx = 0; varidx < EEPROM_NUM_VAR; varidx++)
{
if ((*(__IO uint16_t*)(PAGE1_BASE_ADDRESS + 6)) == eeprom_data[varidx])
{
x = varidx;
}
if (varidx != x)
{
/* Read the last variables' updates */
readstatus = EE_ReadVariable(eeprom_data[varidx], &DataVar);
/* In case variable corresponding to the virtual address was found */
if (readstatus != 0x1)
{
/* Transfer the variable to the Page1 */
eepromstatus = EE_VerifyPageFullWriteVariable(eeprom_data[varidx], DataVar);
/* If program operation was failed, a Flash error code is returned */
if (eepromstatus != HAL_OK)
{
return eepromstatus;
}
}
}
}
/* Mark Page1 as valid */
flashstatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE1_BASE_ADDRESS, VALID_PAGE);
/* If program operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
s_eraseinit.TypeErase = TYPEERASE_PAGES;
s_eraseinit.PageAddress = PAGE0_ID;
s_eraseinit.NbPages = 1;
/* Erase Page0 */
if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS))
{
flashstatus = HAL_FLASHEx_Erase(&s_eraseinit, &page_error);
/* If erase operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
}
break;
default: /* Any other state -> format eeprom */
/* Erase both Page0 and Page1 and set Page0 as valid page */
flashstatus = EE_Format();
/* If erase/program operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
break;
}
return HAL_OK;
}
/**
* @brief Verify if specified page is fully erased.
* @param Address: page address
* This parameter can be one of the following values:
* @arg PAGE0_BASE_ADDRESS: Page0 base address
* @arg PAGE1_BASE_ADDRESS: Page1 base address
* @retval page fully erased status:
* - 0: if Page not erased
* - 1: if Page erased
*/
uint16_t EE_VerifyPageFullyErased(uint32_t Address)
{
uint32_t readstatus = 1;
uint16_t addressvalue = 0x5555;
/* Check each active page address starting from end */
while (Address <= PAGE0_END_ADDRESS)
{
/* Get the current location content to be compared with virtual address */
addressvalue = (*(__IO uint16_t*)Address);
/* Compare the read address with the virtual address */
if (addressvalue != ERASED)
{
/* In case variable value is read, reset readstatus flag */
readstatus = 0;
break;
}
/* Next address location */
Address = Address + 4;
}
/* Return readstatus value: (0: Page not erased, 1: Page erased) */
return readstatus;
}
/**
* @brief Returns the last stored variable data, if found, which correspond to
* the passed virtual address
* @param VirtAddress: Variable virtual address
* @param Data: Global variable contains the read variable value
* @retval Success or error status:
* - 0: if variable was found
* - 1: if the variable was not found
* - NO_VALID_PAGE: if no valid page was found.
*/
uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data)
{
uint16_t validpage = PAGE0;
uint16_t addressvalue = 0x5555, readstatus = 1;
uint32_t address = EEPROM_START_ADDRESS, PageStartAddress = EEPROM_START_ADDRESS;
/* Get active Page for read operation */
validpage = EE_FindValidPage(READ_FROM_VALID_PAGE);
/* Check if there is no valid page */
if (validpage == NO_VALID_PAGE)
{
return NO_VALID_PAGE;
}
/* Get the valid Page start Address */
PageStartAddress = (uint32_t)(EEPROM_START_ADDRESS + (uint32_t)(validpage * PAGE_SIZE));
/* Get the valid Page end Address */
address = (uint32_t)((EEPROM_START_ADDRESS - 2) + (uint32_t)((1 + validpage) * PAGE_SIZE));
/* Check each active page address starting from end */
while (address > (PageStartAddress + 2))
{
/* Get the current location content to be compared with virtual address */
addressvalue = (*(__IO uint16_t*)address);
/* Compare the read address with the virtual address */
if (addressvalue == VirtAddress)
{
/* Get content of Address-2 which is variable value */
*Data = (*(__IO uint16_t*)(address - 2));
/* In case variable value is read, reset readstatus flag */
readstatus = 0;
break;
}
else
{
/* Next address location */
address = address - 4;
}
}
/* Return readstatus value: (0: variable exist, 1: variable doesn't exist) */
return readstatus;
}
/**
* @brief Writes/upadtes variable data in EEPROM.
* @param VirtAddress: Variable virtual address
* @param Data: 16 bit data to be written
* @retval Success or error status:
* - FLASH_COMPLETE: on success
* - PAGE_FULL: if valid page is full
* - NO_VALID_PAGE: if no valid page was found
* - Flash error code: on write Flash error
*/
uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data)
{
uint16_t Status = 0;
/* Write the variable virtual address and value in the EEPROM */
Status = EE_VerifyPageFullWriteVariable(VirtAddress, Data);
/* In case the EEPROM active page is full */
if (Status == PAGE_FULL)
{
/* Perform Page transfer */
Status = EE_PageTransfer(VirtAddress, Data);
}
/* Return last operation status */
return Status;
}
/**
* @brief Erases PAGE and PAGE1 and writes VALID_PAGE header to PAGE
* @param None
* @retval Status of the last operation (Flash write or erase) done during
* EEPROM formating
*/
static HAL_StatusTypeDef EE_Format(void)
{
HAL_StatusTypeDef flashstatus = HAL_OK;
uint32_t page_error = 0;
FLASH_EraseInitTypeDef s_eraseinit;
s_eraseinit.TypeErase = TYPEERASE_PAGES;
s_eraseinit.PageAddress = PAGE0_ID;
s_eraseinit.NbPages = 1;
/* Erase Page0 */
if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS))
{
flashstatus = HAL_FLASHEx_Erase(&s_eraseinit, &page_error);
/* If erase operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
/* Set Page0 as valid page: Write VALID_PAGE at Page0 base address */
flashstatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE);
/* If program operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
s_eraseinit.PageAddress = PAGE1_ID;
/* Erase Page1 */
if(!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS))
{
flashstatus = HAL_FLASHEx_Erase(&s_eraseinit, &page_error);
/* If erase operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
}
return HAL_OK;
}
/**
* @brief Find valid Page for write or read operation
* @param Operation: operation to achieve on the valid page.
* This parameter can be one of the following values:
* @arg READ_FROM_VALID_PAGE: read operation from valid page
* @arg WRITE_IN_VALID_PAGE: write operation from valid page
* @retval Valid page number (PAGE or PAGE1) or NO_VALID_PAGE in case
* of no valid page was found
*/
static uint16_t EE_FindValidPage(uint8_t Operation)
{
uint16_t pagestatus0 = 6, pagestatus1 = 6;
/* Get Page0 actual status */
pagestatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS);
/* Get Page1 actual status */
pagestatus1 = (*(__IO uint16_t*)PAGE1_BASE_ADDRESS);
/* Write or read operation */
switch (Operation)
{
case WRITE_IN_VALID_PAGE: /* ---- Write operation ---- */
if (pagestatus1 == VALID_PAGE)
{
/* Page0 receiving data */
if (pagestatus0 == RECEIVE_DATA)
{
return PAGE0; /* Page0 valid */
}
else
{
return PAGE1; /* Page1 valid */
}
}
else if (pagestatus0 == VALID_PAGE)
{
/* Page1 receiving data */
if (pagestatus1 == RECEIVE_DATA)
{
return PAGE1; /* Page1 valid */
}
else
{
return PAGE0; /* Page0 valid */
}
}
else
{
return NO_VALID_PAGE; /* No valid Page */
}
case READ_FROM_VALID_PAGE: /* ---- Read operation ---- */
if (pagestatus0 == VALID_PAGE)
{
return PAGE0; /* Page0 valid */
}
else if (pagestatus1 == VALID_PAGE)
{
return PAGE1; /* Page1 valid */
}
else
{
return NO_VALID_PAGE ; /* No valid Page */
}
default:
return PAGE0; /* Page0 valid */
}
}
/**
* @brief Verify if active page is full and Writes variable in EEPROM.
* @param VirtAddress: 16 bit virtual address of the variable
* @param Data: 16 bit data to be written as variable value
* @retval Success or error status:
* - FLASH_COMPLETE: on success
* - PAGE_FULL: if valid page is full
* - NO_VALID_PAGE: if no valid page was found
* - Flash error code: on write Flash error
*/
static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data)
{
HAL_StatusTypeDef flashstatus = HAL_OK;
uint16_t validpage = PAGE0;
uint32_t address = EEPROM_START_ADDRESS, pageendaddress = EEPROM_START_ADDRESS+PAGE_SIZE;
/* Get valid Page for write operation */
validpage = EE_FindValidPage(WRITE_IN_VALID_PAGE);
/* Check if there is no valid page */
if (validpage == NO_VALID_PAGE)
{
return NO_VALID_PAGE;
}
/* Get the valid Page start address */
address = (uint32_t)(EEPROM_START_ADDRESS + (uint32_t)(validpage * PAGE_SIZE));
/* Get the valid Page end address */
pageendaddress = (uint32_t)((EEPROM_START_ADDRESS - 1) + (uint32_t)((validpage + 1) * PAGE_SIZE));
/* Check each active page address starting from begining */
while (address < pageendaddress)
{
/* Verify if address and address+2 contents are 0xFFFFFFFF */
if ((*(__IO uint32_t*)address) == 0xFFFFFFFF)
{
/* Set variable data */
flashstatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, address, Data);
/* If program operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
/* Set variable virtual address */
flashstatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, address + 2, VirtAddress);
/* Return program operation status */
return flashstatus;
}
else
{
/* Next address location */
address = address + 4;
}
}
/* Return PAGE_FULL in case the valid page is full */
return PAGE_FULL;
}
/**
* @brief Transfers last updated variables data from the full Page to
* an empty one.
* @param VirtAddress: 16 bit virtual address of the variable
* @param Data: 16 bit data to be written as variable value
* @retval Success or error status:
* - FLASH_COMPLETE: on success
* - PAGE_FULL: if valid page is full
* - NO_VALID_PAGE: if no valid page was found
* - Flash error code: on write Flash error
*/
static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data)
{
HAL_StatusTypeDef flashstatus = HAL_OK;
uint32_t newpageaddress = EEPROM_START_ADDRESS;
uint32_t oldpageid = 0;
uint16_t validpage = PAGE0, varidx = 0;
uint16_t eepromstatus = 0, readstatus = 0;
uint32_t page_error = 0;
FLASH_EraseInitTypeDef s_eraseinit;
/* Get active Page for read operation */
validpage = EE_FindValidPage(READ_FROM_VALID_PAGE);
if (validpage == PAGE1) /* Page1 valid */
{
/* New page address where variable will be moved to */
newpageaddress = PAGE0_BASE_ADDRESS;
/* Old page ID where variable will be taken from */
oldpageid = PAGE1_ID;
}
else if (validpage == PAGE0) /* Page0 valid */
{
/* New page address where variable will be moved to */
newpageaddress = PAGE1_BASE_ADDRESS;
/* Old page ID where variable will be taken from */
oldpageid = PAGE0_ID;
}
else
{
return NO_VALID_PAGE; /* No valid Page */
}
/* Set the new Page status to RECEIVE_DATA status */
flashstatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, newpageaddress, RECEIVE_DATA);
/* If program operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
/* Write the variable passed as parameter in the new active page */
eepromstatus = EE_VerifyPageFullWriteVariable(VirtAddress, Data);
/* If program operation was failed, a Flash error code is returned */
if (eepromstatus != HAL_OK)
{
return eepromstatus;
}
/* Transfer process: transfer variables from old to the new active page */
for (varidx = 0; varidx < EEPROM_NUM_VAR; varidx++)
{
if (eeprom_data[varidx] != VirtAddress) /* Check each variable except the one passed as parameter */
{
/* Read the other last variable updates */
readstatus = EE_ReadVariable(eeprom_data[varidx], &DataVar);
/* In case variable corresponding to the virtual address was found */
if (readstatus != 0x1)
{
/* Transfer the variable to the new active page */
eepromstatus = EE_VerifyPageFullWriteVariable(eeprom_data[varidx], DataVar);
/* If program operation was failed, a Flash error code is returned */
if (eepromstatus != HAL_OK)
{
return eepromstatus;
}
}
}
}
s_eraseinit.TypeErase = TYPEERASE_PAGES;
s_eraseinit.PageAddress = oldpageid;
s_eraseinit.NbPages = 1;
/* Erase the old Page: Set old Page status to ERASED status */
flashstatus = HAL_FLASHEx_Erase(&s_eraseinit, &page_error);
/* If erase operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
/* Set new Page status to VALID_PAGE status */
flashstatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, newpageaddress, VALID_PAGE);
/* If program operation was failed, a Flash error code is returned */
if (flashstatus != HAL_OK)
{
return flashstatus;
}
/* Return last operation flash status */
return flashstatus;
}
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
#include "gpio.h"
#define GPIO_EXP_ADDRESS 0x40
#define GPIO_EXP_NUM_REG 22
#define INTA_GPIO_CLK __GPIOC_CLK_ENABLE()
#define INTA_PIN GPIO_PIN_14
#define INTA_GPIO_PORT GPIOC
#define INTA_IRQn EXTI15_10_IRQn
#define INTA_IRQnHandler EXTI15_10_IRQHandler
#define POLOLU_ENABLE_PORT EXP_PORTA
#define POLOLU_ENABLE_PIN EXP_PIN3
#define POLOLU_FAULT1_PORT EXP_PORTA
#define POLOLU_FAULT1_PIN EXP_PIN2
#define POLOLU_FAULT2_PORT EXP_PORTA
#define POLOLU_FAULT2_PIN EXP_PIN1
#define LIMIT_SW_FWD_CONF_PORT EXP_PORTA
#define LIMIT_SW_FWD_CONF_PIN EXP_PIN8
#define LIMIT_SW_RVS_CONF_PORT EXP_PORTA
#define LIMIT_SW_RVS_CONF_PIN EXP_PIN6
#define LIMIT_SW_HOME_CONF_PORT EXP_PORTA
#define LIMIT_SW_HOME_CONF_PIN EXP_PIN7
#define LED0_PORT EXP_PORTB
#define LED0_PIN EXP_PIN5
#define LED1_PORT EXP_PORTB
#define LED1_PIN EXP_PIN6
#define LED2_PORT EXP_PORTB
#define LED2_PIN EXP_PIN7
#define LED3_PORT EXP_PORTB
#define LED3_PIN EXP_PIN8
/* sync module data */
#define SYNC_IN_PIN GPIO_PIN_12
extern void sync_interrupt(void);
/* GPIO expander registers */
typedef enum {EXP_IODIRA=0x00,
EXP_IODIRB=0x01,
EXP_IPOLA=0x02,
EXP_IPOLB=0x03,
EXP_GPINTENA=0x04,
EXP_GPINTENB=0x05,
EXP_DEFVALA=0x06,
EXP_DEFVALB=0x07,
EXP_INTCONA=0x08,
EXP_INTCONB=0x09,
EXP_IOCONA=0x0A,
EXP_IOCONB=0x0B,
EXP_GPPUA=0x0C,
EXP_GPPUB=0x0D,
EXP_INTFA=0x0E,
EXP_INTFB=0x0F,
EXP_INTCAPA=0x10,
EXP_INTCAPB=0x11,
EXP_GPIOA=0x12,
EXP_GPIOB=0x13,
EXP_OLATA=0x14,
EXP_OLATB=0x15} t_gpio_reg;
typedef enum {EXP_PORTA=0,EXP_PORTB=1} exp_port_t;
typedef enum {EXP_PIN1=0x01,EXP_PIN2=0x02,EXP_PIN3=0x04,EXP_PIN4=0x08,EXP_PIN5=0x10,EXP_PIN6=0x20,EXP_PIN7=0x40,EXP_PIN8=0x80} exp_pin_t;
typedef enum {EXP_IN=1,EXP_OUT=0} exp_dir_t;
typedef enum {EXP_INT_CMP_LAST=0,EXP_INT_CMP_DEFAULT=1} exp_int_op_t;
typedef enum {EXP_NO_EDGE,EXP_RISING_EDGE,EXP_FALLING_EDGE,EXP_BOTH_EDGES} exp_int_edge_t;
// private variables
unsigned char gpio_exp_registers[GPIO_EXP_NUM_REG];
unsigned char gpio_pololu_status;
unsigned char gpio_sw_status;
// private functions
void gpio_process_input_data(void)
{
if(gpio_exp_registers[EXP_INTFA]&0x03)
gpio_pololu_status=gpio_exp_registers[EXP_INTCAPA]&0x03;
if(gpio_exp_registers[EXP_INTFB]&0x0F)
gpio_sw_status=gpio_exp_registers[EXP_INTCAPB]&0x0F;
}
void gpio_set_direction(exp_port_t port, exp_pin_t pin, exp_dir_t dir)
{
unsigned char address;
if(port==EXP_PORTA)
address=EXP_IODIRA;
else
address=EXP_IODIRB;
if(dir==EXP_IN)
gpio_exp_registers[address]|=pin;
else
gpio_exp_registers[address]&=(~pin);
}
void gpio_set_polarity(exp_port_t port, exp_pin_t pin, unsigned char inv_pol)
{
unsigned char address;
if(port==EXP_PORTA)
address=EXP_IPOLA;
else
address=EXP_IPOLB;
if(inv_pol)
gpio_exp_registers[address]|=pin;
else
gpio_exp_registers[address]&=(~pin);
}
void gpio_enable_int(exp_port_t port, exp_pin_t pin, unsigned char enable)
{
unsigned char address;
if(port==EXP_PORTA)
address=EXP_GPINTENA;
else
address=EXP_GPINTENB;
if(enable)
gpio_exp_registers[address]|=pin;
else
gpio_exp_registers[address]&=(~pin);
}
void gpio_set_int_cmp_value(exp_port_t port, exp_pin_t pin, unsigned char value)
{
unsigned char address;
if(port==EXP_PORTA)
address=EXP_DEFVALA;
else
address=EXP_DEFVALB;
if(value)
gpio_exp_registers[address]|=pin;
else
gpio_exp_registers[address]&=(~pin);
}
void gpio_set_int_operation(exp_port_t port, exp_pin_t pin, exp_int_op_t op)
{
unsigned char address;
if(port==EXP_PORTA)
address=EXP_INTCONA;
else
address=EXP_INTCONB;
if(op==EXP_INT_CMP_DEFAULT)
gpio_exp_registers[address]|=pin;
else
gpio_exp_registers[address]&=(~pin);
}
void gpio_enable_pull_up(exp_port_t port, exp_pin_t pin,unsigned char enable)
{
unsigned char address;
if(port==EXP_PORTA)
address=EXP_GPPUA;
else
address=EXP_GPPUB;
if(enable)
gpio_exp_registers[address]|=pin;
else
gpio_exp_registers[address]&=(~pin);
}
void gpio_config(unsigned char shared_int, unsigned char auto_inc_addr, unsigned char slew_rate, unsigned char int_open_drain, unsigned char int_pol)
{
// change the configuration
if(shared_int)
{
gpio_exp_registers[EXP_IOCONA]|=0x40;
gpio_exp_registers[EXP_IOCONB]|=0x40;
}
else
{
gpio_exp_registers[EXP_IOCONA]&=0xBF;
gpio_exp_registers[EXP_IOCONB]&=0xBF;
}
if(auto_inc_addr)
{
gpio_exp_registers[EXP_IOCONA]&=0xDF;
gpio_exp_registers[EXP_IOCONB]&=0xDF;
}
else
{
gpio_exp_registers[EXP_IOCONA]|=0x20;
gpio_exp_registers[EXP_IOCONB]|=0x20;
}
if(slew_rate)
{
gpio_exp_registers[EXP_IOCONA]&=0xEF;
gpio_exp_registers[EXP_IOCONB]&=0xEF;
}
else
{
gpio_exp_registers[EXP_IOCONA]|=0x10;
gpio_exp_registers[EXP_IOCONB]|=0x10;
}
if(int_open_drain)
{
gpio_exp_registers[EXP_IOCONA]|=0x04;
gpio_exp_registers[EXP_IOCONB]|=0x04;
}
else
{
gpio_exp_registers[EXP_IOCONA]&=0xFB;
gpio_exp_registers[EXP_IOCONB]&=0xFB;
}
if(int_pol)
{
gpio_exp_registers[EXP_IOCONA]|=0x02;
gpio_exp_registers[EXP_IOCONB]|=0x02;
}
else
{
gpio_exp_registers[EXP_IOCONA]&=0xFD;
gpio_exp_registers[EXP_IOCONB]&=0xFD;
}
}
void gpio_config_pin(exp_port_t port, exp_pin_t pin,exp_dir_t dir, unsigned char inv_pol, unsigned char pull_up)
{
gpio_set_direction(port,pin,dir);
gpio_set_polarity(port,pin,inv_pol);
gpio_enable_pull_up(port,pin,pull_up);
}
void gpio_set_pin_value(exp_port_t port, exp_pin_t pin, unsigned char value)
{
unsigned char address;
if(port==EXP_PORTA)
address=EXP_OLATA;
else
address=EXP_OLATB;
if(value)
gpio_exp_registers[address]|=pin;
else
gpio_exp_registers[address]&=(~pin);
while(i2c_queue_full());
i2c_write(GPIO_EXP_ADDRESS,address,1,&gpio_exp_registers[address]);
}
unsigned char gpio_get_pin_value(exp_port_t port, exp_pin_t pin)
{
return 0x00;
}
/* interrupt handlers */
void INTA_IRQnHandler(void)
{
if(__HAL_GPIO_EXTI_GET_IT(INTA_PIN) != RESET)
{
__HAL_GPIO_EXTI_CLEAR_IT(INTA_PIN);
/* read the flag and captured values of both ports */
i2c_read_cb(GPIO_EXP_ADDRESS,EXP_INTFA,4,&gpio_exp_registers[EXP_INTFA],gpio_process_input_data);
}
else if(__HAL_GPIO_EXTI_GET_IT(SYNC_IN_PIN) != RESET)
{
__HAL_GPIO_EXTI_CLEAR_IT(SYNC_IN_PIN);
sync_interrupt();
}
}
/* public functions */
void gpio_init(void)
{
GPIO_InitTypeDef GPIO_InitStruct;
// read all the registers
i2c_read(GPIO_EXP_ADDRESS,EXP_IODIRA,GPIO_EXP_NUM_REG,&gpio_exp_registers[0]);
while(!i2c_queue_empty());
// configure the GPIO expansion IC
gpio_config(0x01,// shared interrupts
0x01,// auto increment internal address
0x01,// enable slew rate control
0x00,// use push pull outputs for interrupts
0x01);// use active high interrupts
// configure PORTA
gpio_config_pin(EXP_PORTA,EXP_PIN1,EXP_IN,0x00,0x00);// Pololu FF2 signal
gpio_enable_int(EXP_PORTA,EXP_PIN1,0x01);
gpio_set_int_operation(EXP_PORTA,EXP_PIN1,EXP_INT_CMP_LAST);
gpio_config_pin(EXP_PORTA,EXP_PIN2,EXP_IN,0x00,0x00);// Pololu FF1 signal
gpio_enable_int(EXP_PORTA,EXP_PIN2,0x01);
gpio_set_int_operation(EXP_PORTA,EXP_PIN2,EXP_INT_CMP_LAST);
gpio_config_pin(EXP_PORTA,EXP_PIN3,EXP_OUT,0x00,0x00);// Pololu nRESET signal
gpio_config_pin(EXP_PORTA,EXP_PIN4,EXP_IN,0x00,0x00);//
gpio_config_pin(EXP_PORTA,EXP_PIN5,EXP_IN,0x00,0x00);//
gpio_config_pin(EXP_PORTA,EXP_PIN6,EXP_OUT,0x00,0x00);// Reverse switch control
gpio_config_pin(EXP_PORTA,EXP_PIN7,EXP_OUT,0x00,0x00);// Home switch control
gpio_config_pin(EXP_PORTA,EXP_PIN8,EXP_OUT,0x00,0x00);// Forward switch control
// Configure PORTB
gpio_config_pin(EXP_PORTB,EXP_PIN1,EXP_IN,0x00,0x00);// switch input0
gpio_enable_int(EXP_PORTB,EXP_PIN1,0x01);
gpio_set_int_operation(EXP_PORTB,EXP_PIN1,EXP_INT_CMP_LAST);
gpio_config_pin(EXP_PORTB,EXP_PIN2,EXP_IN,0x00,0x00);// switch input1
gpio_enable_int(EXP_PORTB,EXP_PIN2,0x01);
gpio_set_int_operation(EXP_PORTB,EXP_PIN2,EXP_INT_CMP_LAST);
gpio_config_pin(EXP_PORTB,EXP_PIN3,EXP_IN,0x00,0x00);// switch input2
gpio_enable_int(EXP_PORTB,EXP_PIN3,0x01);
gpio_set_int_operation(EXP_PORTB,EXP_PIN3,EXP_INT_CMP_LAST);
gpio_config_pin(EXP_PORTB,EXP_PIN4,EXP_IN,0x00,0x00);// switch input3
gpio_enable_int(EXP_PORTB,EXP_PIN4,0x01);
gpio_set_int_operation(EXP_PORTB,EXP_PIN4,EXP_INT_CMP_LAST);
gpio_config_pin(EXP_PORTB,EXP_PIN5,EXP_OUT,0x00,0x00);// LED0
gpio_config_pin(EXP_PORTB,EXP_PIN6,EXP_OUT,0x00,0x00);// LED1
gpio_config_pin(EXP_PORTB,EXP_PIN7,EXP_OUT,0x00,0x00);// LED2
gpio_config_pin(EXP_PORTB,EXP_PIN8,EXP_OUT,0x00,0x00);// LED3
// write the configuration of all registers
i2c_write(GPIO_EXP_ADDRESS,EXP_IODIRA,GPIO_EXP_NUM_REG,&gpio_exp_registers[0]);
while(!i2c_queue_empty());
// initialize internal variables
gpio_pololu_status=gpio_exp_registers[EXP_INTCAPA]&0x03;
gpio_sw_status=gpio_exp_registers[EXP_INTCAPB]&0x0F;
// configure the external interrutps
INTA_GPIO_CLK;
/* configure GPIO's */
GPIO_InitStruct.Pin = INTA_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(INTA_GPIO_PORT, &GPIO_InitStruct);
HAL_NVIC_SetPriority(INTA_IRQn, 3, 3);
HAL_NVIC_EnableIRQ(INTA_IRQn);
}
/* output functions */
void gpio_enable_pololu(void)
{
gpio_set_pin_value(POLOLU_ENABLE_PORT,POLOLU_ENABLE_PIN,0x01);
}
void gpio_disable_pololu(void)
{
gpio_set_pin_value(POLOLU_ENABLE_PORT,POLOLU_ENABLE_PIN,0x00);
}
void gpio_set_led(exp_led_t led_id)
{
switch(led_id)
{
case EXP_LED0: gpio_set_pin_value(LED0_PORT,LED0_PIN,0x01);
break;
case EXP_LED1: gpio_set_pin_value(LED1_PORT,LED1_PIN,0x01);
break;
case EXP_LED2: gpio_set_pin_value(LED2_PORT,LED2_PIN,0x01);
break;
case EXP_LED3: gpio_set_pin_value(LED3_PORT,LED3_PIN,0x01);
break;
}
}
void gpio_clear_led(exp_led_t led_id)
{
switch(led_id)
{
case EXP_LED0: gpio_set_pin_value(LED0_PORT,LED0_PIN,0x00);
break;
case EXP_LED1: gpio_set_pin_value(LED1_PORT,LED1_PIN,0x00);
break;
case EXP_LED2: gpio_set_pin_value(LED2_PORT,LED2_PIN,0x00);
break;
case EXP_LED3: gpio_set_pin_value(LED3_PORT,LED3_PIN,0x00);
break;
}
}
void gpio_set_fwd_sw_pol(uint8_t pol)
{
gpio_set_pin_value(LIMIT_SW_FWD_CONF_PORT,LIMIT_SW_FWD_CONF_PIN,pol);
}
void gpio_set_rvs_sw_pol(uint8_t pol)
{
gpio_set_pin_value(LIMIT_SW_RVS_CONF_PORT,LIMIT_SW_RVS_CONF_PIN,pol);
}
void gpio_set_home_sw_pol(uint8_t pol)
{
gpio_set_pin_value(LIMIT_SW_HOME_CONF_PORT,LIMIT_SW_HOME_CONF_PIN,pol);
}
/* input functions */
uint8_t gpio_get_switch(exp_sw_t sw_id)
{
unsigned char data;
switch(sw_id)
{
case EXP_SW0: data=gpio_sw_status&0x01;
break;
case EXP_SW1: data=gpio_sw_status&0x02;
break;
case EXP_SW2: data=gpio_sw_status&0x04;
break;
case EXP_SW3: data=gpio_sw_status&0x08;
break;
default: data=0x00;
break;
}
if(data)
return 0x01;
else
return 0x00;
}
uint8_t gpio_get_pololu_status(void)
{
return gpio_pololu_status;
}
#include "ir_feet_dyn_slave.h"
#include "ir_feet_time.h"
#include "ir_feet_dyn_slave_registers.h"
#include "scheduler.h"
#include "ram.h"
#include "usart1.h"
#define DXL_DIR_Pin GPIO_PIN_5
#define DXL_DIR_Port GPIOB
/* private variables */
TDynamixelSlave ir_feet_dyn_slave;
TTime ir_feet_dyn_slave_timer;
TComm ir_feet_dyn_slave_comm;
UART_InitTypeDef ir_feet_comm_init;
/* memory module */
TMemModule ir_feet_dyn_slave_mem_module;
TMemory *ir_feet_dyn_slave_memory;
/* EEPROM data */
uint16_t ir_feet_dyn_slave_eeprom_data[] __attribute__ ((section (".eeprom")))={DEFAULT_DEVICE_MODEL&0x00FF,DEVICE_MODEL,
(DEFAULT_DEVICE_MODEL>>8)&0x00FF,DEVICE_MODEL+1,
DEFAULT_FIRMWARE_VERSION,FIRMWARE_VERSION,
DEFAULT_DEVICE_ID,DEVICE_ID,
DEFAULT_BAUDRATE,BAUDRATE,
DEFAULT_RETURN_DELAY,RETURN_DELAY,
DEFAULT_RETURN_LEVEL,RETURN_LEVEL};
// private functions
unsigned char ir_feet_on_read(unsigned short int address,unsigned short int length,unsigned char *data)
{
mem_do_read(ir_feet_dyn_slave_memory,address,length,data);
return 0x00;
}
unsigned char ir_feet_on_write(unsigned short int address,unsigned short int length,unsigned char *data)
{
mem_do_write(ir_feet_dyn_slave_memory,address,length,data);
return 0x00;
}
void ir_feet_on_ping(void)
{
}
void ir_feet_set_rx(void)
{
HAL_GPIO_WritePin(DXL_DIR_Port, DXL_DIR_Pin, GPIO_PIN_RESET);
}
void ir_feet_set_tx(void)
{
HAL_GPIO_WritePin(DXL_DIR_Port, DXL_DIR_Pin, GPIO_PIN_SET);
}
void ir_feet_dyn_slave_write_cmd(unsigned short int address,unsigned short int length,unsigned char *data)
{
if(ram_in_range(DEVICE_ID,address,length))
{
dyn_slave_set_address(&ir_feet_dyn_slave,data[DEVICE_ID-address]);
ram_data[DEVICE_ID]=data[DEVICE_ID-address];
}
if(ram_in_range(BAUDRATE,address,length))
{
ir_feet_comm_init.BaudRate=2000000/(data[BAUDRATE-address]+1);
usart1_config(&ir_feet_dyn_slave_comm,&ir_feet_comm_init);
ram_data[BAUDRATE]=data[BAUDRATE-address];
}
if(ram_in_range(RETURN_DELAY,address,length))
{
dyn_slave_set_return_delay(&ir_feet_dyn_slave,data[RETURN_DELAY-address]);
ram_data[RETURN_DELAY]=data[RETURN_DELAY-address];
}
if(ram_in_range(RETURN_LEVEL,address,length))
{
dyn_slave_set_return_level(&ir_feet_dyn_slave,data[RETURN_LEVEL-address]);
ram_data[RETURN_LEVEL]=data[RETURN_LEVEL-address];
}
}
void ir_feet_dyn_slave_read_cmd(unsigned short int address,unsigned short int length,unsigned char *data)
{
ram_read_table(address,length,data);
}
/* interrupt service routines */
void ir_feet_dyn_slave_scheduler(void)
{
dyn_slave_loop(&ir_feet_dyn_slave);
}
// public functions
uint8_t ir_feet_dyn_slave_init(TMemory *memory)
{
TUSART_IRQ_Priorities priorities;
GPIO_InitTypeDef GPIO_InitStruct;
/* configure the DIR pin */
__HAL_RCC_GPIOB_CLK_ENABLE();
GPIO_InitStruct.Pin = DXL_DIR_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(DXL_DIR_Port, &GPIO_InitStruct);
// initialize timer structure
time_init(&ir_feet_dyn_slave_timer,ir_feet_time_get_counts_per_us(),ir_feet_time_get_counts);
/* initialize the comm object */
comm_init(&ir_feet_dyn_slave_comm,0x01,&ir_feet_dyn_slave_timer);
ir_feet_comm_init.BaudRate = 2000000/(DEFAULT_BAUDRATE+1);
ir_feet_comm_init.WordLength = UART_WORDLENGTH_8B;
ir_feet_comm_init.StopBits = UART_STOPBITS_1;
ir_feet_comm_init.Parity = UART_PARITY_NONE;
ir_feet_comm_init.Mode = UART_MODE_TX_RX;
ir_feet_comm_init.HwFlowCtl = UART_HWCONTROL_NONE;
ir_feet_comm_init.OverSampling = UART_OVERSAMPLING_16;
priorities.irq_priority=0;
priorities.irq_subpriority=0;
priorities.dma_rx_priority=1;
priorities.dma_rx_subpriority=1;
priorities.dma_tx_priority=1;
priorities.dma_tx_subpriority=0;
usart1_init(&ir_feet_dyn_slave_comm,&ir_feet_comm_init,&priorities);
dyn_slave_init(&ir_feet_dyn_slave,&ir_feet_dyn_slave_comm,DEFAULT_DEVICE_ID,DYN_VER2);
ir_feet_dyn_slave.on_read=ir_feet_on_read;
ir_feet_dyn_slave.on_write=ir_feet_on_write;
ir_feet_dyn_slave.on_ping=ir_feet_on_ping;
ir_feet_dyn_slave.set_tx_mode=ir_feet_set_tx;
ir_feet_dyn_slave.set_rx_mode=ir_feet_set_rx;
dyn_slave_set_return_delay(&ir_feet_dyn_slave,DEFAULT_RETURN_DELAY);
dyn_slave_set_return_level(&ir_feet_dyn_slave,DEFAULT_RETURN_LEVEL);
/* initialize memory module */
mem_module_init(&ir_feet_dyn_slave_mem_module);
ir_feet_dyn_slave_mem_module.write_cmd=ir_feet_dyn_slave_write_cmd;
ir_feet_dyn_slave_mem_module.read_cmd=ir_feet_dyn_slave_read_cmd;
if(!mem_module_add_eeprom_segment(&ir_feet_dyn_slave_mem_module,EEPROM_DYN_SLAVE_BASE_ADDRESS1,EEPROM_DYN_SLAVE_LENGTH1))
return 0x00;
if(!mem_module_add_eeprom_segment(&ir_feet_dyn_slave_mem_module,EEPROM_DYN_SLAVE_BASE_ADDRESS2,EEPROM_DYN_SLAVE_LENGTH2))
return 0x00;
if(!mem_add_module(memory,&ir_feet_dyn_slave_mem_module))
return 0x00;
ir_feet_dyn_slave_memory=memory;
/* assigna a scheduler channel */
scheduler_set_channel(SCHED_CH2,ir_feet_dyn_slave_scheduler,1);
return 0x00;
}
void ir_feet_dyn_slave_start(void)
{
scheduler_enable_channel(SCHED_CH2);
}
void ir_feet_dyn_slave_stop(void)
{
scheduler_disable_channel(SCHED_CH2);
}
#include "ir_feet_time.h"
TIM_HandleTypeDef us_timer_handle;
unsigned long long int timer_counts;
unsigned short int timer_counts_per_us;
void SysTick_Handler(void)
{
/* USER CODE BEGIN SysTick_IRQn 0 */
/* USER CODE END SysTick_IRQn 0 */
HAL_IncTick();
HAL_SYSTICK_IRQHandler();
/* USER CODE BEGIN SysTick_IRQn 1 */
/* USER CODE END SysTick_IRQn 1 */
}
void TIM4_IRQHandler(void)
{
/* TIM Update event */
if(__HAL_TIM_GET_FLAG(&us_timer_handle, TIM_FLAG_UPDATE) != RESET)
{
if(__HAL_TIM_GET_IT_SOURCE(&us_timer_handle, TIM_IT_UPDATE) !=RESET)
{
__HAL_TIM_CLEAR_IT(&us_timer_handle, TIM_IT_UPDATE);
timer_counts+=1;
}
}
/* TIM Break input event */
if(__HAL_TIM_GET_FLAG(&us_timer_handle, TIM_FLAG_BREAK) != RESET)
{
if(__HAL_TIM_GET_IT_SOURCE(&us_timer_handle, TIM_IT_BREAK) !=RESET)
{
__HAL_TIM_CLEAR_IT(&us_timer_handle, TIM_IT_BREAK);
}
}
/* TIM Trigger detection event */
if(__HAL_TIM_GET_FLAG(&us_timer_handle, TIM_FLAG_TRIGGER) != RESET)
{
if(__HAL_TIM_GET_IT_SOURCE(&us_timer_handle, TIM_IT_TRIGGER) !=RESET)
{
__HAL_TIM_CLEAR_IT(&us_timer_handle, TIM_IT_TRIGGER);
}
}
/* TIM commutation event */
if(__HAL_TIM_GET_FLAG(&us_timer_handle, TIM_FLAG_COM) != RESET)
{
if(__HAL_TIM_GET_IT_SOURCE(&us_timer_handle, TIM_IT_COM) !=RESET)
{
__HAL_TIM_CLEAR_IT(&us_timer_handle, TIM_FLAG_COM);
}
}
}
void ir_feet_time_init(void)
{
TIM_ClockConfigTypeDef sClockSourceConfig;
TIM_MasterConfigTypeDef sMasterConfig;
/* initialize internal variables */
timer_counts=0;
timer_counts_per_us=(SystemCoreClock/1000000)+1;
__HAL_RCC_TIM4_CLK_ENABLE();
us_timer_handle.Instance = TIM4;
us_timer_handle.Init.Prescaler = 0;
us_timer_handle.Init.CounterMode = TIM_COUNTERMODE_UP;
us_timer_handle.Init.Period = 0xffff;
us_timer_handle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
HAL_TIM_Base_Init(&us_timer_handle);
__HAL_TIM_SetCounter(&us_timer_handle,0);
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
HAL_TIM_ConfigClockSource(&us_timer_handle, &sClockSourceConfig);
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
HAL_TIMEx_MasterConfigSynchronization(&us_timer_handle, &sMasterConfig);
HAL_NVIC_SetPriority(TIM4_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(TIM4_IRQn);
HAL_TIM_Base_Start_IT(&us_timer_handle);
}
unsigned long long int ir_feet_time_get_counts(void)
{
return (timer_counts<<16)+__HAL_TIM_GetCounter(&us_timer_handle);
}
unsigned int ir_feet_time_get_counts_per_us(void)
{
return timer_counts_per_us;
}
#include "stm32f1xx.h"
#include "ir_feet_time.h"
#include "ir_feet_dyn_slave.h"
#include "memory.h"
#include "ram.h"
#include "eeprom.h"
#include "scheduler.h"
#include "gpio.h"
TMemory ir_feet_memory;
int main(void)
{
GPIO_InitTypeDef GPIO_InitStruct;
/* initialize the HAL module */
HAL_Init();
/* initialize EEPROM */
EE_Init();
/* initialize memory structure */
mem_init(&ir_feet_memory);
ir_feet_memory.eeprom_write_data=EE_WriteVariable;
ir_feet_memory.eeprom_read_data=EE_ReadVariable;
/* initialize the scheduler */
scheduler_init();
/* initialize the GPIO expansion module*/
gpio_init();
// initialize ADC module
adc_init(&ir_feet_memory);
// initialize time module
ir_feet_time_init();
// initialize the dynamixel slave interface
ir_feet_dyn_slave_init(&ir_feet_memory);
// initialize the Dynamixel RAM memory space
ram_init(&ir_feet_memory);
ir_feet_dyn_slave_start();
while(1)/* main function does not return */
{
}
}
src/ram.c 0 → 100755
#include "ram.h"
#include "eeprom.h"
uint8_t ram_data[RAM_SIZE]={0};
uint8_t ram_init(TMemory *memory)
{
mem_initialize_data(memory);
return 0x01;
}
inline void ram_read_byte(uint16_t address,uint8_t *data)
{
(*data)=ram_data[address];
}
inline void ram_read_word(uint16_t address, uint16_t *data)
{
(*data)=ram_data[address];
(*data)+=ram_data[address+1]*256;
}
uint8_t ram_read_table(uint16_t address, uint16_t length,uint8_t *data)
{
uint16_t i;
if((address+length)<=(RAM_SIZE-1))
{
for(i=0;i<length;i++)
data[i]=ram_data[address+i];
return RAM_SUCCESS;
}
else
return RAM_BAD_ADDRESS;
}
uint8_t ram_set_bit(uint16_t address, uint8_t bit)
{
if(bit>=0 && bit<8)
{
ram_data[address]|=(0x01<<bit);
return RAM_SUCCESS;
}
else
return RAM_BAD_BIT;
}
uint8_t ram_clear_bit(uint16_t address, uint8_t bit)
{
if(bit>=0 && bit<8)
{
ram_data[address]&=(~(0x01<<bit));
return RAM_SUCCESS;
}
else
return RAM_BAD_BIT;
}
uint8_t ram_write_byte(uint16_t address, uint8_t data)
{
ram_data[address]=data;
return RAM_SUCCESS;
}
uint8_t ram_write_word(uint16_t address, uint16_t data)
{
if(address < (RAM_SIZE-1))
{
ram_data[address]=data%256;
ram_data[address+1]=data/256;
return RAM_SUCCESS;
}
else
return RAM_BAD_ADDRESS;
}
uint8_t ram_write_table(uint16_t address, uint16_t length,uint8_t *data)
{
uint16_t i;
if((address+length)<RAM_SIZE)
{
for(i=0;i<length;i++)
ram_data[address+i]=data[i];
return RAM_SUCCESS;
}
else
return RAM_BAD_ADDRESS;
}
inline uint8_t ram_in_range(uint16_t reg,uint16_t address,uint16_t length)
{
if(reg>=address && reg<(address+length))
return 0x01;
else
return 0x00;
}
uint8_t ram_in_window(uint16_t start_reg,uint16_t reg_length,uint16_t start_address,uint16_t address_length)
{
uint16_t end_reg=start_reg+reg_length-1;
uint16_t end_address=start_address+address_length-1;
if((start_reg>=start_address && start_reg<=end_address) || (end_reg>=start_address && end_reg<=end_address))
return 0x01;
else
return 0x00;
}
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment