diff --git a/Firmware/carteHRI.uvoptx b/Firmware/carteHRI.uvoptx
index d6bfb59..e2a61f6 100644
--- a/Firmware/carteHRI.uvoptx
+++ b/Firmware/carteHRI.uvoptx
@@ -1,713 +1,718 @@
1.0
### uVision Project, (C) Keil Software
*.c
*.s*; *.src; *.a*
*.obj
*.lib
*.txt; *.h; *.inc
*.plm
*.cpp
0
0
0
Target 1
0x4
ARM-ADS
168000000
1
1
0
1
0
1
65535
0
0
0
79
66
8
.\lst\
1
1
1
0
1
1
0
1
0
0
0
0
1
1
1
1
1
1
1
0
0
1
0
1
18
0
User Manual (MCBSTM32F400)
C:\Keil_v5\ARM\PACK\Keil\STM32F4xx_DFP\2.3.0\MDK\Boards\Keil\MCBSTM32F400\Documentation\mcbstm32f200.chm
1
Schematics (MCBSTM32F400)
C:\Keil_v5\ARM\PACK\Keil\STM32F4xx_DFP\2.3.0\MDK\Boards\Keil\MCBSTM32F400\Documentation\mcbstm32f400-schematics.pdf
2
Getting Started (STM32F4-Discovery)
C:\Keil_v5\ARM\PACK\Keil\STM32F4xx_DFP\2.3.0\MDK\Boards\ST\STM32F4-Discovery\Documentation\DM00037368.pdf
3
User Manual (STM32F4-Discovery)
C:\Keil_v5\ARM\PACK\Keil\STM32F4xx_DFP\2.3.0\MDK\Boards\ST\STM32F4-Discovery\Documentation\DM00039084.pdf
4
Bill of Materials (STM32F4-Discovery)
C:\Keil_v5\ARM\PACK\Keil\STM32F4xx_DFP\2.3.0\MDK\Boards\ST\STM32F4-Discovery\Documentation\stm32f4discovery_bom.zip
5
Gerber Files (STM32F4-Discovery)
C:\Keil_v5\ARM\PACK\Keil\STM32F4xx_DFP\2.3.0\MDK\Boards\ST\STM32F4-Discovery\Documentation\stm32f4discovery_gerber.zip
6
Schematics (STM32F4-Discovery)
C:\Keil_v5\ARM\PACK\Keil\STM32F4xx_DFP\2.3.0\MDK\Boards\ST\STM32F4-Discovery\Documentation\stm32f4discovery_sch.zip
7
MCBSTM32F400 Evaluation Board Web Page (MCBSTM32F400)
http://www.keil.com/mcbstm32f400/
8
STM32F4-Discovery Web Page (STM32F4-Discovery)
http://www.st.com/web/catalog/tools/FM116/SC959/SS1532/LN1199/PF252419
0
1
1
1
1
1
1
1
1
1
0
1
1
1
0
1
1
1
1
0
0
11
STLink\ST-LINKIII-KEIL_SWO.dll
0
ARMRTXEVENTFLAGS
-L50 -Z18 -C0 -M0 -T0
0
DLGDARM
(1010=-1,-1,-1,-1,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(1009=-1,-1,-1,-1,0)(1012=-1,-1,-1,-1,0)
0
DLGTARM
(1010=-1,-1,-1,-1,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(1009=-1,-1,-1,-1,0)(1012=-1,-1,-1,-1,0)
0
ARMDBGFLAGS
-T0
0
DLGUARM
(105=-1,-1,-1,-1,0)
0
ST-LINKIII-KEIL_SWO
-U303030303030303030303031 -I0 -O8398 -S1 -C0 -A0 -N00("ARM CoreSight SW-DP") -D00(2BA01477) -L00(0) -TO19 -TC168000000 -TP21 -TDS8053 -TDT0 -TDC1F -TIEFFFFFFFF -TIP8 -FO15 -FD20000000 -FC800 -FN1 -FF0STM32F4xx_1024.FLM -FS08000000 -FL0100000 -FP0($$Device:STM32F407VG$CMSIS\Flash\STM32F4xx_1024.FLM)
0
UL2CM3
UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0STM32F4xx_1024 -FS08000000 -FL0100000 -FP0($$Device:STM32F407VG$Flash\STM32F4xx_1024.FLM))
0
1
motorTorque_mNm_dbg
1
1
adc_currentSensOffset,0x0A
+
+ 2
+ 1
+ statusReg,0x0A
+
0
2
motorTorque_mNm
1
2
nCycles
2
2
motorPosCod,0x0A
3
2
CurrentSensOffset,0x0A
4
2
motorCurrent_mA_mean
5
2
motorCurrent_mA
6
2
ADCValuesBuffer,0x0A
7
2
motorCurrent_mA
8
2
motorCurrentSum
9
2
debugVar01,0x0A
10
2
adcValues1,0x0A
11
2
motorCurrent_mA
0
0
1
1
0
0
0
0
1
0
0
0
0
0
0
0
0
0
0
0
0
0
0
0
0
STM32_files
1
0
0
0
1
1
1
0
0
0
0
.\src\system_stm32f4xx.c
system_stm32f4xx.c
0
0
1
2
2
0
0
0
0
.\startup_stm32f4xx.s
startup_stm32f4xx.s
0
0
SRC
1
0
0
0
2
3
1
0
0
0
0
.\src\main.c
main.c
0
0
2
4
1
0
0
0
0
.\src\communication.c
communication.c
0
0
2
5
1
0
0
0
0
.\src\controller.c
controller.c
0
0
STM32_libs
1
0
0
0
3
6
1
0
0
0
0
C:\STM32F4-Discovery_FW_V1.1.0\Libraries\STM32F4xx_StdPeriph_Driver\src\stm32f4xx_gpio.c
stm32f4xx_gpio.c
0
0
3
7
1
0
0
0
0
C:\STM32F4-Discovery_FW_V1.1.0\Libraries\STM32F4xx_StdPeriph_Driver\src\stm32f4xx_rcc.c
stm32f4xx_rcc.c
0
0
3
8
1
0
0
0
0
C:\STM32F4-Discovery_FW_V1.1.0\Libraries\STM32F4xx_StdPeriph_Driver\src\stm32f4xx_tim.c
stm32f4xx_tim.c
0
0
3
9
1
0
0
0
0
C:\STM32F4-Discovery_FW_V1.1.0\Libraries\STM32F4xx_StdPeriph_Driver\src\misc.c
misc.c
0
0
3
10
1
0
0
0
0
C:\STM32F4-Discovery_FW_V1.1.0\Libraries\STM32F4xx_StdPeriph_Driver\src\stm32f4xx_exti.c
stm32f4xx_exti.c
0
0
3
11
1
0
0
0
0
C:\STM32F4-Discovery_FW_V1.1.0\Libraries\STM32F4xx_StdPeriph_Driver\src\stm32f4xx_syscfg.c
stm32f4xx_syscfg.c
0
0
3
12
1
0
0
0
0
C:\STM32F4-Discovery_FW_V1.1.0\Libraries\STM32F4xx_StdPeriph_Driver\src\stm32f4xx_adc.c
stm32f4xx_adc.c
0
0
3
13
1
0
0
0
0
C:\STM32F4-Discovery_FW_V1.1.0\Libraries\STM32F4xx_StdPeriph_Driver\src\stm32f4xx_dac.c
stm32f4xx_dac.c
0
0
3
14
1
0
0
0
0
C:\STM32F4-Discovery_FW_V1.1.0\Libraries\STM32F4xx_StdPeriph_Driver\src\stm32f4xx_dma.c
stm32f4xx_dma.c
0
0
3
15
1
0
0
0
0
C:\STM32F4-Discovery_FW_V1.1.0\Libraries\STM32F4xx_StdPeriph_Driver\src\stm32f4xx_usart.c
stm32f4xx_usart.c
0
0
3
16
4
0
0
0
0
C:\STM32F4-Discovery_FW_V1.1.0\Libraries\CMSIS\Lib\ARM\arm_cortexM4lf_math.lib
arm_cortexM4lf_math.lib
0
0
SRC_drivers
1
0
0
0
4
17
1
0
0
0
0
.\src\drivers\adc.c
adc.c
0
0
4
18
1
0
0
0
0
.\src\drivers\callback_timers.c
callback_timers.c
0
0
4
19
1
0
0
0
0
.\src\drivers\dac.c
dac.c
0
0
4
20
1
0
0
0
0
.\src\drivers\h_bridge.c
h_bridge.c
0
0
4
21
1
0
0
0
0
.\src\drivers\incr_encoder.c
incr_encoder.c
0
0
4
22
1
0
0
0
0
.\src\drivers\uart.c
uart.c
0
0
4
23
1
0
0
0
0
.\src\drivers\hall.c
hall.c
0
0
4
24
1
0
0
0
0
.\src\drivers\strain_gauge.c
strain_gauge.c
0
0
4
25
1
0
0
0
0
.\src\drivers\tachometer.c
tachometer.c
0
0
SRC_lib
1
0
0
0
5
26
1
0
0
0
0
.\src\lib\basic_filter.c
basic_filter.c
0
0
5
27
1
0
0
0
0
.\src\lib\pid.c
pid.c
0
0
5
28
1
0
0
0
0
.\src\lib\utils.c
utils.c
0
0
diff --git a/Firmware/src/communication.c b/Firmware/src/communication.c
index 0914f0a..fbce055 100644
--- a/Firmware/src/communication.c
+++ b/Firmware/src/communication.c
@@ -1,317 +1,317 @@
#include "communication.h"
#include "controller.h"
#include "drivers/callback_timers.h"
#include "drivers/adc.h"
#include "drivers/dac.h"
#include "drivers/hall.h"
#include "drivers/strain_gauge.h"
#include "drivers/tachometer.h"
#include "drivers/uart.h"
#include "lib/basic_filter.h"
#include "lib/pid.h"
#include "lib/utils.h"
extern uint32_t statusReg, ctrl_timestamp, ctrl_currentFilterType;
extern float32_t ctrl_motorPosCod, ctrl_motorPosCod_c;
-extern float32_t ctrl_motorTorque_mNm_c, ctrl_motorPosCodFilt, ctrl_firstOrderFilterTau;
+extern float32_t ctrl_motorTorque_Nm_c, ctrl_motorPosCodFilt, ctrl_firstOrderFilterTau;
extern float32_t hall_angle, tac_speed, sg_force;
extern pid_Pid ctrl_positionPid;
extern bfilt_BasicFilter ctrl_encoderFilter;
extern float32_t ctrl_sineAmplitude, ctrl_sinePeriod;
uint32_t selectedVariablesToStream; // Bitfield that indicates for each variable if it should be streamed or not.
void* variablesArray[N_VARIABLES]; // Pointers to variables to stream.
uint8_t txBuffer[1024];
uint8_t rxCurrentMessageType = PC_MESSAGE_DO_NOTHING; // Current message type for RX bytes.
uint32_t rxBytesCount; // Number of received bytes for the current message.
uint8_t firstHalfByte; // First half of the data byte to receive.
uint8_t rxDataBytesBuffer[32]; // Data bytes received (ready to use, bytes already merged).
void comm_SendPacket(uint8_t messageType, uint8_t *data, uint16_t dataLength);
void comm_HandleByte(uint8_t rxData);
void comm_Stream(void);
uint32_t comm_GetVar(uint8_t variableIndex);
/**
* @brief Init the communication manager.
*/
void comm_Init(void)
{
// Initialize the array with all the pointers on variables.
// Note that this array contains pointers only to uint32_t, even if the
// variables are actually float32_t. This does not matter, since we only use
// these pointers to perform byte-to-byte copies.
// Do not modify this by hand, copy-paste code generated by the excel sheet.
variablesArray[VAR_TIMESTAMP] = (uint32_t*) &ctrl_timestamp;
variablesArray[VAR_POS_REG_PID_P] = (uint32_t*) &ctrl_positionPid.kp;
variablesArray[VAR_POS_REG_PID_I] = (uint32_t*) &ctrl_positionPid.ki;
variablesArray[VAR_POS_REG_PID_D] = (uint32_t*) &ctrl_positionPid.kd;
variablesArray[VAR_POS_REG_PID_ARW] = (uint32_t*) &ctrl_positionPid.arw;
variablesArray[VAR_POS_REG_PID_INTEGRATOR] = (uint32_t*) &ctrl_positionPid.integrator;
- variablesArray[VAR_POS_REG_PID_OUTPUT] = (uint32_t*) &ctrl_motorTorque_mNm_c;
+ variablesArray[VAR_POS_REG_PID_OUTPUT] = (uint32_t*) &ctrl_motorTorque_Nm_c;
variablesArray[VAR_POS_REG_SAMPLING_PERIOD] = NULL;
variablesArray[VAR_WALL_POSITION] = (uint32_t*) &ctrl_motorPosCod_c;
variablesArray[VAR_MEASURED_ANGLE_RAW] = (uint32_t*) &ctrl_motorPosCod;
variablesArray[VAR_MEASURED_ANGLE_FILTERED] = (uint32_t*) &ctrl_motorPosCodFilt;
variablesArray[VAR_COMM_TX_PERIOD] = NULL;
variablesArray[VAR_ACTIVE_FILTER] = (uint32_t*) &ctrl_currentFilterType;
variablesArray[VAR_1ST_FILT_TAU] = (uint32_t*) &ctrl_encoderFilter.tau;
variablesArray[VAR_DAC1_VOLTAGE] = NULL;
variablesArray[VAR_DAC2_VOLTAGE] = NULL;
variablesArray[VAR_ADC1_VOLTAGE] = NULL;
variablesArray[VAR_ADC2_VOLTAGE] = NULL;
variablesArray[VAR_HALL_ANGLE] = NULL;
variablesArray[VAR_TACHO_SPEED] = NULL;
variablesArray[VAR_STRAIN_GAUGE_FORCE] = NULL;
variablesArray[VAR_USER_VAR_1] = NULL;
variablesArray[VAR_USER_VAR_2] = NULL;
variablesArray[VAR_USER_VAR_3] = NULL;
variablesArray[VAR_USER_VAR_4] = NULL;
variablesArray[VAR_USER_VAR_5] = NULL;
// Setup the UART peripheral, and specify the function that will be called
// each time a byte is received.
uart_Init(comm_HandleByte);
// Make the streaming function periodically called by the timer 7.
cbt_SetCommLoopTimer(comm_Stream, TE_DATA_LOOP_DEFAULT_VAL);
}
/**
* @brief UART data streaming "loop" function.
*/
void comm_Stream()
{
// If the data streaming is enabled, send a stream packet to the PC.
if(statusReg & DATA_UPSTREAM_ENB)
{
uint32_t i;
int nDataBytesToSend = 0;
for(i=0; i> 4); // Most significant bits.
uart_SendByte((data[i]&0x0f)); // Least significant bits.
}
}
/**
* @brief Process the received byte to interpret the messages.
* @param rxData: the byte to be processed and interpreted.
*/
void comm_HandleByte(uint8_t rxData)
{
if(rxData & (1<<7)) // The start byte has the most significant bit high.
{
rxCurrentMessageType = (rxData & ~(1<<7)); // Remove the start bit.
rxBytesCount = 0;
}
else
rxBytesCount++;
if(rxBytesCount % 2 == 1) // First half of the data byte has been received.
firstHalfByte = rxData; // Store it until the second half arrives.
else // Second half of the data byte has been received (or no data bytes yet).
{
int dataBytesReady = rxBytesCount/2;
rxDataBytesBuffer[dataBytesReady-1] = (firstHalfByte<<4) + (rxData & 0xf);
switch(rxCurrentMessageType)
{
case PC_MESSAGE_DO_NOTHING:
if(dataBytesReady == 0)
; // Do nothing.
break;
case PC_MESSAGE_SEND_STATUS:
if(dataBytesReady == 0)
comm_SendPacket(STM_MESSAGE_STATUS, (uint8_t*)(&statusReg), 4);
break;
case PC_MESSAGE_START_STREAMING:
if(dataBytesReady == 0)
{
statusReg |= DATA_UPSTREAM_ENB;
TIM_SetCounter(TIM7, 0);
TIM_Cmd(TIM7, ENABLE);
}
break;
case PC_MESSAGE_STOP_STREAMING:
if(dataBytesReady == 0)
{
TIM_Cmd(TIM7, DISABLE);
statusReg &= ~DATA_UPSTREAM_ENB;
}
break;
case PC_MESSAGE_GET_VAR:
if(dataBytesReady == 1)
{
uint32_t variableValue;
// Extract the index, that indicates which variable will be sent.
uint8_t variableIndex = rxDataBytesBuffer[0];
// If the variable index is out of range, ignore the request.
if(variableIndex >= N_VARIABLES)
return;
// Prepare the message to be sent to the PC.
// First byte: variable index.
txBuffer[0] = variableIndex;
// Four following bytes: actual value of the variable.
variableValue = comm_GetVar(variableIndex);
memcpy(&txBuffer[1], &variableValue, 4);
// Send the message to the PC.
comm_SendPacket(STM_MESSAGE_VAR, txBuffer, 5);
}
break;
case PC_MESSAGE_SET_VAR:
if(dataBytesReady == 5)
{
// Extract the index (that indicates which variable will change),
// and the new value of the variable.
uint32_t newValue;
uint8_t variableIndex = rxDataBytesBuffer[0];
memcpy(&newValue, &rxDataBytesBuffer[1], 4);
// Set the selected variable with the new value.
comm_SetVar(variableIndex, newValue);
}
break;
case PC_MESSAGE_SET_STREAMED_VAR:
if(dataBytesReady == 4)
{
uint8_t *newSelectedVars = &rxDataBytesBuffer[0];
memcpy(&selectedVariablesToStream, newSelectedVars, 4);
}
break;
default: // No data bytes for the other message types.
break;
}
}
}
diff --git a/Firmware/src/controller.c b/Firmware/src/controller.c
index 415e9c6..5006400 100644
--- a/Firmware/src/controller.c
+++ b/Firmware/src/controller.c
@@ -1,128 +1,129 @@
#include "controller.h"
#include "communication.h"
#include "drivers/adc.h"
#include "drivers/dac.h"
#include "drivers/incr_encoder.h"
#include "drivers/hall.h"
#include "drivers/h_bridge.h"
#include "drivers/callback_timers.h"
#include "lib/basic_filter.h"
#include "lib/pid.h"
#include "lib/utils.h"
extern uint32_t statusReg;
volatile uint32_t ctrl_timestamp = 0; // [us].
volatile float32_t ctrl_motorPosCod;
volatile float32_t ctrl_motorPosCod_c;
volatile float32_t ctrl_motorPosCodFilt = 0.0f;
-volatile float32_t ctrl_motorTorque_mNm_c = 0.0f;
+volatile float32_t ctrl_motorTorque_Nm_c = 0.0f;
volatile uint32_t ctrl_currentFilterType = FILTER_TYPE_NONE;
volatile pid_Pid ctrl_currentPid, ctrl_positionPid;
volatile bfilt_BasicFilter ctrl_encoderFilter;
-volatile float32_t motorTorque_mNm_dbg;
-
void ctrl_RegulateCurrent(void);
void ctrl_RegulatePosition(void);
/**
* @brief Initialize the position and current controllers.
*/
void ctrl_Init(void)
{
// Setup the PIDs.
- pid_Init((pid_Pid*)&ctrl_currentPid, KP_CURRENT_DEFAULT_VAL, KI_CURRENT_DEFAULT_VAL, 0.0f, CURRENT_INTEGRATOR_SAT);
+ pid_Init((pid_Pid*)&ctrl_currentPid, KP_CURRENT_DEFAULT_VAL, KI_CURRENT_DEFAULT_VAL, 0.0f, CURRENT_INTEGRATOR_SAT, FF_CURRENT_DEFAULT_VAL);
#ifdef REGULATION_TYPE_SYMMETRIC
- pid_Init((pid_Pid*)&ctrl_positionPid, KP_POSITION_DEFAULT_VAL, KI_POSITION_DEFAULT_VAL, KD_POSITION_DEFAULT_VAL, POSITION_INTEGRATOR_SAT_DEFAULT_VAL);
+ pid_Init((pid_Pid*)&ctrl_positionPid, KP_POSITION_DEFAULT_VAL, KI_POSITION_DEFAULT_VAL, KD_POSITION_DEFAULT_VAL, POSITION_INTEGRATOR_SAT_DEFAULT_VAL, 0.0f);
#else
- pid_Init((pid_Pid*)&ctrl_positionPid, KP_POSITION_DEFAULT_VAL, 0.0f, KD_POSITION_DEFAULT_VAL, 0.0f);
+ pid_Init((pid_Pid*)&ctrl_positionPid, KP_POSITION_DEFAULT_VAL, 0.0f, KD_POSITION_DEFAULT_VAL, 0.0f, 0.0f);
#endif
// Setup the increment encoder filter.
bfilt_Init((bfilt_BasicFilter*)&ctrl_encoderFilter, ENCODER_FILT_TAU_DEFAULT_VAL, 0.0f);
// Make the timers call the regulation functions periodically.
cbt_SetCurrentLoopTimer(ctrl_RegulateCurrent, TE_CURRENT_LOOP_DEFAULT_VAL);
cbt_SetPositionLoopTimer(ctrl_RegulatePosition, TE_CONTROL_LOOP_DEFAULT_VAL);
}
/**
* @brief Current regulation "loop" function.
*/
void ctrl_RegulateCurrent()
{
- float32_t pwmNormalizedDutyCycle, motorTorque_mNm;
+ float32_t motorVoltage, // Motor command voltage [V].
+ pwmNormalizedDutyCycle, // Motor normalized PWM duty (-1 ot 1).
+ targetCurrent; // [A].
// Get the current.
- float32_t motorCurrent_mA = adc_GetCurrent();
+ float32_t motorCurrrentCurrent = adc_GetCurrent();
- // Convert to torque.
- motorTorque_mNm = motorCurrent_mA * TORQUE_CONST;
- motorTorque_mNm_dbg = motorTorque_mNm;
+ // Convert the target torque to current.
+ targetCurrent = ctrl_motorTorque_Nm_c / MOTOR_TORQUE_CONST;
// Regulate.
- pwmNormalizedDutyCycle = -pid_Step((pid_Pid*)&ctrl_currentPid,
- motorTorque_mNm,
- ctrl_motorTorque_mNm_c,
- (float32_t)cbt_GetCurrentLoopPeriod()*MICROSECOND_TO_SECOND);
+ motorVoltage = -pid_Step((pid_Pid*)&ctrl_currentPid,
+ motorCurrrentCurrent,
+ targetCurrent,
+ (float32_t)cbt_GetCurrentLoopPeriod()*MICROSECOND_TO_SECOND);
+ // Normalize to get a signed PWM duty (between -1 and 1).
+ pwmNormalizedDutyCycle = motorVoltage / H_BRIDGE_SUPPLY_VOLTAGE;
utils_SaturateF(&pwmNormalizedDutyCycle, -CURRENT_LOOP_PWM_MAX_DUTY_CYCLE, CURRENT_LOOP_PWM_MAX_DUTY_CYCLE);
// Apply the computed PWM duty.
hb_SetPWM(pwmNormalizedDutyCycle);
}
/**
* @brief Position regulation "loop" function.
* @note As an example, a basic position regulator that uses the encoder is
* implemented. Feel free to remove all the content of the function to add your
* own code.
*/
void ctrl_RegulatePosition()
{
// Increment the timestamp.
ctrl_timestamp += cbt_GetPositionLoopPeriod();
-
+ /*
// Get the encoder position.
ctrl_motorPosCod = enc_GetPosition();
// Filter the position given by the encoder.
if(ctrl_currentFilterType == FILTER_TYPE_FIRST_ORDER)
{
ctrl_motorPosCodFilt = bfilt_Step((bfilt_BasicFilter*)&ctrl_encoderFilter, ctrl_motorPosCod);
}
else if(ctrl_currentFilterType == FILTER_TYPE_RUNNING_MEAN)
{
// TODO.
ctrl_motorPosCodFilt = ctrl_motorPosCod;
}
else // No filter.
ctrl_motorPosCodFilt = ctrl_motorPosCod;
// Regulate.
#ifdef REGULATION_TYPE_SYMMETRIC // No wall, just regulation on a point.
- ctrl_motorTorque_mNm_c = -pid_Step((pid_Pid*)&ctrl_positionPid,
+ ctrl_motorTorque_Nm_c = -pid_Step((pid_Pid*)&ctrl_positionPid,
ctrl_motorPosCodFilt,
ctrl_motorPosCod_c,
(float32_t)(cbt_GetPositionLoopPeriod())*MICROSECOND_TO_SECOND);
#else // Wall, regulate only if not touching the wall.
if(ctrl_motorPosCodFilt < ctrl_motorPosCod_c) // Touching the wall.
{
- ctrl_motorTorque_mNm_c = -pid_Step((pid_Pid*)&ctrl_positionPid,
+ ctrl_motorTorque_Nm_c = -pid_Step((pid_Pid*)&ctrl_positionPid,
ctrl_motorPosCodFilt,
(float32_t)ctrl_motorPosCod_c,
(float32_t)(cbt_GetPositionLoopPeriod())*MICROSECOND_TO_SECOND);
}
else
- ctrl_motorTorque_mNm_c = 0.0f;
-#endif
+ ctrl_motorTorque_Nm_c = 0.0f;
+#endif*/
}
diff --git a/Firmware/src/controller.h b/Firmware/src/controller.h
index 8d30590..123687e 100644
--- a/Firmware/src/controller.h
+++ b/Firmware/src/controller.h
@@ -1,63 +1,62 @@
#ifndef __CONTROLLER_H
#define __CONTROLLER_H
#include "main.h"
// Type of regulation.
// Comment out to get the "wall" non-symetric behavior.
#define REGULATION_TYPE_SYMMETRIC
// Loops periode values
#define TE_LOOP_MIN_VALUE 50 // Minimum period for any loop [us].
#define TE_LOOP_MAX_VALUE 65534 // Maximum period for any loop [us].
-#define TE_CURRENT_LOOP_DEFAULT_VAL 60 // Current control loop period [us] (max 2^16-1) (default value at reset).
+#define TE_CURRENT_LOOP_DEFAULT_VAL 30 // Current control loop period [us] (max 2^16-1) (default value at reset).
#define TE_CONTROL_LOOP_DEFAULT_VAL 350 // Main control loop period [us] (max 2^16-1) (default value at reset).
#define TE_DATA_LOOP_DEFAULT_VAL 8000 // Data loop period [us] (max 2^16-1) (default value at reset).
// Current loop parameters
-#define KP_CURRENT_DEFAULT_VAL 0.0011f
-#define KI_CURRENT_DEFAULT_VAL (0.0000002*TE_CURRENT_LOOP_DEFAULT_VAL)
-#define CURRENT_INTEGRATOR_SAT 0.7f
+#define KP_CURRENT_DEFAULT_VAL 0.5f
+#define KI_CURRENT_DEFAULT_VAL 10.0f
+#define FF_CURRENT_DEFAULT_VAL MOTOR_RESISTANCE
+#define CURRENT_INTEGRATOR_SAT 2.0f
#define CURRENT_LOOP_PWM_MAX_DUTY_CYCLE 0.98f // Max PWM value (normalized) duty cycle (less than 1 to ensure bootstrap capacitor charging)
// Main control loop parameters
-#define KP_POSITION_DEFAULT_VAL 4.0f
-#define KD_POSITION_DEFAULT_VAL 0.00075f
-#define KI_POSITION_DEFAULT_VAL 0.0000049f
-#define POSITION_INTEGRATOR_SAT_DEFAULT_VAL 50.0f
+#define KP_POSITION_DEFAULT_VAL 0.1f
+#define KD_POSITION_DEFAULT_VAL 0.0f
+#define KI_POSITION_DEFAULT_VAL 0.0f
+#define POSITION_INTEGRATOR_SAT_DEFAULT_VAL 0.01f
// Increment encoder filter default coef.
#define ENCODER_FILT_TAU_DEFAULT_VAL 0.999f
// Filter types
#define FILTER_TYPE_NONE 0
#define FILTER_TYPE_FIRST_ORDER 1
#define FILTER_TYPE_RUNNING_MEAN 2
-#define TORQUE_CONST 0.0538f // Nm/A =~ (mNm/mA)
-
/** @defgroup Controller Main / Controllers
* @brief Control the paddle
*
* This module is the high-level controller of the board. It runs two "loops"
* (in fact, functions called periodically by the interrupt of a timer), one to
* regulate the motor current (ctrl_RegulateCurrent(), high frequency) and
* another to control the rest (ctrl_RegulatePosition(), lower frequency).
* The content of ctrl_RegulatePosition() is typically what the user of the
* board will modify, depending on the selected sensors and control algorithms.
*
* Call ctrl_Init() to setup this module. Its interrupt functions will be called
* automatically periodically.
*
* @addtogroup Controller
* @{
*/
void ctrl_Init(void);
/**
* @}
*/
#endif
diff --git a/Firmware/src/drivers/adc.c b/Firmware/src/drivers/adc.c
index 1da28f9..582231f 100644
--- a/Firmware/src/drivers/adc.c
+++ b/Firmware/src/drivers/adc.c
@@ -1,235 +1,233 @@
#include "adc.h"
#include "../lib/basic_filter.h"
#include "../lib/utils.h"
volatile uint16_t adc_currentValuesBuffer[ADC_BUFFER_SIZE];
bfilt_BasicFilter adc_currentFilter;
-uint16_t adc_currentSensOffset = 2048;
-
+float32_t adc_currentSensOffset = 0.0f;
void adc_DmaInit(void);
/**
* @brief Initialize the ADC converter (2 analog inputs + current sense).
*/
void adc_Init(void)
{
ADC_InitTypeDef ADC_InitStructure;
ADC_CommonInitTypeDef ADC_CommonInitStructure;
GPIO_InitTypeDef GPIO_InitStructure;
adc_DmaInit();
// Periph clock enable
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1|RCC_APB2Periph_ADC2, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC3,ENABLE);
// GPIO configuration
GPIO_InitStructure.GPIO_Pin = ADC1_Input_Pin;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(ADC1_Input_Port, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = ADC2_Input_Pin;
GPIO_Init(ADC2_Input_Port, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = ADC_Current_Sens_Pin;
GPIO_Init(ADC_Current_Sens_Port, &GPIO_InitStructure);
// ADC Common configuration
ADC_DeInit();
ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent;
ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles; // Useless here (only used in dual or triple interleaved modes).
ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled;
ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div4;
ADC_CommonInit(&ADC_CommonInitStructure);
// ADC regular channel configuration
ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b;
ADC_InitStructure.ADC_ScanConvMode = DISABLE;
ADC_InitStructure.ADC_ContinuousConvMode = DISABLE;
ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;
ADC_InitStructure.ADC_ExternalTrigConv = 0;
ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
ADC_InitStructure.ADC_NbrOfConversion = 1;
ADC_Init(ADC1, &ADC_InitStructure);
ADC_Init(ADC2, &ADC_InitStructure);
// ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_Rising;
// ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T8_TRGO;
// ADC_InitStructure.ADC_ContinuousConvMode = DISABLE;
// Synchronous sampling with the PWM replaced by a high-frequency sampling at ~300kHz (over-sampling), because of the commutation noise of the current measuring amplifier at ~120kHz.
ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
ADC_Init(ADC3, &ADC_InitStructure);
ADC_RegularChannelConfig(ADC1, ADC1_Input_Chan, 1, ADC_SampleTime_56Cycles);
ADC_Cmd(ADC1, ENABLE);
ADC_SoftwareStartConv(ADC1);
ADC_RegularChannelConfig(ADC2, ADC2_Input_Chan, 1, ADC_SampleTime_56Cycles);
ADC_Cmd(ADC2, ENABLE);
ADC_SoftwareStartConv(ADC2);
ADC_RegularChannelConfig(ADC3, ADC_Current_Sens_Chan, 1, ADC_SampleTime_28Cycles);
ADC_DMARequestAfterLastTransferCmd(ADC3, ENABLE);
ADC_DMACmd(ADC3, ENABLE);
ADC_Cmd(ADC3, ENABLE);
ADC_SoftwareStartConv(ADC3);
// Setup the filter of the ADC current samples over time.
bfilt_Init(&adc_currentFilter, 0.2f, 0.0f);
}
/**
* @brief Setup the DMA that copies the current ADC samples to the RAM.
*/
void adc_DmaInit(void)
{
DMA_InitTypeDef DMA_InitStructure;
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA2, ENABLE);
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)&adc_currentValuesBuffer;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
DMA_InitStructure.DMA_BufferSize = ADC_BUFFER_SIZE;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Enable;
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_HalfFull;
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
DMA_InitStructure.DMA_Channel = DMA_Channel_2;
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC3->DR;
DMA_Init(DMA2_Stream1, &DMA_InitStructure);
DMA_Cmd(DMA2_Stream1, ENABLE);
}
/**
* @brief Compute the current sense offset.
* @note Run before enabling current regulation.
*/
void adc_CalibrateCurrentSens(void)
{
+ float32_t offset;
int32_t i=0;
- for(i=0; i<1000; i++)
+ for(i=0; i 0.0f)
- adc_currentSensOffset++;
- else
- adc_currentSensOffset--;
}
+
+ adc_currentSensOffset = offset;
}
/**
* @brief Compute the current sense offset.
* @retval The measured current in [mA].
*/
float32_t adc_GetCurrent(void)
{
int32_t motorCurrentSum;
float32_t motorCurrentMean;
int32_t i;
// Compute the average of all the ADC values in the buffer.
motorCurrentSum = 0; // [ADC raw value].
for(i=0; iCR2 |= (uint32_t)ADC_CR2_SWSTART;
else if(channel == ANIN2)
ADC2->CR2 |= (uint32_t)ADC_CR2_SWSTART;
}
/**
* @brief Get the ADC conversion status of the selected channel.
* @retval 1 if the conversion is finished, 0 otherwise.
*/
uint8_t adc_ConversionIsFinished(AdcChannel channel)
{
if(channel == ANIN1)
return (ADC1->SR & ADC_SR_EOC) != 0;
else if(channel == ANIN2)
return (ADC2->SR & ADC_SR_EOC) != 0;
else
return 0;
}
/**
* @brief Get the voltage measured by the selected ADC channel.
* @param channel: the channel of the ADC.
* @param scale: the full scale, depends of the switches position.
* @return the measured voltage, in [V], or 0.0f if the channel is invalid.
* @note make sure that the conversion is finished before calling.
*/
float32_t adc_GetConversionResult(AdcChannel channel, float32_t scale)
{
float32_t adcRawVal, voltage;
if(channel == ANIN1)
adcRawVal = (float32_t)ADC1->DR;
else if(channel == ANIN2)
adcRawVal = (float32_t)ADC2->DR;
else
adcRawVal = 0.0f;
voltage = (1.0f - (adcRawVal / (float32_t)ADC_MAX) * 2.0f) * scale;
return voltage;
}
/**
* @brief Get the voltage measured by the selected ADC channel.
* @param channel: the channel of the ADC.
* @param scale: the full scale, depends of the switches position.
* @return the measured voltage, in [V], or 0.0f if the channel is invalid.
* @note make sure that the conversion is finished before calling.
*/
float32_t adc_GetChannelVoltage(AdcChannel channel, float32_t scale)
{
int32_t conversionTime = 0;
adc_StartConversion(channel);
while(!adc_ConversionIsFinished(channel))
{
if(conversionTime < ADC_MAX_CONVERSION_TIME)
conversionTime++;
else
break;
}
return adc_GetConversionResult(channel, scale);
}
diff --git a/Firmware/src/drivers/adc.h b/Firmware/src/drivers/adc.h
index a74c388..381e6d8 100644
--- a/Firmware/src/drivers/adc.h
+++ b/Firmware/src/drivers/adc.h
@@ -1,77 +1,78 @@
#ifndef __ADC_H
#define __ADC_H
#include "../main.h"
#define ADC1_Input_Pin GPIO_Pin_4 // Analog diff. input 1
#define ADC1_Input_Port GPIOC
#define ADC1_Input_Chan ADC_Channel_14
#define ADC2_Input_Pin GPIO_Pin_5 // Analog diff. input 2
#define ADC2_Input_Port GPIOC
#define ADC2_Input_Chan ADC_Channel_15
#define ADC_Current_Sens_Pin GPIO_Pin_3 // Current sense channel
#define ADC_Current_Sens_Port GPIOA
#define ADC_Current_Sens_Chan ADC_Channel_3
-#define ADC_BUFFER_SIZE 33 // Fadc =~300kHz -> TE_ADC = 3.33us -> Average over 32 sample => usable bandwidth <10kHz
-#define CURRENT_SCALE (700.0f/1000.0f) // Scale between ADC increment -> mA (700inc. = 1000mA)
-#define ADC_MAX 4095
+#define ADC_MAX 4095 // Maximum value of the ADC register (2^12 - 1).
#define ADC_MAX_CONVERSION_TIME 100 // To avoid locking if the conversion was not started properly.
+#define ADC_BUFFER_SIZE 33 // Fadc =~300kHz -> TE_ADC = 3.33us -> Average over 32 sample => usable bandwidth <10kHz
+#define ADC_CURRENT_SCALE (STM_SUPPLY_VOLTAGE / (CURRENT_SHUNT_RESISTANCE * CURRENT_SHUNT_AMPLIFIER_GAIN * ADC_MAX)) // Scale between ADC increment and current [A/incr].
+#define ADC_CALIB_N_SAMPLES 1000
/** @defgroup ADC Driver / ADC
* @brief Driver for the analog-to-digital peripheral of the STM32.
*
* An analog-to-digital converter (ADC) is used to measure the voltage of one
* or several microcontroller pins. In the HRI board, there are two pins that
* can be used. An intermediate electronic stage allows to modify the input
* range from +-33mV to +-10V, in order to get the best sensitivity and range
* for a wide range of analog sensors. Note that the input connector
* (J2-ANALOG IN) provides differential inputs, so one pair of pins per
* channel.
*
* In addition, there is an additional channel to measure the current going
* through the motor (useful for current regulation).
*
* Call adc_Init() first, in the initialization code. Then, call
* adc_GetChannelVoltage() every time you need the voltage.
*
* To measure accurately the motor current, a calibration has to be performed
* first. Call dc_CalibrateCurrentSens() in the main(), when the current
* regulation is disabled (see H-bridge documentation). Then, call
* adc_GetCurrent() every time it is needed. This function returns the last
* value transfered by the DMA, so there is no conversion delay when calling
* this function.
*
* @addtogroup ADC
* @{
*/
// Switches-selectable scale of the ADC circuit.
// Could be useful to perform a calibration, to precise readings.
#define ADC_SCALE_0_033_V 0.033f ///< +-33mV, switches position: 0100
#define ADC_SCALE_0_165_V 0.165f ///< +-165mV, switches position: 0010
#define ADC_SCALE_0_400_V 0.400f ///< +-400mV, switches position: 1100
#define ADC_SCALE_0_830_V 0.830f ///< +-830mV, switches position: 0001
#define ADC_SCALE_2_V 2.000f ///< +-2V, switches position: 1010
#define ADC_SCALE_10_V 10.00f ///< +-10V, switches position: 1001
/**
* @brief Enum that corresponds to the two ADC input channels of the board.
*/
typedef enum
{
ANIN1=1, ///< Channel 1, pins ANIN1+ (3) and ANIN1- (4) of the connector J2.
ANIN2=2 ///< Channel 2, pins ANIN2+ (7) and ANIN2- (8) of the connector J2.
} AdcChannel;
void adc_Init(void);
void adc_CalibrateCurrentSens(void);
float32_t adc_GetCurrent(void); // [mA].
float32_t adc_GetChannelVoltage(AdcChannel channel, float32_t scale);
/**
* @}
*/
#endif
diff --git a/Firmware/src/lib/pid.c b/Firmware/src/lib/pid.c
index d6ad11a..925d84c 100644
--- a/Firmware/src/lib/pid.c
+++ b/Firmware/src/lib/pid.c
@@ -1,53 +1,58 @@
#include "pid.h"
#include "utils.h"
/**
* @brief Initialize the PID structure.
* @param pid: pointer to the PID structure.
* @param kp: proportionnal coefficient of the PID.
* @param ki: integral coefficient of the PID.
* @param kd: derivative coefficient of the PID.
* @param arw: maximum value of the integrator (anti-reset windup). Disabled if negative.
*/
-void pid_Init(pid_Pid *pid, float32_t kp, float32_t ki, float32_t kd, float32_t arw)
+void pid_Init(pid_Pid *pid, float32_t kp, float32_t ki, float32_t kd,
+ float32_t arw, float32_t feedforward)
{
pid->kp = kp;
pid->ki = ki;
pid->kd = kd;
pid->arw = arw;
pid->previousErr = 0.0f;
pid->integrator = 0.0f;
+ pid->feedforward = feedforward;
}
/**
* @brief Step the PID structure.
* @param pid: pointer to the PID structure.
* @param current: current state of the system to control.
* @param target: target state of the system to control.
* @param dt: timestep (time since the last call of this function) [s].
* @retval command to apply to the system.
*/
float32_t pid_Step(pid_Pid *pid, float32_t current, float32_t target, float32_t dt)
{
float32_t err = target - current;
+ // Feedforward part.
+ pid->command = pid->feedforward * target;
+
// Proportionnal part.
- pid->command = pid->kp * err;
+ pid->command += pid->kp * err;
// Integral part.
if(pid->ki > 0.0f)
{
pid->integrator += pid->ki * (err * dt);
if(pid->arw > 0.0f)
utils_SaturateF(&pid->integrator, -pid->arw, pid->arw);
pid->command += pid->integrator;
}
// Derivative part.
pid->command += pid->kd * ((err - pid->previousErr) / dt);
pid->previousErr = err;
return pid->command;
}
diff --git a/Firmware/src/lib/pid.h b/Firmware/src/lib/pid.h
index 254d67e..ca6f782 100644
--- a/Firmware/src/lib/pid.h
+++ b/Firmware/src/lib/pid.h
@@ -1,39 +1,41 @@
#ifndef __PID_H
#define __PID_H
#include "../main.h"
/** @defgroup PID Lib / PID regulator
* @brief Proportionnal-integral-derivative regulator with integrator
* saturation capability.
*
* First, instantiate a pid_Pid structure (e.g. "pid_Pid pid;"), then
* initialize it once with pid_Init(). Then, every time a new command needs to
* be computed (typically when a new measurement arrives), call pid_Step().
*
* @addtogroup PID
* @{
*/
/**
*@brief PID regulator structure
*/
typedef struct
{
float32_t kp, ///< Proportional coefficient.
ki, ///< Integral coefficient. Disabled if negative or zero.
kd, ///< Derivative coefficient.
arw, ///< Max value of the integrator ("anti-reset windup"). Disabled if negative or zero.
previousErr, ///< Error (current-target) at the previous timestep, for derivative computation.
integrator, ///< Integrator value for the integral part of the PID.
- command; ///< Output command computed by the PID regulator.
+ command, ///< Output command computed by the PID regulator.
+ feedforward; ///< Feedforward coefficient.
} pid_Pid;
-void pid_Init(pid_Pid *pid, float32_t kp, float32_t ki, float32_t kd, float32_t arw);
+void pid_Init(pid_Pid *pid, float32_t kp, float32_t ki, float32_t kd,
+ float32_t arw, float32_t feedforward);
float32_t pid_Step(pid_Pid *pid, float32_t current, float32_t target, float32_t dt);
/**
* @}
*/
#endif
diff --git a/Firmware/src/main.c b/Firmware/src/main.c
index 1eca0c7..e61e1fe 100644
--- a/Firmware/src/main.c
+++ b/Firmware/src/main.c
@@ -1,47 +1,53 @@
#include "main.h"
#include "communication.h"
#include "controller.h"
#include "drivers/adc.h"
#include "drivers/callback_timers.h"
#include "drivers/dac.h"
#include "drivers/h_bridge.h"
#include "drivers/hall.h"
#include "drivers/incr_encoder.h"
#include "drivers/strain_gauge.h"
#include "drivers/tachometer.h"
+#include "lib/utils.h"
volatile uint32_t statusReg = 0x00000000; // Main state register.
/**
* @brief Main function, setups all the drivers and controllers.
*/
int main(void)
{
cbt_Init(); // Setup the timers that will call the loops functions.
adc_Init(); // Setup the ADC.
comm_Init(); // Setup the communication module.
ctrl_Init(); // Setup the controllers.
enc_Init(); // Incremental encoders.
hb_Init(); // H-bridge.
hb_Enable();
+
+ // Delay to let the power electronics stabilize before calibrating the
+ // current sensor.
+ utils_DelayMs(200);
+
adc_CalibrateCurrentSens();
statusReg |= RUN_CURRENT_LOOP;
dac_Init();
// Init external sensors drivers, connected to the ADC.
hall_Init(ANIN1);
//sg_Init(ANIN2);
//tac_Init(ANIN2);
// Endless loop. It is empty, because all the control is performed in the
// functions called periodically by the interrupts.
while(1)
{
}
}
diff --git a/Firmware/src/main.h b/Firmware/src/main.h
index 4dc174c..b2190a0 100644
--- a/Firmware/src/main.h
+++ b/Firmware/src/main.h
@@ -1,92 +1,97 @@
/** \mainpage HRI board firmware documentation
* \section intro_sec Introduction
* This is the documentation of the HRI board firmware. You will find a
* description of the provided library and drivers. As all the hardware and
* software is very new, please do not hesitate to suggest improvements to the
* course assistants (Romain Baud, Philipp Hörler and Laurent Jenni).
*
* \section code_struct_sec Code structure
* The code is divided into 3 parts:
* - main: this is where the controllers and the communication protocol are
* implemented. The call of all the initialization functions is also made here.
* - library: all the algorithms, data structures that could be used at many
* places, are put into the library.
* - drivers: there is one driver per peripheral. All the hardware-specific
* code is wrapped into these files, so that the user does not have to use a
*
* One module (controller, communication, library or driver) is always splitted
* in two files, .h and .c, like in C++.
* @image html soft_architecture.png
*
* \section lib_how_to How to use the provided library
* For most of the driver/library modules, call x_Init() only once, when the
* program starts (typically in the main()). Then, you can call
* x_Step()/x_Set()/x_Get() everytime as needed, typically in the control
* functions called periodically (ctrl_RegulatePosition()...).
*
* See the "Modules" section of this documentation to see how they work.
*/
#ifndef __MAIN_H
#define __MAIN_H
#include "stm32f4_discovery.h"
#include
#include "arm_math.h"
// Clocks configuration.
#define APB1_PRESCALER 4
#define APB2_PRESCALER 2
#define TIM_MULTIPLIER 2
// Interupt priority.
#define CURRENT_LOOP_IRQ_PRIORITY 1 // High freq loop, should not be interrupted.
#define CONTROL_LOOP_IRQ_PRIORITY 2
#define CODER_INDEX_IRQ_PRIORITY 2 // Useless, remove?
#define UART_RX_IRQ_PRIORIY 3
#define DATA_LOOP_IRQ_PRIORITY 4 // Streaming packets, lowest priority.
-// Electrical parameters
+// Electrical parameters.
#define STM_SUPPLY_VOLTAGE 3.3f // [V].
+#define H_BRIDGE_SUPPLY_VOLTAGE 24.0f // [V].
+#define CURRENT_SHUNT_RESISTANCE 0.01f // [ohm].
+#define CURRENT_SHUNT_AMPLIFIER_GAIN 50 // [].
+#define MOTOR_RESISTANCE 10.6f + 5.0f // 10.6 ohm according to the datasheet, actually more, depends on the motor [ohm].
// Mechanical parameters.
#define REDUCTION_RATIO 15.0f
+#define MOTOR_TORQUE_CONST 0.0538f // [N.m/A].
// Status register bit list.
#define STREG_0 ((uint32_t)0x00000001)
#define STREG_1 ((uint32_t)0x00000002)
#define REF_POS_INIT ((uint32_t)0x00000004) // 1 -> Ref position succesfully found
#define CALIBRE ((uint32_t)0x00000008) // 1 -> Calibration done
#define RUN_CURRENT_LOOP ((uint32_t)0x00000010) // 1 -> Current loop active (if motorDrv eneable but RUN_CURRENT_LOOP=false -> fixed 50% PWM on the motor)
#define UN_CONTROL_LOOP ((uint32_t)0x00000020) // 1 -> Control loop active
#define STREG_6 ((uint32_t)0x00000040)
#define STREG_7 ((uint32_t)0x00000080)
#define STREG_8 ((uint32_t)0x00000100)
#define DATA_UPSTREAM_ENB ((uint32_t)0x00000200) // 1 -> data upstream active
#define STREG_10 ((uint32_t)0x00000400)
#define RX_COMPLETED ((uint32_t)0x00000800) // 1 -> packet recieved
#define RX_ERROR ((uint32_t)0x00001000) // 1 -> last received packet incorrect
#define PROCESSING_REQUEST ((uint32_t)0x00002000) // 1 -> processing last received packet in progress (can not receive new data)
#define LAST_REQUEST_IGNORED ((uint32_t)0x00004000)
#define STREG_15 ((uint32_t)0x00008000)
#define STREG_16 ((uint32_t)0x00010000)
#define STREG_17 ((uint32_t)0x00020000)
#define STREG_18 ((uint32_t)0x00040000)
#define STREG_19 ((uint32_t)0x00080000)
#define STREG_20 ((uint32_t)0x00100000)
#define STREG_21 ((uint32_t)0x00200000)
#define STREG_22 ((uint32_t)0x00400000)
#define STREG_23 ((uint32_t)0x00800000)
#define INDEX_ERROR ((uint32_t)0x01000000) // 1 -> wrong step count over 1 rotation
#define STREG_25 ((uint32_t)0x02000000)
#define STREG_26 ((uint32_t)0x04000000)
#define STREG_27 ((uint32_t)0x08000000)
#define STREG_28 ((uint32_t)0x10000000)
#define STREG_29 ((uint32_t)0x20000000)
#define STREG_30 ((uint32_t)0x40000000)
#define STREG_31 ((uint32_t)0x80000000)
#endif