fixed indentation on all files

This commit is contained in:
Jasper Güldenstein 2020-11-15 18:21:34 +01:00
parent 3b3b35d537
commit 642a5ebfdc
18 changed files with 459 additions and 484 deletions

View file

@ -402,22 +402,6 @@
<Bp>
<Number>0</Number>
<Type>0</Type>
<LineNumber>40</LineNumber>
<EnabledFlag>1</EnabledFlag>
<Address>134223706</Address>
<ByteObject>0</ByteObject>
<HtxType>0</HtxType>
<ManyObjects>0</ManyObjects>
<SizeOfObject>0</SizeOfObject>
<BreakByAccess>0</BreakByAccess>
<BreakIfRCount>1</BreakIfRCount>
<Filename>..\Services\RFInput.c</Filename>
<ExecCommand></ExecCommand>
<Expression>\\NUCLEO_F103RB\../Services/RFInput.c\40</Expression>
</Bp>
<Bp>
<Number>1</Number>
<Type>0</Type>
<LineNumber>71</LineNumber>
<EnabledFlag>1</EnabledFlag>
<Address>0</Address>
@ -432,7 +416,7 @@
<Expression></Expression>
</Bp>
<Bp>
<Number>2</Number>
<Number>1</Number>
<Type>0</Type>
<LineNumber>46</LineNumber>
<EnabledFlag>1</EnabledFlag>
@ -628,7 +612,7 @@
<GroupNumber>2</GroupNumber>
<FileNumber>7</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\Services\Accelerometer.c</PathWithFileName>

View file

@ -8,7 +8,7 @@
#include <math.h>
#ifndef M_PI
#define M_PI 3.14159265358979323846
#define M_PI 3.14159265358979323846
#endif
#define ANGLE_LIMIT_DEG 40
@ -20,67 +20,67 @@
#define VOLT_PER_G 0.48
void ACCELEROMETER_Init(void){
RCC -> CFGR |= (0x1<<15);
RCC-> CFGR &= ~ (0x1<<14);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_ADC1);
LL_APB1_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOC);
RCC -> CFGR |= (0x1<<15);
RCC-> CFGR &= ~ (0x1<<14);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_ADC1);
LL_APB1_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOC);
LL_GPIO_InitTypeDef pc0, pc1;
LL_ADC_InitTypeDef adc;
LL_ADC_REG_InitTypeDef adcReg;
LL_GPIO_InitTypeDef pc0, pc1;
LL_ADC_InitTypeDef adc;
LL_ADC_REG_InitTypeDef adcReg;
LL_GPIO_StructInit(&pc0);
pc0.Pin = LL_GPIO_PIN_0;
pc0.Mode = LL_GPIO_MODE_ANALOG;
LL_GPIO_Init(GPIOA, &pc0);
LL_GPIO_StructInit(&pc0);
pc0.Pin = LL_GPIO_PIN_0;
pc0.Mode = LL_GPIO_MODE_ANALOG;
LL_GPIO_Init(GPIOA, &pc0);
LL_GPIO_StructInit(&pc1);
pc1.Pin = LL_GPIO_PIN_1;
pc1.Mode = LL_GPIO_MODE_ANALOG;
LL_GPIO_Init(GPIOA, &pc1);
LL_GPIO_StructInit(&pc1);
pc1.Pin = LL_GPIO_PIN_1;
pc1.Mode = LL_GPIO_MODE_ANALOG;
LL_GPIO_Init(GPIOA, &pc1);
adc.DataAlignment = LL_ADC_DATA_ALIGN_RIGHT;
adc.SequencersScanMode = LL_ADC_SEQ_SCAN_DISABLE;
LL_ADC_Init(ADC1, &adc);
adc.DataAlignment = LL_ADC_DATA_ALIGN_RIGHT;
adc.SequencersScanMode = LL_ADC_SEQ_SCAN_DISABLE;
LL_ADC_Init(ADC1, &adc);
adcReg.TriggerSource = LL_ADC_REG_TRIG_SOFTWARE ;
adcReg.SequencerLength = LL_ADC_REG_SEQ_SCAN_DISABLE;
adcReg.SequencerDiscont = LL_ADC_REG_SEQ_DISCONT_DISABLE;
adcReg.ContinuousMode = LL_ADC_REG_CONV_SINGLE;
adcReg.DMATransfer = LL_ADC_REG_DMA_TRANSFER_NONE;
adcReg.TriggerSource = LL_ADC_REG_TRIG_SOFTWARE ;
adcReg.SequencerLength = LL_ADC_REG_SEQ_SCAN_DISABLE;
adcReg.SequencerDiscont = LL_ADC_REG_SEQ_DISCONT_DISABLE;
adcReg.ContinuousMode = LL_ADC_REG_CONV_SINGLE;
adcReg.DMATransfer = LL_ADC_REG_DMA_TRANSFER_NONE;
LL_ADC_REG_Init(ADC1, &adcReg);
LL_ADC_Enable(ADC1);
LL_ADC_REG_Init(ADC1, &adcReg);
LL_ADC_Enable(ADC1);
}
double ACCELEROMETER_GetX(void){
LL_ADC_REG_SetSequencerRanks(ADC1, LL_ADC_REG_RANK_1, LL_ADC_CHANNEL_1);
LL_ADC_REG_StartConversionSWStart(ADC1);
while (LL_ADC_IsActiveFlag_EOS(ADC1) != 1);
double x= (LL_ADC_REG_ReadConversionData12(ADC1) - ZERO_G_READING) * VOLT_PER_G;
return x;
LL_ADC_REG_SetSequencerRanks(ADC1, LL_ADC_REG_RANK_1, LL_ADC_CHANNEL_1);
LL_ADC_REG_StartConversionSWStart(ADC1);
while (LL_ADC_IsActiveFlag_EOS(ADC1) != 1);
double x= (LL_ADC_REG_ReadConversionData12(ADC1) - ZERO_G_READING) * VOLT_PER_G;
return x;
}
double ACCELEROMETER_GetY(void){
LL_ADC_REG_SetSequencerRanks(ADC1, LL_ADC_REG_RANK_1, LL_ADC_CHANNEL_11);
LL_ADC_REG_StartConversionSWStart(ADC1);
LL_ADC_REG_SetSequencerRanks(ADC1, LL_ADC_REG_RANK_1, LL_ADC_CHANNEL_11);
LL_ADC_REG_StartConversionSWStart(ADC1);
while (LL_ADC_IsActiveFlag_EOS(ADC1) != 1);
double y = (LL_ADC_REG_ReadConversionData12(ADC1)-ZERO_G_READING) * VOLT_PER_G;
return y;
return y;
}
int ACCELEROMETER_AngleGood(void){
double x = ACCELEROMETER_GetX();
double y = ACCELEROMETER_GetY();
double angle = atan(x/y);
double x = ACCELEROMETER_GetX();
double y = ACCELEROMETER_GetY();
double angle = atan(x/y);
if (fabs(angle)>ANGLE_LIMIT_RAD){
return 0;
}else {
return 1;
}
//le flag EOC n'est jamais mis à un ....
// Soit la conversion est mal faite soit on n'utilise pas bien la simulation
//soit on n'utilise pas bien isActiveFlag dans la boucle
if (fabs(angle)>ANGLE_LIMIT_RAD){
return 0;
}else {
return 1;
}
//le flag EOC n'est jamais mis à un ....
// Soit la conversion est mal faite soit on n'utilise pas bien la simulation
//soit on n'utilise pas bien isActiveFlag dans la boucle
}

