This commit is contained in:
v0stap
2026-04-05 11:31:20 +02:00
commit 78e6a1b8aa
254 changed files with 175905 additions and 0 deletions

80
DBW_V2/Core/Src/adc.c Normal file
View File

@@ -0,0 +1,80 @@
/*
* adc.c
*
* Created on: Sep 6, 2017
* Author: dmitrijs
*/
#include "main.h"
void Adc_Init(void) {
RCC->APB2ENR |= RCC_APB2ENR_ADCEN;
ADC1->CFGR2 = (0x00000002 << 30); // pclk/4 -> 12Mhz
ADC1->SMPR = 0x00000001; // Sample 7.5 adc cycles
ADC1->CFGR1 = 0;
/* (1) Ensure that ADEN = 0 */
/* (2) Clear ADEN by setting ADDIS*/
/* (3) Clear DMAEN */
/* (4) Launch the calibration by setting ADCAL */
/* (5) Wait until ADCAL=0 */
if ((ADC1->CR & ADC_CR_ADEN) != 0) /* (1) */
{
ADC1->CR |= ADC_CR_ADDIS; /* (2) */
}
while ((ADC1->CR & ADC_CR_ADEN) != 0) {
/* For robust implementation, add here time-out management */
}
ADC1->CFGR1 &= ~ADC_CFGR1_DMAEN; /* (3) */
ADC1->CR |= ADC_CR_ADCAL; /* (4) */
while ((ADC1->CR & ADC_CR_ADCAL) != 0) /* (5) */
{
/* For robust implementation, add here time-out management */
}
/* (1) Ensure that ADRDY = 0 */
/* (2) Clear ADRDY */
/* (3) Enable the ADC */
/* (4) Wait until ADC ready */
if ((ADC1->ISR & ADC_ISR_ADRDY) != 0) /* (1) */
{
ADC1->ISR |= ADC_ISR_ADRDY; /* (2) */
}
ADC1->CR |= ADC_CR_ADEN; /* (3) */
while ((ADC1->ISR & ADC_ISR_ADRDY) == 0) /* (4) */
{
/*TODO For robust implementation, add here time-out management */
}
ADC1->IER = 0;
//NVIC_EnableIRQ(ADC1_IRQn);
}
unsigned short LPF(unsigned short lpf_c, unsigned short value,
unsigned short old_value) {
// Averageing filtering
float tmp;
tmp = ((float) (value - old_value) * ((float) (lpf_c) / (float) 1000.0)); // filter
if (tmp > 0)
tmp += (float) 0.5; // roundup
else
tmp -= (float) 0.5;
return (unsigned short) ((signed int) old_value + (signed int) tmp);
}
unsigned short Adc_Read(unsigned char ch) {
unsigned short tmp;
if (ADC1->ISR & ADC_ISR_EOC)
tmp = ADC1->DR; //ADC1->ISR |= ADC_ISR_EOC; // clear EOC flag
ADC1->CHSELR = (1 << ch); // select channel
ADC1->CR |= ADC_CR_ADSTART;
while ((~ADC1->ISR) & ADC_ISR_EOC)
;
ADC1->ISR |= ADC_ISR_EOC;
tmp = ADC1->DR;
return tmp;
}

281
DBW_V2/Core/Src/can.c Normal file
View File

@@ -0,0 +1,281 @@
/*
* CAN.c
*
* Created on: Dec 04, 2018
* Author: v0stap
*/
#include "main.h"
#include "CAN.h"
can_msg_typedef CAN_TX_Msg; // CAN message for transmit
can_msg_typedef CAN_RX_Msg; // CAN received message
uint8_t CAN_TX_Rdy = 0; // CAN hardware ready to transmit a message
uint8_t CAN_RX_Rdy = 0; // CAN hardware message received
uint32_t CAN_Speed = CAN_500KBS; // CAN Speed / CAN BTR register
can_buffer_typedef CAN_TX_Buffer, CAN_RX_Buffer;
uint8_t CAN_Filter_Idx = 0; // CAN filter index
void CAN_Init(void) {
CAN_TX_Buffer.todo = 0;
CAN_TX_Buffer.corent = 0;
CAN_TX_Buffer.done = 0;
CAN_RX_Buffer.todo = 0;
CAN_RX_Buffer.corent = 0;
CAN_RX_Buffer.done = 0;
CAN_Setup(CAN_500KBS);
CAN_Write_Filter(0x212, STD_FORMAT);
CAN_Write_Filter(0x643, STD_FORMAT);
//CAN_Write_Filter(0x620, STD_FORMAT);
//CAN_Write_Filter(0x630, STD_FORMAT);
//CAN_Write_Filter(0x240, STD_FORMAT);
CAN_Start();
CAN_Wait_Ready();
}
/*----------------------------------------------------------------------------
setup CAN interface
*----------------------------------------------------------------------------*/
void CAN_Setup(uint32_t speed) {
RCC->AHBENR |= RCC_AHBENR_GPIOBEN;
RCC->APB1ENR |= RCC_APB1ENR_CANEN;
GPIOB->MODER &= ~((3 << (8 * 2)) | (3 << (9 * 2)));
GPIOB->MODER |= ((2 << (8 * 2)) | (2 << (9 * 2)));
GPIOB->OTYPER &= ~((1 << 8) | (1 << 9));
GPIOB->OSPEEDR &= ~((3 << (8 * 2)) | (3 << (9 * 2)));
GPIOB->PUPDR &= ~((3 << (8 * 2)) | (3 << (9 * 2)));
GPIOB->AFR[1] &= ~((15 << (0 * 4)) | (15 << (1 * 4)));
GPIOB->AFR[1] |= ((4 << 0) | (4 << (1 * 4)));
CAN->MCR |= CAN_MCR_INRQ;
while ((CAN->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) {
//some code
}
CAN->MCR &= ~ CAN_MCR_SLEEP;
CAN->BTR &= ~(((0x03) << 24) | ((0x07) << 20) | ((0x0F) << 16) | (0x1FF));
CAN->BTR |= speed;
NVIC_EnableIRQ(CEC_CAN_IRQn);
CAN->IER |= CAN_IER_FMPIE0;
}
/*----------------------------------------------------------------------------
leave initialisation mode
*----------------------------------------------------------------------------*/
void CAN_Start(void) {
CAN->MCR &= ~CAN_MCR_INRQ;
while ((CAN->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) {
}
}
/*----------------------------------------------------------------------------
check if transmit mailbox is empty
*----------------------------------------------------------------------------*/
void CAN_Wait_Ready(void) {
while ((CAN->TSR & CAN_TSR_TME0) == 0) { // Transmit mailbox 0 is empty
}
CAN_TX_Rdy = 1;
}
// CAN send data
void CAN_Send_Msg(can_msg_typedef *msg) {
CAN_TX_Rdy = 0;
CAN->sTxMailBox[0].TIR = (uint32_t) 0;
if (msg->format == STD_FORMAT) {
CAN->sTxMailBox[0].TIR |= (uint32_t) (msg->id << 21) | CAN_ID_STD;
} else {
CAN->sTxMailBox[0].TIR |= (uint32_t) (msg->id << 3) | CAN_ID_EXT;
}
if (msg->frame == DATA_FRAME) {
CAN->sTxMailBox[0].TIR |= CAN_RTR_DATA;
} else {
CAN->sTxMailBox[0].TIR |= CAN_RTR_REMOTE;
}
CAN->sTxMailBox[0].TDLR = (((uint32_t) msg->data[3] << 24)
| ((uint32_t) msg->data[2] << 16) | ((uint32_t) msg->data[1] << 8)
| ((uint32_t) msg->data[0]));
CAN->sTxMailBox[0].TDHR = (((uint32_t) msg->data[7] << 24)
| ((uint32_t) msg->data[6] << 16) | ((uint32_t) msg->data[5] << 8)
| ((uint32_t) msg->data[4]));
CAN->sTxMailBox[0].TDTR &= ~CAN_TDT0R_DLC;
CAN->sTxMailBox[0].TDTR |= (msg->lenght & CAN_TDT0R_DLC);
CAN->IER |= CAN_IER_TMEIE;
CAN->sTxMailBox[0].TIR |= CAN_TI0R_TXRQ;
}
// Read CAN message
void CAN_Recive_Msg(can_msg_typedef *msg) {
if ((CAN->sFIFOMailBox[0].RIR & CAN_ID_EXT) == 0) {
msg->format = STD_FORMAT;
msg->id = (uint32_t) 0x000007FF & (CAN->sFIFOMailBox[0].RIR >> 21);
} else {
msg->format = EXTD_FORMAT;
msg->id = (uint32_t) 0x0003FFFF & (CAN->sFIFOMailBox[0].RIR >> 3);
}
if ((CAN->sFIFOMailBox[0].RIR & CAN_RTR_REMOTE) == 0) {
msg->frame = DATA_FRAME;
} else {
msg->frame = REMOTE_FRAME;
}
msg->lenght = (uint8_t) 0x0000000F & CAN->sFIFOMailBox[0].RDTR;
msg->data[0] = (uint32_t) 0x000000FF & (CAN->sFIFOMailBox[0].RDLR);
msg->data[1] = (uint32_t) 0x000000FF & (CAN->sFIFOMailBox[0].RDLR >> 8);
msg->data[2] = (uint32_t) 0x000000FF & (CAN->sFIFOMailBox[0].RDLR >> 16);
msg->data[3] = (uint32_t) 0x000000FF & (CAN->sFIFOMailBox[0].RDLR >> 24);
msg->data[4] = (uint32_t) 0x000000FF & (CAN->sFIFOMailBox[0].RDHR);
msg->data[5] = (uint32_t) 0x000000FF & (CAN->sFIFOMailBox[0].RDHR >> 8);
msg->data[6] = (uint32_t) 0x000000FF & (CAN->sFIFOMailBox[0].RDHR >> 16);
msg->data[7] = (uint32_t) 0x000000FF & (CAN->sFIFOMailBox[0].RDHR >> 24);
CAN->RF0R |= CAN_RF0R_RFOM0;
CAN_RX_Rdy = 0;
// if (msg->id == 0x643)
// printf(
// "CAN ID: 0x%X%X Data: 0x%X 0x%X 0x%X 0x%X 0x%X 0x%X 0x%X 0x%X \n",
// (uint16_t) (msg->id >> 16), (uint16_t) msg->id, msg->data[0],
// msg->data[1], msg->data[2], msg->data[3], msg->data[4],
// msg->data[5], msg->data[6], msg->data[7]);
// //(&canRxMsg); //TO DO not realy working
}
//Write CAN Filter
void CAN_Write_Filter(uint32_t id, uint8_t format) {
uint32_t CAN_msg_typedefId = 0;
if (CAN_Filter_Idx > 13) {
return;
}
if (format == STD_FORMAT) {
CAN_msg_typedefId |= (uint32_t) (id << 21) | CAN_ID_STD;
} else {
CAN_msg_typedefId |= (uint32_t) (id << 3) | CAN_ID_EXT;
}
CAN->FMR |= CAN_FMR_FINIT;
CAN->FA1R &= ~(uint32_t) (1 << CAN_Filter_Idx);
CAN->FS1R |= (uint32_t) (1 << CAN_Filter_Idx);
CAN->FM1R |= (uint32_t) (1 << CAN_Filter_Idx);
//Comment next to lines for no filter
if (id != 0) {
CAN->sFilterRegister[CAN_Filter_Idx].FR1 = CAN_msg_typedefId;
CAN->sFilterRegister[CAN_Filter_Idx].FR2 = CAN_msg_typedefId;
//Uncomment next to line for no filter
} else {
CAN->sFilterRegister[CAN_Filter_Idx].FR1 = 0; // 32-bit identifier
CAN->sFilterRegister[CAN_Filter_Idx].FR2 = 0; // 32-bit identifier
}
CAN->FFA1R &= ~(uint32_t) (1 << CAN_Filter_Idx);
CAN->FA1R |= (uint32_t) (1 << CAN_Filter_Idx);
CAN->FMR &= ~CAN_FMR_FINIT;
CAN_Filter_Idx++;
}
//CAN recive/transmit irq handler
void CEC_CAN_IRQHandler(void) {
if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) {
CAN->TSR |= CAN_TSR_RQCP0;
CAN->IER &= ~CAN_IER_TMEIE;
CAN_TX_Rdy = 1;
}
if ((CAN->RF0R & CAN_RF0R_FMP0) != 0) {
CAN_Add_RX_Buffer();
// TO DO
CAN->RF0R |= CAN_RF0R_RFOM0;
CAN_RX_Rdy = 1;
}
}
void CAN_Send_TX_Buffer(void) {
if (CAN_TX_Rdy) {
//HAL_GPIO_TogglePin(GPIOB, GPIO_PIN_1);
if (CAN_TX_Buffer.todo > 0) {
CAN_TX_Buffer.todo--;
//HAL_GPIO_TogglePin(GPIOB, GPIO_PIN_1);
CAN_Send_Msg(&CAN_TX_Buffer.data[CAN_TX_Buffer.done]);
if ((CAN_TX_Buffer.done++) > 14) {
CAN_TX_Buffer.done = 0;
}
}
}
}
void CAN_Add_TX_Buffer(can_msg_typedef *data) {
if ((CAN_TX_Buffer.todo++) < 15) {
if ((CAN_TX_Buffer.corent++) > 14) {
CAN_TX_Buffer.corent = 0;
}
//memcpy((void*) &canTX_buffer.data[canTX_buffer.corent], (void*) &data, sizeof(CAN_msg_typedef));
CAN_TX_Buffer.data[CAN_TX_Buffer.corent].id = data->id;
CAN_TX_Buffer.data[CAN_TX_Buffer.corent].format = data->format;
CAN_TX_Buffer.data[CAN_TX_Buffer.corent].frame = data->frame;
CAN_TX_Buffer.data[CAN_TX_Buffer.corent].lenght = data->lenght;
CAN_TX_Buffer.data[CAN_TX_Buffer.corent].data[0] = data->data[0];
CAN_TX_Buffer.data[CAN_TX_Buffer.corent].data[1] = data->data[1];
CAN_TX_Buffer.data[CAN_TX_Buffer.corent].data[2] = data->data[2];
CAN_TX_Buffer.data[CAN_TX_Buffer.corent].data[3] = data->data[3];
CAN_TX_Buffer.data[CAN_TX_Buffer.corent].data[4] = data->data[4];
CAN_TX_Buffer.data[CAN_TX_Buffer.corent].data[5] = data->data[5];
CAN_TX_Buffer.data[CAN_TX_Buffer.corent].data[6] = data->data[6];
CAN_TX_Buffer.data[CAN_TX_Buffer.corent].data[7] = data->data[7];
}
}
void CAN_Add_RX_Buffer(void) {
if ((CAN_RX_Buffer.todo) < 16) {
CAN_RX_Buffer.todo++;
if ((CAN->sFIFOMailBox[0].RIR & CAN_ID_EXT) == 0) {
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].format = STD_FORMAT;
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].id = (uint32_t) 0x000007FF
& (CAN->sFIFOMailBox[0].RIR >> 21);
} else {
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].format = EXTD_FORMAT;
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].id = (uint32_t) 0x0003FFFF
& (CAN->sFIFOMailBox[0].RIR >> 3);
}
if ((CAN->sFIFOMailBox[0].RIR & CAN_RTR_REMOTE) == 0) {
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].frame = DATA_FRAME;
} else {
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].frame = REMOTE_FRAME;
}
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].lenght = (uint8_t) 0x0000000F
& CAN->sFIFOMailBox[0].RDTR;
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].data[0] = (uint32_t) 0x000000FF
& (CAN->sFIFOMailBox[0].RDLR);
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].data[1] = (uint32_t) 0x000000FF
& (CAN->sFIFOMailBox[0].RDLR >> 8);
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].data[2] = (uint32_t) 0x000000FF
& (CAN->sFIFOMailBox[0].RDLR >> 16);
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].data[3] = (uint32_t) 0x000000FF
& (CAN->sFIFOMailBox[0].RDLR >> 24);
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].data[4] = (uint32_t) 0x000000FF
& (CAN->sFIFOMailBox[0].RDHR);
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].data[5] = (uint32_t) 0x000000FF
& (CAN->sFIFOMailBox[0].RDHR >> 8);
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].data[6] = (uint32_t) 0x000000FF
& (CAN->sFIFOMailBox[0].RDHR >> 16);
CAN_RX_Buffer.data[CAN_RX_Buffer.corent].data[7] = (uint32_t) 0x000000FF
& (CAN->sFIFOMailBox[0].RDHR >> 24);
if ((CAN_RX_Buffer.corent++) > 15) {
CAN_RX_Buffer.corent = 0;
}
//canAddRXBuffer(&canRxMsg); //TO DO not realy working
}
CAN->RF0R |= CAN_RF0R_RFOM0;
}
void CAN_Read_RX_Buffer(can_msg_typedef *data) {
if (CAN_RX_Buffer.todo > 0) {
//memcpy((void*) &data, (void*) &canRX_buffer.data[canRX_buffer.done], sizeof(CAN_msg_typedef));
data->id = CAN_RX_Buffer.data[CAN_RX_Buffer.done].id;
data->format = CAN_RX_Buffer.data[CAN_RX_Buffer.done].format;
data->frame = CAN_RX_Buffer.data[CAN_RX_Buffer.done].frame;
data->lenght = CAN_RX_Buffer.data[CAN_RX_Buffer.done].lenght;
data->data[0] = CAN_RX_Buffer.data[CAN_RX_Buffer.done].data[0];
data->data[1] = CAN_RX_Buffer.data[CAN_RX_Buffer.done].data[1];
data->data[2] = CAN_RX_Buffer.data[CAN_RX_Buffer.done].data[2];
data->data[3] = CAN_RX_Buffer.data[CAN_RX_Buffer.done].data[3];
data->data[4] = CAN_RX_Buffer.data[CAN_RX_Buffer.done].data[4];
data->data[5] = CAN_RX_Buffer.data[CAN_RX_Buffer.done].data[5];
data->data[6] = CAN_RX_Buffer.data[CAN_RX_Buffer.done].data[6];
data->data[7] = CAN_RX_Buffer.data[CAN_RX_Buffer.done].data[7];
if ((CAN_RX_Buffer.done++) > 15) {
CAN_RX_Buffer.done = 0;
}
CAN_RX_Buffer.todo--;
}
}

