Add most core functionality, should be drivable
This commit is contained in:
parent
4a5bcc4046
commit
c11c0291c0
File diff suppressed because one or more lines are too long
|
@ -34,7 +34,7 @@
|
|||
*/
|
||||
|
||||
#define HAL_MODULE_ENABLED
|
||||
#define HAL_ADC_MODULE_ENABLED
|
||||
/*#define HAL_ADC_MODULE_ENABLED */
|
||||
/*#define HAL_CRYP_MODULE_ENABLED */
|
||||
#define HAL_CAN_MODULE_ENABLED
|
||||
/*#define HAL_CEC_MODULE_ENABLED */
|
||||
|
|
|
@ -48,23 +48,46 @@ typedef enum {
|
|||
M_MANUAL = 7
|
||||
} mission_t;
|
||||
|
||||
// BITFIELDS ARE LSB FIRST!
|
||||
/*
|
||||
* BO_ 15 SDCL_rx: 3 ABX
|
||||
* SG_ as_close_sdc : 0|1@1+ (1,0) [0|1] "" SDCL
|
||||
* SG_ sdcl_heartbeat : 1|1@1+ (1,0) [0|1] "" SDCL
|
||||
* SG_ asb_error : 2|1@1+ (1,0) [0|1] "" SDCL
|
||||
* SG_ as_mission : 4|3@1+ (1,0) [0|7] "" SDCL
|
||||
*/
|
||||
|
||||
typedef union {
|
||||
uint8_t raw[1];
|
||||
struct {
|
||||
// BITFIELDS ARE LSB FIRST!
|
||||
bool as_close_sdc : 1;
|
||||
bool heartbeat : 1;
|
||||
bool asb_error : 1;
|
||||
bool as_driving_mode : 1;
|
||||
unsigned int _padding1 : 1;
|
||||
mission_t as_mission : 3;
|
||||
unsigned int _padding : 1;
|
||||
unsigned int _padding2 : 1;
|
||||
} __attribute__((packed)) signals;
|
||||
} rx_data_t;
|
||||
|
||||
/*
|
||||
* BO_ 16 SDCL_tx: 4 SDCL
|
||||
* SG_ asms_state : 0|1@1+ (1,0) [0|1] "" ABX
|
||||
* SG_ sdc_state_1 : 1|1@1+ (1,0) [0|1] "" ABX
|
||||
* SG_ sdc_state_2 : 2|1@1+ (1,0) [0|1] "" ABX
|
||||
* SG_ sdc_state_3 : 3|1@1+ (1,0) [0|1] "" ABX
|
||||
* SG_ heartbeat_ok : 4|1@1+ (1,0) [0|1] "" ABX
|
||||
* SG_ sdcl_sdc_ready : 5|1@1+ (1,0) [0|1] "" ABX
|
||||
* SG_ ts_start_muxed : 6|1@1+ (1,0) [0|1] "" ABX
|
||||
* SG_ latch_init_open : 8|1@1+ (1,0) [0|1] "" ABX
|
||||
* SG_ latch_closed : 9|1@1+ (1,0) [0|1] "" ABX
|
||||
* SG_ latch_reopened : 10|1@1+ (1,0) [0|1] "" ABX
|
||||
* SG_ as_mission : 11|3@1+ (1,0) [0|7] "" ABX
|
||||
*/
|
||||
|
||||
typedef union {
|
||||
uint8_t raw[2];
|
||||
struct {
|
||||
// BITFIELDS ARE LSB FIRST!
|
||||
bool asms_state : 1;
|
||||
bool sdc_state_1 : 1;
|
||||
bool sdc_state_2 : 1;
|
||||
|
@ -72,13 +95,13 @@ typedef union {
|
|||
bool heartbeat_ok : 1;
|
||||
bool sdc_ready : 1;
|
||||
bool ts_start_muxed : 1;
|
||||
bool sdc_in : 1;
|
||||
unsigned int _padding1 : 1;
|
||||
// -- byte border
|
||||
bool latch_init_open : 1;
|
||||
bool latch_closed : 1;
|
||||
bool latch_reopened : 1;
|
||||
mission_t as_mission : 3;
|
||||
unsigned int _padding : 2;
|
||||
unsigned int _padding2 : 2;
|
||||
} __attribute__((packed)) signals;
|
||||
} tx_data_t;
|
||||
|
||||
|
@ -93,6 +116,8 @@ typedef union {
|
|||
// Defined in DBC?
|
||||
#define TX_UPDATE_PERIOD 100
|
||||
|
||||
#define AMI_GPIO_Port GPIOB
|
||||
|
||||
/* USER CODE END PD */
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
|
@ -101,13 +126,15 @@ typedef union {
|
|||
/* USER CODE END PM */
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
ADC_HandleTypeDef hadc1;
|
||||
|
||||
CAN_HandleTypeDef hcan;
|
||||
|
||||
/* USER CODE BEGIN PV */
|
||||
|
||||
rx_data_t rxData;
|
||||
// Mission Maps: NONE ACCEL SKIDPAD TRACKDRIVE EBSTEST INSPECTION AUTOX MANUAL
|
||||
const uint16_t mission2led[] = {0 , AMI_ACCEL_Pin , AMI_SKIDPAD_Pin , AMI_TRACKDRIVE_Pin, AMI_EBSTEST_Pin , AMI_INSPECTION_Pin, AMI_AUTOX_Pin , AMI_MANUAL_Pin};
|
||||
const mission_t mission2next[] = {M_MANUAL , M_SKIDPAD , M_AUTOX , M_EBSTEST , M_INSPECTION , M_MANUAL , M_TRACKDRIVE , M_ACCEL };
|
||||
|
||||
mission_t mission = M_NONE;
|
||||
|
||||
/* USER CODE END PV */
|
||||
|
||||
|
@ -115,14 +142,17 @@ rx_data_t rxData;
|
|||
void SystemClock_Config(void);
|
||||
static void MX_GPIO_Init(void);
|
||||
static void MX_CAN_Init(void);
|
||||
static void MX_ADC1_Init(void);
|
||||
/* USER CODE BEGIN PFP */
|
||||
|
||||
/* USER CODE END PFP */
|
||||
|
||||
/* Private user code ---------------------------------------------------------*/
|
||||
/* USER CODE BEGIN 0 */
|
||||
|
||||
void setMissionLED(mission_t mission, GPIO_PinState state)
|
||||
{
|
||||
if (mission != M_NONE)
|
||||
HAL_GPIO_WritePin(AMI_GPIO_Port, mission2led[mission], state);
|
||||
}
|
||||
/* USER CODE END 0 */
|
||||
|
||||
/**
|
||||
|
@ -154,15 +184,12 @@ int main(void)
|
|||
/* Initialize all configured peripherals */
|
||||
MX_GPIO_Init();
|
||||
MX_CAN_Init();
|
||||
MX_ADC1_Init();
|
||||
/* USER CODE BEGIN 2 */
|
||||
|
||||
// Init data as LOW
|
||||
memset(&rxData, 0, sizeof(rx_data_t));
|
||||
|
||||
if (HAL_CAN_Start(&hcan) != HAL_OK)
|
||||
Error_Handler();
|
||||
|
||||
// TODO: Use Filter
|
||||
/*
|
||||
CAN_FilterTypeDef canfilterconfig;
|
||||
|
||||
|
@ -202,63 +229,11 @@ int main(void)
|
|||
/* Infinite loop */
|
||||
/* USER CODE BEGIN WHILE */
|
||||
|
||||
//HAL_GPIO_TogglePin(AS_close_SDC_GPIO_Port, AS_close_SDC_Pin);
|
||||
|
||||
uint16_t mission2led[] = {ASB_Error_Pin, AMI_ACCEL_Pin, AMI_SKIDPAD_Pin, AMI_TRACKDRIVE_Pin, AMI_EBSTEST_Pin, AMI_INSPECTION_Pin, AMI_AUTOX_Pin, AMI_MANUAL_Pin};
|
||||
unsigned int mission_order[] = {M_MANUAL, M_ACCEL, M_SKIDPAD, M_AUTOX, M_TRACKDRIVE, M_EBSTEST, M_INSPECTION};
|
||||
|
||||
unsigned int mission_idx = 0;
|
||||
bool pAMC = false;
|
||||
mission_t new_mission = mission; // By default, don't change mission
|
||||
|
||||
while (true) {
|
||||
|
||||
// Write out all values received via interrupt to the pins
|
||||
/*
|
||||
HAL_GPIO_WritePin(GPIOA, AS_driving_mode_Pin, RxData.signals.as_driving_mode);
|
||||
HAL_GPIO_WritePin(GPIOA, AS_close_SDC_Pin, RxData.signals.as_close_sdc);
|
||||
HAL_GPIO_WritePin(GPIOA, Watchdog_Pin, RxData.signals.watchdog);
|
||||
|
||||
// every nth rx, we tx¨
|
||||
if (++counter >= (TX_UPDATE_PERIOD / RX_UPDATE_PERIOD)) {
|
||||
|
||||
// Read values to send
|
||||
uint8_t s = HAL_GPIO_ReadPin(GPIOA, SDC_in_3V3_Pin) == GPIO_PIN_SET;
|
||||
uint8_t r = HAL_GPIO_ReadPin(GPIOA, SDC_is_ready_Pin) == GPIO_PIN_SET;
|
||||
uint8_t t = HAL_GPIO_ReadPin(GPIOA, TS_activate_MUXed_Pin) == GPIO_PIN_SET;
|
||||
TxData.signals.sdc_in = s;
|
||||
TxData.signals.sdc_ready = r;
|
||||
TxData.signals.ts_start = t;
|
||||
|
||||
// Send out CAN message
|
||||
if (HAL_CAN_AddTxMessage(&hcan, &TxHeader, TxData.raw, &TxMailbox) != HAL_OK)
|
||||
Error_Handler();
|
||||
|
||||
counter = 0;
|
||||
|
||||
}
|
||||
*/
|
||||
|
||||
/*
|
||||
* Values to read:
|
||||
* [ ] TSActivateMUXed
|
||||
* [ ] ASMS
|
||||
* [ ] INITIAL_OPEN
|
||||
* [ ] CLOSED
|
||||
* [ ] REOPENED
|
||||
* [ ] WD_OK
|
||||
* [ ] SDC_is_ready
|
||||
* [ ] SDC_in_3V3
|
||||
* [ ] LV_SENSE_1
|
||||
* [ ] LV_SENSE_2
|
||||
* [x] AMC
|
||||
*
|
||||
* Values to write:
|
||||
* [ ] AS_close_SDC
|
||||
* [ ] (Watchdog)
|
||||
* [ ] ASB_Error
|
||||
* [x] AMI_<Mission>
|
||||
*/
|
||||
|
||||
bool TS_activate_MUXed = HAL_GPIO_ReadPin(TS_activate_MUXed_GPIO_Port, TS_activate_MUXed_Pin) == GPIO_PIN_SET;
|
||||
bool ASMS = HAL_GPIO_ReadPin(ASMS_GPIO_Port, ASMS_Pin) == GPIO_PIN_SET;
|
||||
bool WD_OK = HAL_GPIO_ReadPin(WD_OK_GPIO_Port, WD_OK_Pin) == GPIO_PIN_SET;
|
||||
|
@ -272,17 +247,17 @@ int main(void)
|
|||
bool REOPENED = HAL_GPIO_ReadPin(REOPENED_GPIO_Port, REOPENED_Pin) == GPIO_PIN_SET;
|
||||
|
||||
bool AMC = HAL_GPIO_ReadPin(AMC_GPIO_Port, AMC_Pin) == GPIO_PIN_SET;
|
||||
// On signal edge. Debouncing usually not needed at these polling rates (10Hz)
|
||||
if (AMC < pAMC) {
|
||||
|
||||
HAL_GPIO_WritePin(GPIOB, mission2led[mission_order[mission_idx]], GPIO_PIN_RESET);
|
||||
// Reset LED to indicate transaction / mission change in progress
|
||||
setMissionLED(mission, GPIO_PIN_RESET);
|
||||
|
||||
mission_idx++;
|
||||
mission_idx %= 7;
|
||||
new_mission = mission2next[mission];
|
||||
// New LED will be set once response from ABX is received
|
||||
|
||||
}
|
||||
|
||||
HAL_GPIO_WritePin(GPIOB, mission2led[mission_order[mission_idx]], GPIO_PIN_SET);
|
||||
|
||||
tx_data_t txData = {
|
||||
.signals = {
|
||||
.asms_state = ASMS,
|
||||
|
@ -291,17 +266,18 @@ int main(void)
|
|||
.sdc_state_3 = SDC_in_3V3,
|
||||
.heartbeat_ok = WD_OK,
|
||||
.sdc_ready = SDC_is_ready,
|
||||
.sdc_in = SDC_in_3V3,
|
||||
.ts_start_muxed = TS_activate_MUXed,
|
||||
.latch_init_open = INITIAL_OPEN,
|
||||
.latch_closed = CLOSED,
|
||||
.latch_reopened = REOPENED,
|
||||
.as_mission = mission_order[mission_idx]
|
||||
.as_mission = new_mission
|
||||
}
|
||||
};
|
||||
|
||||
if (HAL_CAN_AddTxMessage(&hcan, &txHeader, txData.raw, &txMailbox) != HAL_OK)
|
||||
Error_Handler();
|
||||
|
||||
// Store previous button value to detect signal edges
|
||||
pAMC = AMC;
|
||||
|
||||
HAL_Delay(TX_UPDATE_PERIOD);
|
||||
|
@ -321,7 +297,6 @@ void SystemClock_Config(void)
|
|||
{
|
||||
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
|
||||
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
|
||||
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
|
||||
|
||||
/** Initializes the RCC Oscillators according to the specified parameters
|
||||
* in the RCC_OscInitTypeDef structure.
|
||||
|
@ -329,9 +304,7 @@ void SystemClock_Config(void)
|
|||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
|
||||
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
|
||||
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
|
||||
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
|
||||
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
|
||||
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL4;
|
||||
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
|
||||
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
|
@ -350,70 +323,6 @@ void SystemClock_Config(void)
|
|||
{
|
||||
Error_Handler();
|
||||
}
|
||||
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC1;
|
||||
PeriphClkInit.Adc1ClockSelection = RCC_ADC1PLLCLK_DIV1;
|
||||
|
||||
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief ADC1 Initialization Function
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
static void MX_ADC1_Init(void)
|
||||
{
|
||||
|
||||
/* USER CODE BEGIN ADC1_Init 0 */
|
||||
|
||||
/* USER CODE END ADC1_Init 0 */
|
||||
|
||||
ADC_ChannelConfTypeDef sConfig = {0};
|
||||
|
||||
/* USER CODE BEGIN ADC1_Init 1 */
|
||||
|
||||
/* USER CODE END ADC1_Init 1 */
|
||||
|
||||
/** Common config
|
||||
*/
|
||||
hadc1.Instance = ADC1;
|
||||
hadc1.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV1;
|
||||
hadc1.Init.Resolution = ADC_RESOLUTION_12B;
|
||||
hadc1.Init.ScanConvMode = ADC_SCAN_DISABLE;
|
||||
hadc1.Init.ContinuousConvMode = DISABLE;
|
||||
hadc1.Init.DiscontinuousConvMode = DISABLE;
|
||||
hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
|
||||
hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START;
|
||||
hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT;
|
||||
hadc1.Init.NbrOfConversion = 1;
|
||||
hadc1.Init.DMAContinuousRequests = DISABLE;
|
||||
hadc1.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
|
||||
hadc1.Init.LowPowerAutoWait = DISABLE;
|
||||
hadc1.Init.Overrun = ADC_OVR_DATA_OVERWRITTEN;
|
||||
if (HAL_ADC_Init(&hadc1) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
/** Configure Regular Channel
|
||||
*/
|
||||
sConfig.Channel = ADC_CHANNEL_11;
|
||||
sConfig.Rank = ADC_REGULAR_RANK_1;
|
||||
sConfig.SingleDiff = ADC_DIFFERENTIAL_ENDED;
|
||||
sConfig.SamplingTime = ADC_SAMPLETIME_1CYCLE_5;
|
||||
sConfig.OffsetNumber = ADC_OFFSET_NONE;
|
||||
sConfig.Offset = 0;
|
||||
if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)
|
||||
{
|
||||
Error_Handler();
|
||||
}
|
||||
/* USER CODE BEGIN ADC1_Init 2 */
|
||||
|
||||
/* USER CODE END ADC1_Init 2 */
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -483,6 +392,12 @@ static void MX_GPIO_Init(void)
|
|||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
/*Configure GPIO pins : LV_SENSE_1_Pin LV_SENSE_2_Pin */
|
||||
GPIO_InitStruct.Pin = LV_SENSE_1_Pin|LV_SENSE_2_Pin;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
|
||||
|
||||
/*Configure GPIO pins : AMI_EBSTEST_Pin AMI_INSPECTION_Pin ASB_Error_Pin AMI_TRACKDRIVE_Pin
|
||||
AMI_AUTOX_Pin AMI_SKIDPAD_Pin AMI_ACCEL_Pin AMI_MANUAL_Pin */
|
||||
GPIO_InitStruct.Pin = AMI_EBSTEST_Pin|AMI_INSPECTION_Pin|ASB_Error_Pin|AMI_TRACKDRIVE_Pin
|
||||
|
@ -507,15 +422,37 @@ static void MX_GPIO_Init(void)
|
|||
void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) {
|
||||
|
||||
CAN_RxHeaderTypeDef rxHeader;
|
||||
// TODO: Remove buffer once filter is implemented?
|
||||
uint8_t rxBuffer[8];
|
||||
rx_data_t rxData;
|
||||
|
||||
// Read frame from HW into buffer
|
||||
if (HAL_CAN_GetRxMessage(hcan, CAN_RX_FIFO0, &rxHeader, rxBuffer) != HAL_OK)
|
||||
Error_Handler();
|
||||
|
||||
// Copy into the bitfield if it's for us
|
||||
if (rxHeader.StdId == CAN_ID_RX)
|
||||
rxData.raw[0] = rxBuffer[0];
|
||||
// Discard if it's not for us
|
||||
if (rxHeader.StdId != CAN_ID_RX)
|
||||
return;
|
||||
|
||||
// copy to bitfield
|
||||
rxData.raw[0] = rxBuffer[0];
|
||||
|
||||
HAL_GPIO_WritePin(ASB_Error_GPIO_Port, ASB_Error_Pin, rxData.signals.asb_error);
|
||||
HAL_GPIO_WritePin(AS_close_SDC_GPIO_Port, AS_close_SDC_Pin, rxData.signals.as_close_sdc);
|
||||
|
||||
/*
|
||||
* TODO: Heartbeat -> Watchdog via STM Watchdog
|
||||
* Also alternative implementation for UCC? With ifdefs?
|
||||
* rxData.signals.heartbeat
|
||||
*/
|
||||
|
||||
// TODO: TEMP!
|
||||
HAL_GPIO_WritePin(Watchdog_GPIO_Port, Watchdog_Pin, true);
|
||||
|
||||
// Reset old mission LED
|
||||
setMissionLED(mission, GPIO_PIN_RESET);
|
||||
mission = rxData.signals.as_mission;
|
||||
setMissionLED(mission, GPIO_PIN_SET);
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -76,69 +76,6 @@ void HAL_MspInit(void)
|
|||
/* USER CODE END MspInit 1 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief ADC MSP Initialization
|
||||
* This function configures the hardware resources used in this example
|
||||
* @param hadc: ADC handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStruct = {0};
|
||||
if(hadc->Instance==ADC1)
|
||||
{
|
||||
/* USER CODE BEGIN ADC1_MspInit 0 */
|
||||
|
||||
/* USER CODE END ADC1_MspInit 0 */
|
||||
/* Peripheral clock enable */
|
||||
__HAL_RCC_ADC1_CLK_ENABLE();
|
||||
|
||||
__HAL_RCC_GPIOB_CLK_ENABLE();
|
||||
/**ADC1 GPIO Configuration
|
||||
PB0 ------> ADC1_IN11
|
||||
PB1 ------> ADC1_IN12
|
||||
*/
|
||||
GPIO_InitStruct.Pin = LV_SENSE_1_Pin|LV_SENSE_2_Pin;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
|
||||
|
||||
/* USER CODE BEGIN ADC1_MspInit 1 */
|
||||
|
||||
/* USER CODE END ADC1_MspInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief ADC MSP De-Initialization
|
||||
* This function freeze the hardware resources used in this example
|
||||
* @param hadc: ADC handle pointer
|
||||
* @retval None
|
||||
*/
|
||||
void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc)
|
||||
{
|
||||
if(hadc->Instance==ADC1)
|
||||
{
|
||||
/* USER CODE BEGIN ADC1_MspDeInit 0 */
|
||||
|
||||
/* USER CODE END ADC1_MspDeInit 0 */
|
||||
/* Peripheral clock disable */
|
||||
__HAL_RCC_ADC1_CLK_DISABLE();
|
||||
|
||||
/**ADC1 GPIO Configuration
|
||||
PB0 ------> ADC1_IN11
|
||||
PB1 ------> ADC1_IN12
|
||||
*/
|
||||
HAL_GPIO_DeInit(GPIOB, LV_SENSE_1_Pin|LV_SENSE_2_Pin);
|
||||
|
||||
/* USER CODE BEGIN ADC1_MspDeInit 1 */
|
||||
|
||||
/* USER CODE END ADC1_MspDeInit 1 */
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief CAN MSP Initialization
|
||||
* This function configures the hardware resources used in this example
|
||||
|
|
|
@ -1,273 +0,0 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f3xx_hal_adc.h
|
||||
* @author MCD Application Team
|
||||
* @brief Header file containing functions prototypes of ADC HAL library.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© Copyright (c) 2016 STMicroelectronics.
|
||||
* All rights reserved.</center></h2>
|
||||
*
|
||||
* This software component is licensed by ST under BSD 3-Clause license,
|
||||
* the "License"; You may not use this file except in compliance with the
|
||||
* License. You may obtain a copy of the License at:
|
||||
* opensource.org/licenses/BSD-3-Clause
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __STM32F3xx_ADC_H
|
||||
#define __STM32F3xx_ADC_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "stm32f3xx_hal_def.h"
|
||||
|
||||
/* Include ADC HAL Extended module */
|
||||
/* (include on top of file since ADC structures are defined in extended file) */
|
||||
#include "stm32f3xx_hal_adc_ex.h"
|
||||
|
||||
/** @addtogroup STM32F3xx_HAL_Driver
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup ADC
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/** @defgroup ADC_Exported_Types ADC Exported Types
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @brief HAL ADC state machine: ADC states definition (bitfields)
|
||||
* @note ADC state machine is managed by bitfields, state must be compared
|
||||
* with bit by bit.
|
||||
* For example:
|
||||
* " if (HAL_IS_BIT_SET(HAL_ADC_GetState(hadc1), HAL_ADC_STATE_REG_BUSY)) "
|
||||
* " if (HAL_IS_BIT_SET(HAL_ADC_GetState(hadc1), HAL_ADC_STATE_AWD1) ) "
|
||||
*/
|
||||
/* States of ADC global scope */
|
||||
#define HAL_ADC_STATE_RESET (0x00000000U) /*!< ADC not yet initialized or disabled */
|
||||
#define HAL_ADC_STATE_READY (0x00000001U) /*!< ADC peripheral ready for use */
|
||||
#define HAL_ADC_STATE_BUSY_INTERNAL (0x00000002U) /*!< ADC is busy to internal process (initialization, calibration) */
|
||||
#define HAL_ADC_STATE_TIMEOUT (0x00000004U) /*!< TimeOut occurrence */
|
||||
|
||||
/* States of ADC errors */
|
||||
#define HAL_ADC_STATE_ERROR_INTERNAL (0x00000010U) /*!< Internal error occurrence */
|
||||
#define HAL_ADC_STATE_ERROR_CONFIG (0x00000020U) /*!< Configuration error occurrence */
|
||||
#define HAL_ADC_STATE_ERROR_DMA (0x00000040U) /*!< DMA error occurrence */
|
||||
|
||||
/* States of ADC group regular */
|
||||
#define HAL_ADC_STATE_REG_BUSY (0x00000100U) /*!< A conversion on group regular is ongoing or can occur (either by continuous mode,
|
||||
external trigger, low power auto power-on, multimode ADC master control) */
|
||||
#define HAL_ADC_STATE_REG_EOC (0x00000200U) /*!< Conversion data available on group regular */
|
||||
#define HAL_ADC_STATE_REG_OVR (0x00000400U) /*!< Overrun occurrence */
|
||||
#define HAL_ADC_STATE_REG_EOSMP (0x00000800U) /*!< End Of Sampling flag raised */
|
||||
|
||||
/* States of ADC group injected */
|
||||
#define HAL_ADC_STATE_INJ_BUSY (0x00001000U) /*!< A conversion on group injected is ongoing or can occur (either by auto-injection mode,
|
||||
external trigger, low power auto power-on, multimode ADC master control) */
|
||||
#define HAL_ADC_STATE_INJ_EOC (0x00002000U) /*!< Conversion data available on group injected */
|
||||
#define HAL_ADC_STATE_INJ_JQOVF (0x00004000U) /*!< Injected queue overflow occurrence */
|
||||
|
||||
/* States of ADC analog watchdogs */
|
||||
#define HAL_ADC_STATE_AWD1 (0x00010000U) /*!< Out-of-window occurrence of analog watchdog 1 */
|
||||
#define HAL_ADC_STATE_AWD2 (0x00020000U) /*!< Out-of-window occurrence of analog watchdog 2 */
|
||||
#define HAL_ADC_STATE_AWD3 (0x00040000U) /*!< Out-of-window occurrence of analog watchdog 3 */
|
||||
|
||||
/* States of ADC multi-mode */
|
||||
#define HAL_ADC_STATE_MULTIMODE_SLAVE (0x00100000U) /*!< ADC in multimode slave state, controlled by another ADC master ( */
|
||||
|
||||
|
||||
/**
|
||||
* @brief ADC handle Structure definition
|
||||
*/
|
||||
typedef struct __ADC_HandleTypeDef
|
||||
{
|
||||
ADC_TypeDef *Instance; /*!< Register base address */
|
||||
|
||||
ADC_InitTypeDef Init; /*!< ADC required parameters */
|
||||
|
||||
DMA_HandleTypeDef *DMA_Handle; /*!< Pointer DMA Handler */
|
||||
|
||||
HAL_LockTypeDef Lock; /*!< ADC locking object */
|
||||
|
||||
__IO uint32_t State; /*!< ADC communication state (bitmap of ADC states) */
|
||||
|
||||
__IO uint32_t ErrorCode; /*!< ADC Error code */
|
||||
|
||||
#if defined(STM32F302xE) || defined(STM32F303xE) || defined(STM32F398xx) || \
|
||||
defined(STM32F302xC) || defined(STM32F303xC) || defined(STM32F358xx) || \
|
||||
defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F328xx) || \
|
||||
defined(STM32F301x8) || defined(STM32F302x8) || defined(STM32F318xx)
|
||||
ADC_InjectionConfigTypeDef InjectionConfig ; /*!< ADC injected channel configuration build-up structure */
|
||||
#endif /* STM32F302xE || STM32F303xE || STM32F398xx || */
|
||||
/* STM32F302xC || STM32F303xC || STM32F358xx || */
|
||||
/* STM32F303x8 || STM32F334x8 || STM32F328xx || */
|
||||
/* STM32F301x8 || STM32F302x8 || STM32F318xx */
|
||||
|
||||
#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
|
||||
void (* ConvCpltCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC conversion complete callback */
|
||||
void (* ConvHalfCpltCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC conversion DMA half-transfer callback */
|
||||
void (* LevelOutOfWindowCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC analog watchdog 1 callback */
|
||||
void (* ErrorCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC error callback */
|
||||
void (* InjectedConvCpltCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC group injected conversion complete callback */ /*!< ADC end of sampling callback */
|
||||
void (* MspInitCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC Msp Init callback */
|
||||
void (* MspDeInitCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC Msp DeInit callback */
|
||||
#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
|
||||
}ADC_HandleTypeDef;
|
||||
|
||||
#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
|
||||
/**
|
||||
* @brief HAL ADC Callback ID enumeration definition
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
HAL_ADC_CONVERSION_COMPLETE_CB_ID = 0x00U, /*!< ADC conversion complete callback ID */
|
||||
HAL_ADC_CONVERSION_HALF_CB_ID = 0x01U, /*!< ADC conversion DMA half-transfer callback ID */
|
||||
HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID = 0x02U, /*!< ADC analog watchdog 1 callback ID */
|
||||
HAL_ADC_ERROR_CB_ID = 0x03U, /*!< ADC error callback ID */
|
||||
HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID = 0x04U, /*!< ADC group injected conversion complete callback ID */
|
||||
HAL_ADC_MSPINIT_CB_ID = 0x09U, /*!< ADC Msp Init callback ID */
|
||||
HAL_ADC_MSPDEINIT_CB_ID = 0x0AU /*!< ADC Msp DeInit callback ID */
|
||||
} HAL_ADC_CallbackIDTypeDef;
|
||||
|
||||
/**
|
||||
* @brief HAL ADC Callback pointer definition
|
||||
*/
|
||||
typedef void (*pADC_CallbackTypeDef)(ADC_HandleTypeDef *hadc); /*!< pointer to a ADC callback function */
|
||||
|
||||
#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
/* Exported macros -----------------------------------------------------------*/
|
||||
|
||||
/** @defgroup ADC_Exported_Macro ADC Exported Macros
|
||||
* @{
|
||||
*/
|
||||
/** @brief Reset ADC handle state
|
||||
* @param __HANDLE__ ADC handle
|
||||
* @retval None
|
||||
*/
|
||||
#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
|
||||
#define __HAL_ADC_RESET_HANDLE_STATE(__HANDLE__) \
|
||||
do{ \
|
||||
(__HANDLE__)->State = HAL_ADC_STATE_RESET; \
|
||||
(__HANDLE__)->MspInitCallback = NULL; \
|
||||
(__HANDLE__)->MspDeInitCallback = NULL; \
|
||||
} while(0)
|
||||
#else
|
||||
#define __HAL_ADC_RESET_HANDLE_STATE(__HANDLE__) \
|
||||
((__HANDLE__)->State = HAL_ADC_STATE_RESET)
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/** @addtogroup ADC_Exported_Functions ADC Exported Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup ADC_Exported_Functions_Group1 Initialization and de-initialization functions
|
||||
* @{
|
||||
*/
|
||||
/* Initialization and de-initialization functions **********************************/
|
||||
HAL_StatusTypeDef HAL_ADC_Init(ADC_HandleTypeDef* hadc);
|
||||
HAL_StatusTypeDef HAL_ADC_DeInit(ADC_HandleTypeDef *hadc);
|
||||
void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc);
|
||||
void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc);
|
||||
|
||||
#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1)
|
||||
/* Callbacks Register/UnRegister functions ***********************************/
|
||||
HAL_StatusTypeDef HAL_ADC_RegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID, pADC_CallbackTypeDef pCallback);
|
||||
HAL_StatusTypeDef HAL_ADC_UnRegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID);
|
||||
#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup ADC_Exported_Functions_Group2 Input and Output operation functions
|
||||
* @{
|
||||
*/
|
||||
/* Blocking mode: Polling */
|
||||
HAL_StatusTypeDef HAL_ADC_Start(ADC_HandleTypeDef* hadc);
|
||||
HAL_StatusTypeDef HAL_ADC_Stop(ADC_HandleTypeDef* hadc);
|
||||
HAL_StatusTypeDef HAL_ADC_PollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout);
|
||||
HAL_StatusTypeDef HAL_ADC_PollForEvent(ADC_HandleTypeDef* hadc, uint32_t EventType, uint32_t Timeout);
|
||||
|
||||
/* Non-blocking mode: Interruption */
|
||||
HAL_StatusTypeDef HAL_ADC_Start_IT(ADC_HandleTypeDef* hadc);
|
||||
HAL_StatusTypeDef HAL_ADC_Stop_IT(ADC_HandleTypeDef* hadc);
|
||||
|
||||
/* Non-blocking mode: DMA */
|
||||
HAL_StatusTypeDef HAL_ADC_Start_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length);
|
||||
HAL_StatusTypeDef HAL_ADC_Stop_DMA(ADC_HandleTypeDef* hadc);
|
||||
|
||||
/* ADC retrieve conversion value intended to be used with polling or interruption */
|
||||
uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef* hadc);
|
||||
|
||||
/* ADC IRQHandler and Callbacks used in non-blocking modes (Interruption and DMA) */
|
||||
void HAL_ADC_IRQHandler(ADC_HandleTypeDef* hadc);
|
||||
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc);
|
||||
void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef* hadc);
|
||||
void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef* hadc);
|
||||
void HAL_ADC_ErrorCallback(ADC_HandleTypeDef *hadc);
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup ADC_Exported_Functions_Group3 Peripheral Control functions
|
||||
* @{
|
||||
*/
|
||||
/* Peripheral Control functions ***********************************************/
|
||||
HAL_StatusTypeDef HAL_ADC_ConfigChannel(ADC_HandleTypeDef* hadc, ADC_ChannelConfTypeDef* sConfig);
|
||||
HAL_StatusTypeDef HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef* hadc, ADC_AnalogWDGConfTypeDef* AnalogWDGConfig);
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup ADC_Exported_Functions_Group4 Peripheral State functions
|
||||
* @brief ADC Peripheral State functions
|
||||
* @{
|
||||
*/
|
||||
/* Peripheral State functions *************************************************/
|
||||
uint32_t HAL_ADC_GetState(ADC_HandleTypeDef* hadc);
|
||||
uint32_t HAL_ADC_GetError(ADC_HandleTypeDef *hadc);
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /*__STM32F3xx_ADC_H */
|
||||
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -1,15 +1,4 @@
|
|||
#MicroXplorer Configuration settings - do not modify
|
||||
ADC1.Channel-0\#ChannelRegularConversion=ADC_CHANNEL_11
|
||||
ADC1.IPParameters=SubFamily,Rank-0\#ChannelRegularConversion,Channel-0\#ChannelRegularConversion,SamplingTime-0\#ChannelRegularConversion,SamplingTimeOPAMP-0\#ChannelRegularConversion,OffsetNumber-0\#ChannelRegularConversion,Offset-0\#ChannelRegularConversion,NbrOfConversionFlag,master,SingleDiff-0\#ChannelRegularConversion
|
||||
ADC1.NbrOfConversionFlag=1
|
||||
ADC1.Offset-0\#ChannelRegularConversion=0
|
||||
ADC1.OffsetNumber-0\#ChannelRegularConversion=ADC_OFFSET_NONE
|
||||
ADC1.Rank-0\#ChannelRegularConversion=1
|
||||
ADC1.SamplingTime-0\#ChannelRegularConversion=ADC_SAMPLETIME_1CYCLE_5
|
||||
ADC1.SamplingTimeOPAMP-0\#ChannelRegularConversion=ADC_SAMPLETIME_4CYCLES_5
|
||||
ADC1.SingleDiff-0\#ChannelRegularConversion=ADC_DIFFERENTIAL_ENDED
|
||||
ADC1.SubFamily=STM32F302x8
|
||||
ADC1.master=1
|
||||
CAN.BS1=CAN_BS1_13TQ
|
||||
CAN.BS2=CAN_BS2_2TQ
|
||||
CAN.CalculateBaudRate=500000
|
||||
|
@ -24,12 +13,11 @@ GPIO.groupedBy=Group By Peripherals
|
|||
KeepUserPlacement=false
|
||||
Mcu.CPN=STM32F302C8T6
|
||||
Mcu.Family=STM32F3
|
||||
Mcu.IP0=ADC1
|
||||
Mcu.IP1=CAN
|
||||
Mcu.IP2=NVIC
|
||||
Mcu.IP3=RCC
|
||||
Mcu.IP4=SYS
|
||||
Mcu.IPNb=5
|
||||
Mcu.IP0=CAN
|
||||
Mcu.IP1=NVIC
|
||||
Mcu.IP2=RCC
|
||||
Mcu.IP3=SYS
|
||||
Mcu.IPNb=4
|
||||
Mcu.Name=STM32F302C(6-8)Tx
|
||||
Mcu.Package=LQFP48
|
||||
Mcu.Pin0=PA0
|
||||
|
@ -134,13 +122,11 @@ PA9.Signal=GPIO_Output
|
|||
PB0.GPIOParameters=GPIO_Label
|
||||
PB0.GPIO_Label=LV_SENSE_1
|
||||
PB0.Locked=true
|
||||
PB0.Mode=IN11-Differential
|
||||
PB0.Signal=ADC1_IN11
|
||||
PB0.Signal=GPIO_Input
|
||||
PB1.GPIOParameters=GPIO_Label
|
||||
PB1.GPIO_Label=LV_SENSE_2
|
||||
PB1.Locked=true
|
||||
PB1.Mode=IN11-Differential
|
||||
PB1.Signal=ADC1_IN12
|
||||
PB1.Signal=GPIO_Input
|
||||
PB10.GPIOParameters=GPIO_Label
|
||||
PB10.GPIO_Label=AMI_EBSTEST
|
||||
PB10.Locked=true
|
||||
|
@ -258,7 +244,7 @@ ProjectManager.FreePins=false
|
|||
ProjectManager.HalAssertFull=false
|
||||
ProjectManager.HeapSize=0x200
|
||||
ProjectManager.KeepUserCode=true
|
||||
ProjectManager.LastFirmware=true
|
||||
ProjectManager.LastFirmware=false
|
||||
ProjectManager.LibraryCopy=1
|
||||
ProjectManager.MainLocation=Core/Src
|
||||
ProjectManager.NoMain=false
|
||||
|
|
Loading…
Reference in New Issue