View file

@ -10,28 +10,28 @@
/**
* @brief Initializes for reading the Accelerometer
* Peripherals used: ADC1
* Pins used: PC0 (Analog Input, X channel accelerometer)
* Pins used: PC1 (Analog Input, Y channel accelerometer)
* Peripherals used: ADC1
* Pins used: PC0 (Analog Input, X channel accelerometer)
* Pins used: PC1 (Analog Input, Y channel accelerometer)
*/
void ACCELEROMETER_Init(void);
/**
* @brief Reads the accelerometer x channel
* @retval acceleration in x direction in g
* @retval acceleration in x direction in g
*/
double ACCELEROMETER_GetX(void);
/**
* @brief Reads the accelerometer y channel
* @retval acceleration in y direction in g
* @retval acceleration in y direction in g
*/
double ACCELEROMETER_GetY(void);
/**
* @brief Reads the accelerometer x and y channel
Calculates if the roll angle lies between -40 and 40 degrees
* @retval state (0 or 1)
Calculates if the roll angle lies between -40 and 40 degrees
* @retval state (0 or 1)
*/
int ACCELEROMETER_AngleGood(void);

View file

@ -7,52 +7,51 @@
#include <math.h>
void ALIMENTATION_Init(void){
RCC -> CFGR |= (0x1<<15);
RCC-> CFGR &= ~ (0x1<<14);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_ADC1);
LL_APB1_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOC);
RCC -> CFGR |= (0x1<<15);
RCC-> CFGR &= ~ (0x1<<14);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_ADC1);
LL_APB1_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOC);
LL_GPIO_InitTypeDef pc2;
LL_ADC_InitTypeDef adc;
LL_ADC_REG_InitTypeDef adcReg;
LL_GPIO_InitTypeDef pc2;
LL_ADC_InitTypeDef adc;
LL_ADC_REG_InitTypeDef adcReg;
LL_GPIO_StructInit(&pc2);
pc2.Pin = LL_GPIO_PIN_0;
pc2.Mode = LL_GPIO_MODE_ANALOG;
LL_GPIO_Init(GPIOC, &pc2);
LL_GPIO_StructInit(&pc2);
pc2.Pin = LL_GPIO_PIN_0;
pc2.Mode = LL_GPIO_MODE_ANALOG;
LL_GPIO_Init(GPIOC, &pc2);
adc.DataAlignment = LL_ADC_DATA_ALIGN_RIGHT;
adc.SequencersScanMode = LL_ADC_SEQ_SCAN_DISABLE;
LL_ADC_Init(ADC1, &adc);
adc.DataAlignment = LL_ADC_DATA_ALIGN_RIGHT;
adc.SequencersScanMode = LL_ADC_SEQ_SCAN_DISABLE;
LL_ADC_Init(ADC1, &adc);
adcReg.TriggerSource = LL_ADC_REG_TRIG_SOFTWARE ;
adcReg.SequencerLength = LL_ADC_REG_SEQ_SCAN_DISABLE;
adcReg.SequencerDiscont = LL_ADC_REG_SEQ_DISCONT_DISABLE;
adcReg.ContinuousMode = LL_ADC_REG_CONV_SINGLE;
adcReg.DMATransfer = LL_ADC_REG_DMA_TRANSFER_NONE;
adcReg.TriggerSource = LL_ADC_REG_TRIG_SOFTWARE ;
adcReg.SequencerLength = LL_ADC_REG_SEQ_SCAN_DISABLE;
adcReg.SequencerDiscont = LL_ADC_REG_SEQ_DISCONT_DISABLE;
adcReg.ContinuousMode = LL_ADC_REG_CONV_SINGLE;
adcReg.DMATransfer = LL_ADC_REG_DMA_TRANSFER_NONE;
LL_ADC_REG_Init(ADC1, &adcReg);
LL_ADC_Enable(ADC1);
LL_ADC_REG_Init(ADC1, &adcReg);
LL_ADC_Enable(ADC1);
}
float ALIMENTATION_GetBatteryLevel(void){
float u2;
float battery_level;
LL_ADC_REG_SetSequencerRanks(ADC1, LL_ADC_REG_RANK_1, LL_ADC_CHANNEL_12);
LL_ADC_REG_StartConversionSWStart(ADC1);
while (LL_ADC_IsActiveFlag_EOS(ADC1) != 1);
battery_level = LL_ADC_REG_ReadConversionData12(ADC1);
u2 = (battery_level*3.3)/4095.0;
float level = u2*13.0;
return level;
float u2;
float battery_level;
LL_ADC_REG_SetSequencerRanks(ADC1, LL_ADC_REG_RANK_1, LL_ADC_CHANNEL_12);
LL_ADC_REG_StartConversionSWStart(ADC1);
while (LL_ADC_IsActiveFlag_EOS(ADC1) != 1);
battery_level = LL_ADC_REG_ReadConversionData12(ADC1);
u2 = (battery_level*3.3)/4095.0;
float level = u2*13.0;
return level;
}
int ALIMENTATION_IsLevelEnough(void){
if (ALIMENTATION_GetBatteryLevel()<(0.8*12)){
return 0;
}else{
return 1;
}
if (ALIMENTATION_GetBatteryLevel()<(0.8*12)){
return 0;
}else{
return 1;
}
}

View file

@ -10,20 +10,20 @@
/**
* @brief Initializes for reading of the power supply/battery level
* Peripherals used: ADC1
* Pins used: PC2 (Analog input)
* Peripherals used: ADC1
* Pins used: PC2 (Analog input)
*/
void ALIMENTATION_Init(void);
/**
* @brief Reads the power supply/battery level
* @retval battery level in Volts
* @retval battery level in Volts
*/
float ALIMENTATION_GetBatteryLevel(void);
/**
* @brief Returns if the power supply/battery level is above acceptable level
* @retval state (0 or 1)
* @retval state (0 or 1)
*/
int ALIMENTATION_IsLevelEnough(void);