664
DBW_V2/Core/Src/dbw.c Normal file
View File

@@ -0,0 +1,664 @@
/*
* dbw.c
*
* Created on: May 5, 2021
* Author: Dmitrijs
*/
#include "main.h"
volatile config_t config_ram;
volatile var_t var;
volatile config_t *config;
volatile uint32_t ac_timer = 100, ac_mode = 0;
const config_t config_flash __attribute__((section(".config"), used)) = {
PPS2_CALC_OPTION_LINEAR,
TPS2_CALC_OPTION_LINEAR,
100, 3990,
100, 2048, 500, 3990,
100, 3990,
100, 2048, 500, 3990,
PPS2TPS_OPTION_CURVE,
IDLE_OPTION_NO_IDLE_INPUT,
{ 0, 67, 132, 198, 264, 330, 396, 462, 528, 594, 660, 726, 792, 858,
924, 1000 }, { 0, 67, 132, 198, 264, 330, 396, 462, 528, 594,
660, 726, 792, 858, 924, 1000 },
// Idle pps modifier curve. when Idle input is used. it modifies tps target
{ 0, 142, 284, 426, 568, 710, 852, 1000 }, //input pwm duty [0.1%]
{ 0, 8, 17, 25, 34, 42, 51, 60 },
1000, // frequency in Hz
10, // ctl_teriod in [100uS]
MOTOR_PID_OPTION_STATIC,// PID static coefs, static coef, but different for forward and backward moving
// 3D table
// PID COEFICIENTS for forward and reward
700, 50, 10, 700, 50, 10,
{ 0, 67, 132, 198, 264, 330, 396, 462, 528, 594, 660, 726, 792, 858,
924, 1000 }, { -325, -281, -239, -196, -153, -110, -67, -24, 18,
61, 104, 146, 189, 232, 275, 325 }, { { 700, 700, 700, 700, 700,
700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700 }, { 700,
700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700,
700, 700 }, { 700, 700, 700, 700, 700, 700, 700, 700, 700, 700,
700, 700, 700, 700, 700, 700 }, { 700, 700, 700, 700, 700, 700,
700, 700, 700, 700, 700, 700, 700, 700, 700, 700 }, { 700, 700,
700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700,
700 }, { 700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700,
700, 700, 700, 700, 700 }, { 700, 700, 700, 700, 700, 700, 700,
700, 700, 700, 700, 700, 700, 700, 700, 700 },
{ 700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700,
700, 700, 700, 700 }, { 700, 700, 700, 700, 700, 700,
700, 700, 700, 700, 700, 700, 700, 700, 700, 700 }, {
700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700,
700, 700, 700, 700, 700 }, { 700, 700, 700, 700, 700,
700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700 },
{ 700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700,
700, 700, 700, 700 }, { 700, 700, 700, 700, 700, 700,
700, 700, 700, 700, 700, 700, 700, 700, 700, 700 }, {
700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700,
700, 700, 700, 700, 700 }, { 700, 700, 700, 700, 700,
700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700 },
{ 700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700, 700,
700, 700, 700, 700 }, },
//PID limmits
100, 10000, -10000,
//DC offset curve
{ 0, 67, 132, 198, 264, 330, 396, 462, 528, 594, 660, 726, 792, 858,
924, 1000 }, // tps bins [0.1%]
{ 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }, // DC
//Battery voltage correction curve
{ 0, 585, 1170, 1755, 2340, 2925, 3510, 4095 }, // battery voltage ADC bins []
{ 0, 0, 0, 0, 0, 0, 0, 0 }, // motor pwm correction [0.1%]
30, 0x100, 0x5e8, 0x00,
//limmits
30, 30, 15, 30, 30, 15, 100, 500, 10, 5000,
5, 7, // my MS CAN ID
1, 0, 100, 0x300 };
volatile unsigned short ctl_period;
volatile pwm_t ttl1_pwm;
volatile float pps1_gain, pps1_offset, pps2_gain, pps2_offset, tps1_gain,
tps1_offset, tps2_gain, tps2_offset;
volatile uint16_t dbw_fast_process_timer, dbw_slow_process_timer;
volatile int32_t vbat_corr, tps_slow_t, p_comp, i_comp, d_comp, tps_error_t,
can_target, spring_preload, idle_adder;
void Apply_Sensor_Calibration(void) {
pps1_gain = (1000.0F / (float) (config->pps1_max - config->pps1_min));
pps1_offset = (config->pps1_min * 1000.0F
/ (config->pps1_min - config->pps1_max));
pps2_gain = (1000.0F / (float) (config->pps2_max - config->pps2_min));
pps2_offset = (config->pps2_min * 1000.0F
/ (config->pps2_min - config->pps2_max));
tps1_gain = (1000.0F / (float) (config->tps1_max - config->tps1_min));
tps1_offset = (short) (config->tps1_min * 1000.0F
/ (config->tps1_min - config->tps1_max));
tps2_gain = (1000.0F / (float) (config->tps2_max - config->tps2_min));
tps2_offset = (config->tps2_min * 1000.0F
/ (config->tps2_min - config->tps2_max));
}
void DBW_Init(void) {
dbw_fast_process_timer = 1;
dbw_slow_process_timer = config->motor_ctl_period;
vbat_corr = 0;
tps_slow_t = var.tps;
p_comp = 0;
i_comp = 0;
d_comp = 0;
tps_error_t = var.tps_error;
can_target = 0;
spring_preload = 0;
idle_adder = 0;
}
int DBW_Process(void) {
int32_t pwm_output = 0;
int32_t pct = 0;
if (dbw_fast_process_timer == 0) {
//process DBW every 1 mS
dbw_fast_process_timer = 1;
// Read all sensors and calculate error
// calculate PPS sensor reading
var.pps1_adc = LPF(700, Adc_Read(0), var.pps1_adc);
var.pps1 = var.pps1_adc * pps1_gain + pps1_offset;
var.pps2_adc = LPF(700, Adc_Read(3), var.pps2_adc); //orig 1
var.pps2 = var.pps2_adc * pps2_gain + pps2_offset;
var.pps_delta = var.pps1 - var.pps2;
var.pps = (var.pps1 + var.pps2) >> 1;
//Calculate TPS sensor reading
var.tps1_adc = LPF(700, Adc_Read(2), var.tps1_adc);
var.tps1 = var.tps1_adc * tps1_gain + tps1_offset;
var.tps2_adc = LPF(700, Adc_Read(1), var.tps2_adc); //orig 3
var.tps2 = var.tps2_adc * tps2_gain + tps2_offset;
// calculate tps and pps delta and values
var.tps_delta = var.tps1 - var.tps2;
var.tps = (var.tps1 + var.tps2) >> 1;
var.pps_delta = var.pps1 - var.pps2;
var.pps = (var.pps1 + var.pps2) >> 1;
// set tps target
if (config->pps2tps_option == PPS2TPS_OPTION_CURVE) {
var.tps_target = intrp_1d_ss_table(var.pps, 16,
(signed short*) config->pps_bins, 1,
(signed short*) config->tps_bins);
}
// if MS3 DBW protocol is used
else if (config->pps2tps_option == PPS2TPS_OPTION_MS3_CAN) {
// if no RX errors
//if(var.status0 & DBW_STATUS0_CAN_MSDBW_F)
if (config->pps2tps_option == PPS2TPS_OPTION_MS3_CAN) {
// use MS3 TPS TARGET
var.tps_target = can_target;
} else {
// on CAN error fall back to internal curve
var.tps_target = intrp_1d_ss_table(var.pps, 16,
(signed short*) config->pps_bins, 1,
(signed short*) config->tps_bins);
}
}
else {
// All other TPS target options are considered as fault
Error_Handler();
}
// add idle TPS target adder
var.tps_target += idle_adder;
//limit TPS target
if (var.tps_target > 1000)
var.tps_target = 1000;
if (var.tps_target < 0)
var.tps_target = 0;
//calculate regulation error
var.tps_error = var.tps_target - var.tps;
// Proportional regulator
p_comp = (((int32_t) var.tps_error) * (int32_t) config->motor_fw_p)
/ 10;
// calculate spring preload compensation using interpolation
spring_preload = intrp_1d_ss_table(var.tps_target, 16,
(signed short*) config->tps_dc_tps_bins, 1,
(signed short*) config->tps_dc_offset_bins);
if (dbw_slow_process_timer > 0) {
dbw_slow_process_timer--;
if (dbw_slow_process_timer == 0) {
dbw_slow_process_timer = config->motor_ctl_period;
//calculate slow changing thinks
//read Battery voltage and apply corrections
var.vbat_adc = LPF(700, Adc_Read(5), var.vbat_adc);
pct = intrp_1d_ss_table(var.vbat_adc, 8,
(signed short*) config->vbat_bins, 1,
(signed short*) config->motor_pwm_corr_bins);
//read motor current
var.motor_current_adc = LPF(700, Adc_Read(4),
var.motor_current_adc);
// calculate I component
i_comp += ((int32_t) var.tps_error
* (int32_t) config->motor_fw_i) / 100;
if (i_comp > config->i_limmit)
i_comp = config->i_limmit;
if (i_comp < (-config->i_limmit))
i_comp = (-config->i_limmit);
// calculate D component
d_comp = (((int32_t) var.tps_error - tps_error_t)
* (int32_t) config->motor_fw_d) / 10;
tps_error_t = var.tps_error;
// calculate single shot
//single_shot = var.tps_error *
// Calculate Idle adder
if (config->idle_input_option == IDLE_OPTION_NO_IDLE_INPUT)
idle_adder = 0;
else if (config->idle_input_option == IDLE_OPTION_MS_CAN) {
idle_adder = intrp_1d_ss_table(var.idle_dc, 8,
(signed short*) config->idle_input_bins, 1,
(signed short*) config->idle_tps_adder_bins);
} else if (config->idle_input_option == IDLE_OPTION_PWM_INPUT1) {
idle_adder = intrp_1d_ss_table(var.idle_dc, 8,
(signed short*) config->idle_input_bins, 1,
(signed short*) config->idle_tps_adder_bins)
- (var.pps / 5);
if (idle_adder < 0) {
idle_adder = 0;
}
}
}
}
pwm_output = p_comp + i_comp + d_comp + spring_preload;
vbat_corr = (int16_t) (((int32_t) var.motor_pwm) * vbat_corr / 1000);
pwm_output += pct;
//limmit pwm
if (pwm_output > config->motor_dc_max)
pwm_output = config->motor_dc_max;
if (pwm_output < config->motor_dc_min)
pwm_output = config->motor_dc_min;
//apply pwm
DBW_Pwm_Set_Duty((signed short) (pwm_output), (pwm_t*) &ttl1_pwm);
}
return 0;
}
void DBW_Pwm_Init(void) {
// Setup PWM ports
ttl1_pwm.pos_port = GPIOB;
ttl1_pwm.pos_pin = 10;
ttl1_pwm.neg_port = GPIOB;
ttl1_pwm.neg_pin = 11;
// setup pwm status default -> no drive
ttl1_pwm.status = PWM_STATUS_DEFAULT;
// calculate how many tick are in given freq period
ttl1_pwm.period_ticks = (unsigned int) 1000000UL / config->motor_pwm_fq;
// set initian pwm from current settings
ttl1_pwm.pwm = var.motor_pwm;
ttl1_pwm.pwm_t = var.motor_pwm;
ttl1_pwm.single_pulse = 0;
//tmp = (float)ttl1_pwm.period_ticks * (float)ttl1_pwm.pwm/10000.0F;
//ttl1_pwm.duty_ticks = (unsigned int) tmp;
DBW_Pwm_Set_Duty(var.motor_pwm, (pwm_t*) &ttl1_pwm);
if (var.motor_pwm < 0)
ttl1_pwm.state = PWM_STATE_NEGATIVE_INACTIVE;
else if (var.motor_pwm > 0)
ttl1_pwm.state = PWM_STATE_POSITIVE_INACTIVE;
else
ttl1_pwm.state = PWM_STATE_POSITIVE_INACTIVE;
ttl1_pwm.status = PWM_STATUS_IDLE;
DBW_Stop();
ttl1_pwm.pos_port->BSRR = (1 << (16 + ttl1_pwm.pos_pin));
ttl1_pwm.neg_port->BSRR = (1 << (16 + ttl1_pwm.neg_pin));
// configure TIM2 to 1uS / tick timer
// setup CCR interrupt happen after sturtup delay is over
RCC->APB1ENR |= RCC_APB1ENR_TIM2EN;
TIM2->CNT = 0xFFFFFFFE;
TIM2->PSC = 48; //2400; // (1uS precision)
TIM2->ARR = 0xFFFFFFFF;
TIM2->CR1 = (TIM_CR1_URS | TIM_CR1_CEN);
TIM2->CCER = 0x0000;
TIM2->CCMR1 = 0x0000;
TIM2->CCR1 = (unsigned int) 20000; // startup delay
TIM2->CCR2 = 0;
TIM2->SR &= ~TIM_SR_CC1IF;
TIM2->DIER |= TIM_DIER_CC1IE;
NVIC_EnableIRQ(TIM2_IRQn);
}
void TIM2_IRQHandler(void) {
if (TIM2->SR & TIM_SR_CC1IF) {
// capture compare intrrupt
TIM2->SR &= ~TIM_SR_CC1IF;
if (ttl1_pwm.status == PWM_STATUS_DEFAULT) {
// here ends startup delay
// enable drive here
ttl1_pwm.status = PWM_STATUS_STARTED;
}
//Set duty
if (ttl1_pwm.pwm > 0) {
// pwm > 0
if ((ttl1_pwm.pwm > 0) && (ttl1_pwm.pwm_t < 0)) {
// if changeing PWM polarity insert dead time
ttl1_pwm.state = PWM_STATE_POSITIVE_INACTIVE;
ttl1_pwm.pos_port->BSRR = (1 << (16 + ttl1_pwm.pos_pin));
ttl1_pwm.neg_port->BSRR = (1 << (16 + ttl1_pwm.neg_pin));
TIM2->CCR1 = TIM2->CNT + config->pwm_deadtime;
} else if (ttl1_pwm.state == PWM_STATE_POSITIVE_INACTIVE) {
ttl1_pwm.state = PWM_STATE_POSITIVE_ACTIVE;
ttl1_pwm.pos_port->BSRR = (1 << ttl1_pwm.pos_pin);
ttl1_pwm.neg_port->BSRR = (1 << (16 + ttl1_pwm.neg_pin));
TIM2->CCR1 = TIM2->CNT + ttl1_pwm.duty_ticks;
} else {
ttl1_pwm.state = PWM_STATE_POSITIVE_INACTIVE;
ttl1_pwm.pos_port->BSRR = (1 << (16 + ttl1_pwm.pos_pin));
ttl1_pwm.neg_port->BSRR = (1 << (16 + ttl1_pwm.neg_pin));
TIM2->CCR1 = TIM2->CNT
+ (ttl1_pwm.period_ticks - ttl1_pwm.duty_ticks);
}
} else if (ttl1_pwm.pwm < 0) {
//pwm < 0
//if((ttl1_pwm.state == PWM_STATE_POSITIVE_INACTIVE) && (ttl1_pwm.state == PWM_STATE_POSITIVE_ACTIVE))
if ((ttl1_pwm.pwm < 0) && (ttl1_pwm.pwm_t > 0)) {
// if changeing PWM polarity insert dead time
ttl1_pwm.state = PWM_STATE_NEGATIVE_INACTIVE;
ttl1_pwm.pos_port->BSRR = (1 << (16 + ttl1_pwm.pos_pin));
ttl1_pwm.neg_port->BSRR = (1 << (16 + ttl1_pwm.neg_pin));
TIM2->CCR1 = TIM2->CNT + config->pwm_deadtime;
} else if (ttl1_pwm.state == PWM_STATE_NEGATIVE_INACTIVE) {
ttl1_pwm.state = PWM_STATE_NEGATIVE_ACTIVE;
ttl1_pwm.pos_port->BSRR = (1 << (16 + ttl1_pwm.pos_pin));
ttl1_pwm.neg_port->BSRR = (1 << ttl1_pwm.neg_pin);
TIM2->CCR1 = TIM2->CNT + ttl1_pwm.duty_ticks;
} else {
ttl1_pwm.state = PWM_STATE_NEGATIVE_INACTIVE;
ttl1_pwm.pos_port->BSRR = (1 << (16 + ttl1_pwm.pos_pin));
ttl1_pwm.neg_port->BSRR = (1 << (16 + ttl1_pwm.neg_pin));
TIM2->CCR1 = TIM2->CNT
+ (ttl1_pwm.period_ticks - ttl1_pwm.duty_ticks);
}
} else {
// if pwm == 0
ttl1_pwm.pos_port->BSRR = (1 << (16 + ttl1_pwm.pos_pin));
ttl1_pwm.neg_port->BSRR = (1 << (16 + ttl1_pwm.neg_pin));
TIM2->CCR1 = TIM2->CNT + ttl1_pwm.period_ticks;
if (ttl1_pwm.state == PWM_STATE_POSITIVE_ACTIVE
|| ttl1_pwm.state == PWM_STATE_POSITIVE_INACTIVE) {
ttl1_pwm.state = PWM_STATE_POSITIVE_INACTIVE;
} else {
ttl1_pwm.state = PWM_STATE_NEGATIVE_INACTIVE;
}
}
// store new pwm value as old pwm value for the nex iteration
ttl1_pwm.pwm_t = ttl1_pwm.pwm;
}
if (TIM2->SR & TIM_SR_UIF) {
//TIM2 overflow interrupt jaust clear update interrupt flag
TIM2->SR &= ~TIM_SR_UIF;
}
}
void DBW_Pwm_Set_Duty(signed int duty, pwm_t *ttl) {
float tmp;
unsigned int period_ticks;
//check limmits
if (duty > 10000)
duty = 10000;
else if (duty < -10000)
duty = -10000;
//calculate period - needed to change frequency on-the-fly
period_ticks = (unsigned int) 1000000UL / config->motor_pwm_fq;
if (duty > 0)
tmp = (float) period_ticks * (float) duty / 10000.0F;
else if (duty < 0)
tmp = (float) period_ticks * (0 - ((float) duty)) / 10000.0F;
else
tmp = 20;
// check minimum duty period;
// do not allow duty cylce <20uS
if ((period_ticks - (unsigned int) tmp) < 20) {
tmp = period_ticks - 20;
if (duty > 0)
duty = (signed int) tmp * 10000.0F / ttl->period_ticks;
else if (duty < 0)
duty = 0 - (signed int) tmp * 10000.0F / ttl->period_ticks;
} else if (tmp < 20) {
tmp = 20;
duty = 0;
}
//update variables
var.motor_pwm = duty;
//apply new settings
__disable_irq();
ttl->duty_ticks = (unsigned int) tmp;
ttl->period_ticks = period_ticks;
ttl->pwm = duty;
__enable_irq();
}
unsigned int intrp_1d_uitable(unsigned int x, unsigned char nx,
unsigned int *x_table, unsigned int *z_table) {
int ix;
long interp, interp3;
// bound input arguments
if (x > x_table[nx - 1])
return (z_table[nx - 1]);
else if (x < x_table[0])
return (z_table[0]);
// Find bounding indiex in table
for (ix = nx - 2; ix > -1; ix--) { // Start w highest index
// because will generally have least time for calculations at hi y
if (x > x_table[ix]) {
break;
}
}
if (ix < 0)
ix = 0;
// do 1D interpolate
interp = (long) (x_table[ix + 1] - x_table[ix]);
if (interp != 0) {
interp3 = (long) (x - x_table[ix]);
interp3 = (100 * interp3);
interp = interp3 / interp;
}
return ((unsigned int) (z_table[ix]
+ interp * (int) (z_table[ix + 1] - z_table[ix]) / 100));
}
signed short intrp_1d_ss_table(signed short x, unsigned char n,
signed short *x_table, char sgn, signed short *z_table) {
int ix;
int interp, interp3;
// bound input arguments
if (x > x_table[n - 1])
return z_table[n - 1];
if (x < x_table[0])
return z_table[0];
for (ix = n - 2; ix > -1; ix--) {
if (x > x_table[ix]) {
break;
}
}
if (ix < 0)
ix = 0;
interp = x_table[ix + 1] - x_table[ix];
if (interp != 0) {
interp3 = (x - x_table[ix]);
interp3 = (100 * interp3);
interp = interp3 / interp;
}
return ((short) ((int) z_table[ix]
+ interp * ((int) z_table[ix + 1] - (int) z_table[ix]) / 100));
}
int intrp_1dstable(signed short x, unsigned char n, signed short *x_table,
char sgn, signed short *z_table) {
int ix;
long interp, interp3;
// bound input arguments
if (x > x_table[n - 1]) {
if (!sgn)
return ((int) z_table[n - 1]);
else
return ((signed int) ((signed short) z_table[n - 1]));
}
if (x < x_table[0]) {
if (!sgn)
return ((signed int) z_table[0]);
else
return ((signed int) ((signed short) z_table[0]));
}
for (ix = n - 2; ix > -1; ix--) {
if (x > x_table[ix]) {
break;
}
}
if (ix < 0)
ix = 0;
interp = x_table[ix + 1] - x_table[ix];
if (interp != 0) {
interp3 = (x - x_table[ix]);
interp3 = (100 * interp3);
interp = interp3 / interp;
}
if (!sgn)
return ((signed int) (z_table[ix]
+ interp * (z_table[ix + 1] - z_table[ix]) / 100));
else
return ((int) ((signed short) z_table[ix]
+ interp
* ((signed short) z_table[ix + 1]
- (signed short) z_table[ix]) / 100));
}
void DBW_Start(void) {
GPIOB->ODR &= ~D1_Pin;
GPIOB->ODR |= D2_Pin;
}
void DBW_Stop(void) {
GPIOB->ODR |= D1_Pin;
GPIOB->ODR &= ~D2_Pin;
}
void DBW_TPS_AutoCal(void) {
// if time to process autocal
if ((ac_timer == 0) && (ac_mode != 0)) {
if (ac_mode == 1) {
var.status0 |= DBW_STATUS0_PPSTPS_CAL_F;
DBW_Pwm_Set_Duty((signed short) (-6000), (pwm_t*) &ttl1_pwm);
DBW_Start();
ac_timer = 1500;
ac_mode = 2;
} else if (ac_mode == 2) {
uint32_t tmp = 0;
for (int i = 0; i < 16; i++)
tmp += Adc_Read(2);
config->tps1_min = tmp >> 4;
tmp = 0;
for (int i = 0; i < 16; i++)
tmp += Adc_Read(3);
config->tps2_min = tmp >> 4;
DBW_Stop();
ac_timer = 2000;
ac_mode = 3;
} else if (ac_mode == 3) {
DBW_Pwm_Set_Duty((signed short) (9000), (pwm_t*) &ttl1_pwm);
DBW_Start();
ac_timer = 1500;
ac_mode = 4;
} else if (ac_mode == 4) {
uint32_t tmp = 0;
for (int i = 0; i < 16; i++)
tmp += Adc_Read(2);
config->tps1_max = tmp >> 4;
tmp = 0;
for (int i = 0; i < 16; i++)
tmp += Adc_Read(3);
config->tps2_max = tmp >> 4;
DBW_Stop();
DBW_Pwm_Set_Duty((signed short) (0), (pwm_t*) &ttl1_pwm);
Apply_Sensor_Calibration();
Write_Config();
ac_timer = 10000;
ac_mode = 5;
Comms_Reset(&RX);
Comms_Reset(&TX);
USART1->ICR &= ~USART_CR1_RXNEIE;
NVIC_DisableIRQ(USART1_IRQn);
} else if (ac_mode == 5) {
ac_mode = 0;
var.status0 &= ~DBW_STATUS0_PPSTPS_CAL_F;
USART1->ICR |= USART_CR1_RXNEIE;
NVIC_EnableIRQ(USART1_IRQn);
}
}
}
void DBW_Read_sensors(void) {
var.pps1_adc = LPF(700, Adc_Read(0), var.pps1_adc);
var.pps1 = var.pps1_adc * pps1_gain + pps1_offset;
var.pps2_adc = LPF(700, Adc_Read(3), var.pps2_adc); // 1 is orig
var.pps2 = var.pps2_adc * pps2_gain + pps2_offset;
var.pps_delta = var.pps1 - var.pps2;
var.pps = (var.pps1 + var.pps2) >> 1;
//Calculate TPS sensor reading
var.tps1_adc = LPF(700, Adc_Read(2), var.tps1_adc);
var.tps1 = var.tps1_adc * tps1_gain + tps1_offset;
var.tps2_adc = LPF(700, Adc_Read(1), var.tps2_adc); //3 is orig
var.tps2 = var.tps2_adc * tps2_gain + tps2_offset;
// calculate tps and pps delta and values
var.tps_delta = var.tps1 - var.tps2;
var.tps = (var.tps1 + var.tps2) >> 1;
var.pps_delta = var.pps1 - var.pps2;
var.pps = (var.pps1 + var.pps2) >> 1;
}

