Merge pull request #5 from MDHSweden/pwmDriver
Drivers Oneshot125 approved by Lennart
This commit is contained in:
commit
4370f1b413
@ -8,18 +8,24 @@
|
|||||||
#ifndef DRIVERS_MOTORS_H_
|
#ifndef DRIVERS_MOTORS_H_
|
||||||
#define DRIVERS_MOTORS_H_
|
#define DRIVERS_MOTORS_H_
|
||||||
|
|
||||||
|
/* Struct of motor output protocol */
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
PWM, Oneshot125
|
||||||
|
}motorOutput;
|
||||||
|
|
||||||
/**************************************************************************
|
/**************************************************************************
|
||||||
* BRIEF: Initializing a motor (maps a pwm signal to a certain pin) *
|
* BRIEF: Initializing a motor (maps a pwm signal to a certain pin) *
|
||||||
* INFORMATION: The motor becomes active, Each motor configuration is changed in the "stm32f4xx_revo.h" file *
|
* INFORMATION: The motor becomes active, Each motor configuration is changed in the "stm32f4xx_revo.h" file *
|
||||||
* Example - pwmEnableMotor(MOTOR_1) *
|
* Example - pwmEnableMotor(MOTOR_1) *
|
||||||
**************************************************************************/
|
**************************************************************************/
|
||||||
void pwmEnableMotor(uint8_t motor);
|
void pwmEnableMotor(uint8_t motor, motorOutput motorOutput);
|
||||||
|
|
||||||
/**************************************************************************
|
/**************************************************************************
|
||||||
* BRIEF: Enables all motors (maps a pwm signal to all pins which will be connected to a motor) *
|
* BRIEF: Enables all motors (maps a pwm signal to all pins which will be connected to a motor) *
|
||||||
* INFORMATION: All motors become active
|
* INFORMATION: All motors become active
|
||||||
**************************************************************************/
|
**************************************************************************/
|
||||||
void pwmEnableAllMotors(void);
|
void pwmEnableAllMotors(motorOutput motorOutput);
|
||||||
|
|
||||||
/**************************************************************************
|
/**************************************************************************
|
||||||
* BRIEF: Deactivates a motor (Disables the pwm signal for the motor pin )
|
* BRIEF: Deactivates a motor (Disables the pwm signal for the motor pin )
|
||||||
|
@ -21,7 +21,7 @@
|
|||||||
* period = Period of PWM signal
|
* period = Period of PWM signal
|
||||||
* pulse = the "duty cycle" of the pwm signal *
|
* pulse = the "duty cycle" of the pwm signal *
|
||||||
**************************************************************************/
|
**************************************************************************/
|
||||||
void pwmInit(GPIO_TypeDef * GPIO, uint16_t pin, TIM_TypeDef * tim, uint32_t Channel, uint16_t period, uint16_t pulse);
|
void pwmInit(GPIO_TypeDef * GPIO, uint16_t pin, TIM_TypeDef * tim, uint32_t Channel, uint16_t period, uint16_t pulse, uint32_t prescaler);
|
||||||
|
|
||||||
/**************************************************************************
|
/**************************************************************************
|
||||||
* BRIEF: setPwmPulse changes a certain pulse for an initialized pwm signal *
|
* BRIEF: setPwmPulse changes a certain pulse for an initialized pwm signal *
|
||||||
|
@ -4,8 +4,8 @@
|
|||||||
* INFORMATION: *
|
* INFORMATION: *
|
||||||
* GLOBAL VARIABLES: *
|
* GLOBAL VARIABLES: *
|
||||||
* Variable Type Description *
|
* Variable Type Description *
|
||||||
* MOTOR_PWM_INIT_PERIODE define The initializing periode of the pwm signal to each motor *
|
* MotorPWMPeriode define The initializing periode of the pwm signal to each motor *
|
||||||
* MOTOR_PWM_INIT_PULSE define The initializing pulse of the pwm signal to each motor
|
* MotorPWMInitPulse define The initializing pulse of the pwm signal to each motor
|
||||||
* **************************************************************************/
|
* **************************************************************************/
|
||||||
|
|
||||||
#include "stm32f4xx.h"
|
#include "stm32f4xx.h"
|
||||||
@ -13,8 +13,8 @@
|
|||||||
#include "drivers/pwm.h"
|
#include "drivers/pwm.h"
|
||||||
#include "drivers/motors.h"
|
#include "drivers/motors.h"
|
||||||
|
|
||||||
#define MOTOR_PWM_INIT_PERIODE 2000
|
int MotorPWMPeriode = 2000; //Micro seconds
|
||||||
#define MOTOR_PWM_INIT_PULSE MOTOR_PWM_INIT_PERIODE/2
|
int MotorPWMInitPulse = 1000;
|
||||||
|
|
||||||
/* A struct of a pwm motor profile */
|
/* A struct of a pwm motor profile */
|
||||||
typedef struct
|
typedef struct
|
||||||
@ -32,7 +32,7 @@ typedef struct
|
|||||||
**************************************************************************/
|
**************************************************************************/
|
||||||
uint16_t checkPulse(uint16_t pulse)
|
uint16_t checkPulse(uint16_t pulse)
|
||||||
{
|
{
|
||||||
return ((pulse/MOTOR_PWM_INIT_PERIODE)*100 < 94)? pulse: MOTOR_PWM_INIT_PERIODE*0.94;
|
return ((pulse/MotorPWMPeriode)*100 < 94)? pulse: MotorPWMPeriode*0.94;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**************************************************************************
|
/**************************************************************************
|
||||||
@ -114,25 +114,54 @@ motorProfile getMotorProfile(uint8_t motor)
|
|||||||
return profile;
|
return profile;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**************************************************************************
|
||||||
|
* BRIEF: Sets the motor output protocol to be either oneshot125 or pwm
|
||||||
|
* INFORMATION:
|
||||||
|
* Example - uint32_t prescaler = setMotorOutput(Oneshot125)
|
||||||
|
*************************************************************************/
|
||||||
|
uint32_t setMotorOutput(motorOutput motorOutput)
|
||||||
|
{
|
||||||
|
uint32_t prescaler;
|
||||||
|
|
||||||
|
switch(motorOutput)
|
||||||
|
{
|
||||||
|
case PWM:
|
||||||
|
MotorPWMPeriode = 2000;
|
||||||
|
prescaler = 88;
|
||||||
|
break;
|
||||||
|
case Oneshot125:
|
||||||
|
MotorPWMPeriode = 16000;
|
||||||
|
prescaler = 11;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
MotorPWMPeriode = 2000;
|
||||||
|
prescaler = 88;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return prescaler;
|
||||||
|
}
|
||||||
|
|
||||||
/**************************************************************************
|
/**************************************************************************
|
||||||
* BRIEF: Initializing a motor (maps a pwm signal to a certain pin) *
|
* BRIEF: Initializing a motor (maps a pwm signal to a certain pin) *
|
||||||
* INFORMATION: The motor becomes active, Each motor configuration is changed in the "stm32f4xx_revo.h" file *
|
* INFORMATION: The motor becomes active, Each motor configuration is changed in the "stm32f4xx_revo.h" file *
|
||||||
* Example - pwmEnableMotor(MOTOR_1) *
|
* Example - pwmEnableMotor(MOTOR_1) *
|
||||||
**************************************************************************/
|
**************************************************************************/
|
||||||
void pwmEnableMotor(uint8_t motor)
|
void pwmEnableMotor(uint8_t motor, motorOutput motorOutput)
|
||||||
{
|
{
|
||||||
motorProfile profile = getMotorProfile(motor);
|
motorProfile profile = getMotorProfile(motor);
|
||||||
|
uint32_t prescaler = setMotorOutput(motorOutput);
|
||||||
|
|
||||||
pwmInit(profile.port, profile.pin, profile.tim, profile.channel, MOTOR_PWM_INIT_PERIODE, MOTOR_PWM_INIT_PULSE);
|
pwmInit(profile.port, profile.pin, profile.tim, profile.channel, MotorPWMPeriode, MotorPWMInitPulse, prescaler);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**************************************************************************
|
/**************************************************************************
|
||||||
* BRIEF: Enables all motors (maps a pwm signal to all pins which will be connected to a motor) *
|
* BRIEF: Enables all motors (maps a pwm signal to all pins which will be connected to a motor) *
|
||||||
* INFORMATION: All motors become active
|
* INFORMATION: All motors become active
|
||||||
**************************************************************************/
|
**************************************************************************/
|
||||||
void pwmEnableAllMotors(void)
|
void pwmEnableAllMotors(motorOutput motorOutput)
|
||||||
{
|
{
|
||||||
for (uint8_t i = 1; i < 11; i++ ) pwmEnableMotor(i);
|
for (uint8_t i = 1; i < 11; i++ ) pwmEnableMotor(i, motorOutput);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**************************************************************************
|
/**************************************************************************
|
||||||
@ -165,7 +194,7 @@ void pwmDeactivateMotor(uint8_t motor)
|
|||||||
**************************************************************************/
|
**************************************************************************/
|
||||||
void pwmActivateAllMotors(void)
|
void pwmActivateAllMotors(void)
|
||||||
{
|
{
|
||||||
for (uint8_t i = 1; i < 11; i++ ) pwmDeactivateMotor(i);
|
for (uint8_t i = 1; i < 11; i++ ) pwmActivateMotor(i);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**************************************************************************
|
/**************************************************************************
|
||||||
@ -175,7 +204,7 @@ void pwmActivateAllMotors(void)
|
|||||||
**************************************************************************/
|
**************************************************************************/
|
||||||
void pwmDeactivateAllMotors(void)
|
void pwmDeactivateAllMotors(void)
|
||||||
{
|
{
|
||||||
for (uint8_t i = 1; i < 11; i++ ) pwmActivateMotor(i);
|
for (uint8_t i = 1; i < 11; i++ ) pwmDeactivateMotor(i);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**************************************************************************
|
/**************************************************************************
|
||||||
@ -197,7 +226,7 @@ void pwmAdjustSpeedOfMotor(uint8_t motor, uint16_t pulse)
|
|||||||
**************************************************************************/
|
**************************************************************************/
|
||||||
void pwmAdjustSpeedOfMotorDutyCycle(uint8_t motor, uint16_t DutyCycle)
|
void pwmAdjustSpeedOfMotorDutyCycle(uint8_t motor, uint16_t DutyCycle)
|
||||||
{
|
{
|
||||||
uint16_t pulse = (DutyCycle*MOTOR_PWM_INIT_PERIODE)/100; /* Converts the DutyCycle to a pulse */
|
uint16_t pulse = (DutyCycle*MotorPWMPeriode)/100; /* Converts the DutyCycle to a pulse */
|
||||||
motorProfile profile = getMotorProfile(motor);
|
motorProfile profile = getMotorProfile(motor);
|
||||||
|
|
||||||
setPwmPulse(profile.channel, profile.tim, checkPulse(pulse));
|
setPwmPulse(profile.channel, profile.tim, checkPulse(pulse));
|
||||||
|
@ -47,7 +47,7 @@ pwmProfile get_Pwm_Profile(GPIO_TypeDef * GPIO, uint16_t pin, uint32_t Channel,
|
|||||||
* period = Period of PWM signal
|
* period = Period of PWM signal
|
||||||
* pulse = the "duty cycle" of the pwm signal *
|
* pulse = the "duty cycle" of the pwm signal *
|
||||||
**************************************************************************/
|
**************************************************************************/
|
||||||
void pwmInit(GPIO_TypeDef * GPIO, uint16_t pin, TIM_TypeDef * tim, uint32_t Channel, uint16_t period, uint16_t pulse)
|
void pwmInit(GPIO_TypeDef * GPIO, uint16_t pin, TIM_TypeDef * tim, uint32_t Channel, uint16_t period, uint16_t pulse, uint32_t prescaler)
|
||||||
{
|
{
|
||||||
pwmProfile profile;
|
pwmProfile profile;
|
||||||
|
|
||||||
@ -83,7 +83,7 @@ void pwmInit(GPIO_TypeDef * GPIO, uint16_t pin, TIM_TypeDef * tim, uint32_t Chan
|
|||||||
|
|
||||||
TimHandle.Instance = profile.tim; /* Sets timer */
|
TimHandle.Instance = profile.tim; /* Sets timer */
|
||||||
TimHandle.Init.Period = period; /* Sets period of pwm */
|
TimHandle.Init.Period = period; /* Sets period of pwm */
|
||||||
TimHandle.Init.Prescaler = 88; /* pwm prescaler of clk */
|
TimHandle.Init.Prescaler = prescaler; /* pwm prescaler of clk */
|
||||||
TimHandle.Init.ClockDivision = 0;
|
TimHandle.Init.ClockDivision = 0;
|
||||||
TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
|
TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||||
|
|
||||||
|
Reference in New Issue
Block a user