View file

@ -5,61 +5,61 @@
#define ARR_DC_MOTOR 100
void DC_MOTOR_Init(void) {
// setup timer 2
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2);
LL_TIM_InitTypeDef tim_init;
tim_init.Prescaler = 35;
tim_init.Autoreload = ARR_DC_MOTOR - 1;
tim_init.ClockDivision=LL_TIM_CLOCKDIVISION_DIV1;
tim_init.CounterMode=LL_TIM_COUNTERMODE_UP;
tim_init.RepetitionCounter=0;
LL_TIM_Init(TIM2, &tim_init);
// setup timer 2
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM2);
LL_TIM_InitTypeDef tim_init;
tim_init.Prescaler = 35;
tim_init.Autoreload = ARR_DC_MOTOR - 1;
tim_init.ClockDivision=LL_TIM_CLOCKDIVISION_DIV1;
tim_init.CounterMode=LL_TIM_COUNTERMODE_UP;
tim_init.RepetitionCounter=0;
LL_TIM_Init(TIM2, &tim_init);
// setup gpio
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
LL_GPIO_InitTypeDef servo_gpio_init;
servo_gpio_init.Pin = LL_GPIO_PIN_1;
// setup gpio
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
LL_GPIO_InitTypeDef servo_gpio_init;
servo_gpio_init.Pin = LL_GPIO_PIN_1;
servo_gpio_init.Mode = LL_GPIO_MODE_ALTERNATE;
servo_gpio_init.Speed = LL_GPIO_SPEED_FREQ_LOW;
servo_gpio_init.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
LL_GPIO_Init(GPIOA, &servo_gpio_init);
LL_GPIO_Init(GPIOA, &servo_gpio_init);
// setup output compare
LL_TIM_OC_InitTypeDef oc_init;
oc_init.OCMode = LL_TIM_OCMODE_PWM1;
oc_init.OCState = LL_TIM_OCSTATE_ENABLE;
oc_init.OCNState = LL_TIM_OCSTATE_ENABLE;
oc_init.CompareValue = 0; // off at start
oc_init.OCPolarity = LL_TIM_OCPOLARITY_HIGH;
oc_init.OCNPolarity = LL_TIM_OCPOLARITY_LOW;
oc_init.OCIdleState = LL_TIM_OCIDLESTATE_LOW;
oc_init.OCNIdleState = LL_TIM_OCIDLESTATE_HIGH;
LL_TIM_OC_Init(TIM2, LL_TIM_CHANNEL_CH2, &oc_init);
LL_TIM_EnableCounter(TIM2);
// setup output compare
LL_TIM_OC_InitTypeDef oc_init;
oc_init.OCMode = LL_TIM_OCMODE_PWM1;
oc_init.OCState = LL_TIM_OCSTATE_ENABLE;
oc_init.OCNState = LL_TIM_OCSTATE_ENABLE;
oc_init.CompareValue = 0; // off at start
oc_init.OCPolarity = LL_TIM_OCPOLARITY_HIGH;
oc_init.OCNPolarity = LL_TIM_OCPOLARITY_LOW;
oc_init.OCIdleState = LL_TIM_OCIDLESTATE_LOW;
oc_init.OCNIdleState = LL_TIM_OCIDLESTATE_HIGH;
LL_TIM_OC_Init(TIM2, LL_TIM_CHANNEL_CH2, &oc_init);
LL_TIM_EnableCounter(TIM2);
// init gpio for direction (sense) pin
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
// init gpio for direction (sense) pin
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
LL_GPIO_InitTypeDef pa2_init_conf;
pa2_init_conf.Mode = LL_GPIO_MODE_OUTPUT;
pa2_init_conf.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
pa2_init_conf.Speed = LL_GPIO_SPEED_FREQ_LOW;
pa2_init_conf.Pin = LL_GPIO_PIN_2;
LL_GPIO_Init(GPIOA, &pa2_init_conf);
LL_GPIO_InitTypeDef pa2_init_conf;
pa2_init_conf.Mode = LL_GPIO_MODE_OUTPUT;
pa2_init_conf.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
pa2_init_conf.Speed = LL_GPIO_SPEED_FREQ_LOW;
pa2_init_conf.Pin = LL_GPIO_PIN_2;
LL_GPIO_Init(GPIOA, &pa2_init_conf);
}
void DC_MOTOR_SetSpeed(int speed){
if(speed <= 100 && speed >= 0){
LL_GPIO_SetOutputPin(GPIOA,LL_GPIO_PIN_2);
int converted_speed = speed * (ARR_DC_MOTOR / 100);
TIM2->CCR2 = converted_speed;
} else if (speed >= -100 && speed <= 0) {
LL_GPIO_ResetOutputPin(GPIOA,LL_GPIO_PIN_2); // TODO maybe switch around set and reset, depending on direction of turning
int converted_speed = (-1) * speed * (ARR_DC_MOTOR / 100);
TIM2->CCR2 = converted_speed;
} else {
TIM2->CCR2 = 0;
}
if(speed <= 100 && speed >= 0){
LL_GPIO_SetOutputPin(GPIOA,LL_GPIO_PIN_2);
int converted_speed = speed * (ARR_DC_MOTOR / 100);
TIM2->CCR2 = converted_speed;
} else if (speed >= -100 && speed <= 0) {
LL_GPIO_ResetOutputPin(GPIOA,LL_GPIO_PIN_2); // TODO maybe switch around set and reset, depending on direction of turning
int converted_speed = (-1) * speed * (ARR_DC_MOTOR / 100);
TIM2->CCR2 = converted_speed;
} else {
TIM2->CCR2 = 0;
}
}

View file

@ -10,16 +10,16 @@
/**
* @brief Initialziation function for the DC_MOTOR module.
* Peripherals used: TIM2
* Pins used: PA1 (TIM2 channel 1, PWM Output)
* PA2 (GPIO, direction control)
* Peripherals used: TIM2
* Pins used: PA1 (TIM2 channel 1, PWM Output)
* PA2 (GPIO, direction control)
*/
void DC_MOTOR_Init(void);
/**
* @brief Sets the speed of the DC motor using a PWM signal with a period of 50us -> frequency of 20kHz and a resolution of 0.5us
* @param speed value between -100 (full throttle clockwise), 0 (stop), and 100 (full throttle counterclockwise)
*/
* @param speed value between -100 (full throttle clockwise), 0 (stop), and 100 (full throttle counterclockwise)
*/
void DC_MOTOR_SetSpeed(int speed);
#endif

View file