119
DBW_V2/Core/Src/inputs.c Normal file
View File

@@ -0,0 +1,119 @@
/*
* inputs.c
*
* Created on: Mar 15, 2022
* Author: v0stap
*/
//Includes
#include "main.h"
//Variables
uint32_t counter0 = 0, counter1 = 0, Counter = 0;
uint8_t gap = 0;
// idle in section
void TIM3_Init(void) { //configure IN1 as Iddle input PB4 TIM3
// PB4 AF1 TIM3 Input1
RCC->AHBENR |= RCC_AHBENR_GPIOBEN;
GPIOB->MODER &= ~(3 << (4 * 2));
GPIOB->MODER |= (2 << (4 * 2));
GPIOB->OTYPER &= ~(1 << 4 * 1);
GPIOB->OSPEEDR &= ~(3 << (4 * 2));
GPIOB->PUPDR &= ~(3 << (4 * 2));
GPIOB->AFR[0] &= ~(15 << (4 * 4));
GPIOB->AFR[0] |= (1 << (4 * 4));
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN;
/* (1) Select the active input TI1 for TIM3_CCR1 (CC1S = 01),
select the active input TI1 for TIM3_CCR2 (CC2S = 10) */
/* (2) Select TI1FP1 as valid trigger input (TS = 101)
configure the slave mode in reset mode (SMS = 100) */
/* (3) Enable capture by setting CC1E and CC2E
select the rising edge on CC1 and CC1N (CC1P = 0 and CC1NP = 0, reset
value),
select the falling edge on CC2 (CC2P = 1). */
/* (4) Enable interrupt on Capture/Compare 1 */
/* (5) Enable counter */
TIM3->CCMR1 |= TIM_CCMR1_CC1S_0 | TIM_CCMR1_CC2S_1; /* (1)*/
TIM3->SMCR |= TIM_SMCR_TS_2 | TIM_SMCR_TS_0 | TIM_SMCR_SMS_2; /* (2) */
TIM3->CCER |= TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC2P; /* (3) */
TIM3->DIER |= TIM_DIER_CC1IE; /* (4) */
TIM3->CR1 |= TIM_CR1_CEN; /* (5) */
NVIC_EnableIRQ(TIM3_IRQn);
}
void TIM14_Init(void) { //configure IN2 as rpm input PB1 TIM14
// PB1 AF0 TIM14 Input1
// prescaler 1:21 ->1/4uS tick (since APBx presc !=1, timer clocks = APBx_cls x 2)
RCC->AHBENR |= RCC_AHBENR_GPIOBEN;
GPIOB->MODER &= ~(3 << (1 * 2));
GPIOB->MODER |= (2 << (1 * 2));
GPIOB->OTYPER &= ~(1 << 1 * 1);
GPIOB->OSPEEDR &= ~(3 << (1 * 2));
GPIOB->PUPDR &= ~(3 << (1 * 2));
GPIOB->AFR[0] &= ~(15 << (1 * 4));
GPIOB->AFR[0] |= (0 << (1 * 4));
RCC->APB1ENR |= RCC_APB1ENR_TIM14EN;
TIM14->ARR = 0xFFFF;
TIM14->PSC = 599;
/* (1) Select the active input TI1 (CC1S = 01),
program the input filter for 8 clock cycles (IC1F = 0011),
select the rising edge on CC1 (CC1P = 0, reset value)
and prescaler at each valid transition (IC1PS = 00, reset value) */
/* (2) Enable capture by setting CC1E */
/* (3) Enable interrupt on Capture/Compare */
/* (4) Enable counter */
TIM14->CCMR1 |= TIM_CCMR1_CC1S_0 | TIM_CCMR1_IC1F_0 | TIM_CCMR1_IC1F_1; /* (1)*/
TIM14->CCER |= TIM_CCER_CC1E; /* (2) */
TIM14->DIER |= TIM_DIER_CC1IE; /* (3) */
TIM14->CR1 |= TIM_CR1_CEN; /* (4) */
NVIC_EnableIRQ(TIM14_IRQn);
}
void TIM3_IRQHandler(void) {
if ((TIM3->SR & TIM_SR_CC1IF) != 0) {
if ((TIM3->SR & TIM_SR_CC1OF) != 0) /* Check the overflow */
{
/* Overflow error management */
/* Reinitialize the laps computing */
TIM3->SR &= ~(TIM_SR_CC1OF | TIM_SR_CC1IF); /* Clear the flags */
return;
} else {
counter0 = TIM3->CCR1;
var.idle_dc = (TIM3->CCR2) * 1000 / TIM3->CCR1; //Get DC
// printf("data1 =%d; data2 =%d \n",counter0,counter1);
}
} else {
/* Unexpected Interrupt */
/* Manage an error for robust application */
}
}
void TIM14_IRQHandler(void) {
if ((TIM14->SR & TIM_SR_CC1IF) != 0) {
if ((TIM14->SR & TIM_SR_CC1OF) != 0) /* Check the overflow */
{
/* Overflow error management */
/* Reinitialize the laps computing */
TIM14->SR &= ~(TIM_SR_CC1OF | TIM_SR_CC1IF); /* Clear the flags */
var.rpm = 0;
gap = 0;
return;
}
if (gap == 0) /* Test if it is the first rising edge */
{
counter0 = TIM14->CCR1; /* Read the capture counter which clears the
CC1ICF */
gap = 1; /* Indicate that the first rising edge has yet been detected */
} else {
counter1 = TIM14->CCR1; /* Read the capture counter which clears the
CC1ICF */
if (counter1 > counter0) /* Check capture counter overflow */
{
Counter = counter1 - counter0;
} else {
Counter = counter1 + 0xFFFF - counter0 + 1;
}
counter0 = counter1;
var.rpm = Counter;
}
} else {
/* Unexpected Interrupt */
/* Manage an error for robust application */
}
}