@ -15,96 +15,93 @@ int index_passed = 0;
void INCR_ENCODER_Init(void){
// GPIO initialization for channels a and b of the encoder
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
LL_GPIO_InitTypeDef channel_a_pin_conf, channel_b_pin_conf;
// GPIO initialization for channels a and b of the encoder
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
LL_GPIO_InitTypeDef channel_a_pin_conf, channel_b_pin_conf;
channel_a_pin_conf.Mode = LL_GPIO_MODE_FLOATING;
channel_a_pin_conf.Pin = LL_GPIO_PIN_6;
LL_GPIO_Init(GPIOA, &channel_a_pin_conf);
channel_a_pin_conf.Mode = LL_GPIO_MODE_FLOATING;
channel_a_pin_conf.Pin = LL_GPIO_PIN_6;
LL_GPIO_Init(GPIOA, &channel_a_pin_conf);
channel_b_pin_conf.Mode = LL_GPIO_MODE_FLOATING;
channel_b_pin_conf.Pin = LL_GPIO_PIN_7;
LL_GPIO_Init(GPIOA, &channel_b_pin_conf);
channel_b_pin_conf.Mode = LL_GPIO_MODE_FLOATING;
channel_b_pin_conf.Pin = LL_GPIO_PIN_7;
LL_GPIO_Init(GPIOA, &channel_b_pin_conf);
// timer init
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM3);
LL_TIM_InitTypeDef tim3_init_struct;
// timer init
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM3);
LL_TIM_InitTypeDef tim3_init_struct;
tim3_init_struct.Autoreload= TICKS_PER_REVOLUTION-1;
tim3_init_struct.Prescaler=0;
tim3_init_struct.ClockDivision=LL_TIM_CLOCKDIVISION_DIV1;
tim3_init_struct.CounterMode=LL_TIM_COUNTERMODE_UP;
tim3_init_struct.RepetitionCounter=0;
tim3_init_struct.Autoreload= TICKS_PER_REVOLUTION-1;
tim3_init_struct.Prescaler=0;
tim3_init_struct.ClockDivision=LL_TIM_CLOCKDIVISION_DIV1;
tim3_init_struct.CounterMode=LL_TIM_COUNTERMODE_UP;
tim3_init_struct.RepetitionCounter=0;
LL_TIM_Init(TIM3, &tim3_init_struct);
LL_TIM_Init(TIM3, &tim3_init_struct);
// timer as encoder init
LL_TIM_ENCODER_InitTypeDef encoder_init_struct;
encoder_init_struct.EncoderMode = LL_TIM_ENCODERMODE_X4_TI12;
encoder_init_struct.IC1Polarity = LL_TIM_IC_POLARITY_RISING;
encoder_init_struct.IC2Polarity = LL_TIM_IC_POLARITY_RISING;
encoder_init_struct.IC1ActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI;
encoder_init_struct.IC2ActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI;
encoder_init_struct.IC1Prescaler = LL_TIM_ICPSC_DIV1;
encoder_init_struct.IC2Prescaler= LL_TIM_ICPSC_DIV1;
encoder_init_struct.IC1Filter = LL_TIM_IC_FILTER_FDIV1 ;
encoder_init_struct.IC2Filter = LL_TIM_IC_FILTER_FDIV1 ;
// timer as encoder init
LL_TIM_ENCODER_InitTypeDef encoder_init_struct;
encoder_init_struct.EncoderMode = LL_TIM_ENCODERMODE_X4_TI12;
encoder_init_struct.IC1Polarity = LL_TIM_IC_POLARITY_RISING;
encoder_init_struct.IC2Polarity = LL_TIM_IC_POLARITY_RISING;
encoder_init_struct.IC1ActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI;
encoder_init_struct.IC2ActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI;
encoder_init_struct.IC1Prescaler = LL_TIM_ICPSC_DIV1;
encoder_init_struct.IC2Prescaler= LL_TIM_ICPSC_DIV1;
encoder_init_struct.IC1Filter = LL_TIM_IC_FILTER_FDIV1 ;
encoder_init_struct.IC2Filter = LL_TIM_IC_FILTER_FDIV1 ;
LL_TIM_ENCODER_Init(TIM3, &encoder_init_struct);
LL_TIM_ENCODER_Init(TIM3, &encoder_init_struct);
LL_TIM_EnableCounter(TIM3);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_AFIO);
LL_TIM_EnableCounter(TIM3);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_AFIO);
// gpio init for index (interrup) pin
LL_GPIO_InitTypeDef index_pin_conf;
// gpio init for index (interrup) pin
LL_GPIO_InitTypeDef index_pin_conf;
index_pin_conf.Pin = LL_GPIO_PIN_5;
index_pin_conf.Mode = LL_GPIO_MODE_FLOATING;
index_pin_conf.Pin = LL_GPIO_PIN_5;
index_pin_conf.Mode = LL_GPIO_MODE_FLOATING;
LL_GPIO_Init(GPIOC, &index_pin_conf);
LL_GPIO_Init(GPIOC, &index_pin_conf);
// exti init (interrupt)
LL_EXTI_InitTypeDef exti;
// exti init (interrupt)
LL_EXTI_InitTypeDef exti;
exti.Line_0_31 = LL_EXTI_LINE_5;
exti.LineCommand = ENABLE;
exti.Mode = LL_EXTI_MODE_IT;
exti.Trigger = LL_EXTI_TRIGGER_RISING;
exti.Line_0_31 = LL_EXTI_LINE_5;
exti.LineCommand = ENABLE;
exti.Mode = LL_EXTI_MODE_IT;
exti.Trigger = LL_EXTI_TRIGGER_RISING;
LL_EXTI_Init(&exti);
LL_GPIO_AF_SetEXTISource(LL_GPIO_AF_EXTI_PORTA, LL_GPIO_AF_EXTI_LINE5);
// enable interrupt from exti in NVIC
NVIC_SetPriority(EXTI9_5_IRQn, 12); // prio??
NVIC_EnableIRQ(EXTI9_5_IRQn);
LL_EXTI_Init(&exti);
LL_GPIO_AF_SetEXTISource(LL_GPIO_AF_EXTI_PORTA, LL_GPIO_AF_EXTI_LINE5);
// enable interrupt from exti in NVIC
NVIC_SetPriority(EXTI9_5_IRQn, 12); // prio??
NVIC_EnableIRQ(EXTI9_5_IRQn);
}
void EXTI9_5_IRQHandler(void){
index_passed = 1;
// reset counter = encoder position to 0 position
LL_TIM_WriteReg(TIM3,CNT,0);
// clear pending (EXTI necessary ?)
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_5);
NVIC_ClearPendingIRQ(EXTI9_5_IRQn);
index_passed = 1;
// reset counter = encoder position to 0 position
LL_TIM_WriteReg(TIM3,CNT,0);
// clear pending (EXTI necessary ?)
LL_EXTI_ClearFlag_0_31(LL_EXTI_LINE_5);
NVIC_ClearPendingIRQ(EXTI9_5_IRQn);
}
int INCR_ENCODER_IsAbsolute(void)
{
return index_passed;
return index_passed;
};
float INCR_ENCODER_GetAngle(void)
{
int counter_value = LL_TIM_ReadReg(TIM3, CNT);
// center
int centered_counter_value = (counter_value - ZERO_POSITION) % TICKS_PER_REVOLUTION;
// translate ticks to angle
float angle = centered_counter_value * DEGREE_PER_TICKS;
return angle;
int counter_value = LL_TIM_ReadReg(TIM3, CNT);
// center
int centered_counter_value = (counter_value - ZERO_POSITION) % TICKS_PER_REVOLUTION;
// translate ticks to angle
float angle = centered_counter_value * DEGREE_PER_TICKS;
return angle;
};

View file

@ -10,23 +10,23 @@
/**
* @brief Initialziation function for the RF_OUTPUT module.
* Peripherals used: TIM3, EXTI
* Pins used: PA5 (incremental encoder index, interrupt)
* PA6 (incremental encoder channel a, TIM3 channel 1)
* PA7 (incremental encoder channel b, TIM3 channel 2)
* Peripherals used: TIM3, EXTI
* Pins used: PA5 (incremental encoder index, interrupt)
* PA6 (incremental encoder channel a, TIM3 channel 1)
* PA7 (incremental encoder channel b, TIM3 channel 2)
*/
void INCR_ENCODER_Init(void);
/**
* @brief Indicates whether the index has been passed at least once.
* If this is not the case, the reading is not absolute.
* @retval state (0 or 1)
* If this is not the case, the reading is not absolute.
* @retval state (0 or 1)
*/
int INCR_ENCODER_IsAbsolute(void);
/**
* @brief Returns the angle reading of the incremental encoder
* @retval -180 to 180 where 0 is the incremental encoder pointing towards the back of the boat
* @retval -180 to 180 where 0 is the incremental encoder pointing towards the back of the boat
*/
float INCR_ENCODER_GetAngle(void);

View file

@ -8,70 +8,69 @@
void RF_INPUT_Init(void)
{
// GPIO setup
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOB);
LL_GPIO_InitTypeDef pb6_init_conf, pb7_init_conf;
// GPIO setup
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOB);
LL_GPIO_InitTypeDef pb6_init_conf, pb7_init_conf;
pb6_init_conf.Mode = LL_GPIO_MODE_FLOATING;
pb6_init_conf.Pin = LL_GPIO_PIN_6;
pb6_init_conf.Pull = LL_GPIO_PULL_DOWN;
LL_GPIO_Init(GPIOB, &pb6_init_conf);
pb6_init_conf.Mode = LL_GPIO_MODE_FLOATING;
pb6_init_conf.Pin = LL_GPIO_PIN_6;
pb6_init_conf.Pull = LL_GPIO_PULL_DOWN;
LL_GPIO_Init(GPIOB, &pb6_init_conf);
pb7_init_conf.Mode = LL_GPIO_MODE_FLOATING;
pb7_init_conf.Pin = LL_GPIO_PIN_7;
pb7_init_conf.Pull = LL_GPIO_PULL_DOWN;
LL_GPIO_Init(GPIOB, &pb7_init_conf);
pb7_init_conf.Mode = LL_GPIO_MODE_FLOATING;
pb7_init_conf.Pin = LL_GPIO_PIN_7;
pb7_init_conf.Pull = LL_GPIO_PULL_DOWN;
LL_GPIO_Init(GPIOB, &pb7_init_conf);
// timer setup to
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM4);
LL_TIM_InitTypeDef tim4_init_struct;
// timer setup to
LL_APB1_GRP1_EnableClock(LL_APB1_GRP1_PERIPH_TIM4);
LL_TIM_InitTypeDef tim4_init_struct;
tim4_init_struct.Autoreload= 0xFFFF;
tim4_init_struct.Prescaler=71;
tim4_init_struct.ClockDivision=LL_TIM_CLOCKDIVISION_DIV1;
tim4_init_struct.CounterMode=LL_TIM_COUNTERMODE_UP;
tim4_init_struct.RepetitionCounter=0;
tim4_init_struct.Autoreload= 0xFFFF;
tim4_init_struct.Prescaler=71;
tim4_init_struct.ClockDivision=LL_TIM_CLOCKDIVISION_DIV1;
tim4_init_struct.CounterMode=LL_TIM_COUNTERMODE_UP;
tim4_init_struct.RepetitionCounter=0;
LL_TIM_Init(TIM4, &tim4_init_struct);
LL_TIM_Init(TIM4, &tim4_init_struct);
// setup channel 1 to capture period of pwm
LL_TIM_IC_InitTypeDef tim4_ic_conf;
tim4_ic_conf.ICPolarity= LL_TIM_IC_POLARITY_RISING;
tim4_ic_conf.ICActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI;
tim4_ic_conf.ICFilter = LL_TIM_IC_FILTER_FDIV1;
tim4_ic_conf.ICPrescaler = LL_TIM_ICPSC_DIV1;
// setup channel 1 to capture period of pwm
LL_TIM_IC_InitTypeDef tim4_ic_conf;
tim4_ic_conf.ICPolarity= LL_TIM_IC_POLARITY_RISING;
tim4_ic_conf.ICActiveInput = LL_TIM_ACTIVEINPUT_DIRECTTI;
tim4_ic_conf.ICFilter = LL_TIM_IC_FILTER_FDIV1;
tim4_ic_conf.ICPrescaler = LL_TIM_ICPSC_DIV1;
LL_TIM_IC_Init(TIM4, LL_TIM_CHANNEL_CH1, &tim4_ic_conf);
LL_TIM_IC_Init(TIM4, LL_TIM_CHANNEL_CH1, &tim4_ic_conf);
// setup channel 2 to capture duty time of pwm
LL_TIM_IC_InitTypeDef tim4_ic_conf_2;
tim4_ic_conf_2.ICPolarity= LL_TIM_IC_POLARITY_FALLING;
tim4_ic_conf_2.ICActiveInput = LL_TIM_ACTIVEINPUT_INDIRECTTI;
tim4_ic_conf_2.ICFilter = LL_TIM_IC_FILTER_FDIV1;
tim4_ic_conf_2.ICPrescaler = LL_TIM_ICPSC_DIV1;
// setup channel 2 to capture duty time of pwm
LL_TIM_IC_InitTypeDef tim4_ic_conf_2;
tim4_ic_conf_2.ICPolarity= LL_TIM_IC_POLARITY_FALLING;
tim4_ic_conf_2.ICActiveInput = LL_TIM_ACTIVEINPUT_INDIRECTTI;
tim4_ic_conf_2.ICFilter = LL_TIM_IC_FILTER_FDIV1;
tim4_ic_conf_2.ICPrescaler = LL_TIM_ICPSC_DIV1;
LL_TIM_IC_Init(TIM4, LL_TIM_CHANNEL_CH2, &tim4_ic_conf_2);
LL_TIM_IC_Init(TIM4, LL_TIM_CHANNEL_CH2, &tim4_ic_conf_2);
// setup reset of clock at rising edge
LL_TIM_SetSlaveMode(TIM4, LL_TIM_SLAVEMODE_RESET);
LL_TIM_SetTriggerInput(TIM4, LL_TIM_TS_TI1FP1);
// setup reset of clock at rising edge
LL_TIM_SetSlaveMode(TIM4, LL_TIM_SLAVEMODE_RESET);
LL_TIM_SetTriggerInput(TIM4, LL_TIM_TS_TI1FP1);
LL_TIM_EnableCounter(TIM4);
LL_TIM_EnableCounter(TIM4);
}
int RF_INPUT_GetPeriodUs(void)
{
return LL_TIM_ReadReg(TIM4, CCR1);
return LL_TIM_ReadReg(TIM4, CCR1);
}
int RF_INPUT_GetDutyTimeUs(void)
{
return LL_TIM_ReadReg(TIM4, CCR2);
return LL_TIM_ReadReg(TIM4, CCR2);
}
int RF_INPUT_GetDutyTimeRelative(void)
{
int d = RF_INPUT_GetDutyTimeUs();
return (d - 1500) / 5;
int d = RF_INPUT_GetDutyTimeUs();
return (d - 1500) / 5;
}