466
DBW_V2/Core/Src/main.c Normal file
View File

@@ -0,0 +1,466 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 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
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include <stdio.h>
#include <string.h>
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
ADC_HandleTypeDef hadc;
CAN_HandleTypeDef hcan;
UART_HandleTypeDef huart1;
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_ADC_Init(void);
//static void MX_CAN_Init(void);
static void MX_USART1_UART_Init(void);
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/**
* @brief The application entry point.
* @retval int
*/
int main(void) {
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
/* MCU Configuration--------------------------------------------------------*/
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
HAL_Init();
/* USER CODE BEGIN Init */
/* USER CODE END Init */
/* Configure the system clock */
SystemClock_Config();
/* USER CODE BEGIN SysInit */
/* USER CODE END SysInit */
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_ADC_Init();
// MX_CAN_Init();
MX_USART1_UART_Init();
/* USER CODE BEGIN 2 */
//load flash copy of config to RAM
// memcpy((void*)&config_ram,(void*)(0x0800F000), sizeof(config_t));
memcpy((void*) &config_ram, (void*) &config_flash, sizeof(config_t));
config = &config_ram;
//calculate gain and offset for PPS and TPS calc
Apply_Sensor_Calibration();
config->config_bits &= ~CONFIG_TESTMODE_F;
//clear momms
memset((void*) &var, 0, sizeof(var_t));
//Initialize TS Comms
Comms_Init();
NVIC_EnableIRQ(USART1_IRQn);
// check if safety features are enabled
if (config->config_bits & CONFIG_SAFETY_FEATURES_F) {
Check_Safety_Limits();
Safety_TPS_Safety_Timer_Start();
//TODO Watch_Dog_Init();
// change status
var.status1 |= DBW_STATUS1_SAFETY_F;
}
// if not change status to safy disabled
else
var.status1 &= ~DBW_STATUS1_SAFETY_F;
// Check if CAN has to be initialized
if ((config->pps2tps_option == PPS2TPS_OPTION_MS3_CAN)
|| (config->idle_input_option == IDLE_OPTION_MS_CAN)
|| config->can_ms29bit_options == 0x01) {
// Can_Init();
}
if (config->idle_input_option == IDLE_OPTION_PWM_INPUT1) {
TIM3_Init();
}
if (1) {
TIM14_Init(); //rpm input init
TIM16_Init(); // vss out init
TIM17_Init(); //Mazda rx8 can message init
}
Adc_Init();
DBW_Init();
DBW_Pwm_Init();
//check if program flash is write protected and set status
if (FLASH->WRPR & 0x00003FFF)
var.status0 |= DBW_STATUS0_UNPROTECTED_F;
else
var.status0 &= ~DBW_STATUS0_UNPROTECTED_F;
//check if agreement is set if so start DBW drive
if (config->config_bits & CONFIG_AGREEMENT_F) {
var.status0 |= DBW_STATUS0_AGREEMENT_F;
} else
var.status0 &= ~DBW_STATUS0_AGREEMENT_F;
// check if TPS and PPS are calibrated
if (config->config_bits & CONFIG_SENSORS_CALIBRATED_F) {
var.status0 |= DBW_STATUS0_SENSOR_CAL_F;
}
else {
var.status0 &= ~DBW_STATUS0_SENSOR_CAL_F;
}
// start DBW if sensors are calibrated and agreement is accepted
if ((var.status0 & DBW_STATUS0_AGREEMENT_F)
&& (var.status0 & DBW_STATUS0_SENSOR_CAL_F)) {
DBW_Start();
} else
DBW_Stop();
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while (1) {
/* USER CODE END WHILE */
// is something to be transmitted on serial
Poll_Tx();
// Update WDT and check ADC range if safety features are enabled
if ((var.status1 & DBW_STATUS1_SAFETY_F) && var.clock > 1000) {
//TODO Watch_Dog_Update();
Check_Adc_Range();
Check_TPS_Target();
}
//check if tesmode is turned on
if (config->config_bits & CONFIG_TESTMODE_F) {
var.status0 &= ~DBW_STATUS0_READY_F;
DBW_TPS_AutoCal();
DBW_Read_sensors();
} else {
DBW_Process();
}
CAN_Send_TX_Buffer();
if (1) {
MAZDA_CAN_Read();
}
/* USER CODE BEGIN 3 */
}
/* USER CODE END 3 */
}
/**
* @brief System Clock Configuration
* @retval None
*/
void SystemClock_Config(void) {
RCC_OscInitTypeDef RCC_OscInitStruct = { 0 };
RCC_ClkInitTypeDef RCC_ClkInitStruct = { 0 };
RCC_PeriphCLKInitTypeDef PeriphClkInit = { 0 };
/** Initializes the CPU, AHB and APB busses clocks
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI14
| RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.HSI14State = RCC_HSI14_ON;
RCC_OscInitStruct.HSI14CalibrationValue = 16;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL12;
RCC_OscInitStruct.PLL.PREDIV = RCC_PREDIV_DIV2;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
Error_Handler();
}
/** Initializes the CPU, AHB and APB busses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK
| RCC_CLOCKTYPE_PCLK1;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) {
Error_Handler();
}
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1;
PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK1;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) {
Error_Handler();
}
}
/**
* @brief ADC Initialization Function
* @param None
* @retval None
*/
static void MX_ADC_Init(void) {
/* USER CODE BEGIN ADC_Init 0 */
/* USER CODE END ADC_Init 0 */
ADC_ChannelConfTypeDef sConfig = { 0 };
/* USER CODE BEGIN ADC_Init 1 */
/* USER CODE END ADC_Init 1 */
/** Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)
*/
hadc.Instance = ADC1;
hadc.Init.ClockPrescaler = ADC_CLOCK_ASYNC_DIV1;
hadc.Init.Resolution = ADC_RESOLUTION_12B;
hadc.Init.DataAlign = ADC_DATAALIGN_RIGHT;
hadc.Init.ScanConvMode = ADC_SCAN_DIRECTION_FORWARD;
hadc.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
hadc.Init.LowPowerAutoWait = DISABLE;
hadc.Init.LowPowerAutoPowerOff = DISABLE;
hadc.Init.ContinuousConvMode = DISABLE;
hadc.Init.DiscontinuousConvMode = DISABLE;
hadc.Init.ExternalTrigConv = ADC_SOFTWARE_START;
hadc.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE;
hadc.Init.DMAContinuousRequests = DISABLE;
hadc.Init.Overrun = ADC_OVR_DATA_PRESERVED;
if (HAL_ADC_Init(&hadc) != HAL_OK) {
Error_Handler();
}
/** Configure for the selected ADC regular channel to be converted.
*/
sConfig.Channel = ADC_CHANNEL_0;
sConfig.Rank = ADC_RANK_CHANNEL_NUMBER;
sConfig.SamplingTime = ADC_SAMPLETIME_1CYCLE_5;
if (HAL_ADC_ConfigChannel(&hadc, &sConfig) != HAL_OK) {
Error_Handler();
}
/** Configure for the selected ADC regular channel to be converted.
*/
sConfig.Channel = ADC_CHANNEL_1;
if (HAL_ADC_ConfigChannel(&hadc, &sConfig) != HAL_OK) {
Error_Handler();
}
/** Configure for the selected ADC regular channel to be converted.
*/
sConfig.Channel = ADC_CHANNEL_2;
if (HAL_ADC_ConfigChannel(&hadc, &sConfig) != HAL_OK) {
Error_Handler();
}
/** Configure for the selected ADC regular channel to be converted.
*/
sConfig.Channel = ADC_CHANNEL_3;
if (HAL_ADC_ConfigChannel(&hadc, &sConfig) != HAL_OK) {
Error_Handler();
}
/** Configure for the selected ADC regular channel to be converted.
*/
sConfig.Channel = ADC_CHANNEL_4;
if (HAL_ADC_ConfigChannel(&hadc, &sConfig) != HAL_OK) {
Error_Handler();
}
/** Configure for the selected ADC regular channel to be converted.
*/
sConfig.Channel = ADC_CHANNEL_5;
if (HAL_ADC_ConfigChannel(&hadc, &sConfig) != HAL_OK) {
Error_Handler();
}
/* USER CODE BEGIN ADC_Init 2 */
/* USER CODE END ADC_Init 2 */
}
/**
* @brief CAN Initialization Function
* @param None
* @retval None
*/
//static void MX_CAN_Init(void) {
//
// /* USER CODE BEGIN CAN_Init 0 */
//
// /* USER CODE END CAN_Init 0 */
//
// /* USER CODE BEGIN CAN_Init 1 */
//
// /* USER CODE END CAN_Init 1 */
// hcan.Instance = CAN;
// hcan.Init.Prescaler = 16;
// hcan.Init.Mode = CAN_MODE_NORMAL;
// hcan.Init.SyncJumpWidth = CAN_SJW_1TQ;
// hcan.Init.TimeSeg1 = CAN_BS1_1TQ;
// hcan.Init.TimeSeg2 = CAN_BS2_1TQ;
// hcan.Init.TimeTriggeredMode = DISABLE;
// hcan.Init.AutoBusOff = DISABLE;
// hcan.Init.AutoWakeUp = DISABLE;
// hcan.Init.AutoRetransmission = DISABLE;
// hcan.Init.ReceiveFifoLocked = DISABLE;
// hcan.Init.TransmitFifoPriority = DISABLE;
// if (HAL_CAN_Init(&hcan) != HAL_OK) {
// Error_Handler();
// }
// /* USER CODE BEGIN CAN_Init 2 */
//
// /* USER CODE END CAN_Init 2 */
//
//}
/**
* @brief USART1 Initialization Function
* @param None
* @retval None
*/
static void MX_USART1_UART_Init(void) {
/* USER CODE BEGIN USART1_Init 0 */
/* USER CODE END USART1_Init 0 */
/* USER CODE BEGIN USART1_Init 1 */
/* USER CODE END USART1_Init 1 */
huart1.Instance = USART1;
huart1.Init.BaudRate = 115200;
huart1.Init.WordLength = UART_WORDLENGTH_8B;
huart1.Init.StopBits = UART_STOPBITS_1;
huart1.Init.Parity = UART_PARITY_NONE;
huart1.Init.Mode = UART_MODE_TX_RX;
huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart1.Init.OverSampling = UART_OVERSAMPLING_16;
huart1.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
huart1.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
if (HAL_UART_Init(&huart1) != HAL_OK) {
Error_Handler();
}
/* USER CODE BEGIN USART1_Init 2 */
/* USER CODE END USART1_Init 2 */
}
/**
* @brief GPIO Initialization Function
* @param None
* @retval None
*/
static void MX_GPIO_Init(void) {
GPIO_InitTypeDef GPIO_InitStruct = { 0 };
/* GPIO Ports Clock Enable */
__HAL_RCC_GPIOF_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOB,
PWM1_Pin | PWM2_Pin | FAULT_Pin | D2_Pin | D1_Pin | GPO1_Pin
| GPO2_1_Pin | GPO2_2_Pin, GPIO_PIN_RESET);
/*Configure GPIO pins : IN1_Pin IN2_Pin STATUS_FLAG_Pin */
// GPIO_InitStruct.Pin = IN1_Pin|IN2_Pin|STATUS_FLAG_Pin;
// GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
// GPIO_InitStruct.Pull = GPIO_NOPULL;
// HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/*Configure GPIO pins : PWM1_Pin PWM2_Pin FAULT_Pin D2_Pin
D1_Pin GPO1_Pin GPO2_1_Pin GPO2_2_Pin */
GPIO_InitStruct.Pin = PWM1_Pin | PWM2_Pin | FAULT_Pin | D2_Pin | D1_Pin
| GPO1_Pin | GPO2_1_Pin | GPO2_2_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
}
/* USER CODE BEGIN 4 */
/* USER CODE END 4 */
/**
* @brief This function is executed in case of error occurrence.
* @retval None
*/
void Error_Handler(void) {
/* USER CODE BEGIN Error_Handler_Debug */
/* User can add his own implementation to report the HAL error return state */
/* USER CODE END Error_Handler_Debug */
}
#ifdef USE_FULL_ASSERT
/**
* @brief Reports the name of the source file and the source line number
* where the assert_param error has occurred.
* @param file: pointer to the source file name
* @param line: assert_param error line source number
* @retval None
*/
void assert_failed(char *file, uint32_t line)
{
/* USER CODE BEGIN 6 */
/* User can add his own implementation to report the file name and line number,
tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
/* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

171
DBW_V2/Core/Src/mazda_can.c Normal file
View File

@@ -0,0 +1,171 @@
/*
* mazda_can.c
*
* Created on: Mar 17, 2022
* Author: v0stap
*/
/*
* app.c
*
* Created on: Jul 25, 2020
* Author: v0stap
*/
#include "main.h"
uint32_t var_time = 0, rpm_time = 0, can_tim = 0;
can_msg_typedef tmpCanMsg;
//https://www.chamberofunderstanding.co.uk/2021/06/11/rx8-project-part-21-canbus-6-working-code/
void MAZDA_Send_Data(void) {
can_tim++;
tmpCanMsg.id = 0x201; // Send RPM = Actual RPM * 3.85 Throttle Pedal 0x00 - 0xC8 in 0.5% increments Send KPH = (Actual KPH * 100) + 10000
tmpCanMsg.format = STD_FORMAT;
tmpCanMsg.frame = DATA_FRAME;
tmpCanMsg.lenght = 7;
tmpCanMsg.data[0] = (((uint16_t) (var.rpm * 3.85)) >> 8); // RPM high
tmpCanMsg.data[1] = (uint8_t) ((var.rpm) * 3.85); // RPM low
tmpCanMsg.data[2] = 0xFF;
tmpCanMsg.data[3] = 0xFF;
tmpCanMsg.data[4] = (var.vss * 100 + 10000) >> 8; // VSS KPH high
tmpCanMsg.data[5] = (var.vss * 100 + 10000); // VSS KPH low
tmpCanMsg.data[6] = var.pps / 5; // TPS
tmpCanMsg.data[7] = 0xFF;
CAN_Add_TX_Buffer(&tmpCanMsg);
tmpCanMsg.id = 0x250;
tmpCanMsg.format = STD_FORMAT;
tmpCanMsg.frame = DATA_FRAME;
tmpCanMsg.lenght = 8;
tmpCanMsg.data[0] = 0x00;
tmpCanMsg.data[1] = 0x00;
tmpCanMsg.data[2] = 0xCF;
tmpCanMsg.data[3] = 0x87;
tmpCanMsg.data[4] = 0x7F;
tmpCanMsg.data[5] = 0x83;
tmpCanMsg.data[6] = 0x00;
tmpCanMsg.data[7] = 0x00;
CAN_Add_TX_Buffer(&tmpCanMsg);
tmpCanMsg.id = 0x620; // Type of ABS
tmpCanMsg.format = STD_FORMAT;
tmpCanMsg.frame = DATA_FRAME;
tmpCanMsg.lenght = 1;
tmpCanMsg.data[0] = 0x00;
tmpCanMsg.data[1] = 0x00;
tmpCanMsg.data[2] = 0x00;
tmpCanMsg.data[3] = 0x00;
tmpCanMsg.data[4] = 0x00;
tmpCanMsg.data[5] = 0x00;
tmpCanMsg.data[6] = 0x02; // ABS type 2,3 or 4
tmpCanMsg.data[7] = 0x00;
CAN_Add_TX_Buffer(&tmpCanMsg);
tmpCanMsg.id = 0x630; // Type of Transmission and Wheel Size
tmpCanMsg.format = STD_FORMAT;
tmpCanMsg.frame = DATA_FRAME;
tmpCanMsg.lenght = 1;
tmpCanMsg.data[0] = 0x08; //8 = MT, 2 = AT
tmpCanMsg.data[1] = 0x00;
tmpCanMsg.data[2] = 0x00;
tmpCanMsg.data[3] = 0x00;
tmpCanMsg.data[4] = 0x00;
tmpCanMsg.data[5] = 0x00;
tmpCanMsg.data[6] = 0x6A; // Wheel Size
tmpCanMsg.data[7] = 0x6A; // Wheel Size
CAN_Add_TX_Buffer(&tmpCanMsg);
tmpCanMsg.id = 0x650; // CRUISE CONTROL
tmpCanMsg.format = STD_FORMAT;
tmpCanMsg.frame = DATA_FRAME;
tmpCanMsg.lenght = 1;
tmpCanMsg.data[0] = 0x00; // 0x40 Green 0x80 Yellow 0xC0 Both
//tmpCanMsg.data[1] = 0;
//tmpCanMsg.data[2] = 0xcf;
//tmpCanMsg.data[3] = 0x87;
//tmpCanMsg.data[4] = 0x7f;
//tmpCanMsg.data[5] = 0x83;
//tmpCanMsg.data[6] = 0;
//tmpCanMsg.data[7] = 0;
CAN_Add_TX_Buffer(&tmpCanMsg);
if (can_tim>4){
can_tim = 0;
tmpCanMsg.id = 0x203; //This needs sending witin 0.5 seconds of ignition otherwise traction light will come on
tmpCanMsg.format = STD_FORMAT;
tmpCanMsg.frame = DATA_FRAME;
tmpCanMsg.lenght = 7;
tmpCanMsg.data[0] = 0x16;
tmpCanMsg.data[1] = 0x16;
tmpCanMsg.data[2] = 0x16;
tmpCanMsg.data[3] = 0x16;
tmpCanMsg.data[4] = 0xAF;
tmpCanMsg.data[5] = 3;
tmpCanMsg.data[6] = 0x16;
//tmpCanMsg.data[7] = ;
CAN_Add_TX_Buffer(&tmpCanMsg);
tmpCanMsg.id = 0x215; // This needs sending witin 0.5 seconds of ignition otherwise traction light will come on
tmpCanMsg.format = STD_FORMAT;
tmpCanMsg.frame = DATA_FRAME;
tmpCanMsg.lenght = 8;
tmpCanMsg.data[0] = 0x02;
tmpCanMsg.data[1] = 0x2D;
tmpCanMsg.data[2] = 0x02;
tmpCanMsg.data[3] = 0x2D;
tmpCanMsg.data[4] = 0x02;
tmpCanMsg.data[5] = 0x2A;
tmpCanMsg.data[6] = 0x06;
tmpCanMsg.data[7] = 0x81;
CAN_Add_TX_Buffer(&tmpCanMsg);
tmpCanMsg.id = 0x231; // This needs sending witin 0.5 seconds of ignition otherwise traction light will come on
tmpCanMsg.format = STD_FORMAT;
tmpCanMsg.frame = DATA_FRAME;
tmpCanMsg.lenght = 5;
tmpCanMsg.data[0] = 15;
tmpCanMsg.data[1] = 0;
tmpCanMsg.data[2] = 0xff;
tmpCanMsg.data[3] = 0xff;
tmpCanMsg.data[4] = 0x00;
//tmpCanMsg.data[5] = 0x37;
//tmpCanMsg.data[6] = 0x06;
//tmpCanMsg.data[7] = 0x81;
CAN_Add_TX_Buffer(&tmpCanMsg);
tmpCanMsg.id = 0x240; // This needs sending witin 0.5 seconds of ignition otherwise traction light will come on
tmpCanMsg.format = STD_FORMAT;
tmpCanMsg.frame = DATA_FRAME;
tmpCanMsg.lenght = 8;
tmpCanMsg.data[0] = 0x04;
tmpCanMsg.data[1] = 0;
tmpCanMsg.data[2] = 40;
tmpCanMsg.data[3] = 0x00;
tmpCanMsg.data[4] = 0x02;
tmpCanMsg.data[5] = 55;
tmpCanMsg.data[6] = 0x06;
tmpCanMsg.data[7] = 0x81;
CAN_Add_TX_Buffer(&tmpCanMsg);
}
}
void MAZDA_CAN_Read(void) {
CAN_Read_RX_Buffer(&tmpCanMsg);
if (tmpCanMsg.id == 0x4c0) {
tmpCanMsg.id = 0x420; // Engine Temp Odometer from 4c0 Oil Pressure Check Engine Low Water Bat Charge Oil Pressure
tmpCanMsg.format = STD_FORMAT;
tmpCanMsg.frame = DATA_FRAME;
tmpCanMsg.lenght = 8;
tmpCanMsg.data[0] = 0x00; // clt
tmpCanMsg.data[1] = tmpCanMsg.data[1]; // Odometer from 4c0 (pwm)
tmpCanMsg.data[2] = 0x00;
tmpCanMsg.data[3] = 0x00;
tmpCanMsg.data[4] = 0x00; //Oil Pressure 0x00 - 0x01 (pwm)
tmpCanMsg.data[5] = 0x00; // Check Engine Bit 7 MIL Check Engine Bit 8 BL
tmpCanMsg.data[6] = 0;
if (var.vbat_adc < 1200) {
tmpCanMsg.data[6] |= 1 << 2;
} else {
tmpCanMsg.data[6] &= ~(1 << 2);
}
//tmpCanMsg.data[6] = var.ic_status2; //Low Water Bit 2 MIL Bat Charge Bit 7 MIL Oil Pressure Bit 8 MIL
tmpCanMsg.data[7] = 0x00;
CAN_Add_TX_Buffer(&tmpCanMsg);
} else if (tmpCanMsg.id == 0x4B1) {
var.vss = ((tmpCanMsg.data[4] << 8) + tmpCanMsg.data[5] + (tmpCanMsg.data[6] << 8) + tmpCanMsg.data[7]) / 4;
//todo // add option to make vss output on/off
VSS_Set((uint8_t)var.vss);
}
}

60
DBW_V2/Core/Src/outputs.c Normal file
View File

@@ -0,0 +1,60 @@
/*
* outputs.c
*
* Created on: Mar 16, 2022
* Author: v0stap
*/
#include "main.h"
void TIM16_Init(void) {
RCC->APB2ENR |= RCC_APB2ENR_TIM16EN;
TIM16->PSC = 480;
TIM16->ARR = 70287;
TIM16->CR1 |= 1 << 0 | 1 << 7;
TIM16->CR2 = 0;
TIM16->SMCR = 0;
TIM16->DIER = 1 << 0;
TIM16->CCMR1 = 0;
TIM16->CCMR2 = 0;
TIM16->CCER = 0x1111;
TIM16->SR = 0;
NVIC_EnableIRQ(TIM16_IRQn);
}
void TIM17_Init(void) {
RCC->APB2ENR |= RCC_APB2ENR_TIM17EN;
TIM17->PSC = 479;
TIM17->ARR = 10000;
TIM17->CR1 |= 1 << 0 | 1 << 7;
TIM17->CR2 = 0;
TIM17->SMCR = 0;
TIM17->DIER = 1 << 0;
TIM17->CCMR1 = 0;
TIM17->CCMR2 = 0;
TIM17->CCER = 0x1111;
TIM17->SR = 0;
NVIC_EnableIRQ(TIM17_IRQn);
}
void VSS_Set(uint8_t vss) {
if (vss < 3) {
TIM16->CR1 &= ~(1 << 0);
} else {
TIM16->CR1 |= 1 << 0;
TIM16->ARR = 70287 / vss;
}
}
void TIM16_IRQHandler(void) {
TIM16->SR &= ~(1 << 0);
//TIM2->CNT = 600;
HAL_GPIO_TogglePin(GPIOB, GPO1_Pin);
}
void TIM17_IRQHandler(void) {
TIM17->SR &= ~(1 << 0);
//TIM2->CNT = 600;
MAZDA_Send_Data();
}

390
DBW_V2/Core/Src/safety.c Normal file
View File

@@ -0,0 +1,390 @@
/*
* safety.c
*
* Created on: 12 May 2021
* Author: Dmitrijs
*/
#include "main.h"
#include "dbw.h"
#include "ts_comms.h"
#include "safety.h"
const char msg1[42] = { "PPS1 Safety margin >4095 or less then 0\r\n" };
const char msg2[42] = { "PPS2 Safety margin >4095 or less then 0\r\n" };
const char msg3[42] = { "TPS1 Safety margin >4095 or less then 0\r\n" };
const char msg4[42] = { "TPS2 Safety margin >4095 or less then 0\r\n" };
void Flash_Write_Protect(void) {
FLASH_OBProgramInitTypeDef p;
p.OptionType = OPTIONBYTE_WRP;
p.WRPState = OB_WRPSTATE_ENABLE;
HAL_FLASH_Unlock();
HAL_FLASH_OB_Unlock();
HAL_FLASHEx_OBErase();
p.WRPPage = 0x00003FFF;
HAL_FLASHEx_OBProgram(&p);
FLASH_WaitForLastOperation((uint32_t) FLASH_TIMEOUT_VALUE);
HAL_FLASH_OB_Lock();
HAL_FLASH_Lock();
HAL_FLASH_OB_Launch();
}
void Flash_Write_Unprotect(void) {
FLASH_OBProgramInitTypeDef p;
p.OptionType = OPTIONBYTE_WRP;
p.WRPState = OB_WRPSTATE_DISABLE;
HAL_FLASH_Unlock();
HAL_FLASH_OB_Unlock();
HAL_FLASHEx_OBErase();
p.WRPPage = 0x00003FFF;
HAL_FLASHEx_OBProgram(&p);
FLASH_WaitForLastOperation((uint32_t) FLASH_TIMEOUT_VALUE);
HAL_FLASH_OB_Lock();
HAL_FLASH_Lock();
HAL_FLASH_OB_Launch();
}
void Watch_Dog_Update(void) {
IWDG->KR = 0x0000AAAA; // update wd timer
}
void Watch_Dog_Init(void) {
IWDG->KR = 0x0000CCCC; // enable watchdog
IWDG->KR = 0x00005555; // enable register access
while (IWDG->SR)
;
IWDG->PR = 0x00000000; // prescaler LSI / 4
while (IWDG->SR)
;
IWDG->RLR = 1000; // set timeout to 100mS
while (IWDG->SR)
;
IWDG->KR = 0x0000AAAA; // enable register access
while (IWDG->SR)
;
}
void Check_Safety_Limits(void) {
//PPS1
if (config->pps1_min < config->pps1_max) {
if ((config->pps1_margin > config->pps1_min)
|| ((config->pps1_max + config->pps1_margin) > 4095)) {
//config errror
var.status0 |= DBW_STATUS0_CONF_ERROR_F;
DBW_Stop();
TX_Schedule((unsigned char*) msg1, 42);
}
} else {
//config->pps1_min > config->pps1_max
if ((config->pps1_margin > config->pps1_max)
|| ((config->pps1_min + config->pps1_margin) > 4095)) {
//config errror
var.status0 |= DBW_STATUS0_CONF_ERROR_F;
DBW_Stop();
TX_Schedule((unsigned char*) msg1, 42);
}
}
//PPS2
if (config->pps2_min < config->pps2_max) {
if ((config->pps2_margin > config->pps2_min)
|| ((config->pps2_max + config->pps2_margin) > 4095)) {
//config errror
var.status0 |= DBW_STATUS0_CONF_ERROR_F;
DBW_Stop();
TX_Schedule((unsigned char*) msg2, 42);
}
} else {
//config->pps2_min > config->pps1_max
if ((config->pps2_margin > config->pps2_max)
|| ((config->pps2_min + config->pps2_margin) > 4095)) {
//config errror
var.status0 |= DBW_STATUS0_CONF_ERROR_F;
DBW_Stop();
TX_Schedule((unsigned char*) msg2, 42);
}
}
//TPS1
if (config->tps1_min < config->tps1_max) {
if ((config->tps1_margin > config->tps1_min)
|| ((config->tps1_max + config->tps1_margin) > 4095)) {
//config errror
var.status0 |= DBW_STATUS0_CONF_ERROR_F;
DBW_Stop();
TX_Schedule((unsigned char*) msg3, 42);
}
} else {
//config->tps1_min > config->tps1_max
if ((config->tps1_margin > config->tps1_max)
|| ((config->tps1_min + config->tps1_margin) > 4095)) {
//config errror
var.status0 |= DBW_STATUS0_CONF_ERROR_F;
DBW_Stop();
TX_Schedule((unsigned char*) msg3, 42);
}
}
//TPS2
if (config->tps2_min < config->tps2_max) {
if ((config->tps2_margin > config->tps2_min)
|| ((config->tps2_max + config->tps2_margin) > 4095)) {
//config errror
var.status0 |= DBW_STATUS0_CONF_ERROR_F;
DBW_Stop();
TX_Schedule((unsigned char*) msg4, 42);
}
} else {
//config->tps2_min > config->tps1_max
if ((config->tps2_margin > config->tps2_max)
|| ((config->tps2_min + config->tps2_margin) > 4095)) {
//config errror
var.status0 |= DBW_STATUS0_CONF_ERROR_F;
DBW_Stop();
TX_Schedule((unsigned char*) msg4, 42);
}
}
}
void Check_Adc_Range(void) {
//PPS1
if (config->pps1_min < config->pps1_max) {
if (var.pps1_adc < (config->pps1_min - config->pps1_margin)) {
//Fault condition PPS1 min
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_PPS1_SS_GND;
}
if (var.pps1_adc > (config->pps1_max + config->pps1_margin)) {
//Fault condition PPS1 MAX
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_PPS1_SS_VREF;
}
} else {
//config->pps1_min < config->pps1_max
if (var.pps1_adc < (config->pps1_max - config->pps1_margin)) {
//Fault condition PPS1 min
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_PPS1_SS_GND;
}
if (var.pps1_adc > (config->pps1_min + config->pps1_margin)) {
//Fault condition PPS1 MAX
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_PPS1_SS_VREF;
}
}
//PPS2
if (config->pps2_min < config->pps2_max) {
if (var.pps2_adc < (config->pps2_min - config->pps2_margin)) {
//Fault condition PPS1 min
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_PPS2_SS_GND;
}
if (var.pps2_adc > (config->pps2_max + config->pps2_margin)) {
//Fault condition PPS1 MAX
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_PPS1_SS_VREF;
}
} else {
if (var.pps2_adc < (config->pps2_max - config->pps2_margin)) {
//Fault condition PPS1 min
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_PPS2_SS_GND;
}
if (var.pps2_adc > (config->pps2_min + config->pps2_margin)) {
//Fault condition PPS1 MAX
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_PPS1_SS_VREF;
}
}
//PPS Delta
if ((var.pps_delta > config->pps_delta_margin)
|| (var.pps_delta < ((int16_t) -config->pps_delta_margin))) {
//Fault condition PPS DELTA
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_PPS_DELTA;
}
//##########################################
//TPS1
if (config->tps1_min < config->tps1_max) {
if (var.tps1_adc < (config->tps1_min - config->tps1_margin)) {
//Fault condition PPS1 min
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_TPS1_SS_GND;
}
if (var.tps1_adc > (config->tps1_max + config->tps1_margin)) {
//Fault condition TPS1 MAX
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_TPS1_SS_VREF;
}
} else {
if (var.tps1_adc < (config->tps1_max - config->tps1_margin)) {
//Fault condition PPS1 min
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_TPS1_SS_GND;
}
if (var.tps1_adc > (config->tps1_min + config->tps1_margin)) {
//Fault condition TPS1 MAX
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_TPS1_SS_VREF;
}
}
//TPS2
if (config->tps2_min < config->tps2_max) {
if (var.tps2_adc < (config->tps2_min - config->tps2_margin)) {
//Fault condition PPS1 min
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_TPS2_SS_GND;
}
if (var.tps2_adc > (config->tps2_max + config->tps2_margin)) {
//Fault condition TPS2 MAX
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_TPS2_SS_VREF;
}
} else {
if (var.tps2_adc < (config->tps2_max - config->tps2_margin)) {
//Fault condition PPS1 min
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_TPS2_SS_GND;
}
if (var.tps2_adc > (config->tps2_min + config->tps2_margin)) {
//Fault condition TPS2 MAX
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_TPS2_SS_VREF;
}
}
//TPS Delta
if ((var.tps_delta > config->tps_delta_margin)
|| (var.tps_delta < ((int16_t) -config->tps_delta_margin))) {
//Fault condition PPS DELTA
var.status0 |= DBW_STATUS0_SENSOR_FAULT_F;
DBW_Stop();
var.status3 = STATUS3_TPS_DELTA;
}
}
volatile int dbw_target_tmr1, dbw_target_tmr2;
void Safety_TPS_Safety_Timer(void) {
if (dbw_target_tmr1 > 0)
dbw_target_tmr1--;
if (dbw_target_tmr2 > 0)
dbw_target_tmr2--;
}
void Safety_TPS_Safety_Timer_Start(void) {
//enable timers. add 1S time to start, because safety system starts in 1S after startup
dbw_target_tmr1 = config->tps_error_time1 + 1000;
dbw_target_tmr2 = config->tps_error_time2 + 1000;
}
void Check_TPS_Target() {
if (var.tps_error > 0) {
//check if tps is within specified target
if (var.tps_error < config->tps_error_margin1)
dbw_target_tmr1 = config->tps_error_time1;
else {
// if not in range in specified time
if (dbw_target_tmr1 == 0) {
//fault
var.status0 |= DBW_STATUS0_FAULT_F;
DBW_Stop();
var.status2 = STATUS3_TARGET1_FAULT;
}
}
if (var.tps_error < config->tps_error_margin2)
dbw_target_tmr2 = config->tps_error_time2;
else {
// if not in range in specified time
if (dbw_target_tmr2 == 0) {
//fault
var.status0 |= DBW_STATUS0_FAULT_F;
DBW_Stop();
var.status2 = STATUS3_TARGET2_FAULT;
}
}
}
else {
//tps_error<0
//check if tps is within specified target
if (var.tps_error > (-config->tps_error_margin1))
dbw_target_tmr1 = config->tps_error_time1;
else {
// if not in range in specified time
if (dbw_target_tmr1 == 0) {
//fault
var.status0 |= DBW_STATUS0_FAULT_F;
DBW_Stop();
var.status2 = STATUS3_TARGET1_FAULT;
}
}
if (var.tps_error > (-config->tps_error_margin2))
dbw_target_tmr2 = config->tps_error_time2;
else {
// if not in range in specified time
if (dbw_target_tmr2 == 0) {
//fault
var.status0 |= DBW_STATUS0_FAULT_F;
DBW_Stop();
var.status2 = STATUS3_TARGET2_FAULT;
}
}
}
}

View File

@@ -0,0 +1,275 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* File Name : stm32f0xx_hal_msp.c
* Description : This file provides code for the MSP Initialization
* and de-Initialization codes.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 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
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN TD */
/* USER CODE END TD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN Define */
/* USER CODE END Define */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN Macro */
/* USER CODE END Macro */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* External functions --------------------------------------------------------*/
/* USER CODE BEGIN ExternalFunctions */
/* USER CODE END ExternalFunctions */
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/**
* Initializes the Global MSP.
*/
void HAL_MspInit(void) {
/* USER CODE BEGIN MspInit 0 */
/* USER CODE END MspInit 0 */
__HAL_RCC_SYSCFG_CLK_ENABLE();
__HAL_RCC_PWR_CLK_ENABLE();
/* System interrupt init*/
/* USER CODE BEGIN MspInit 1 */
/* 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_GPIOA_CLK_ENABLE();
/**ADC GPIO Configuration
PA0 ------> ADC_IN0
PA1 ------> ADC_IN1
PA2 ------> ADC_IN2
PA3 ------> ADC_IN3
PA4 ------> ADC_IN4
PA5 ------> ADC_IN5
*/
GPIO_InitStruct.Pin = PPS1_Pin | PPS2_Pin | TPS1_Pin | TPS2_Pin
| TTL_FB_Pin | VBAT_SENSE_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &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();
/**ADC GPIO Configuration
PA0 ------> ADC_IN0
PA1 ------> ADC_IN1
PA2 ------> ADC_IN2
PA3 ------> ADC_IN3
PA4 ------> ADC_IN4
PA5 ------> ADC_IN5
*/
HAL_GPIO_DeInit(GPIOA,
PPS1_Pin | PPS2_Pin | TPS1_Pin | TPS2_Pin | TTL_FB_Pin
| VBAT_SENSE_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
* @param hcan: CAN handle pointer
* @retval None
*/
void HAL_CAN_MspInit(CAN_HandleTypeDef *hcan) {
GPIO_InitTypeDef GPIO_InitStruct = { 0 };
if (hcan->Instance == CAN) {
/* USER CODE BEGIN CAN_MspInit 0 */
/* USER CODE END CAN_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_CAN1_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**CAN GPIO Configuration
PA11 ------> CAN_RX
PA12 ------> CAN_TX
*/
GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF4_CAN;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USER CODE BEGIN CAN_MspInit 1 */
/* USER CODE END CAN_MspInit 1 */
}
}
/**
* @brief CAN MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hcan: CAN handle pointer
* @retval None
*/
void HAL_CAN_MspDeInit(CAN_HandleTypeDef *hcan) {
if (hcan->Instance == CAN) {
/* USER CODE BEGIN CAN_MspDeInit 0 */
/* USER CODE END CAN_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_CAN1_CLK_DISABLE();
/**CAN GPIO Configuration
PA11 ------> CAN_RX
PA12 ------> CAN_TX
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11 | GPIO_PIN_12);
/* USER CODE BEGIN CAN_MspDeInit 1 */
/* USER CODE END CAN_MspDeInit 1 */
}
}
/**
* @brief UART MSP Initialization
* This function configures the hardware resources used in this example
* @param huart: UART handle pointer
* @retval None
*/
void HAL_UART_MspInit(UART_HandleTypeDef *huart) {
GPIO_InitTypeDef GPIO_InitStruct = { 0 };
if (huart->Instance == USART1) {
/* USER CODE BEGIN USART1_MspInit 0 */
/* USER CODE END USART1_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_USART1_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**USART1 GPIO Configuration
PA9 ------> USART1_TX
PA10 ------> USART1_RX
*/
GPIO_InitStruct.Pin = GPIO_PIN_9 | GPIO_PIN_10;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF1_USART1;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USER CODE BEGIN USART1_MspInit 1 */
/* USER CODE END USART1_MspInit 1 */
}
}
/**
* @brief UART MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param huart: UART handle pointer
* @retval None
*/
void HAL_UART_MspDeInit(UART_HandleTypeDef *huart) {
if (huart->Instance == USART1) {
/* USER CODE BEGIN USART1_MspDeInit 0 */
/* USER CODE END USART1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_USART1_CLK_DISABLE();
/**USART1 GPIO Configuration
PA9 ------> USART1_TX
PA10 ------> USART1_RX
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_9 | GPIO_PIN_10);
/* USER CODE BEGIN USART1_MspDeInit 1 */
/* USER CODE END USART1_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,156 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f0xx_it.c
* @brief Interrupt Service Routines.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 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
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "stm32f0xx_it.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "ts_comms.h"
#include "dbw.h"
#include "can.h"
#include "safety.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN TD */
/* USER CODE END TD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/******************************************************************************/
/* Cortex-M0 Processor Interruption and Exception Handlers */
/******************************************************************************/
/**
* @brief This function handles Non maskable interrupt.
*/
void NMI_Handler(void) {
/* USER CODE BEGIN NonMaskableInt_IRQn 0 */
/* USER CODE END NonMaskableInt_IRQn 0 */
/* USER CODE BEGIN NonMaskableInt_IRQn 1 */
/* USER CODE END NonMaskableInt_IRQn 1 */
}
/**
* @brief This function handles Hard fault interrupt.
*/
void HardFault_Handler(void) {
/* USER CODE BEGIN HardFault_IRQn 0 */
/* USER CODE END HardFault_IRQn 0 */
while (1) {
/* USER CODE BEGIN W1_HardFault_IRQn 0 */
/* USER CODE END W1_HardFault_IRQn 0 */
}
}
/**
* @brief This function handles System service call via SWI instruction.
*/
void SVC_Handler(void) {
/* USER CODE BEGIN SVC_IRQn 0 */
/* USER CODE END SVC_IRQn 0 */
/* USER CODE BEGIN SVC_IRQn 1 */
/* USER CODE END SVC_IRQn 1 */
}
/**
* @brief This function handles Pendable request for system service.
*/
void PendSV_Handler(void) {
/* USER CODE BEGIN PendSV_IRQn 0 */
/* USER CODE END PendSV_IRQn 0 */
/* USER CODE BEGIN PendSV_IRQn 1 */
/* USER CODE END PendSV_IRQn 1 */
}
/**
* @brief This function handles System tick timer.
*/
void SysTick_Handler(void) {
/* USER CODE BEGIN SysTick_IRQn 0 */
/* USER CODE END SysTick_IRQn 0 */
HAL_IncTick();
/* USER CODE BEGIN SysTick_IRQn 1 */
var.clock++;
TS_Comms_RX_Timeout();
if (dbw_fast_process_timer)
dbw_fast_process_timer--;
//Can_Timeouts();
if ((ac_mode != 0) && (config->config_bits & CONFIG_TESTMODE_F)) {
if (ac_timer)
ac_timer--;
}
Safety_TPS_Safety_Timer();
/* USER CODE END SysTick_IRQn 1 */
}
/******************************************************************************/
/* STM32F0xx Peripheral Interrupt Handlers */
/* Add here the Interrupt Handlers for the used peripherals. */
/* For the available peripheral interrupt handler names, */
/* please refer to the startup file (startup_stm32f0xx.s). */
/******************************************************************************/
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

162
DBW_V2/Core/Src/syscalls.c Normal file
View File

@@ -0,0 +1,162 @@
/**
*****************************************************************************
**
** File : syscalls.c
**
** Author : Auto-generated by STM32CubeIDE
**
** Abstract : STM32CubeIDE Minimal System calls file
**
** For more information about which c-functions
** need which of these lowlevel functions
** please consult the Newlib libc-manual
**
** Environment : STM32CubeIDE MCU
**
** Distribution: The file is distributed as is, without any warranty
** of any kind.
**
*****************************************************************************
**
** <h2><center>&copy; COPYRIGHT(c) 2018 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.
**
**
*****************************************************************************
*/
/* Includes */
#include <sys/stat.h>
#include <stdlib.h>
#include <errno.h>
#include <stdio.h>
#include <signal.h>
#include <time.h>
#include <sys/time.h>
#include <sys/times.h>
/* Variables */
//#undef errno
extern int errno;
extern int __io_putchar(int ch) __attribute__((weak));
extern int __io_getchar(void) __attribute__((weak));
register char *stack_ptr asm("sp");
char *__env[1] = { 0 };
char **environ = __env;
/* Functions */
void initialise_monitor_handles() {
}
int _getpid(void) {
return 1;
}
int _kill(int pid, int sig) {
errno = EINVAL;
return -1;
}
void _exit(int status) {
_kill(status, -1);
while (1) {
} /* Make sure we hang here */
}
__attribute__((weak)) int _read(int file, char *ptr, int len) {
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++) {
*ptr++ = __io_getchar();
}
return len;
}
__attribute__((weak)) int _write(int file, char *ptr, int len) {
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++) {
__io_putchar(*ptr++);
}
return len;
}
int _close(int file) {
return -1;
}
int _fstat(int file, struct stat *st) {
st->st_mode = S_IFCHR;
return 0;
}
int _isatty(int file) {
return 1;
}
int _lseek(int file, int ptr, int dir) {
return 0;
}
int _open(char *path, int flags, ...) {
/* Pretend like we always fail */
return -1;
}
int _wait(int *status) {
errno = ECHILD;
return -1;
}
int _unlink(char *name) {
errno = ENOENT;
return -1;
}
int _times(struct tms *buf) {
return -1;
}
int _stat(char *file, struct stat *st) {
st->st_mode = S_IFCHR;
return 0;
}
int _link(char *old, char *new) {
errno = EMLINK;
return -1;
}
int _fork(void) {
errno = EAGAIN;
return -1;
}
int _execve(char *name, char **argv, char **env) {
errno = ENOMEM;
return -1;
}

84
DBW_V2/Core/Src/sysmem.c Normal file
View File

@@ -0,0 +1,84 @@
/**
*****************************************************************************
**
** File : sysmem.c
**
** Author : Auto-generated by STM32CubeIDE
**
** Abstract : STM32CubeIDE Minimal System Memory calls file
**
** For more information about which c-functions
** need which of these lowlevel functions
** please consult the Newlib libc-manual
**
** Environment : STM32CubeIDE MCU
**
** Distribution: The file is distributed as is, without any warranty
** of any kind.
**
*****************************************************************************
**
** <h2><center>&copy; COPYRIGHT(c) 2018 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.
**
**
*****************************************************************************
*/
/* Includes */
#include <errno.h>
#include <stdio.h>
#include <sys/types.h>
/* Variables */
extern int errno;
register char *stack_ptr asm("sp");
/* Functions */
/**
_sbrk
Increase program data space. Malloc and related functions depend on this
**/
caddr_t _sbrk(int incr) {
extern char end asm("end");
static char *heap_end;
char *prev_heap_end;
if (heap_end == 0)
heap_end = &end;
prev_heap_end = heap_end;
if (heap_end + incr > stack_ptr) {
errno = ENOMEM;
return (caddr_t) -1;
}
heap_end += incr;
return (caddr_t) prev_heap_end;
}

View File

@@ -0,0 +1,242 @@
/**
******************************************************************************
* @file system_stm32f0xx.c
* @author MCD Application Team
* @brief CMSIS Cortex-M0 Device Peripheral Access Layer System Source File.
*
* 1. This file provides two functions and one global variable to be called from
* user application:
* - SystemInit(): This function is called at startup just after reset and
* before branch to main program. This call is made inside
* the "startup_stm32f0xx.s" file.
*
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
* by the user application to setup the SysTick
* timer or configure other parameters.
*
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
* be called whenever the core clock is changed
* during program execution.
*
*
******************************************************************************
* @attention
*
* <h2><center>&copy; 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
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f0xx_system
* @{
*/
/** @addtogroup STM32F0xx_System_Private_Includes
* @{
*/
#include "stm32f0xx.h"
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_Defines
* @{
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz.
This value can be provided and adapted by the user application. */
#endif /* HSE_VALUE */
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)8000000) /*!< Default value of the Internal oscillator in Hz.
This value can be provided and adapted by the user application. */
#endif /* HSI_VALUE */
#if !defined (HSI48_VALUE)
#define HSI48_VALUE ((uint32_t)48000000) /*!< Default value of the HSI48 Internal oscillator in Hz.
This value can be provided and adapted by the user application. */
#endif /* HSI48_VALUE */
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_Variables
* @{
*/
/* This variable is updated in three ways:
1) by calling CMSIS function SystemCoreClockUpdate()
2) by calling HAL API function HAL_RCC_GetHCLKFreq()
3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
Note: If you use this function to configure the system clock; then there
is no need to call the 2 first functions listed above, since SystemCoreClock
variable is updated automatically.
*/
uint32_t SystemCoreClock = 8000000;
const uint8_t AHBPrescTable[16] = { 0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8,
9 };
const uint8_t APBPrescTable[8] = { 0, 0, 0, 0, 1, 2, 3, 4 };
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F0xx_System_Private_Functions
* @{
*/
/**
* @brief Setup the microcontroller system
* @param None
* @retval None
*/
void SystemInit(void) {
/* NOTE :SystemInit(): This function is called at startup just after reset and
before branch to main program. This call is made inside
the "startup_stm32f0xx.s" file.
User can setups the default system clock (System clock source, PLL Multiplier
and Divider factors, AHB/APBx prescalers and Flash settings).
*/
}
/**
* @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock (HCLK), it can
* be used by the user application to setup the SysTick timer or configure
* other parameters.
*
* @note Each time the core clock (HCLK) changes, this function must be called
* to update SystemCoreClock variable value. Otherwise, any configuration
* based on this variable will be incorrect.
*
* @note - The system frequency computed by this function is not the real
* frequency in the chip. It is calculated based on the predefined
* constant and the selected clock source:
*
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
*
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
*
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
*
* (*) HSI_VALUE is a constant defined in stm32f0xx_hal_conf.h file (default value
* 8 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (**) HSE_VALUE is a constant defined in stm32f0xx_hal_conf.h file (its value
* depends on the application requirements), user has to ensure that HSE_VALUE
* is same as the real frequency of the crystal used. Otherwise, this function
* may have wrong result.
*
* - The result of this function could be not correct when using fractional
* value for HSE crystal.
*
* @param None
* @retval None
*/
void SystemCoreClockUpdate(void) {
uint32_t tmp = 0, pllmull = 0, pllsource = 0, predivfactor = 0;
/* Get SYSCLK source -------------------------------------------------------*/
tmp = RCC->CFGR & RCC_CFGR_SWS;
switch (tmp) {
case RCC_CFGR_SWS_HSI: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
case RCC_CFGR_SWS_HSE: /* HSE used as system clock */
SystemCoreClock = HSE_VALUE;
break;
case RCC_CFGR_SWS_PLL: /* PLL used as system clock */
/* Get PLL clock source and multiplication factor ----------------------*/
pllmull = RCC->CFGR & RCC_CFGR_PLLMUL;
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
pllmull = (pllmull >> 18) + 2;
predivfactor = (RCC->CFGR2 & RCC_CFGR2_PREDIV) + 1;
if (pllsource == RCC_CFGR_PLLSRC_HSE_PREDIV) {
/* HSE used as PLL clock source : SystemCoreClock = HSE/PREDIV * PLLMUL */
SystemCoreClock = (HSE_VALUE / predivfactor) * pllmull;
}
#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F091xC) || defined(STM32F098xx)
else if (pllsource == RCC_CFGR_PLLSRC_HSI48_PREDIV) {
/* HSI48 used as PLL clock source : SystemCoreClock = HSI48/PREDIV * PLLMUL */
SystemCoreClock = (HSI48_VALUE / predivfactor) * pllmull;
}
#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || STM32F078xx || STM32F091xC || STM32F098xx */
else {
#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6) \
|| defined(STM32F078xx) || defined(STM32F071xB) || defined(STM32F072xB) \
|| defined(STM32F070xB) || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
/* HSI used as PLL clock source : SystemCoreClock = HSI/PREDIV * PLLMUL */
SystemCoreClock = (HSI_VALUE / predivfactor) * pllmull;
#else
/* HSI used as PLL clock source : SystemCoreClock = HSI/2 * PLLMUL */
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
#endif /* STM32F042x6 || STM32F048xx || STM32F070x6 ||
STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB ||
STM32F091xC || STM32F098xx || STM32F030xC */
}
break;
default: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
}
/* Compute HCLK clock frequency ----------------*/
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
/* HCLK clock frequency */
SystemCoreClock >>= tmp;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

444
DBW_V2/Core/Src/ts_comms.c Normal file
View File

@@ -0,0 +1,444 @@
/*
* ts_comms.cpp
*
* Created on: 22 Oct 2020
* Author: Dmitrijs
*/
#include "main.h"
#include "dbw.h"
comms_status RX;
comms_status TX;
unsigned char SCI_flags;
const char Signature[20];
const char Revision[20];
char crc32_bufer[8];
void (*Store_config)(void) = Write_Config;
const char Signature[20] = { "speeduino DBW 2.0.0" };
const char Revision[20] = { "speeduino DBW 2.0.0" };
volatile var_t tx_bufer;
void Comms_Init(void) {
Comms_Reset(&TX);
Comms_Reset(&RX);
USART1->ISR &= ~USART_ISR_RXNE;
USART1->CR1 |= USART_CR1_RXNEIE;
}
void USART1_IRQHandler(void) {
uint8_t tmp;
if (USART1->ISR & USART_ISR_RXNE) {
tmp = USART1->RDR;
USART1->ISR &= ~USART_ISR_RXNE;
//if there are any RX errors reset comms else process data
if (USART1->ISR & 0x000F) {
Comms_Reset(&RX);
USART1->ISR &= ~0x000F;
} else {
Rx_Char(tmp);
}
}
//transmit interrupt
if (USART1->ISR & USART_ISR_TC) {
if (TX.bytes_done < TX.cnt) {
USART1->TDR = *TX.address;
TX.address++;
TX.bytes_done++;
} else
TX_Done();
}
}
void Comms_Reset(comms_status *CS) {
CS->mode = IDLE; //Mode Idle
CS->cnt = 0; //Nothing to receive
CS->bytes_done = 0; //Nothing received
CS->crc32 = 0; //Reset crc32
CS->pause_flag = 0;
CS->address = &CS->cmd; //Point incoming characters to cmd_bufer
CS->timeout = 0;
}
void Rx_Char(unsigned char data) {
RX.bytes_done++;
if (RX.bytes_done == 1) {
if (data == 'A') {
SCI_flags |= SCI_FLAGS_TX_VARIABLES;
Comms_Reset(&RX);
} else if (data == 'Q') {
TX_Schedule((unsigned char*) Revision, 20);
Comms_Reset(&RX);
} else if (data == 'S') {
TX_Schedule((unsigned char*) Signature, 20);
Comms_Reset(&RX);
} else if (data == 'B') {
Store_config();
Comms_Reset(&RX);
} else if ((data == 'r') || (data == 'w') || (data == 'k')
|| (data == 'b') || (data == 'z')) {
RX.timeout = 500;
RX.cmd = data;
} else {
Comms_Reset(&RX);
return;
}
} else if (RX.bytes_done == 2) {
RX.CANid = data;
} else if (RX.bytes_done == 3) {
RX.table_index = data;
if (RX.cmd == 'b') {
Store_config();
Comms_Reset(&RX);
return;
}
} else if (RX.bytes_done == 4) {
RX.offset = 0x00;
RX.offset = (unsigned short) data;
} else if (RX.bytes_done == 5) {
RX.offset |= ((unsigned short) data) << 8;
} else if (RX.bytes_done == 6) {
RX.data_size = 0x00;
RX.data_size = (unsigned short) data;
} else if (RX.bytes_done == 7) {
RX.data_size += ((unsigned short) data) << 8;
if (RX.CANid == TS_CAN_ID) {
if (RX.cmd == 'k') {
SCI_flags |= SCI_FLAGS_CRC32;
Comms_Reset(&RX);
return;
} else if (RX.cmd == 'z') {
// process command buttons
if (RX.data_size == 0x0100) {
Apply_Sensor_Calibration();
} else if (RX.data_size == 0x0200) {
DBW_Stop();
config->config_bits |= CONFIG_TESTMODE_F;
} else if (RX.data_size == 0x0300) {
config->config_bits &= ~CONFIG_TESTMODE_F;
} else if (RX.data_size == 0x0400) {
//Start TPS AUTOCAL
ac_timer = 200;
ac_mode = 1;
}
Comms_Reset(&RX);
} else if (RX.cmd == 'r') {
// Read different tables
if (RX.table_index == 0x01) {
TX_Schedule((unsigned char*) config + RX.offset,
RX.data_size);
} else if (RX.table_index == 0x07) {
Copy_Tx_Vars();
TX_Schedule((unsigned char*) &tx_bufer + RX.offset,
RX.data_size);
} else if (RX.table_index == 0x0e) {
TX_Schedule((unsigned char*) Signature, 20);
} else if (RX.table_index == 0x0f) {
TX_Schedule((unsigned char*) Revision, 20);
}
Comms_Reset(&RX);
return;
} else {
//Comms are not reset for 'w' command
// setup write pointer
RX.cnt = RX.bytes_done + RX.data_size;
if (RX.table_index == 0x01) {
RX.address = (unsigned char*) config + RX.offset;
} else {
RX.address = (unsigned char*) RX.can_bufer;
// Do not allow more then 256 bytes to be written to CAN buffer
if (RX.data_size > 256)
Comms_Reset(&RX);
}
return;
}
} else {
// if received CANID != TS_CANID
if ((RX.cmd == 'k') || (RX.cmd == 'r')) {
//TODO pass data to CAN device
Comms_Reset(&RX);
return;
}
Comms_Reset(&RX);
return;
}
} else {
//receive data TX.bytes_done >7
*(RX.address) = data;
RX.address++;
if (RX.bytes_done >= RX.cnt) {
if (RX.table_index == 0x0d) {
//TODO Call command by index
Comms_Reset(&RX);
} else {
// Expecting here ends data write chain
Comms_Reset(&RX);
}
}
}
} // RX Char
void TX_Schedule(unsigned char *data, unsigned short count) {
//Schedule transmission
TX.mode = TRANSMISSION_IN_PROGRESS; // Set TX mode to transmit
TX.cnt = count; // Set number of byte to be transmited
TX.bytes_done = 0; // Set number of bytes transmitted
TX.address = data; // Store updated address
//transmit first data byte
USART1->ICR |= USART_ICR_TCCF;
USART1->TDR = *data;
USART1->CR1 |= USART_CR1_TCIE;
TX.bytes_done++;
TX.address++;
// if(TX.cnt==1)
// {
// TX_Done();
// }
// else{
//
//
// }
return;
}
void Poll_Tx(void) {
if (TX.mode == TRANSMISSION_IN_PROGRESS) {
// do nothing because transmitter is busy;
}
// Check if variables should be transmitted
else if (SCI_flags & SCI_FLAGS_TX_VARIABLES) {
//Copy variables to tx_bufer
Copy_Tx_Vars();
TX_Schedule((unsigned char*) &tx_bufer, sizeof(var_t));
SCI_flags &= ~SCI_FLAGS_TX_VARIABLES;
return;
} else if (SCI_flags & SCI_FLAGS_CRC32) {
SCI_flags &= ~SCI_FLAGS_CRC32;
CRC32();
TX_Schedule((unsigned char*) &crc32_bufer[0], 4);
return;
}
}
void TX_Done(void) {
Comms_Reset(&TX);
//disable TX interrupt
USART1->CR1 &= ~USART_CR1_TCIE;
USART1->ICR |= USART_ICR_TCCF;
}
void CRC32(void) {
unsigned int tmp;
tmp = (unsigned int) crc32((void*) config, sizeof(config_t));
crc32_bufer[0] = (unsigned char) ((tmp >> 24) & 0x000000ff);
crc32_bufer[1] = (unsigned char) ((tmp >> 16) & 0x000000ff);
crc32_bufer[2] = (unsigned char) ((tmp >> 8) & 0x000000ff);
crc32_bufer[3] = (unsigned char) ((tmp) & 0x000000ff);
}
void Copy_Tx_Vars(void) {
//TODO copy all variables from *var to tx_bufer to make sure
// nothing is changed while transmission is in progress
//tx_bufer.a = var->a;
tx_bufer.clock = var.clock;
tx_bufer.status0 = var.rpm;
tx_bufer.status1 = var.status1;
tx_bufer.status2 = var.status2;
tx_bufer.status3 = var.status3;
tx_bufer.pps1_adc = var.pps1_adc;
tx_bufer.pps2_adc = var.pps2_adc;
tx_bufer.tps1_adc = var.tps1_adc;
tx_bufer.tps2_adc = var.tps2_adc;
tx_bufer.motor_current_adc = var.motor_current_adc;
tx_bufer.vbat_adc = var.vbat_adc;
tx_bufer.pps1 = var.pps1;
tx_bufer.pps2 = var.pps2;
tx_bufer.tps1 = var.tps1;
tx_bufer.tps2 = var.tps2;
tx_bufer.pps = var.pps;
tx_bufer.tps = var.tps;
tx_bufer.tps_error = var.tps_error;
tx_bufer.motor_pwm = var.motor_pwm;
tx_bufer.idle_dc = var.idle_dc;
tx_bufer.pps_delta = var.pps_delta;
tx_bufer.tps_delta = var.tps_delta;
tx_bufer.tps_target = var.tps_target;
}
#define WIDTH (8)
#define TOPBIT (1 << (WIDTH - 1))
#define POLYNOMIAL 0xD8
crc_t calc_crc(crc_t message[], int nBytes) {
crc_t remainder = 0;
/*
* Perform modulo-2 division, a byte at a time.
*/
for (int byte = 0; byte < nBytes; ++byte) {
/*
* Bring the next byte into the remainder.
*/
remainder ^= (message[byte] << (WIDTH - 8));
/*
* Perform modulo-2 division, a bit at a time.
*/
for (unsigned char bit = 8; bit > 0; --bit) {
/*
* Try to divide the current data bit.
*/
if (remainder & TOPBIT) {
remainder = (remainder << 1) ^ POLYNOMIAL;
} else {
remainder = (remainder << 1);
}
}
}
/*
* The final remainder is the CRC result.
*/
return remainder;
}
static uint32_t crc32_tab[] = { 0x00000000, 0x77073096, 0xee0e612c, 0x990951ba,
0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3, 0x0edb8832, 0x79dcb8a4,
0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb,
0xf4d4b551, 0x83d385c7, 0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec,
0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5, 0x3b6e20c8, 0x4c69105e,
0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75,
0xdcd60dcf, 0xabd13d59, 0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116,
0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f, 0x2802b89e, 0x5f058808,
0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f,
0x9fbfe4a5, 0xe8b8d433, 0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818,
0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01, 0x6b6b51f4, 0x1c6c6162,
0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49,
0x8cd37cf3, 0xfbd44c65, 0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2,
0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb, 0x4369e96a, 0x346ed9fc,
0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3,
0xb966d409, 0xce61e49f, 0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4,
0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad, 0xedb88320, 0x9abfb3b6,
0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d,
0x0a00ae27, 0x7d079eb1, 0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe,
0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7, 0xfed41b76, 0x89d32be0,
0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767,
0x3fb506dd, 0x48b2364b, 0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60,
0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79, 0xcb61b38c, 0xbc66831a,
0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31,
0x2cd99e8b, 0x5bdeae1d, 0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a,
0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713, 0x95bf4a82, 0xe2b87a14,
0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b,
0x6fb077e1, 0x18b74777, 0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c,
0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45, 0xa00ae278, 0xd70dd2ee,
0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5,
0x47b2cf7f, 0x30b5ffe9, 0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6,
0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf, 0xb3667a2e, 0xc4614ab8,
0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d };
/**
* Online CRC calculator:
* http://www.zorc.breitbandkatze.de/crc.html
*/
uint32_t crc32(void *buf, uint32_t size) {
return crc32inc(buf, 0, size);
}
uint32_t crc32inc(void *buf, uint32_t crc, uint32_t size) {
uint8_t *p;
p = (uint8_t*) buf;
crc = crc ^ 0xFFFFFFFF;
while (size--) {
crc = crc32_tab[(crc ^ *p++) & 0xFF] ^ (crc >> 8);
}
return crc ^ 0xFFFFFFFF;
}
void Write_Config(void) {
__disable_irq();
uint32_t error;
FLASH_EraseInitTypeDef erase_pages;
erase_pages.NbPages = 2;
erase_pages.TypeErase = TYPEERASE_PAGES;
erase_pages.PageAddress = (uint32_t) &config_flash;
HAL_FLASH_Unlock();
HAL_FLASHEx_Erase(&erase_pages, &error);
HAL_FLASH_Lock();
uint16_t num_wrt;
if (sizeof(config_t) & 0x0001)
num_wrt = (sizeof(config_t) << 1) + 1;
else
num_wrt = sizeof(config_t) << 1;
if (num_wrt > 2048)
Error_Handler();
HAL_FLASH_Unlock();
uint16_t *data, *flash_address;
data = (uint16_t*) &config_ram;
flash_address = (uint16_t*) &config_flash;
for (int i = 0; i < num_wrt; i++) {
HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, (uint32_t) flash_address,
*data);
data++;
flash_address++;
}
HAL_FLASH_Lock();
__enable_irq();
}
void TS_Comms_RX_Timeout(void) {
if (RX.mode != IDLE) {
if (RX.timeout) {
RX.timeout--;
if (RX.timeout == 0) {
Comms_Reset(&RX);
}
}
}
}