View file

@ -10,27 +10,27 @@
/**
* @brief Initialziation function for the RF_INPUT module.
* Peripherals used: TIM4
* Pins used: PB6 (PWM Input)
* Peripherals used: TIM4
* Pins used: PB6 (PWM Input)
*/
void RF_INPUT_Init(void);
/**
* @brief Reads the period of the PWM signal
* @retval period of the PWM signal in microseconds (10^(-6))
* @retval period of the PWM signal in microseconds (10^(-6))
*/
int RF_INPUT_GetPeriodUs(void);
/**
* @brief Reads the length of the active time of the PWM signal
* @retval active time of the PWM signal in microseconds (10^(-6))
* @retval active time of the PWM signal in microseconds (10^(-6))
*/
int RF_INPUT_GetDutyTimeUs(void);
/**
* @brief Reads the length of the active time of the PWM signal and converts it to a relative value
* @retval value between -100 corresponding to 1000us and 100 corresponding to 2000us active time of the PWM signal
* @retval value between -100 corresponding to 1000us and 100 corresponding to 2000us active time of the PWM signal
*/
int RF_INPUT_GetDutyTimeRelative(void);

View file

@ -9,51 +9,48 @@ char RF_OUTPUT_buf[100];
void RF_OUTPUT_Init(void){
LL_USART_InitTypeDef My_LL_Usart_Init_Struct;
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_USART1);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
LL_GPIO_InitTypeDef tx;
tx.Mode = LL_GPIO_MODE_ALTERNATE;
tx.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
tx.Speed = LL_GPIO_SPEED_FREQ_LOW;
tx.Pin = LL_GPIO_PIN_9;
LL_GPIO_Init(GPIOA, &tx);
LL_GPIO_InitTypeDef pa11_init_conf;
pa11_init_conf.Mode = LL_GPIO_MODE_OUTPUT;
pa11_init_conf.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
pa11_init_conf.Speed = LL_GPIO_SPEED_FREQ_LOW;
pa11_init_conf.Pin = LL_GPIO_PIN_11;
LL_GPIO_Init(GPIOA, &pa11_init_conf);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_USART1);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
LL_GPIO_InitTypeDef tx;
tx.Mode = LL_GPIO_MODE_ALTERNATE;
tx.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
tx.Speed = LL_GPIO_SPEED_FREQ_LOW;
tx.Pin = LL_GPIO_PIN_9;
LL_GPIO_Init(GPIOA, &tx);
LL_USART_InitTypeDef My_LL_Usart_Init_Struct;
My_LL_Usart_Init_Struct.BaudRate = 9600;
My_LL_Usart_Init_Struct.DataWidth = LL_USART_DATAWIDTH_8B ;
My_LL_Usart_Init_Struct.HardwareFlowControl = LL_USART_HWCONTROL_NONE;
My_LL_Usart_Init_Struct.OverSampling = LL_USART_OVERSAMPLING_16;
My_LL_Usart_Init_Struct.Parity = LL_USART_PARITY_NONE;
My_LL_Usart_Init_Struct.StopBits = LL_USART_STOPBITS_1;
My_LL_Usart_Init_Struct.TransferDirection = LL_USART_DIRECTION_TX_RX ;
LL_GPIO_InitTypeDef pa11_init_conf;
pa11_init_conf.Mode = LL_GPIO_MODE_OUTPUT;
pa11_init_conf.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
pa11_init_conf.Speed = LL_GPIO_SPEED_FREQ_LOW;
pa11_init_conf.Pin = LL_GPIO_PIN_11;
LL_GPIO_Init(GPIOA, &pa11_init_conf);
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
My_LL_Usart_Init_Struct.BaudRate = 9600;
My_LL_Usart_Init_Struct.DataWidth = LL_USART_DATAWIDTH_8B ;
My_LL_Usart_Init_Struct.HardwareFlowControl = LL_USART_HWCONTROL_NONE;
My_LL_Usart_Init_Struct.OverSampling = LL_USART_OVERSAMPLING_16;
My_LL_Usart_Init_Struct.Parity = LL_USART_PARITY_NONE;
My_LL_Usart_Init_Struct.StopBits = LL_USART_STOPBITS_1;
My_LL_Usart_Init_Struct.TransferDirection = LL_USART_DIRECTION_TX_RX ;
LL_USART_Init(USART1,&My_LL_Usart_Init_Struct);
LL_USART_Enable(USART1);
}
LL_USART_Init(USART1,&My_LL_Usart_Init_Struct);
LL_USART_Enable(USART1);
}
void RF_OUTPUT_SendBytes(char* buf, int len){
LL_GPIO_SetOutputPin(GPIOA,LL_GPIO_PIN_11);
for(int i = 0; i < len; i++){
LL_USART_TransmitData8(USART1, buf[i]);
while(!LL_USART_IsActiveFlag_TXE(USART1));
}
LL_GPIO_ResetOutputPin(GPIOA,LL_GPIO_PIN_11);
LL_GPIO_SetOutputPin(GPIOA,LL_GPIO_PIN_11);
for(int i = 0; i < len; i++){
LL_USART_TransmitData8(USART1, buf[i]);
while(!LL_USART_IsActiveFlag_TXE(USART1));
}
LL_GPIO_ResetOutputPin(GPIOA,LL_GPIO_PIN_11);
}
void RF_OUTPUT_SendMessage(int rouli_bon, int alimentation_bon, float angle_voile){
int len = sprintf(RF_OUTPUT_buf, "Alim bon: %d, Rouli bon: %d, Angle de voile: %2f\r\n", alimentation_bon, rouli_bon, angle_voile);
RF_OUTPUT_SendBytes(RF_OUTPUT_buf, len);
int len = sprintf(RF_OUTPUT_buf, "Alim bon: %d, Rouli bon: %d, Angle de voile: %2f\r\n", alimentation_bon, rouli_bon, angle_voile);
RF_OUTPUT_SendBytes(RF_OUTPUT_buf, len);
}

View file

@ -10,26 +10,26 @@
/**
* @brief Initialziation function for the RF_OUTPUT module.
* Peripherals used: USART1
* Pins used: PA9 (USART1 TX)
* PA11 (TX Enable)
* Peripherals used: USART1
* Pins used: PA9 (USART1 TX)
* PA11 (TX Enable)
*/
void RF_OUTPUT_Init(void);
/**
* @brief Transmits a given number of bytes from a buffer using the RF Module
* @param buf pointer to start of buffer to be transmitted
* @param len length of the data to be transmitted
*/
* @param buf pointer to start of buffer to be transmitted
* @param len length of the data to be transmitted
*/
void RF_OUTPUT_SendBytes(char* buf, int len);
/**
* @brief Transmits a formatted string of the given parameters
* @param rouli_bon whether or not the angle is in an acceptable range
* @param alimentation_bon whether or not the battery voltage has acceptable level
* @param angle_voile opening angle of the sail between 0 and 90
*/
* @param rouli_bon whether or not the angle is in an acceptable range
* @param alimentation_bon whether or not the battery voltage has acceptable level
* @param angle_voile opening angle of the sail between 0 and 90
*/
void RF_OUTPUT_SendMessage(int rouli_bon, int alimentation_bon, float angle_voile);

View file

@ -11,24 +11,24 @@
void SAIL_Init(void)
{
SERVO_Init();
SERVO_Init();
}
int SAIL_AngleFromGirouette(float girouette_value){
float vabs = fabs(girouette_value);
float vabs = fabs(girouette_value);
if(vabs < ANGLE_DEBUT)
{
return 0;
}else{
// map 45 to 180 -> 0 to 90 and floor it to get an integer
return floor((90 / (180 - ANGLE_DEBUT)) * (vabs - ANGLE_DEBUT));
}
if(vabs < ANGLE_DEBUT)
{
return 0;
}else{
// map 45 to 180 -> 0 to 90 and floor it to get an integer
return floor((90 / (180 - ANGLE_DEBUT)) * (vabs - ANGLE_DEBUT));
}
}
void SAIL_SetAngle(float angle)
{
float servo_angle = angle * SAIL_TRANSFER_FACTOR + SAIL_TRANSFER_OFFSET;
SERVO_SetAngle(servo_angle);
float servo_angle = angle * SAIL_TRANSFER_FACTOR + SAIL_TRANSFER_OFFSET;
SERVO_SetAngle(servo_angle);
}

View file

@ -12,16 +12,16 @@ void SAIL_Init(void);
/**
* @brief Calculates the "optimal" opening angle of the sail depending on the reading of the girouette
* @param girouette_value angle reading where 0 corresponds to the wind blowing from the front
*
* @retval angle between 0 and 90 (degrees)
*/
* @param girouette_value angle reading where 0 corresponds to the wind blowing from the front
*
* @retval angle between 0 and 90 (degrees)
*/
int SAIL_AngleFromGirouette(float girouette_value);
/**
* @brief Sets the opening angle of the sail
* @param opening angle of the sail between 0 and 90 (degrees)
*/
* @param opening angle of the sail between 0 and 90 (degrees)
*/
void SAIL_SetAngle(float angle);
#endif

View file

@ -7,53 +7,52 @@
void SERVO_Init(void){
// use TIM1 since it has pa8 at channel 1 output
// use TIM1 since it has pa8 at channel 1 output
// setup timer 1
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_TIM1);
LL_TIM_InitTypeDef tim_init;
tim_init.Prescaler = 71;
tim_init.Autoreload = 19999;
tim_init.ClockDivision=LL_TIM_CLOCKDIVISION_DIV1;
tim_init.CounterMode=LL_TIM_COUNTERMODE_UP;
tim_init.RepetitionCounter=0;
LL_TIM_Init(TIM1, &tim_init);
// setup timer 1
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_TIM1);
LL_TIM_InitTypeDef tim_init;
tim_init.Prescaler = 71;
tim_init.Autoreload = 19999;
tim_init.ClockDivision=LL_TIM_CLOCKDIVISION_DIV1;
tim_init.CounterMode=LL_TIM_COUNTERMODE_UP;
tim_init.RepetitionCounter=0;
LL_TIM_Init(TIM1, &tim_init);
// setup main output enabled
LL_TIM_EnableAllOutputs(TIM1);
// setup main output enabled
LL_TIM_EnableAllOutputs(TIM1);
// setup gpio
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
LL_GPIO_InitTypeDef servo_gpio_init;
servo_gpio_init.Pin = LL_GPIO_PIN_8;
servo_gpio_init.Mode = LL_GPIO_MODE_ALTERNATE;
servo_gpio_init.Speed = LL_GPIO_MODE_OUTPUT_2MHz ;
servo_gpio_init.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
servo_gpio_init.Pull = LL_GPIO_PULL_DOWN; // dont know why but otherwise it crashes
LL_GPIO_Init(GPIOA, &servo_gpio_init);
// setup gpio
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_GPIOA);
LL_GPIO_InitTypeDef servo_gpio_init;
servo_gpio_init.Pin = LL_GPIO_PIN_8;
servo_gpio_init.Mode = LL_GPIO_MODE_ALTERNATE;
servo_gpio_init.Speed = LL_GPIO_MODE_OUTPUT_2MHz ;
servo_gpio_init.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
servo_gpio_init.Pull = LL_GPIO_PULL_DOWN; // dont know why but otherwise it crashes
LL_GPIO_Init(GPIOA, &servo_gpio_init);
// setup output compare
LL_TIM_OC_InitTypeDef oc_init;
oc_init.OCMode = LL_TIM_OCMODE_PWM1;
oc_init.OCState = LL_TIM_OCSTATE_ENABLE;
oc_init.OCNState = LL_TIM_OCSTATE_ENABLE;
oc_init.CompareValue = 999;
oc_init.OCPolarity = LL_TIM_OCPOLARITY_HIGH;
oc_init.OCNPolarity = LL_TIM_OCPOLARITY_LOW;
oc_init.OCIdleState = LL_TIM_OCIDLESTATE_LOW;
oc_init.OCNIdleState = LL_TIM_OCIDLESTATE_HIGH;
LL_TIM_OC_Init(TIM1, LL_TIM_CHANNEL_CH1, &oc_init);
// setup output compare
LL_TIM_OC_InitTypeDef oc_init;
oc_init.OCMode = LL_TIM_OCMODE_PWM1;
oc_init.OCState = LL_TIM_OCSTATE_ENABLE;
oc_init.OCNState = LL_TIM_OCSTATE_ENABLE;
oc_init.CompareValue = 999;
oc_init.OCPolarity = LL_TIM_OCPOLARITY_HIGH;
oc_init.OCNPolarity = LL_TIM_OCPOLARITY_LOW;
oc_init.OCIdleState = LL_TIM_OCIDLESTATE_LOW;
oc_init.OCNIdleState = LL_TIM_OCIDLESTATE_HIGH;
LL_TIM_OC_Init(TIM1, LL_TIM_CHANNEL_CH1, &oc_init);
LL_TIM_EnableCounter(TIM1);
LL_TIM_EnableCounter(TIM1);
}
void SERVO_SetAngle(int angle){
// set ccr3 register to alter pwm output between 1 and 2 ms
float vminCOR = 999, vmaxCOR = 1999;
float diffCOR = vmaxCOR - vminCOR;
int ccr3Value = round(angle*diffCOR/90)+vminCOR;
// set ccr3 register to alter pwm output between 1 and 2 ms
float vminCOR = 999, vmaxCOR = 1999;
float diffCOR = vmaxCOR - vminCOR;
int ccr3Value = round(angle*diffCOR/90)+vminCOR;
LL_TIM_WriteReg(TIM1, CCR1, ccr3Value);
LL_TIM_WriteReg(TIM1, CCR1, ccr3Value);
}

View file

@ -10,15 +10,15 @@
/**
* @brief Initialziation function for the RF_OUTPUT module.
* The period of the PWM signal is 20ms.
* Peripherals used: TIM1
* Pins used: PA8 (TIM1 channel 1)
* The period of the PWM signal is 20ms.
* Peripherals used: TIM1
* Pins used: PA8 (TIM1 channel 1)
*/
void SERVO_Init(void);
/**
* @brief Sets the angle of the servo using a PWM signal with a on time between 1ms and 2ms and a resolution of 1us
* @param angle of the servo between XXXXX and YYYYY degree
* @param angle of the servo between XXXXX and YYYYY degree
*/
void SERVO_SetAngle(int angle);

View file

@ -45,55 +45,55 @@ char wait_for_girouette[] = "En attente d'initialisation de la girouette\r\n";
int main(void)
{
/* Configure the system clock to 72 MHz */
SystemClock_Config();
ALIMENTATION_Init();
ACCELEROMETER_Init();
RF_INPUT_Init();
DC_MOTOR_Init();
SAIL_Init();
RF_OUTPUT_Init();
SystemClock_Config();
ALIMENTATION_Init();
ACCELEROMETER_Init();
RF_INPUT_Init();
DC_MOTOR_Init();
SAIL_Init();
RF_OUTPUT_Init();
while(!INCR_ENCODER_IsAbsolute())
{
RF_OUTPUT_SendBytes(wait_for_girouette, sizeof(wait_for_girouette));
LL_mDelay(500);
}
while(!INCR_ENCODER_IsAbsolute())
{
RF_OUTPUT_SendBytes(wait_for_girouette, sizeof(wait_for_girouette));
LL_mDelay(500);
}
while (1)
{
if(CONTROL_LOOP_Flag){
battery_level_good = ALIMENTATION_IsLevelEnough();
angle_roulis_good = ACCELEROMETER_AngleGood();
if(CONTROL_LOOP_Flag){
battery_level_good = ALIMENTATION_IsLevelEnough();
angle_roulis_good = ACCELEROMETER_AngleGood();
if(!angle_roulis_good){
SAIL_SetAngle(90);
DC_MOTOR_SetSpeed(0);
}else{
angle_incr_encoder = INCR_ENCODER_GetAngle();
angle_sail = SAIL_AngleFromGirouette(angle_incr_encoder);
SAIL_SetAngle(angle_sail);
RF_Input_Duty = RF_INPUT_GetDutyTimeRelative();
DC_MOTOR_SetSpeed(RF_Input_Duty);
}
CONTROL_LOOP_Flag = 0;
}
if(TX_Flag){
RF_OUTPUT_SendMessage(angle_roulis_good, battery_level_good, angle_sail);
TX_Flag = 0;
}
if(!angle_roulis_good){
SAIL_SetAngle(90);
DC_MOTOR_SetSpeed(0);
}else{
angle_incr_encoder = INCR_ENCODER_GetAngle();
angle_sail = SAIL_AngleFromGirouette(angle_incr_encoder);
SAIL_SetAngle(angle_sail);
RF_Input_Duty = RF_INPUT_GetDutyTimeRelative();
DC_MOTOR_SetSpeed(RF_Input_Duty);
}
CONTROL_LOOP_Flag = 0;
}
if(TX_Flag){
RF_OUTPUT_SendMessage(angle_roulis_good, battery_level_good, angle_sail);
TX_Flag = 0;
}
}
}
void SysTick_Handler(void)
{
if(counter % CONTROL_LOOP_PERIOD == 0){
CONTROL_LOOP_Flag = 1;
}
if(counter % MSG_TRANSFER_PERIOD == 0){
TX_Flag = 1;
}
counter = (counter+1) % (CONTROL_LOOP_PERIOD*MSG_TRANSFER_PERIOD) ;
if(counter % CONTROL_LOOP_PERIOD == 0){
CONTROL_LOOP_Flag = 1;
}
if(counter % MSG_TRANSFER_PERIOD == 0){
TX_Flag = 1;
}
counter = (counter+1) % (CONTROL_LOOP_PERIOD*MSG_TRANSFER_PERIOD) ;
}
@ -118,8 +118,8 @@ void SystemClock_Config(void)
LL_FLASH_SetLatency(LL_FLASH_LATENCY_2);
/* Enable HSE oscillator */
// ********* Commenter la ligne ci-dessous pour MCBSTM32 *****************
// ********* Conserver la ligne si Nucléo*********************************
// ********* Commenter la ligne ci-dessous pour MCBSTM32 *****************
// ********* Conserver la ligne si Nucléo*********************************
LL_RCC_HSE_EnableBypass();
LL_RCC_HSE_Enable();
while(LL_RCC_HSE_IsReady() != 1)