/******************************************************//** | |||||
* @file l6208.h | |||||
* @author IPC Rennes | |||||
* @version V1.5.0 | |||||
* @date June 1st, 2018 | |||||
* @brief Header for l6208.c module | |||||
* @note (C) COPYRIGHT 2016 STMicroelectronics | |||||
****************************************************************************** | |||||
* @attention | |||||
* | |||||
* <h2><center>© COPYRIGHT(c) 2016 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. | |||||
* | |||||
****************************************************************************** | |||||
*/ | |||||
/* Define to prevent recursive inclusion -------------------------------------*/ | |||||
#ifndef _L6208_H_INCLUDED | |||||
#define _L6208_H_INCLUDED | |||||
#ifdef __cplusplus | |||||
extern "C" { | |||||
#endif | |||||
/* Includes ------------------------------------------------------------------*/ | |||||
#include "l6208_target_config.h" | |||||
#include "motor.h" | |||||
/** @addtogroup BSP | |||||
* @{ | |||||
*/ | |||||
/** @addtogroup L6208 | |||||
* @{ | |||||
*/ | |||||
/* Exported Constants --------------------------------------------------------*/ | |||||
/** @addtogroup L6208_Exported_Constants | |||||
* @{ | |||||
*/ | |||||
/// Current FW major version | |||||
#define L6208_FW_MAJOR_VERSION (uint8_t)(1) | |||||
/// Current FW minor version | |||||
#define L6208_FW_MINOR_VERSION (uint8_t)(4) | |||||
/// Current FW patch version | |||||
#define L6208_FW_PATCH_VERSION (uint8_t)(0) | |||||
/// Current FW version | |||||
#define L6208_FW_VERSION (uint32_t)((L6208_FW_MAJOR_VERSION<<16)|\ | |||||
(L6208_FW_MINOR_VERSION<<8)|\ | |||||
(L6208_FW_PATCH_VERSION)) | |||||
/// Max position | |||||
#define L6208_MAX_POSITION (0x7FFFFFFF) | |||||
/// Min position | |||||
#define L6208_MIN_POSITION (0x80000000) | |||||
/// Position range | |||||
#define L6208_POSITION_RANGE ((uint32_t)(L6208_MAX_POSITION -\ | |||||
L6208_MIN_POSITION)) | |||||
/// micro step samples per period/4 | |||||
#define L6208_USTEPS_PER_QUARTER_PERIOD (16) | |||||
/// minimum speed | |||||
#define L6208_MIN_SPEED (16) | |||||
/// minimum acceleration and deceleration rate | |||||
#define L6208_MIN_ACC_DEC_RATE (24) | |||||
/// Mask for HiZ bit in motorDecayMode_t enum | |||||
#define L6208_FAST_DECAY_MODE_MASK (0x1) | |||||
/// L6208 error base number | |||||
#define L6208_ERROR_BASE (0x9000) | |||||
/** | |||||
* @} | |||||
*/ | |||||
/* Exported types ------------------------------------------------------------*/ | |||||
/** @defgroup Error_Types Error Types | |||||
* @{ | |||||
*/ | |||||
/// Errors | |||||
typedef enum { | |||||
L6208_ERROR_SET_HOME = L6208_ERROR_BASE, /// Error while setting home position | |||||
L6208_ERROR_SET_MAX_SPEED = L6208_ERROR_BASE + 1, /// Error while setting max speed | |||||
L6208_ERROR_SET_MIN_SPEED = L6208_ERROR_BASE + 2, /// Error while setting min speed | |||||
L6208_ERROR_SET_ACCELERATION = L6208_ERROR_BASE + 3, /// Error while setting acceleration | |||||
L6208_ERROR_SET_DECELERATION = L6208_ERROR_BASE + 4, /// Error while setting decelaration | |||||
L6208_ERROR_MCU_OSC_CONFIG = L6208_ERROR_BASE + 5, /// Error while configuring mcu oscillator | |||||
L6208_ERROR_MCU_CLOCK_CONFIG = L6208_ERROR_BASE + 6, /// Error while configuring mcu clock | |||||
L6208_ERROR_POSITION = L6208_ERROR_BASE + 7, /// Unexpected current position (wrong number of steps) | |||||
L6208_ERROR_SPEED = L6208_ERROR_BASE + 8, /// Unexpected current speed | |||||
L6208_ERROR_INIT = L6208_ERROR_BASE + 9, /// Unexpected number of devices | |||||
L6208_ERROR_SET_DIRECTION = L6208_ERROR_BASE + 10,/// Error while setting direction | |||||
L6208_ERROR_SET_STEP_MODE = L6208_ERROR_BASE + 11,/// Attempt to set an unsupported step mode | |||||
L6208_ERROR_SET_PWM = L6208_ERROR_BASE + 12,/// Error while setting a PWM parameter | |||||
}errorTypes_t; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup Device_Parameters Device Parameters | |||||
* @{ | |||||
*/ | |||||
/// Device Parameters Structure Type | |||||
typedef struct | |||||
{ | |||||
/// dwelling waiting time counter (tick) | |||||
volatile uint32_t dwellCounter; | |||||
/// motor position indicator (tick) | |||||
uint32_t ticks; | |||||
/// LSByte copy of the previous position (tick) | |||||
uint8_t lsbOldTicks; | |||||
/// LSByte copy of the previous position (tick) ( micro stepping ) | |||||
uint8_t lsbOldUSteppingTicks; | |||||
/// LSByte copy of the current position (tick) | |||||
uint8_t lsbTicks; | |||||
/// P1 = acceleration phase steps number (motor position control mode) | |||||
uint32_t positionTarget1; | |||||
/// P2 = constant speed steps number (motor position control mode) | |||||
uint32_t positionTarget2; | |||||
/// P3 = deceleration phase steps number (motor position control mode) | |||||
uint32_t positionTarget3; | |||||
/// P = total move distance in steps (motor position control mode) | |||||
uint32_t positionTarget; | |||||
/// absolute motor position in microsteps (motor position control mode) | |||||
volatile int32_t absolutePos; | |||||
/// mark position in microsteps (motor position control mode) | |||||
volatile int32_t markPos; | |||||
/// motor position in microsteps (motor position control mode) | |||||
volatile uint32_t step; | |||||
/// dwelling time after position got (ms) | |||||
volatile uint16_t moveDwellTime; | |||||
/// number of micro stepping waveform samples to be rescaled according to selected torque value | |||||
volatile uint8_t uStepsample2scale; | |||||
/// number of micro stepping waveform samples to be updated into the waveform scanning table | |||||
volatile uint8_t uStepsample2update; | |||||
/// microstepping waveform sample index | |||||
volatile uint8_t uStepSample; | |||||
/// system status flags | |||||
volatile uint32_t flags; | |||||
/// current stepper state machine index | |||||
volatile motorState_t motionState; | |||||
/// current step mode | |||||
volatile motorStepMode_t stepMode; | |||||
/// micro stepping waveform scanning sample index increment | |||||
uint8_t uStepInc; | |||||
/// frequency of the VREFA and VREFB PWM | |||||
uint32_t vrefPwmFreq; | |||||
/// current selected torque value | |||||
volatile uint8_t curTorqueScaler; | |||||
/// constant speed phase torque value (%) | |||||
volatile uint8_t runTorque; | |||||
/// acceleration phase torque value (%) | |||||
volatile uint8_t accelTorque; | |||||
/// deceleration phase torque value (%) | |||||
volatile uint8_t decelTorque; | |||||
/// holding phase torque value (%) | |||||
volatile uint8_t holdTorque; | |||||
/// acceleration (steps/s^2) | |||||
volatile uint16_t accelerationSps2; | |||||
/// deceleration (steps/s^2) | |||||
volatile uint16_t decelerationSps2; | |||||
/// acceleration (steps/tick^2) | |||||
volatile uint16_t accelerationSpt2; | |||||
/// deceleration (steps/tick^2) | |||||
volatile uint16_t decelerationSpt2; | |||||
/// maximum speed (steps/s) | |||||
volatile uint16_t maxSpeedSps; | |||||
/// minimum speed (steps/s) | |||||
volatile uint16_t minSpeedSps; | |||||
/// current speed (steps/s) | |||||
volatile uint16_t speedSps; | |||||
/// maximum speed (steps/tick) | |||||
volatile uint32_t maxSpeedSpt; | |||||
/// minimum speed (steps/tick) | |||||
volatile uint32_t minSpeedSpt; | |||||
/// current speed (steps/tick) | |||||
volatile uint32_t speedSpt; | |||||
}deviceParams_t; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/// Motor driver initialization structure definition | |||||
typedef struct | |||||
{ | |||||
/// acceleration (steps/s^2) | |||||
uint16_t accelerationSps2; | |||||
/// acceleration phase torque value (%) | |||||
uint8_t accelTorque; | |||||
/// deceleration (steps/s^2) | |||||
uint16_t decelerationSps2; | |||||
/// deceleration phase torque value (%) | |||||
uint8_t decelTorque; | |||||
/// maximum speed (steps/s) | |||||
uint16_t maxSpeedSps; | |||||
/// constant speed phase torque value (%) | |||||
uint8_t runTorque; | |||||
/// holding phase torque value (%) | |||||
uint8_t holdTorque; | |||||
/// current step mode | |||||
motorStepMode_t stepMode; | |||||
/// current decay mode (SLOW_DECAY or FAST_DECAY) | |||||
motorDecayMode_t decayMode; | |||||
/// dwelling time after position got (ms) | |||||
uint16_t moveDwellTime; | |||||
/// automatic HiZ on stop | |||||
bool autoHiZstop; | |||||
/// frequency of the VREFA and VREFB PWM | |||||
uint32_t vrefPwmFreq; | |||||
} l6208_Init_t; | |||||
/* Exported functions --------------------------------------------------------*/ | |||||
/** @defgroup L6208_Exported_Functions L6208 Exported Functions | |||||
* @{ | |||||
*/ | |||||
motorDrv_t* L6208_GetMotorHandle(void); //Return handle of the motor driver handle | |||||
void L6208_Init(void* pInit); //Start the L6208 library | |||||
uint16_t L6208_ReadId(void); //Read Id to get driver instance | |||||
void L6208_AttachErrorHandler(void (*callback)(uint16_t error)); //Attach a user callback to the error Handler | |||||
void L6208_AttachFlagInterrupt(void (*callback)(void)); //Attach a user callback to the flag Interrupt | |||||
uint8_t L6208_CheckStatusHw(void); //Check if L6208 has a fault by reading EN pin position | |||||
void L6208_Disable(uint8_t deviceId); //Disable the power bridge | |||||
void L6208_ErrorHandler(uint16_t error); //Error handler which calls the user callback | |||||
void L6208_Enable(uint8_t deviceId); //Enable the power bridge | |||||
void L6208_FlagInterruptHandler(void); //Handler of the flag interrupt which calls the user callback (if defined) | |||||
uint16_t L6208_GetAcceleration(uint8_t deviceId); //Return the acceleration in pps^2 | |||||
uint16_t L6208_GetCurrentSpeed(uint8_t deviceId); //Return the current speed in pps | |||||
motorDecayMode_t L6208_GetDecayMode(uint8_t deviceId); //Get the motor decay mode | |||||
uint16_t L6208_GetDeceleration(uint8_t deviceId); //Return the deceleration in pps^2 | |||||
motorDir_t L6208_GetDirection(uint8_t deviceId); //Get the motor current direction | |||||
uint32_t L6208_GetFwVersion(void); //Return the FW version | |||||
int32_t L6208_GetMark(uint8_t deviceId); //Get the mark position (32b signed) | |||||
uint16_t L6208_GetMaxSpeed(uint8_t deviceId); //Return the max speed in pps | |||||
uint16_t L6208_GetMinSpeed(uint8_t deviceId); //Return the min speed in pps | |||||
motorState_t L6208_GetMotionState(uint8_t deviceId); //Return the motion state | |||||
int32_t L6208_GetPosition(uint8_t deviceId); //Get the current position (32b signed) | |||||
motorStepMode_t L6208_GetStepMode(uint8_t deviceId); //Get the motor step mode | |||||
motorStopMode_t L6208_GetStopMode(uint8_t deviceId); //Get the selected mode to stop the motor | |||||
uint8_t L6208_GetTorque(uint8_t deviceId, motorTorqueMode_t torqueMode); //Get the torque value according to the torque mode | |||||
void L6208_GoHome(uint8_t deviceId); //Go to the home position | |||||
void L6208_GoMark(uint8_t deviceId); //Go to the Mark position | |||||
void L6208_GoTo(uint8_t deviceId, int32_t abs_pos); //Go to the specified position | |||||
void L6208_GoToDir(uint8_t deviceId, motorDir_t direction, int32_t abs_pos); //Go to the specified position using the specified direction | |||||
void L6208_HardHiZ(uint8_t deviceId); //Stop the motor by using the device deceleration and disables the power bridges | |||||
void L6208_HardStop(uint8_t deviceId); //Stop the motor and keeps holding torque | |||||
void L6208_Move(uint8_t deviceId, motorDir_t direction, uint32_t stepCount); //Move the motor by the specified number of steps in the specified direction | |||||
void L6208_ReleaseReset(uint8_t deviceId); //Release the reset pin | |||||
void L6208_Reset(uint8_t deviceId); //Set the reset pin | |||||
void L6208_ResetDevice(void); //Reset L6208 device | |||||
void L6208_Run(uint8_t deviceId, motorDir_t direction); //Run the motor in the specified direction | |||||
bool L6208_SetAcceleration(uint8_t deviceId, uint16_t newAcc); //Set the acceleration in pps^2 | |||||
void L6208_SetDecayMode(uint8_t deviceId, motorDecayMode_t decayMode); //Set the motor decay mode | |||||
bool L6208_SetDeceleration(uint8_t deviceId, uint16_t newDec); //Set the deceleration in pps^2 | |||||
void L6208_SetDirection(uint8_t deviceId, motorDir_t direction); //Set the motor direction | |||||
void L6208_SetHome(uint8_t deviceId, int32_t homePos); //Set the home position | |||||
void L6208_SetMark(uint8_t deviceId, int32_t markPos); //Set the mark position | |||||
bool L6208_SetMaxSpeed(uint8_t deviceId, uint16_t volatile newSpeed); //Set the max speed value in pps | |||||
bool L6208_SetMinSpeed(uint8_t deviceId, uint16_t volatile newSpeed); //Set the max speed value in pps | |||||
bool L6208_SetNbDevices(uint8_t nbDevices); //Set the number of devices | |||||
bool L6208_SetStepMode(uint8_t deviceId, motorStepMode_t stepMode); //Set the motor step mode | |||||
void L6208_SetStopMode(uint8_t deviceId, motorStopMode_t stopMode); //Select the mode to stop the motor | |||||
void L6208_SetTorque(uint8_t deviceId, motorTorqueMode_t torqueMode, uint8_t torqueValue); //Set the torque value according to the torque mode | |||||
bool L6208_SoftStop(uint8_t deviceId); //Progressively stop the motor by using the device deceleration and set deceleration torque | |||||
void L6208_TickHandler(uint8_t deviceId); //Handle the device state machine at each tick timer pulse end | |||||
uint32_t L6208_VrefPwmGetFreq(uint8_t deviceId); //Get the frequency of VREFA and VREFB PWM | |||||
void L6208_VrefPwmSetFreq(uint8_t deviceId, uint32_t newFreq); //Set the frequency of the VREFA and VREFB PWM | |||||
void L6208_WaitWhileActive(uint8_t deviceId); //Wait for the device state becomes Inactive | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup MotorControl_Board_Linked_Functions MotorControl Board Linked Functions | |||||
* @{ | |||||
*/ | |||||
///Delay of the requested number of milliseconds | |||||
extern void L6208_Board_Delay(uint32_t delay); | |||||
///Enable Irq | |||||
extern void L6208_Board_EnableIrq(void); | |||||
///Disable Irq | |||||
extern void L6208_Board_DisableIrq(void); | |||||
///Initialise GPIOs used for L6208 | |||||
extern void L6208_Board_GpioInit(void); | |||||
//Initialize the VREFA or VREFB PWM | |||||
extern bool L6208_Board_VrefPwmInit(uint8_t bridgeId, uint32_t pwmFreq); | |||||
///Set duty cycle of VREFA or VREFB PWM | |||||
extern bool L6208_Board_VrefPwmSetDutyCycle(uint8_t bridgeId,\ | |||||
uint16_t value,\ | |||||
bool valueIsPwmDutyCycle); | |||||
///Start the timer for the VREFA or VREFB PWM | |||||
extern bool L6208_Board_VrefPwmStart(uint8_t bridgeId,\ | |||||
uint32_t pwmFreq); | |||||
///Stop the timer for the VREFA or VREFB PWM | |||||
extern bool L6208_Board_VrefPwmStop(uint8_t bridgeId); | |||||
///Get the period of VREFA and VREFB PWM | |||||
extern uint32_t L6208_Board_VrefPwmGetPeriod(void); | |||||
///Check that the new VREFA and VREFB PWM frequency is nor too low nor too high | |||||
bool L6208_Board_VrefPwmFreqCheck(uint32_t newFreq); | |||||
///Initialize the tick | |||||
extern void L6208_Board_TickInit(void); | |||||
///Start the timer for the tick by using the set tick frequency | |||||
extern void L6208_Board_TickStart(void); | |||||
///Stop the timer for the tick | |||||
extern void L6208_Board_TickStop(void); | |||||
///Get the tick frequency in Hz | |||||
extern uint32_t L6208_Board_TickGetFreq(void); | |||||
///Release the reset pin | |||||
extern void L6208_Board_ReleaseReset(void); | |||||
///Set the reset pin | |||||
extern void L6208_Board_Reset(void); | |||||
///Set the control pin | |||||
extern void L6208_Board_CONTROL_PIN_Set(void); | |||||
///Reset the control pin | |||||
extern void L6208_Board_CONTROL_PIN_Reset(void); | |||||
///Set the clock pin | |||||
extern void L6208_Board_CLOCK_PIN_Set(void); | |||||
///Reset the clock pin | |||||
extern void L6208_Board_CLOCK_PIN_Reset(void); | |||||
///Set the half full pin | |||||
extern void L6208_Board_HALF_FULL_PIN_Set(void); | |||||
///Reset the half full pin | |||||
extern void L6208_Board_HALF_FULL_PIN_Reset(void); | |||||
///Set the dir pin | |||||
extern void L6208_Board_DIR_PIN_Set(void); | |||||
///Reset the dir pin | |||||
extern void L6208_Board_DIR_PIN_Reset(void); | |||||
///Returns the EN pin state | |||||
extern uint32_t L6208_Board_FLAG_PIN_GetState(void); | |||||
///Enable the power bridges (leave the output bridges HiZ) | |||||
extern void L6208_Board_Enable(void); | |||||
///Disable the power bridges (leave the output bridges HiZ) | |||||
extern void L6208_Board_Disable(void); | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
#ifdef __cplusplus | |||||
} | |||||
#endif | |||||
#endif /* __L6208_H */ | |||||
/******************* (C) COPYRIGHT 2016 STMicroelectronics *****END OF FILE****/ |
/******************************************************//** | |||||
* @file l6208_target_config.h | |||||
* @author IPC Rennes | |||||
* @version V1.5.0 | |||||
* @date June 1st, 2018 | |||||
* @brief Predefines values for the L6208 parameters | |||||
* @note (C) COPYRIGHT 2016 STMicroelectronics | |||||
****************************************************************************** | |||||
* @attention | |||||
* | |||||
* <h2><center>© COPYRIGHT(c) 2016 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. | |||||
* | |||||
****************************************************************************** | |||||
*/ | |||||
/* Define to prevent recursive inclusion -------------------------------------*/ | |||||
#ifndef __L6208_TARGET_CONFIG_H | |||||
#define __L6208_TARGET_CONFIG_H | |||||
#ifdef __cplusplus | |||||
extern "C" { | |||||
#endif | |||||
/** @addtogroup BSP | |||||
* @{ | |||||
*/ | |||||
/** @addtogroup L6208 | |||||
* @{ | |||||
*/ | |||||
/** @addtogroup L6208_Exported_Constants | |||||
* @{ | |||||
*/ | |||||
/** @defgroup Predefined_L6208_Parameters_Values Predefined L6208 Parameters Values | |||||
* @{ | |||||
*/ | |||||
/// Acceleration rate in step/s^2 or (1/16)th step/s^2 for microstep modes | |||||
#define L6208_CONF_PARAM_ACC_RATE (1000) | |||||
/// Acceleration current torque in % (from 0 to 100) | |||||
#define L6208_CONF_PARAM_ACC_CURRENT (10) | |||||
/// Deceleration rate in step/s^2 or (1/16)th step/s^2 for microstep modes | |||||
#define L6208_CONF_PARAM_DEC_RATE (1000) | |||||
/// Deceleration current torque in % (from 0 to 100) | |||||
#define L6208_CONF_PARAM_DEC_CURRENT (10) | |||||
/// Running speed in step/s or (1/16)th step/s for microstep modes | |||||
#define L6208_CONF_PARAM_RUNNING_SPEED (1000) | |||||
/// Running current torque in % (from 0 to 100) | |||||
#define L6208_CONF_PARAM_RUNNING_CURRENT (10) | |||||
/// Holding current torque in % (from 0 to 100) | |||||
#define L6208_CONF_PARAM_HOLDING_CURRENT (10) | |||||
/// Step mode via enum motorStepMode_t | |||||
#define L6208_CONF_PARAM_STEP_MODE (STEP_MODE_1_16) | |||||
/// Decay mode via enum motorDecayMode_t | |||||
#define L6208_CONF_PARAM_DECAY_MODE (FAST_DECAY) | |||||
/// Dwelling time in ms | |||||
#define L6208_CONF_PARAM_DWELL_TIME (0) | |||||
/// Automatic HIZ STOP | |||||
#define L6208_CONF_PARAM_AUTO_HIZ_STOP (FALSE) | |||||
/// VREFA and VREFB PWM frequency (Hz) | |||||
#define L6208_CONF_VREF_PWM_FREQUENCY (100000) | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
#ifdef __cplusplus | |||||
} | |||||
#endif | |||||
#endif /* __L6208_TARGET_CONFIG_H */ | |||||
/******************* (C) COPYRIGHT 2016 STMicroelectronics *****END OF FILE****/ |
/** | |||||
****************************************************************************** | |||||
* @file motor.h | |||||
* @author IPC Rennes | |||||
* @version V1.7.0 | |||||
* @date March 16th, 2018 | |||||
* @brief This file contains all the functions prototypes for motor drivers. | |||||
****************************************************************************** | |||||
* @attention | |||||
* | |||||
* <h2><center>© COPYRIGHT(c) 2016 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. | |||||
* | |||||
****************************************************************************** | |||||
*/ | |||||
/* Define to prevent recursive inclusion -------------------------------------*/ | |||||
#ifndef __MOTOR_H | |||||
#define __MOTOR_H | |||||
#ifdef __cplusplus | |||||
extern "C" { | |||||
#endif | |||||
/* Includes ------------------------------------------------------------------*/ | |||||
#include <stdint.h> | |||||
/** @addtogroup BSP | |||||
* @{ | |||||
*/ | |||||
/** @addtogroup Components | |||||
* @{ | |||||
*/ | |||||
/** @defgroup Motor Motor | |||||
* @{ | |||||
*/ | |||||
/** @defgroup Motor_Exported_Constants Motor Exported Constants | |||||
* @{ | |||||
*/ | |||||
/// boolean for false condition | |||||
#ifndef FALSE | |||||
#define FALSE (0) | |||||
#endif | |||||
/// boolean for true condition | |||||
#ifndef TRUE | |||||
#define TRUE (1) | |||||
#endif | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup Motor_Exported_Types Motor Exported Types | |||||
* @{ | |||||
*/ | |||||
/** @defgroup Motor_Boolean_Type Motor Boolean Type | |||||
* @{ | |||||
*/ | |||||
///bool Type | |||||
typedef uint8_t bool; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup Device_Direction_Options Device Direction Options | |||||
* @{ | |||||
*/ | |||||
/// Direction options | |||||
typedef enum { | |||||
BACKWARD = 0, | |||||
FORWARD = 1, | |||||
UNKNOW_DIR = ((uint8_t)0xFF) | |||||
} motorDir_t; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup Device_Action_Options Device Action Options | |||||
* @{ | |||||
*/ | |||||
/// Action options | |||||
typedef enum { | |||||
ACTION_RESET = ((uint8_t)0x00), | |||||
ACTION_COPY = ((uint8_t)0x08) | |||||
} motorAction_t; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup Device_States Device States | |||||
* @{ | |||||
*/ | |||||
/// Device states | |||||
typedef enum { | |||||
ACCELERATING = 0, | |||||
DECELERATINGTOSTOP = 1, | |||||
DECELERATING = 2, | |||||
STEADY = 3, | |||||
INDEX_ACCEL = 4, | |||||
INDEX_RUN = 5, | |||||
INDEX_DECEL = 6, | |||||
INDEX_DWELL = 7, | |||||
INACTIVE = 8, | |||||
STANDBY = 9, | |||||
STANDBYTOINACTIVE = 10 | |||||
} motorState_t; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup Device_Step_mode Device Step mode | |||||
* @{ | |||||
*/ | |||||
/// Stepping options | |||||
typedef enum { | |||||
STEP_MODE_FULL = ((uint8_t)0x00), | |||||
STEP_MODE_HALF = ((uint8_t)0x01), | |||||
STEP_MODE_1_4 = ((uint8_t)0x02), | |||||
STEP_MODE_1_8 = ((uint8_t)0x03), | |||||
STEP_MODE_1_16 = ((uint8_t)0x04), | |||||
STEP_MODE_1_32 = ((uint8_t)0x05), | |||||
STEP_MODE_1_64 = ((uint8_t)0x06), | |||||
STEP_MODE_1_128 = ((uint8_t)0x07), | |||||
STEP_MODE_1_256 = ((uint8_t)0x08), | |||||
STEP_MODE_UNKNOW = ((uint8_t)0xFE), | |||||
STEP_MODE_WAVE = ((uint8_t)0xFF) | |||||
} motorStepMode_t; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup Decay_mode Decay mode | |||||
* @{ | |||||
*/ | |||||
/// Decay Mode | |||||
typedef enum { | |||||
SLOW_DECAY = 0, | |||||
FAST_DECAY = 1, | |||||
UNKNOW_DECAY = ((uint8_t)0xFF) | |||||
} motorDecayMode_t; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup Stop_mode Stop mode | |||||
* @{ | |||||
*/ | |||||
/// Stop mode | |||||
typedef enum | |||||
{ | |||||
HOLD_MODE = 0, | |||||
HIZ_MODE = 1, | |||||
STANDBY_MODE = 2, | |||||
UNKNOW_STOP_MODE = ((uint8_t)0xFF) | |||||
} motorStopMode_t; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup Torque_mode Torque mode | |||||
* @{ | |||||
*/ | |||||
/// Torque mode | |||||
typedef enum | |||||
{ | |||||
ACC_TORQUE = 0, | |||||
DEC_TORQUE = 1, | |||||
RUN_TORQUE = 2, | |||||
HOLD_TORQUE = 3, | |||||
CURRENT_TORQUE = 4, | |||||
UNKNOW_TORQUE = ((uint8_t)0xFF) | |||||
} motorTorqueMode_t; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup Dual_Full_Bridge_Configuration Dual Full Bridge Configuration | |||||
* @{ | |||||
*/ | |||||
///Dual full bridge configurations for brush DC motors | |||||
typedef enum { | |||||
PARALLELING_NONE___1_BIDIR_MOTOR_BRIDGE_A__1_BIDIR_MOTOR_BRIDGE_B = 0, | |||||
PARALLELING_NONE___1_BIDIR_MOTOR_BRIDGE_A__2_UNDIR_MOTOR_BRIDGE_B = 1, | |||||
PARALLELING_NONE___2_UNDIR_MOTOR_BRIDGE_A__1_BIDIR_MOTOR_BRIDGE_B = 2, | |||||
PARALLELING_NONE___2_UNDIR_MOTOR_BRIDGE_A__2_UNDIR_MOTOR_BRIDGE_B = 3, | |||||
PARALLELING_IN1A_IN2A__1_UNDIR_MOTOR_BRIDGE_A__1_BIDIR_MOTOR_BRIDGE_B = 4, | |||||
PARALLELING_IN1A_IN2A__1_UNDIR_MOTOR_BRIDGE_A__2_UNDIR_MOTOR_BRIDGE_B = 5, | |||||
PARALLELING_IN1B_IN2B__1_BIDIR_MOTOR_BRIDGE_A__1_UNDIR_MOTOR_BRIDGE_B = 6, | |||||
PARALLELING_IN1B_IN2B__2_UNDIR_MOTOR_BRIDGE_A__1_UNDIR_MOTOR_BRIDGE_B = 7, | |||||
PARALLELING_IN1A_IN2A__IN1B_IN2B__1_UNDIR_MOTOR_BRIDGE_A__1_UNDIR_MOTOR_BRIDGE_B = 8, | |||||
PARALLELING_IN1A_IN2A__IN1B_IN2B__1_BIDIR_MOTOR = 9, | |||||
PARALLELING_IN1A_IN1B__IN2A_IN2B__1_UNDIR_MOTOR_BRIDGE_1A__1_UNDIR_MOTOR_BRIDGE_2A = 10, | |||||
PARALLELING_IN1A_IN1B__IN2A_IN2B__1_BIDIR_MOTOR = 11, | |||||
PARALLELING_ALL_WITH_IN1A___1_UNDIR_MOTOR = 12, | |||||
PARALLELING_END_ENUM = 13 | |||||
} dualFullBridgeConfig_t; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup Motor_Driver_Structure Motor Driver Structure | |||||
* @{ | |||||
*/ | |||||
/// Motor driver structure definition | |||||
typedef struct | |||||
{ | |||||
/// Function pointer to Init | |||||
void (*Init)(void*); | |||||
/// Function pointer to ReadID | |||||
uint16_t (*ReadID)(void); | |||||
/// Function pointer to AttachErrorHandler | |||||
void(*AttachErrorHandler)(void (*callback)(uint16_t)); | |||||
/// Function pointer to AttachFlagInterrupt | |||||
void (*AttachFlagInterrupt)(void (*callback)(void)); | |||||
/// Function pointer to AttachBusyInterrupt | |||||
void (*AttachBusyInterrupt)(void (*callback)(void)); | |||||
/// Function pointer to FlagInterruptHandler | |||||
void (*FlagInterruptHandler)(void); | |||||
/// Function pointer to GetAcceleration | |||||
uint16_t (*GetAcceleration)(uint8_t); | |||||
/// Function pointer to GetCurrentSpeed | |||||
uint16_t (*GetCurrentSpeed)(uint8_t); | |||||
/// Function pointer to GetDeceleration | |||||
uint16_t (*GetDeceleration)(uint8_t); | |||||
/// Function pointer to GetDeviceState | |||||
motorState_t(*GetDeviceState)(uint8_t); | |||||
/// Function pointer to GetFwVersion | |||||
uint32_t (*GetFwVersion)(void); | |||||
/// Function pointer to GetMark | |||||
int32_t (*GetMark)(uint8_t); | |||||
/// Function pointer to GetMaxSpeed | |||||
uint16_t (*GetMaxSpeed)(uint8_t); | |||||
/// Function pointer to GetMinSpeed | |||||
uint16_t (*GetMinSpeed)(uint8_t); | |||||
/// Function pointer to GetPosition | |||||
int32_t (*GetPosition)(uint8_t); | |||||
/// Function pointer to GoHome | |||||
void (*GoHome)(uint8_t); | |||||
/// Function pointer to GoMark | |||||
void (*GoMark)(uint8_t); | |||||
/// Function pointer to GoTo | |||||
void (*GoTo)(uint8_t, int32_t); | |||||
/// Function pointer to HardStop | |||||
void (*HardStop)(uint8_t); | |||||
/// Function pointer to Move | |||||
void (*Move)(uint8_t, motorDir_t, uint32_t ); | |||||
/// Function pointer to ResetAllDevices | |||||
void (*ResetAllDevices)(void); | |||||
/// Function pointer to Run | |||||
void (*Run)(uint8_t, motorDir_t); | |||||
/// Function pointer to SetAcceleration | |||||
bool(*SetAcceleration)(uint8_t ,uint16_t ); | |||||
/// Function pointer to SetDeceleration | |||||
bool(*SetDeceleration)(uint8_t , uint16_t ); | |||||
/// Function pointer to SetHome | |||||
void (*SetHome)(uint8_t, int32_t); | |||||
/// Function pointer to SetMark | |||||
void (*SetMark)(uint8_t, int32_t); | |||||
/// Function pointer to SetMaxSpeed | |||||
bool (*SetMaxSpeed)(uint8_t, uint16_t ); | |||||
/// Function pointer to SetMinSpeed | |||||
bool (*SetMinSpeed)(uint8_t, uint16_t ); | |||||
/// Function pointer to SoftStop | |||||
bool (*SoftStop)(uint8_t); | |||||
/// Function pointer to StepClockHandler | |||||
void (*StepClockHandler)(uint8_t deviceId); | |||||
/// Function pointer to WaitWhileActive | |||||
void (*WaitWhileActive)(uint8_t); | |||||
/// Function pointer to CmdDisable | |||||
void (*CmdDisable)(uint8_t); | |||||
/// Function pointer to CmdEnable | |||||
void (*CmdEnable)(uint8_t); | |||||
/// Function pointer to CmdGetParam | |||||
uint32_t (*CmdGetParam)(uint8_t, uint32_t); | |||||
/// Function pointer to CmdGetStatus | |||||
uint16_t (*CmdGetStatus)(uint8_t); | |||||
/// Function pointer to CmdNop | |||||
void (*CmdNop)(uint8_t); | |||||
/// Function pointer to CmdSetParam | |||||
void (*CmdSetParam)(uint8_t, uint32_t, uint32_t); | |||||
/// Function pointer to ReadStatusRegister | |||||
uint16_t (*ReadStatusRegister)(uint8_t); | |||||
/// Function pointer to ReleaseReset | |||||
void (*ReleaseReset)(uint8_t); | |||||
/// Function pointer to Reset | |||||
void (*Reset)(uint8_t); | |||||
/// Function pointer to SelectStepMode | |||||
bool (*SelectStepMode)(uint8_t deviceId, motorStepMode_t); | |||||
/// Function pointer to SetDirection | |||||
void (*SetDirection)(uint8_t, motorDir_t); | |||||
/// Function pointer to CmdGoToDir | |||||
void (*CmdGoToDir)(uint8_t, motorDir_t, int32_t); | |||||
/// Function pointer to CheckBusyHw | |||||
uint8_t (*CheckBusyHw)(void); | |||||
/// Function pointer to CheckStatusHw | |||||
uint8_t (*CheckStatusHw)(void); | |||||
/// Function pointer to CmdGoUntil | |||||
void (*CmdGoUntil)(uint8_t, motorAction_t, motorDir_t, uint32_t); | |||||
/// Function pointer to CmdHardHiZ | |||||
void (*CmdHardHiZ)(uint8_t); | |||||
/// Function pointer to CmdReleaseSw | |||||
void (*CmdReleaseSw)(uint8_t, motorAction_t, motorDir_t); | |||||
/// Function pointer to CmdResetDevice | |||||
void (*CmdResetDevice)(uint8_t); | |||||
/// Function pointer to CmdResetPos | |||||
void (*CmdResetPos)(uint8_t); | |||||
/// Function pointer to CmdRun | |||||
void (*CmdRun)(uint8_t, motorDir_t, uint32_t); | |||||
/// Function pointer to CmdSoftHiZ | |||||
void (*CmdSoftHiZ)(uint8_t); | |||||
/// Function pointer to CmdStepClock | |||||
void (*CmdStepClock)(uint8_t, motorDir_t); | |||||
/// Function pointer to FetchAndClearAllStatus | |||||
void (*FetchAndClearAllStatus)(void); | |||||
/// Function pointer to GetFetchedStatus | |||||
uint16_t (*GetFetchedStatus)(uint8_t); | |||||
/// Function pointer to GetNbDevices | |||||
uint8_t (*GetNbDevices)(void); | |||||
/// Function pointer to IsDeviceBusy | |||||
bool (*IsDeviceBusy)(uint8_t); | |||||
/// Function pointer to SendQueuedCommands | |||||
void (*SendQueuedCommands)(void); | |||||
/// Function pointer to QueueCommands | |||||
void (*QueueCommands)(uint8_t, uint8_t, int32_t); | |||||
/// Function pointer to WaitForAllDevicesNotBusy | |||||
void (*WaitForAllDevicesNotBusy)(void); | |||||
/// Function pointer to ErrorHandler | |||||
void (*ErrorHandler)(uint16_t); | |||||
/// Function pointer to BusyInterruptHandler | |||||
void (*BusyInterruptHandler)(void); | |||||
/// Function pointer to CmdSoftStop | |||||
void (*CmdSoftStop)(uint8_t); | |||||
/// Function pointer to StartStepClock | |||||
void (*StartStepClock)(uint16_t); | |||||
/// Function pointer to StopStepClock | |||||
void (*StopStepClock)(void); | |||||
/// Function pointer to SetDualFullBridgeConfig | |||||
void (*SetDualFullBridgeConfig)(uint8_t); | |||||
/// Function pointer to GetBridgeInputPwmFreq | |||||
uint32_t (*GetBridgeInputPwmFreq)(uint8_t); | |||||
/// Function pointer to SetBridgeInputPwmFreq | |||||
void (*SetBridgeInputPwmFreq)(uint8_t, uint32_t); | |||||
/// Function pointer to SetStopMode | |||||
void (*SetStopMode)(uint8_t, motorStopMode_t); | |||||
/// Function pointer to GetStopMode | |||||
motorStopMode_t (*GetStopMode)(uint8_t); | |||||
/// Function pointer to SetDecayMode | |||||
void (*SetDecayMode)(uint8_t, motorDecayMode_t); | |||||
/// Function pointer to GetDecayMode | |||||
motorDecayMode_t (*GetDecayMode)(uint8_t); | |||||
/// Function pointer to GetStepMode | |||||
motorStepMode_t (*GetStepMode)(uint8_t); | |||||
/// Function pointer to GetDirection | |||||
motorDir_t (*GetDirection)(uint8_t); | |||||
/// Function pointer to ExitDeviceFromReset | |||||
void (*ExitDeviceFromReset)(uint8_t); | |||||
/// Function pointer to SetTorque | |||||
void (*SetTorque)(uint8_t, motorTorqueMode_t, uint8_t); | |||||
/// Function pointer to GetTorque | |||||
uint8_t (*GetTorque)(uint8_t, motorTorqueMode_t); | |||||
/// Function pointer to SetVRefFreq | |||||
void (*SetRefFreq)(uint8_t, uint32_t); | |||||
/// Function pointer to GetVRefFreq | |||||
uint32_t (*GetRefFreq)(uint8_t); | |||||
/// Function pointer to SetVRefDc | |||||
void (*SetRefDc)(uint8_t, uint8_t); | |||||
/// Function pointer to GetVRefDc | |||||
uint8_t (*GetRefDc)(uint8_t); | |||||
/// Function pointer to SetNbDevices | |||||
bool (*SetNbDevices)(uint8_t); | |||||
/// Function pointer to SetAnalogValue | |||||
bool (*SetAnalogValue)(uint8_t, uint32_t, float); | |||||
/// Function pointer to GetAnalogValue | |||||
float (*GetAnalogValue)(uint8_t, uint32_t); | |||||
/// Function pointer to SetTorqueBoostEnable | |||||
void (*SetTorqueBoostEnable) (uint8_t, bool); | |||||
/// Function pointer to GetTorqueBoostEnable | |||||
bool (*GetTorqueBoostEnable) (uint8_t); | |||||
/// Function pointer to SetTorqueBoostThreshold | |||||
void (*SetTorqueBoostThreshold) (uint8_t, uint16_t); | |||||
/// Function pointer to GetTorqueBoostThreshold | |||||
uint16_t (*GetTorqueBoostThreshold) (uint8_t); | |||||
/// Function pointer to GetDualFullBridgeConfig | |||||
uint8_t (*GetDualFullBridgeConfig) (void); | |||||
}motorDrv_t; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
#ifdef __cplusplus | |||||
} | |||||
#endif | |||||
#endif /* __MOTOR_H */ | |||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
/** | |||||
****************************************************************************** | |||||
* @file stm32f4xx_nucleo.h | |||||
* @author MCD Application Team | |||||
* @brief This file contains definitions for: | |||||
* - LEDs and push-button available on STM32F4XX-Nucleo Kit | |||||
* from STMicroelectronics | |||||
* - LCD, joystick and microSD available on Adafruit 1.8" TFT LCD | |||||
* shield (reference ID 802) | |||||
****************************************************************************** | |||||
* @attention | |||||
* | |||||
* <h2><center>© COPYRIGHT(c) 2017 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. | |||||
* | |||||
****************************************************************************** | |||||
*/ | |||||
/* Define to prevent recursive inclusion -------------------------------------*/ | |||||
#ifndef __STM32F4XX_NUCLEO_H | |||||
#define __STM32F4XX_NUCLEO_H | |||||
#ifdef __cplusplus | |||||
extern "C" { | |||||
#endif | |||||
/* Includes ------------------------------------------------------------------*/ | |||||
#include "stm32f4xx_hal.h" | |||||
/* To be defined only if the board is provided with the related shield */ | |||||
/* https://www.adafruit.com/products/802 */ | |||||
#define ADAFRUIT_TFT_JOY_SD_ID802 | |||||
/** @addtogroup BSP | |||||
* @{ | |||||
*/ | |||||
/** @addtogroup STM32F4XX_NUCLEO | |||||
* @{ | |||||
*/ | |||||
/** @addtogroup STM32F4XX_NUCLEO_LOW_LEVEL | |||||
* @{ | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_Exported_Types STM32F4XX NUCLEO LOW LEVEL Exported Types | |||||
* @{ | |||||
*/ | |||||
typedef enum | |||||
{ | |||||
LED2 = 0 | |||||
}Led_TypeDef; | |||||
typedef enum | |||||
{ | |||||
BUTTON_USER = 0, | |||||
/* Alias */ | |||||
BUTTON_KEY = BUTTON_USER | |||||
} Button_TypeDef; | |||||
typedef enum | |||||
{ | |||||
BUTTON_MODE_GPIO = 0, | |||||
BUTTON_MODE_EXTI = 1 | |||||
}ButtonMode_TypeDef; | |||||
typedef enum | |||||
{ | |||||
JOY_NONE = 0, | |||||
JOY_SEL = 1, | |||||
JOY_DOWN = 2, | |||||
JOY_LEFT = 3, | |||||
JOY_RIGHT = 4, | |||||
JOY_UP = 5 | |||||
}JOYState_TypeDef; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_Exported_Constants STM32F4XX NUCLEO LOW LEVEL Exported Constants | |||||
* @{ | |||||
*/ | |||||
/** | |||||
* @brief Define for STM32F4XX_NUCLEO board | |||||
*/ | |||||
#if !defined (USE_STM32F4XX_NUCLEO) | |||||
#define USE_STM32F4XX_NUCLEO | |||||
#endif | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_LED STM32F4XX NUCLEO LOW LEVEL LED | |||||
* @{ | |||||
*/ | |||||
#define LEDn 1 | |||||
#define LED2_PIN GPIO_PIN_5 | |||||
#define LED2_GPIO_PORT GPIOA | |||||
#define LED2_GPIO_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE() | |||||
#define LED2_GPIO_CLK_DISABLE() __HAL_RCC_GPIOA_CLK_DISABLE() | |||||
#define LEDx_GPIO_CLK_ENABLE(__INDEX__) LED2_GPIO_CLK_ENABLE() | |||||
#define LEDx_GPIO_CLK_DISABLE(__INDEX__) LED2_GPIO_CLK_DISABLE() | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_BUTTON STM32F4XX NUCLEO LOW LEVEL BUTTON | |||||
* @{ | |||||
*/ | |||||
#define BUTTONn 1 | |||||
/** | |||||
* @brief Key push-button | |||||
*/ | |||||
#define USER_BUTTON_PIN GPIO_PIN_13 | |||||
#define USER_BUTTON_GPIO_PORT GPIOC | |||||
#define USER_BUTTON_GPIO_CLK_ENABLE() __HAL_RCC_GPIOC_CLK_ENABLE() | |||||
#define USER_BUTTON_GPIO_CLK_DISABLE() __HAL_RCC_GPIOC_CLK_DISABLE() | |||||
#define USER_BUTTON_EXTI_LINE GPIO_PIN_13 | |||||
#define USER_BUTTON_EXTI_IRQn EXTI15_10_IRQn | |||||
#define BUTTONx_GPIO_CLK_ENABLE(__INDEX__) USER_BUTTON_GPIO_CLK_ENABLE() | |||||
#define BUTTONx_GPIO_CLK_DISABLE(__INDEX__) USER_BUTTON_GPIO_CLK_DISABLE() | |||||
/* Aliases */ | |||||
#define KEY_BUTTON_PIN USER_BUTTON_PIN | |||||
#define KEY_BUTTON_GPIO_PORT USER_BUTTON_GPIO_PORT | |||||
#define KEY_BUTTON_GPIO_CLK_ENABLE() USER_BUTTON_GPIO_CLK_ENABLE() | |||||
#define KEY_BUTTON_GPIO_CLK_DISABLE() USER_BUTTON_GPIO_CLK_DISABLE() | |||||
#define KEY_BUTTON_EXTI_LINE USER_BUTTON_EXTI_LINE | |||||
#define KEY_BUTTON_EXTI_IRQn USER_BUTTON_EXTI_IRQn | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_BUS STM32F4XX NUCLEO LOW LEVEL BUS | |||||
* @{ | |||||
*/ | |||||
/*############################### SPI1 #######################################*/ | |||||
#ifdef HAL_SPI_MODULE_ENABLED | |||||
#define NUCLEO_SPIx SPI1 | |||||
#define NUCLEO_SPIx_CLK_ENABLE() __HAL_RCC_SPI1_CLK_ENABLE() | |||||
#define NUCLEO_SPIx_SCK_AF GPIO_AF5_SPI1 | |||||
#define NUCLEO_SPIx_SCK_GPIO_PORT GPIOA | |||||
#define NUCLEO_SPIx_SCK_PIN GPIO_PIN_5 | |||||
#define NUCLEO_SPIx_SCK_GPIO_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE() | |||||
#define NUCLEO_SPIx_SCK_GPIO_CLK_DISABLE() __HAL_RCC_GPIOA_CLK_DISABLE() | |||||
#define NUCLEO_SPIx_MISO_MOSI_AF GPIO_AF5_SPI1 | |||||
#define NUCLEO_SPIx_MISO_MOSI_GPIO_PORT GPIOA | |||||
#define NUCLEO_SPIx_MISO_MOSI_GPIO_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE() | |||||
#define NUCLEO_SPIx_MISO_MOSI_GPIO_CLK_DISABLE() __HAL_RCC_GPIOA_CLK_DISABLE() | |||||
#define NUCLEO_SPIx_MISO_PIN GPIO_PIN_6 | |||||
#define NUCLEO_SPIx_MOSI_PIN GPIO_PIN_7 | |||||
/* Maximum Timeout values for flags waiting loops. These timeouts are not based | |||||
on accurate values, they just guarantee that the application will not remain | |||||
stuck if the SPI communication is corrupted. | |||||
You may modify these timeout values depending on CPU frequency and application | |||||
conditions (interrupts routines ...). */ | |||||
#define NUCLEO_SPIx_TIMEOUT_MAX 1000 | |||||
/** | |||||
* @brief SD Control Lines management | |||||
*/ | |||||
#define SD_CS_LOW() HAL_GPIO_WritePin(SD_CS_GPIO_PORT, SD_CS_PIN, GPIO_PIN_RESET) | |||||
#define SD_CS_HIGH() HAL_GPIO_WritePin(SD_CS_GPIO_PORT, SD_CS_PIN, GPIO_PIN_SET) | |||||
/** | |||||
* @brief LCD Control Lines management | |||||
*/ | |||||
#define LCD_CS_LOW() HAL_GPIO_WritePin(LCD_CS_GPIO_PORT, LCD_CS_PIN, GPIO_PIN_RESET) | |||||
#define LCD_CS_HIGH() HAL_GPIO_WritePin(LCD_CS_GPIO_PORT, LCD_CS_PIN, GPIO_PIN_SET) | |||||
#define LCD_DC_LOW() HAL_GPIO_WritePin(LCD_DC_GPIO_PORT, LCD_DC_PIN, GPIO_PIN_RESET) | |||||
#define LCD_DC_HIGH() HAL_GPIO_WritePin(LCD_DC_GPIO_PORT, LCD_DC_PIN, GPIO_PIN_SET) | |||||
/** | |||||
* @brief SD Control Interface pins (shield D4) | |||||
*/ | |||||
#define SD_CS_PIN GPIO_PIN_5 | |||||
#define SD_CS_GPIO_PORT GPIOB | |||||
#define SD_CS_GPIO_CLK_ENABLE() __HAL_RCC_GPIOB_CLK_ENABLE() | |||||
#define SD_CS_GPIO_CLK_DISABLE() __HAL_RCC_GPIOB_CLK_DISABLE() | |||||
/** | |||||
* @brief LCD Control Interface pins (shield D10) | |||||
*/ | |||||
#define LCD_CS_PIN GPIO_PIN_6 | |||||
#define LCD_CS_GPIO_PORT GPIOB | |||||
#define LCD_CS_GPIO_CLK_ENABLE() __HAL_RCC_GPIOB_CLK_ENABLE() | |||||
#define LCD_CS_GPIO_CLK_DISABLE() __HAL_RCC_GPIOB_CLK_DISABLE() | |||||
/** | |||||
* @brief LCD Data/Command Interface pins (shield D8) | |||||
*/ | |||||
#define LCD_DC_PIN GPIO_PIN_9 | |||||
#define LCD_DC_GPIO_PORT GPIOA | |||||
#define LCD_DC_GPIO_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE() | |||||
#define LCD_DC_GPIO_CLK_DISABLE() __HAL_RCC_GPIOA_CLK_DISABLE() | |||||
#endif /* HAL_SPI_MODULE_ENABLED */ | |||||
/*################################ ADC1 ######################################*/ | |||||
/** | |||||
* @brief ADC Interface pins | |||||
* used to detect motion of Joystick available on Adafruit 1.8" TFT shield | |||||
*/ | |||||
#ifdef HAL_ADC_MODULE_ENABLED | |||||
#define NUCLEO_ADCx ADC1 | |||||
#define NUCLEO_ADCx_CLK_ENABLE() __HAL_RCC_ADC1_CLK_ENABLE() | |||||
#define NUCLEO_ADCx_CLK_DISABLE() __HAL_RCC_ADC1_CLK_DISABLE() | |||||
#define NUCLEO_ADCx_CHANNEL ADC_CHANNEL_8 | |||||
#define NUCLEO_ADCx_GPIO_PORT GPIOB | |||||
#define NUCLEO_ADCx_GPIO_PIN GPIO_PIN_0 | |||||
#define NUCLEO_ADCx_GPIO_CLK_ENABLE() __HAL_RCC_GPIOB_CLK_ENABLE() | |||||
#define NUCLEO_ADCx_GPIO_CLK_DISABLE() __HAL_RCC_GPIOB_CLK_DISABLE() | |||||
#endif /* HAL_ADC_MODULE_ENABLED */ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_Exported_Macros STM32F4XX NUCLEO LOW LEVEL Exported Macros | |||||
* @{ | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_Exported_Functions STM32F4XX NUCLEO LOW LEVEL Exported Functions | |||||
* @{ | |||||
*/ | |||||
uint32_t BSP_GetVersion(void); | |||||
void BSP_LED_Init(Led_TypeDef Led); | |||||
void BSP_LED_DeInit(Led_TypeDef Led); | |||||
void BSP_LED_On(Led_TypeDef Led); | |||||
void BSP_LED_Off(Led_TypeDef Led); | |||||
void BSP_LED_Toggle(Led_TypeDef Led); | |||||
void BSP_PB_Init(Button_TypeDef Button, ButtonMode_TypeDef ButtonMode); | |||||
void BSP_PB_DeInit(Button_TypeDef Button); | |||||
uint32_t BSP_PB_GetState(Button_TypeDef Button); | |||||
#ifdef HAL_ADC_MODULE_ENABLED | |||||
uint8_t BSP_JOY_Init(void); | |||||
JOYState_TypeDef BSP_JOY_GetState(void); | |||||
void BSP_JOY_DeInit(void); | |||||
#endif /* HAL_ADC_MODULE_ENABLED */ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
#ifdef __cplusplus | |||||
} | |||||
#endif | |||||
#endif /* __STM32F4XX_NUCLEO_H */ | |||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
/** | |||||
****************************************************************************** | |||||
* @file x_nucleo_ihm05a1_stm32f4xx.h | |||||
* @author IPC Rennes | |||||
* @version V1.5.0 | |||||
* @date June 1st, 2018 | |||||
* @brief Header for BSP driver for x-nucleo-ihm05a1 Nucleo extension board | |||||
* (based on L6208) | |||||
****************************************************************************** | |||||
* @attention | |||||
* | |||||
* <h2><center>© 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. | |||||
* | |||||
****************************************************************************** | |||||
*/ | |||||
/* Define to prevent recursive inclusion -------------------------------------*/ | |||||
#ifndef X_NUCLEO_IHM05A1_STM32F4XX_H | |||||
#define X_NUCLEO_IHM05A1_STM32F4XX_H | |||||
#ifdef __cplusplus | |||||
extern "C" { | |||||
#endif | |||||
/* Includes ------------------------------------------------------------------*/ | |||||
#include "stm32f4xx_nucleo.h" | |||||
/** @addtogroup BSP | |||||
* @{ | |||||
*/ | |||||
/** @addtogroup X_NUCLEO_IHM05A1_STM32F4XX | |||||
* @{ | |||||
*/ | |||||
/* Exported Constants --------------------------------------------------------*/ | |||||
/** @defgroup IHM05A1_Exported_Constants IHM05A1 Exported Constants | |||||
* @{ | |||||
*/ | |||||
/******************************************************************************/ | |||||
/* USE_STM32F4XX_NUCLEO */ | |||||
/******************************************************************************/ | |||||
/** @defgroup Constants_For_STM32F4XX_NUCLEO Constants For STM32F4XX NUCLEO | |||||
* @{ | |||||
*/ | |||||
/// GPIO Pin used for the VREFA | |||||
#define BSP_MOTOR_CONTROL_BOARD_VREFA_PIN (GPIO_PIN_3) | |||||
/// GPIO port used for the VREFA | |||||
#define BSP_MOTOR_CONTROL_BOARD_VREFA_PORT (GPIOB) | |||||
/// Interrupt line used for L6208 OCD and OVT | |||||
#define FLAG_EXTI_LINE_IRQn (EXTI15_10_IRQn) | |||||
/// Timer used to generate the VREFA PWM | |||||
#define BSP_MOTOR_CONTROL_BOARD_TIMER_VREFA_PWM (TIM2) | |||||
/// Timer used to generate the VREFB PWM | |||||
#define BSP_MOTOR_CONTROL_BOARD_TIMER_VREFB_PWM (TIM3) | |||||
/// Channel Timer used for the VREFA PWM | |||||
#define BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_VREFA_PWM (TIM_CHANNEL_2) | |||||
/// Channel Timer used for the VREFB PWM | |||||
#define BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_VREFB_PWM (TIM_CHANNEL_2) | |||||
/// HAL Active Channel Timer used for the VREFA PWM | |||||
#define BSP_MOTOR_CONTROL_BOARD_HAL_ACT_CHAN_TIMER_VREFA_PWM (HAL_TIM_ACTIVE_CHANNEL_2) | |||||
/// HAL Active Channel Timer used for the VREFB PWM | |||||
#define BSP_MOTOR_CONTROL_BOARD_HAL_ACT_CHAN_TIMER_VREFB_PWM (HAL_TIM_ACTIVE_CHANNEL_2) | |||||
/// Timer Clock Enable for the VREFA PWM | |||||
#define __BSP_MOTOR_CONTROL_BOARD_TIMER_VREFA_PWM_CLCK_ENABLE() __TIM2_CLK_ENABLE() | |||||
/// Timer Clock Disable for the VREFA PWM | |||||
#define __BSP_MOTOR_CONTROL_BOARD_TIMER_VREFA_PWM_CLCK_DISABLE() __TIM2_CLK_DISABLE() | |||||
/// Timer Clock Enable for the VREFB PWMs | |||||
#define __BSP_MOTOR_CONTROL_BOARD_TIMER_VREFB_PWM_CLCK_ENABLE() __TIM3_CLK_ENABLE() | |||||
/// Timer Clock Disable for the VREFB PWMs | |||||
#define __BSP_MOTOR_CONTROL_BOARD_TIMER_VREFB_PWM_CLCK_DISABLE() __TIM3_CLK_DISABLE() | |||||
/// VREFA PWM GPIO alternate function | |||||
#define BSP_MOTOR_CONTROL_BOARD_AFx_TIMx_VREFA_PWM (GPIO_AF1_TIM2) | |||||
/// VREFB PWM GPIO alternate function | |||||
#define BSP_MOTOR_CONTROL_BOARD_AFx_TIMx_VREFB_PWM (GPIO_AF2_TIM3) | |||||
/// Timer used to generate the tick | |||||
#define BSP_MOTOR_CONTROL_BOARD_TIMER_TICK (TIM4) | |||||
/// tick timer global interrupt | |||||
#define BSP_MOTOR_CONTROL_BOARD_TIMER_TICK_IRQn (TIM4_IRQn) | |||||
/// Channel Timer used for the tick | |||||
#define BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_TICK (TIM_CHANNEL_1) | |||||
/// Timer Clock Enable for the tick | |||||
#define __BSP_MOTOR_CONTROL_BOARD_TIMER_TICK_CLCK_ENABLE() __TIM4_CLK_ENABLE() | |||||
/// Timer Clock Disable for the tick | |||||
#define __BSP_MOTOR_CONTROL_BOARD_TIMER_TICK_CLCK_DISABLE() __TIM4_CLK_DISABLE() | |||||
/// HAL Active Channel Timer used for the tick | |||||
#define BSP_MOTOR_CONTROL_BOARD_HAL_ACT_CHAN_TIMER_TICK (HAL_TIM_ACTIVE_CHANNEL_1) | |||||
/// Flag interrupt priority | |||||
#define BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PRIORITY (1) | |||||
/// tick timer priority (lower than flag interrupt priority) | |||||
#define BSP_MOTOR_CONTROL_BOARD_TIMER_TICK_PRIORITY (BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PRIORITY + 1) | |||||
/** | |||||
* @} | |||||
*/ | |||||
/******************************************************************************/ | |||||
/* Independent plateform definitions */ | |||||
/******************************************************************************/ | |||||
/** @defgroup Constants_For_All_Nucleo_Platforms Constants For All Nucleo Platforms | |||||
* @{ | |||||
*/ | |||||
/// GPIO Pin used for the VREFB | |||||
#define BSP_MOTOR_CONTROL_BOARD_VREFB_PIN (GPIO_PIN_7) | |||||
/// GPIO Port used for the VREFB | |||||
#define BSP_MOTOR_CONTROL_BOARD_VREFB_PORT (GPIOC) | |||||
/// GPIO Pin used for the L6208 clock pin (step clock input) | |||||
#define BSP_MOTOR_CONTROL_BOARD_CLOCK_PIN (GPIO_PIN_10) | |||||
/// GPIO port used for the L6208 clock pin (step clock input) | |||||
#define BSP_MOTOR_CONTROL_BOARD_CLOCK_PORT (GPIOB) | |||||
/// GPIO Pin used for the L6208 CW/CCW pin (direction) | |||||
#define BSP_MOTOR_CONTROL_BOARD_DIR_PIN (GPIO_PIN_8) | |||||
/// GPIO port used for the L6208 CW/CCW pin (direction) | |||||
#define BSP_MOTOR_CONTROL_BOARD_DIR_PORT (GPIOA) | |||||
/// GPIO Pin used for the L6208 HALF/FULL pin (step mode selector) | |||||
#define BSP_MOTOR_CONTROL_BOARD_HALF_FULL_PIN (GPIO_PIN_5) | |||||
/// GPIO port used for the L6208 HALF/FULL pin (step mode selector) | |||||
#define BSP_MOTOR_CONTROL_BOARD_HALF_FULL_PORT (GPIOB) | |||||
/// GPIO Pin used for the L6208 control pin (decay mode selector) | |||||
#define BSP_MOTOR_CONTROL_BOARD_CONTROL_PIN (GPIO_PIN_4) | |||||
/// GPIO port used for the L6208 control pin (decay mode selector) | |||||
#define BSP_MOTOR_CONTROL_BOARD_CONTROL_PORT (GPIOB) | |||||
/// GPIO Pin used for the L6208 reset pin | |||||
#define BSP_MOTOR_CONTROL_BOARD_RESET_PIN (GPIO_PIN_9) | |||||
/// GPIO port used for the L6208 reset pin | |||||
#define BSP_MOTOR_CONTROL_BOARD_RESET_PORT (GPIOA) | |||||
/// GPIO Pin used for the L6208 EN pin (chip enable) and OCD and OVT alarms | |||||
#define BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PIN (GPIO_PIN_10) | |||||
/// GPIO port used for the L6208 EN pin (chip enable) OCD and OVT alarms | |||||
#define BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PORT (GPIOA) | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
#ifdef __cplusplus | |||||
} | |||||
#endif | |||||
#endif /* X_NUCLEO_IHM05A1_STM32F4XX_H */ | |||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
/** | |||||
****************************************************************************** | |||||
* @file x_nucleo_ihmxx.h | |||||
* @author IPC Rennes | |||||
* @version V1.7.0 | |||||
* @date March 16th, 2018 | |||||
* @brief This file provides common definitions for motor control | |||||
****************************************************************************** | |||||
* @attention | |||||
* | |||||
* <h2><center>© 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. | |||||
* | |||||
****************************************************************************** | |||||
*/ | |||||
/* Define to prevent recursive inclusion -------------------------------------*/ | |||||
#ifndef X_NUCLEO_IHMXX_H | |||||
#define X_NUCLEO_IHMXX_H | |||||
#ifdef __cplusplus | |||||
extern "C" { | |||||
#endif | |||||
/* Includes ------------------------------------------------------------------*/ | |||||
#include "motor.h" | |||||
/** @addtogroup BSP | |||||
* @{ | |||||
*/ | |||||
/** @addtogroup MOTOR_CONTROL | |||||
* @{ | |||||
*/ | |||||
/** @defgroup MOTOR_CONTROL_Exported_Types MOTOR CONTROL Exported Types | |||||
* @{ | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup MOTOR_CONTROL_Exported_Constants MOTOR CONTROL Exported Constants | |||||
* @{ | |||||
*/ | |||||
/// Motor control error tag (used when trying to call undefined functions via motorDrvHandle) | |||||
#define MOTOR_CONTROL_ERROR_TAG (0x0800) | |||||
///Motor control board id for L6474 | |||||
#define BSP_MOTOR_CONTROL_BOARD_ID_L6474 (6474) | |||||
///Motor control board id for L6470 | |||||
#define BSP_MOTOR_CONTROL_BOARD_ID_L6470 (6470) | |||||
///Motor control board id for L6472 | |||||
#define BSP_MOTOR_CONTROL_BOARD_ID_L6472 (6472) | |||||
///Motor control board id for L6480 | |||||
#define BSP_MOTOR_CONTROL_BOARD_ID_L6480 (6480) | |||||
///Motor control board id for L6482 | |||||
#define BSP_MOTOR_CONTROL_BOARD_ID_L6482 (6482) | |||||
///Motor control board id for L6474 | |||||
#define BSP_MOTOR_CONTROL_BOARD_ID_L6474 (6474) | |||||
///Motor control board id for Powerstep01 | |||||
#define BSP_MOTOR_CONTROL_BOARD_ID_POWERSTEP01 (0001) | |||||
///Motor control board id for L6206 | |||||
#define BSP_MOTOR_CONTROL_BOARD_ID_L6206 (6206) | |||||
///Motor control board id for L6208 | |||||
#define BSP_MOTOR_CONTROL_BOARD_ID_L6208 (6208) | |||||
///Motor control board id for STSPIN220 | |||||
#define BSP_MOTOR_CONTROL_BOARD_ID_STSPIN220 (220) | |||||
///Motor control board id for STSPIN240 | |||||
#define BSP_MOTOR_CONTROL_BOARD_ID_STSPIN240 (240) | |||||
///Motor control board id for STSPIN250 | |||||
#define BSP_MOTOR_CONTROL_BOARD_ID_STSPIN250 (250) | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup MOTOR_CONTROL_Exported_Macros MOTOR CONTROL Exported Macros | |||||
* @{ | |||||
*/ | |||||
#if defined ( __GNUC__ ) | |||||
#ifndef __weak | |||||
#define __weak __attribute__((weak)) | |||||
#endif /* __weak */ | |||||
#endif /* __GNUC__ */ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup MOTOR_CONTROL_Weak_Function_Prototypes MOTOR CONTROL Weak Function Prototypes | |||||
* @{ | |||||
*/ | |||||
__weak motorDrv_t* L6474_GetMotorHandle(void); | |||||
__weak motorDrv_t* l647x_GetMotorHandle(void); | |||||
__weak motorDrv_t* l648x_GetMotorHandle(void); | |||||
__weak motorDrv_t* Powerstep01_GetMotorHandle(void); | |||||
__weak motorDrv_t* L6206_GetMotorHandle(void); | |||||
__weak motorDrv_t* L6208_GetMotorHandle(void); | |||||
__weak motorDrv_t* Stspin220_GetMotorHandle(void); | |||||
__weak motorDrv_t* Stspin240_250_GetMotorHandle(void); | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup MOTOR_CONTROL_Exported_Functions MOTOR CONTROL Exported Functions | |||||
* @{ | |||||
*/ | |||||
void BSP_MotorControl_AttachErrorHandler(void (*callback)(uint16_t)); | |||||
void BSP_MotorControl_AttachFlagInterrupt(void (*callback)(void)); | |||||
void BSP_MotorControl_AttachBusyInterrupt(void (*callback)(void)); | |||||
void BSP_MotorControl_ErrorHandler(uint16_t error); | |||||
void BSP_MotorControl_Init(uint16_t id, void* initDeviceParameters); | |||||
void BSP_MotorControl_FlagInterruptHandler(void); | |||||
uint16_t BSP_MotorControl_GetAcceleration(uint8_t deviceId); | |||||
uint16_t BSP_MotorControl_GetBoardId(void); | |||||
uint16_t BSP_MotorControl_GetCurrentSpeed(uint8_t deviceId); | |||||
uint16_t BSP_MotorControl_GetDeceleration(uint8_t deviceId); | |||||
motorState_t BSP_MotorControl_GetDeviceState(uint8_t deviceId); | |||||
uint32_t BSP_MotorControl_GetFwVersion(void); | |||||
int32_t BSP_MotorControl_GetMark(uint8_t deviceId); | |||||
uint16_t BSP_MotorControl_GetMaxSpeed(uint8_t deviceId); | |||||
uint16_t BSP_MotorControl_GetMinSpeed(uint8_t deviceId); | |||||
int32_t BSP_MotorControl_GetPosition(uint8_t deviceId); | |||||
void BSP_MotorControl_GoHome(uint8_t deviceId); | |||||
void BSP_MotorControl_GoMark(uint8_t deviceId); | |||||
void BSP_MotorControl_GoTo(uint8_t deviceId, int32_t targetPosition); | |||||
void BSP_MotorControl_HardStop(uint8_t deviceId); | |||||
void BSP_MotorControl_Move(uint8_t deviceId, motorDir_t direction, uint32_t stepCount); | |||||
void BSP_MotorControl_ResetAllDevices(void); | |||||
void BSP_MotorControl_Run(uint8_t deviceId, motorDir_t direction); | |||||
bool BSP_MotorControl_SetAcceleration(uint8_t deviceId,uint16_t newAcc); | |||||
bool BSP_MotorControl_SetDeceleration(uint8_t deviceId, uint16_t newDec); | |||||
void BSP_MotorControl_SetHome(uint8_t deviceId, int32_t homePosition); | |||||
void BSP_MotorControl_SetMark(uint8_t deviceId, int32_t markPosition); | |||||
bool BSP_MotorControl_SetMaxSpeed(uint8_t deviceId, uint16_t newMaxSpeed); | |||||
bool BSP_MotorControl_SetMinSpeed(uint8_t deviceId, uint16_t newMinSpeed); | |||||
bool BSP_MotorControl_SoftStop(uint8_t deviceId); | |||||
void BSP_MotorControl_StepClockHandler(uint8_t deviceId); | |||||
void BSP_MotorControl_WaitWhileActive(uint8_t deviceId); | |||||
void BSP_MotorControl_CmdDisable(uint8_t deviceId); | |||||
void BSP_MotorControl_CmdEnable(uint8_t deviceId); | |||||
uint32_t BSP_MotorControl_CmdGetParam(uint8_t deviceId, uint32_t param); | |||||
uint16_t BSP_MotorControl_CmdGetStatus(uint8_t deviceId); | |||||
void BSP_MotorControl_CmdNop(uint8_t deviceId); | |||||
void BSP_MotorControl_CmdSetParam(uint8_t deviceId, uint32_t param, uint32_t value); | |||||
uint16_t BSP_MotorControl_ReadStatusRegister(uint8_t deviceId); | |||||
void BSP_MotorControl_ReleaseReset(uint8_t deviceId); | |||||
void BSP_MotorControl_Reset(uint8_t deviceId); | |||||
bool BSP_MotorControl_SelectStepMode(uint8_t deviceId, motorStepMode_t stepMode); | |||||
void BSP_MotorControl_SetDirection(uint8_t deviceId, motorDir_t dir); | |||||
void BSP_MotorControl_CmdGoToDir(uint8_t deviceId, motorDir_t dir, int32_t abs_pos); | |||||
uint8_t BSP_MotorControl_CheckBusyHw(void); | |||||
uint8_t BSP_MotorControl_CheckStatusHw(void); | |||||
void BSP_MotorControl_CmdGoUntil(uint8_t deviceId, motorAction_t action, motorDir_t dir, uint32_t speed); | |||||
void BSP_MotorControl_CmdHardHiZ(uint8_t deviceId); | |||||
void BSP_MotorControl_CmdReleaseSw(uint8_t deviceId, motorAction_t action, motorDir_t dir); | |||||
void BSP_MotorControl_CmdResetDevice(uint8_t deviceId); | |||||
void BSP_MotorControl_CmdResetPos(uint8_t deviceId); | |||||
void BSP_MotorControl_CmdRun(uint8_t deviceId, motorDir_t dir, uint32_t speed); | |||||
void BSP_MotorControl_CmdSoftHiZ(uint8_t deviceId); | |||||
void BSP_MotorControl_CmdStepClock(uint8_t deviceId, motorDir_t dir); | |||||
void BSP_MotorControl_FetchAndClearAllStatus(void); | |||||
uint16_t BSP_MotorControl_GetFetchedStatus(uint8_t deviceId); | |||||
uint8_t BSP_MotorControl_GetNbDevices(void); | |||||
bool BSP_MotorControl_IsDeviceBusy(uint8_t deviceId); | |||||
void BSP_MotorControl_SendQueuedCommands(void); | |||||
void BSP_MotorControl_QueueCommands(uint8_t deviceId, uint8_t command, int32_t value); | |||||
void BSP_MotorControl_WaitForAllDevicesNotBusy(void); | |||||
void BSP_MotorControl_BusyInterruptHandler(void); | |||||
void BSP_MotorControl_CmdSoftStop(uint8_t deviceId); | |||||
void BSP_MotorControl_StartStepClock(uint16_t newFreq); | |||||
void BSP_MotorControl_StopStepClock(void); | |||||
void BSP_MotorControl_SetDualFullBridgeConfig(uint8_t config); | |||||
uint32_t BSP_MotorControl_GetBridgeInputPwmFreq(uint8_t bridgeId); | |||||
void BSP_MotorControl_SetBridgeInputPwmFreq(uint8_t bridgeId, uint32_t newFreq); | |||||
void BSP_MotorControl_SetStopMode(uint8_t deviceId, motorStopMode_t stopMode); | |||||
motorStopMode_t BSP_MotorControl_GetStopMode(uint8_t deviceId); | |||||
void BSP_MotorControl_SetDecayMode(uint8_t deviceId, motorDecayMode_t decayMode); | |||||
motorDecayMode_t BSP_MotorControl_GetDecayMode(uint8_t deviceId); | |||||
motorStepMode_t BSP_MotorControl_GetStepMode(uint8_t deviceId); | |||||
motorDir_t BSP_MotorControl_GetDirection(uint8_t deviceId); | |||||
void BSP_MotorControl_ExitDeviceFromReset(uint8_t deviceId); | |||||
uint8_t BSP_MotorControl_GetTorque(uint8_t deviceId, motorTorqueMode_t torqueMode); | |||||
void BSP_MotorControl_SetTorque(uint8_t deviceId, motorTorqueMode_t torqueMode, uint8_t torqueValue); | |||||
void BSP_MotorControl_SetRefFreq(uint8_t refId, uint32_t newFreq); | |||||
uint32_t BSP_MotorControl_GetRefFreq(uint8_t refId); | |||||
void BSP_MotorControl_SetRefDc(uint8_t refId, uint8_t newDc); | |||||
uint8_t BSP_MotorControl_GetRefDc(uint8_t refId); | |||||
bool BSP_MotorControl_SetNbDevices(uint16_t id, uint8_t nbDevices); | |||||
bool BSP_MotorControl_SetAnalogValue(uint8_t deviceId, uint32_t param, float value); | |||||
float BSP_MotorControl_GetAnalogValue(uint8_t deviceId, uint32_t param); | |||||
void BSP_MotorControl_SetTorqueBoostEnable(uint8_t deviceId, bool enable); | |||||
bool BSP_MotorControl_GetTorqueBoostEnable(uint8_t deviceId); | |||||
void BSP_MotorControl_SetTorqueBoostThreshold(uint8_t deviceId, uint16_t speedThreshold); | |||||
uint16_t BSP_MotorControl_GetTorqueBoostThreshold(uint8_t deviceId); | |||||
uint8_t BSP_MotorControl_GetDualFullBridgeConfig(void); | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
#ifdef __cplusplus | |||||
} | |||||
#endif | |||||
#endif /* X_NUCLEO_IHMXX_H */ | |||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
/** | |||||
****************************************************************************** | |||||
* @file stm32f4xx_nucleo.c | |||||
* @author MCD Application Team | |||||
* @brief This file provides set of firmware functions to manage: | |||||
* - LEDs and push-button available on STM32F4XX-Nucleo Kit | |||||
* from STMicroelectronics | |||||
* - LCD, joystick and microSD available on Adafruit 1.8" TFT LCD | |||||
* shield (reference ID 802) | |||||
****************************************************************************** | |||||
* @attention | |||||
* | |||||
* <h2><center>© COPYRIGHT(c) 2017 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 "stm32f4xx_nucleo.h" | |||||
/** @defgroup BSP BSP | |||||
* @{ | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO STM32F4XX NUCLEO | |||||
* @{ | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL STM32F4XX NUCLEO LOW LEVEL | |||||
* @brief This file provides set of firmware functions to manage Leds and push-button | |||||
* available on STM32F4xx-Nucleo Kit from STMicroelectronics. | |||||
* @{ | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_Private_TypesDefinitions STM32F4XX NUCLEO LOW LEVEL Private TypesDefinitions | |||||
* @{ | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_Private_Defines STM32F4XX NUCLEO LOW LEVEL Private Defines | |||||
* @{ | |||||
*/ | |||||
/** | |||||
* @brief STM32F4xx NUCLEO BSP Driver version number V1.2.7 | |||||
*/ | |||||
#define __STM32F4xx_NUCLEO_BSP_VERSION_MAIN (0x01) /*!< [31:24] main version */ | |||||
#define __STM32F4xx_NUCLEO_BSP_VERSION_SUB1 (0x02) /*!< [23:16] sub1 version */ | |||||
#define __STM32F4xx_NUCLEO_BSP_VERSION_SUB2 (0x07) /*!< [15:8] sub2 version */ | |||||
#define __STM32F4xx_NUCLEO_BSP_VERSION_RC (0x00) /*!< [7:0] release candidate */ | |||||
#define __STM32F4xx_NUCLEO_BSP_VERSION ((__STM32F4xx_NUCLEO_BSP_VERSION_MAIN << 24)\ | |||||
|(__STM32F4xx_NUCLEO_BSP_VERSION_SUB1 << 16)\ | |||||
|(__STM32F4xx_NUCLEO_BSP_VERSION_SUB2 << 8 )\ | |||||
|(__STM32F4xx_NUCLEO_BSP_VERSION_RC)) | |||||
/** | |||||
* @brief LINK SD Card | |||||
*/ | |||||
#define SD_DUMMY_BYTE 0xFF | |||||
#define SD_NO_RESPONSE_EXPECTED 0x80 | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_Private_Macros STM32F4XX NUCLEO LOW LEVEL Private Macros | |||||
* @{ | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_Private_Variables STM32F4XX NUCLEO LOW LEVEL Private Variables | |||||
* @{ | |||||
*/ | |||||
GPIO_TypeDef* GPIO_PORT[LEDn] = {LED2_GPIO_PORT}; | |||||
const uint16_t GPIO_PIN[LEDn] = {LED2_PIN}; | |||||
GPIO_TypeDef* BUTTON_PORT[BUTTONn] = {KEY_BUTTON_GPIO_PORT}; | |||||
const uint16_t BUTTON_PIN[BUTTONn] = {KEY_BUTTON_PIN}; | |||||
const uint8_t BUTTON_IRQn[BUTTONn] = {KEY_BUTTON_EXTI_IRQn}; | |||||
/** | |||||
* @brief BUS variables | |||||
*/ | |||||
#ifdef ADAFRUIT_TFT_JOY_SD_ID802 | |||||
#ifdef HAL_SPI_MODULE_ENABLED | |||||
uint32_t SpixTimeout = NUCLEO_SPIx_TIMEOUT_MAX; /*<! Value of Timeout when SPI communication fails */ | |||||
static SPI_HandleTypeDef hnucleo_Spi; | |||||
#endif /* HAL_SPI_MODULE_ENABLED */ | |||||
#ifdef HAL_ADC_MODULE_ENABLED | |||||
static ADC_HandleTypeDef hnucleo_Adc; | |||||
/* ADC channel configuration structure declaration */ | |||||
static ADC_ChannelConfTypeDef sConfig; | |||||
#endif /* HAL_ADC_MODULE_ENABLED */ | |||||
#endif /* ADAFRUIT_TFT_JOY_SD_ID802 */ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_Private_FunctionPrototypes STM32F4XX NUCLEO LOW LEVEL Private FunctionPrototypes | |||||
* @{ | |||||
*/ | |||||
#ifdef ADAFRUIT_TFT_JOY_SD_ID802 | |||||
#ifdef HAL_SPI_MODULE_ENABLED | |||||
static void SPIx_Init(void); | |||||
static void SPIx_Write(uint8_t Value); | |||||
static void SPIx_WriteReadData(const uint8_t *DataIn, uint8_t *DataOut, uint16_t DataLegnth); | |||||
static void SPIx_Error(void); | |||||
static void SPIx_MspInit(SPI_HandleTypeDef *hspi); | |||||
/* SD IO functions */ | |||||
void SD_IO_Init(void); | |||||
void SD_IO_CSState(uint8_t state); | |||||
void SD_IO_WriteReadData(const uint8_t *DataIn, uint8_t *DataOut, uint16_t DataLength); | |||||
uint8_t SD_IO_WriteByte(uint8_t Data); | |||||
/* LCD IO functions */ | |||||
void LCD_IO_Init(void); | |||||
void LCD_IO_WriteData(uint8_t Data); | |||||
void LCD_IO_WriteMultipleData(uint8_t *pData, uint32_t Size); | |||||
void LCD_IO_WriteReg(uint8_t LCDReg); | |||||
void LCD_Delay(uint32_t delay); | |||||
#endif /* HAL_SPI_MODULE_ENABLED */ | |||||
#ifdef HAL_ADC_MODULE_ENABLED | |||||
static void ADCx_Init(void); | |||||
static void ADCx_DeInit(void); | |||||
static void ADCx_MspInit(ADC_HandleTypeDef *hadc); | |||||
static void ADCx_MspDeInit(ADC_HandleTypeDef *hadc); | |||||
#endif /* HAL_ADC_MODULE_ENABLED */ | |||||
#endif /* ADAFRUIT_TFT_JOY_SD_ID802 */ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_Private_Functions STM32F4XX NUCLEO LOW LEVEL Private Functions | |||||
* @{ | |||||
*/ | |||||
/** | |||||
* @brief This method returns the STM32F4xx NUCLEO BSP Driver revision | |||||
* @retval version: 0xXYZR (8bits for each decimal, R for RC) | |||||
*/ | |||||
uint32_t BSP_GetVersion(void) | |||||
{ | |||||
return __STM32F4xx_NUCLEO_BSP_VERSION; | |||||
} | |||||
/** | |||||
* @brief Configures LED GPIO. | |||||
* @param Led: Specifies the Led to be configured. | |||||
* This parameter can be one of following parameters: | |||||
* @arg LED2 | |||||
*/ | |||||
void BSP_LED_Init(Led_TypeDef Led) | |||||
{ | |||||
GPIO_InitTypeDef GPIO_InitStruct; | |||||
/* Enable the GPIO_LED Clock */ | |||||
LEDx_GPIO_CLK_ENABLE(Led); | |||||
/* Configure the GPIO_LED pin */ | |||||
GPIO_InitStruct.Pin = GPIO_PIN[Led]; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; | |||||
GPIO_InitStruct.Pull = GPIO_NOPULL; | |||||
GPIO_InitStruct.Speed = GPIO_SPEED_FAST; | |||||
HAL_GPIO_Init(GPIO_PORT[Led], &GPIO_InitStruct); | |||||
HAL_GPIO_WritePin(GPIO_PORT[Led], GPIO_PIN[Led], GPIO_PIN_RESET); | |||||
} | |||||
/** | |||||
* @brief DeInit LEDs. | |||||
* @param Led: LED to be de-init. | |||||
* This parameter can be one of the following values: | |||||
* @arg LED2 | |||||
* @note Led DeInit does not disable the GPIO clock nor disable the Mfx | |||||
*/ | |||||
void BSP_LED_DeInit(Led_TypeDef Led) | |||||
{ | |||||
GPIO_InitTypeDef gpio_init_structure; | |||||
/* Turn off LED */ | |||||
HAL_GPIO_WritePin(GPIO_PORT[Led], GPIO_PIN[Led], GPIO_PIN_RESET); | |||||
/* DeInit the GPIO_LED pin */ | |||||
gpio_init_structure.Pin = GPIO_PIN[Led]; | |||||
HAL_GPIO_DeInit(GPIO_PORT[Led], gpio_init_structure.Pin); | |||||
} | |||||
/** | |||||
* @brief Turns selected LED On. | |||||
* @param Led: Specifies the Led to be set on. | |||||
* This parameter can be one of following parameters: | |||||
* @arg LED2 | |||||
*/ | |||||
void BSP_LED_On(Led_TypeDef Led) | |||||
{ | |||||
HAL_GPIO_WritePin(GPIO_PORT[Led], GPIO_PIN[Led], GPIO_PIN_SET); | |||||
} | |||||
/** | |||||
* @brief Turns selected LED Off. | |||||
* @param Led: Specifies the Led to be set off. | |||||
* This parameter can be one of following parameters: | |||||
* @arg LED2 | |||||
*/ | |||||
void BSP_LED_Off(Led_TypeDef Led) | |||||
{ | |||||
HAL_GPIO_WritePin(GPIO_PORT[Led], GPIO_PIN[Led], GPIO_PIN_RESET); | |||||
} | |||||
/** | |||||
* @brief Toggles the selected LED. | |||||
* @param Led: Specifies the Led to be toggled. | |||||
* This parameter can be one of following parameters: | |||||
* @arg LED2 | |||||
*/ | |||||
void BSP_LED_Toggle(Led_TypeDef Led) | |||||
{ | |||||
HAL_GPIO_TogglePin(GPIO_PORT[Led], GPIO_PIN[Led]); | |||||
} | |||||
/** | |||||
* @brief Configures Button GPIO and EXTI Line. | |||||
* @param Button: Specifies the Button to be configured. | |||||
* This parameter should be: BUTTON_KEY | |||||
* @param ButtonMode: Specifies Button mode. | |||||
* This parameter can be one of following parameters: | |||||
* @arg BUTTON_MODE_GPIO: Button will be used as simple IO | |||||
* @arg BUTTON_MODE_EXTI: Button will be connected to EXTI line with interrupt | |||||
* generation capability | |||||
*/ | |||||
void BSP_PB_Init(Button_TypeDef Button, ButtonMode_TypeDef ButtonMode) | |||||
{ | |||||
GPIO_InitTypeDef GPIO_InitStruct; | |||||
/* Enable the BUTTON Clock */ | |||||
BUTTONx_GPIO_CLK_ENABLE(Button); | |||||
if(ButtonMode == BUTTON_MODE_GPIO) | |||||
{ | |||||
/* Configure Button pin as input */ | |||||
GPIO_InitStruct.Pin = BUTTON_PIN[Button]; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_INPUT; | |||||
GPIO_InitStruct.Pull = GPIO_PULLDOWN; | |||||
GPIO_InitStruct.Speed = GPIO_SPEED_FAST; | |||||
HAL_GPIO_Init(BUTTON_PORT[Button], &GPIO_InitStruct); | |||||
} | |||||
if(ButtonMode == BUTTON_MODE_EXTI) | |||||
{ | |||||
/* Configure Button pin as input with External interrupt */ | |||||
GPIO_InitStruct.Pin = BUTTON_PIN[Button]; | |||||
GPIO_InitStruct.Pull = GPIO_NOPULL; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING; | |||||
HAL_GPIO_Init(BUTTON_PORT[Button], &GPIO_InitStruct); | |||||
/* Enable and set Button EXTI Interrupt to the lowest priority */ | |||||
HAL_NVIC_SetPriority((IRQn_Type)(BUTTON_IRQn[Button]), 0x0F, 0x00); | |||||
HAL_NVIC_EnableIRQ((IRQn_Type)(BUTTON_IRQn[Button])); | |||||
} | |||||
} | |||||
/** | |||||
* @brief Push Button DeInit. | |||||
* @param Button: Button to be configured | |||||
* This parameter should be: BUTTON_KEY | |||||
* @note PB DeInit does not disable the GPIO clock | |||||
*/ | |||||
void BSP_PB_DeInit(Button_TypeDef Button) | |||||
{ | |||||
GPIO_InitTypeDef gpio_init_structure; | |||||
gpio_init_structure.Pin = BUTTON_PIN[Button]; | |||||
HAL_NVIC_DisableIRQ((IRQn_Type)(BUTTON_IRQn[Button])); | |||||
HAL_GPIO_DeInit(BUTTON_PORT[Button], gpio_init_structure.Pin); | |||||
} | |||||
/** | |||||
* @brief Returns the selected Button state. | |||||
* @param Button: Specifies the Button to be checked. | |||||
* This parameter should be: BUTTON_KEY | |||||
* @retval The Button GPIO pin value. | |||||
*/ | |||||
uint32_t BSP_PB_GetState(Button_TypeDef Button) | |||||
{ | |||||
return HAL_GPIO_ReadPin(BUTTON_PORT[Button], BUTTON_PIN[Button]); | |||||
} | |||||
/****************************************************************************** | |||||
BUS OPERATIONS | |||||
*******************************************************************************/ | |||||
#ifdef ADAFRUIT_TFT_JOY_SD_ID802 | |||||
/******************************* SPI ********************************/ | |||||
#ifdef HAL_SPI_MODULE_ENABLED | |||||
/** | |||||
* @brief Initializes SPI MSP. | |||||
*/ | |||||
static void SPIx_MspInit(SPI_HandleTypeDef *hspi) | |||||
{ | |||||
GPIO_InitTypeDef GPIO_InitStruct; | |||||
/*** Configure the GPIOs ***/ | |||||
/* Enable GPIO clock */ | |||||
NUCLEO_SPIx_SCK_GPIO_CLK_ENABLE(); | |||||
NUCLEO_SPIx_MISO_MOSI_GPIO_CLK_ENABLE(); | |||||
/* Configure SPI SCK */ | |||||
GPIO_InitStruct.Pin = NUCLEO_SPIx_SCK_PIN; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; | |||||
GPIO_InitStruct.Pull = GPIO_PULLUP; | |||||
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; | |||||
GPIO_InitStruct.Alternate = NUCLEO_SPIx_SCK_AF; | |||||
HAL_GPIO_Init(NUCLEO_SPIx_SCK_GPIO_PORT, &GPIO_InitStruct); | |||||
/* Configure SPI MISO and MOSI */ | |||||
GPIO_InitStruct.Pin = NUCLEO_SPIx_MOSI_PIN; | |||||
GPIO_InitStruct.Alternate = NUCLEO_SPIx_MISO_MOSI_AF; | |||||
GPIO_InitStruct.Pull = GPIO_PULLDOWN; | |||||
HAL_GPIO_Init(NUCLEO_SPIx_MISO_MOSI_GPIO_PORT, &GPIO_InitStruct); | |||||
GPIO_InitStruct.Pin = NUCLEO_SPIx_MISO_PIN; | |||||
GPIO_InitStruct.Pull = GPIO_PULLDOWN; | |||||
HAL_GPIO_Init(NUCLEO_SPIx_MISO_MOSI_GPIO_PORT, &GPIO_InitStruct); | |||||
/*** Configure the SPI peripheral ***/ | |||||
/* Enable SPI clock */ | |||||
NUCLEO_SPIx_CLK_ENABLE(); | |||||
} | |||||
/** | |||||
* @brief Initializes SPI HAL. | |||||
*/ | |||||
static void SPIx_Init(void) | |||||
{ | |||||
if(HAL_SPI_GetState(&hnucleo_Spi) == HAL_SPI_STATE_RESET) | |||||
{ | |||||
/* SPI Config */ | |||||
hnucleo_Spi.Instance = NUCLEO_SPIx; | |||||
/* SPI baudrate is set to 12,5 MHz maximum (APB1/SPI_BaudRatePrescaler = 100/8 = 12,5 MHz) | |||||
to verify these constraints: | |||||
- ST7735 LCD SPI interface max baudrate is 15MHz for write and 6.66MHz for read | |||||
Since the provided driver doesn't use read capability from LCD, only constraint | |||||
on write baudrate is considered. | |||||
- SD card SPI interface max baudrate is 25MHz for write/read | |||||
- PCLK2 max frequency is 100 MHz | |||||
*/ | |||||
hnucleo_Spi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8; | |||||
hnucleo_Spi.Init.Direction = SPI_DIRECTION_2LINES; | |||||
hnucleo_Spi.Init.CLKPhase = SPI_PHASE_2EDGE; | |||||
hnucleo_Spi.Init.CLKPolarity = SPI_POLARITY_HIGH; | |||||
hnucleo_Spi.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLED; | |||||
hnucleo_Spi.Init.CRCPolynomial = 7; | |||||
hnucleo_Spi.Init.DataSize = SPI_DATASIZE_8BIT; | |||||
hnucleo_Spi.Init.FirstBit = SPI_FIRSTBIT_MSB; | |||||
hnucleo_Spi.Init.NSS = SPI_NSS_SOFT; | |||||
hnucleo_Spi.Init.TIMode = SPI_TIMODE_DISABLED; | |||||
hnucleo_Spi.Init.Mode = SPI_MODE_MASTER; | |||||
SPIx_MspInit(&hnucleo_Spi); | |||||
HAL_SPI_Init(&hnucleo_Spi); | |||||
} | |||||
} | |||||
/** | |||||
* @brief SPI Write a byte to device | |||||
* @param DataIn: value to be written | |||||
* @param DataOut: value to be read | |||||
* @param DataLegnth: length of data | |||||
*/ | |||||
static void SPIx_WriteReadData(const uint8_t *DataIn, uint8_t *DataOut, uint16_t DataLegnth) | |||||
{ | |||||
HAL_StatusTypeDef status = HAL_OK; | |||||
status = HAL_SPI_TransmitReceive(&hnucleo_Spi, (uint8_t*) DataIn, DataOut, DataLegnth, SpixTimeout); | |||||
/* Check the communication status */ | |||||
if(status != HAL_OK) | |||||
{ | |||||
/* Execute user timeout callback */ | |||||
SPIx_Error(); | |||||
} | |||||
} | |||||
/** | |||||
* @brief SPI Write a byte to device. | |||||
* @param Value: value to be written | |||||
*/ | |||||
static void SPIx_Write(uint8_t Value) | |||||
{ | |||||
HAL_StatusTypeDef status = HAL_OK; | |||||
uint8_t data; | |||||
status = HAL_SPI_TransmitReceive(&hnucleo_Spi, (uint8_t*) &Value, &data, 1, SpixTimeout); | |||||
/* Check the communication status */ | |||||
if(status != HAL_OK) | |||||
{ | |||||
/* Execute user timeout callback */ | |||||
SPIx_Error(); | |||||
} | |||||
} | |||||
/** | |||||
* @brief SPI error treatment function. | |||||
*/ | |||||
static void SPIx_Error (void) | |||||
{ | |||||
/* De-initialize the SPI communication BUS */ | |||||
HAL_SPI_DeInit(&hnucleo_Spi); | |||||
/* Re-Initiaize the SPI communication BUS */ | |||||
SPIx_Init(); | |||||
} | |||||
/****************************************************************************** | |||||
LINK OPERATIONS | |||||
*******************************************************************************/ | |||||
/********************************* LINK SD ************************************/ | |||||
/** | |||||
* @brief Initializes the SD Card and put it into StandBy State (Ready for | |||||
* data transfer). | |||||
*/ | |||||
void SD_IO_Init(void) | |||||
{ | |||||
GPIO_InitTypeDef GPIO_InitStruct; | |||||
uint8_t counter; | |||||
/* SD_CS_GPIO Periph clock enable */ | |||||
SD_CS_GPIO_CLK_ENABLE(); | |||||
/* Configure SD_CS_PIN pin: SD Card CS pin */ | |||||
GPIO_InitStruct.Pin = SD_CS_PIN; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; | |||||
GPIO_InitStruct.Pull = GPIO_PULLUP; | |||||
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; | |||||
HAL_GPIO_Init(SD_CS_GPIO_PORT, &GPIO_InitStruct); | |||||
/*------------Put SD in SPI mode--------------*/ | |||||
/* SD SPI Config */ | |||||
SPIx_Init(); | |||||
/* SD chip select high */ | |||||
SD_CS_HIGH(); | |||||
/* Send dummy byte 0xFF, 10 times with CS high */ | |||||
/* Rise CS and MOSI for 80 clocks cycles */ | |||||
for (counter = 0; counter <= 9; counter++) | |||||
{ | |||||
/* Send dummy byte 0xFF */ | |||||
SD_IO_WriteByte(SD_DUMMY_BYTE); | |||||
} | |||||
} | |||||
/** | |||||
* @brief Set the SD_CS pin. | |||||
* @param val: pin value. | |||||
*/ | |||||
void SD_IO_CSState(uint8_t val) | |||||
{ | |||||
if(val == 1) | |||||
{ | |||||
SD_CS_HIGH(); | |||||
} | |||||
else | |||||
{ | |||||
SD_CS_LOW(); | |||||
} | |||||
} | |||||
/** | |||||
* @brief Write a byte on the SD. | |||||
* @param DataIn: value to be written | |||||
* @param DataOut: value to be read | |||||
* @param DataLength: length of data | |||||
*/ | |||||
void SD_IO_WriteReadData(const uint8_t *DataIn, uint8_t *DataOut, uint16_t DataLength) | |||||
{ | |||||
/* Send the byte */ | |||||
SPIx_WriteReadData(DataIn, DataOut, DataLength); | |||||
} | |||||
/** | |||||
* @brief Writes a byte on the SD. | |||||
* @param Data: byte to send. | |||||
*/ | |||||
uint8_t SD_IO_WriteByte(uint8_t Data) | |||||
{ | |||||
uint8_t tmp; | |||||
/* Send the byte */ | |||||
SPIx_WriteReadData(&Data,&tmp,1); | |||||
return tmp; | |||||
} | |||||
/********************************* LINK LCD ***********************************/ | |||||
/** | |||||
* @brief Initializes the LCD. | |||||
*/ | |||||
void LCD_IO_Init(void) | |||||
{ | |||||
GPIO_InitTypeDef GPIO_InitStruct; | |||||
/* LCD_CS_GPIO and LCD_DC_GPIO Periph clock enable */ | |||||
LCD_CS_GPIO_CLK_ENABLE(); | |||||
LCD_DC_GPIO_CLK_ENABLE(); | |||||
/* Configure LCD_CS_PIN pin: LCD Card CS pin */ | |||||
GPIO_InitStruct.Pin = LCD_CS_PIN; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; | |||||
GPIO_InitStruct.Pull = GPIO_NOPULL; | |||||
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; | |||||
HAL_GPIO_Init(LCD_CS_GPIO_PORT, &GPIO_InitStruct); | |||||
/* Configure LCD_DC_PIN pin: LCD Card DC pin */ | |||||
GPIO_InitStruct.Pin = LCD_DC_PIN; | |||||
HAL_GPIO_Init(LCD_DC_GPIO_PORT, &GPIO_InitStruct); | |||||
/* LCD chip select high */ | |||||
LCD_CS_HIGH(); | |||||
/* LCD SPI Config */ | |||||
SPIx_Init(); | |||||
} | |||||
/** | |||||
* @brief Writes command to select the LCD register. | |||||
* @param LCDReg: Address of the selected register. | |||||
*/ | |||||
void LCD_IO_WriteReg(uint8_t LCDReg) | |||||
{ | |||||
/* Reset LCD control line CS */ | |||||
LCD_CS_LOW(); | |||||
/* Set LCD data/command line DC to Low */ | |||||
LCD_DC_LOW(); | |||||
/* Send Command */ | |||||
SPIx_Write(LCDReg); | |||||
/* Deselect : Chip Select high */ | |||||
LCD_CS_HIGH(); | |||||
} | |||||
/** | |||||
* @brief Writes data to select the LCD register. | |||||
* This function must be used after st7735_WriteReg() function | |||||
* @param Data: data to write to the selected register. | |||||
*/ | |||||
void LCD_IO_WriteData(uint8_t Data) | |||||
{ | |||||
/* Reset LCD control line CS */ | |||||
LCD_CS_LOW(); | |||||
/* Set LCD data/command line DC to High */ | |||||
LCD_DC_HIGH(); | |||||
/* Send Data */ | |||||
SPIx_Write(Data); | |||||
/* Deselect : Chip Select high */ | |||||
LCD_CS_HIGH(); | |||||
} | |||||
/** | |||||
* @brief Writes register value. | |||||
* @param pData: Pointer on the register value | |||||
* @param Size: Size of byte to transmit to the register | |||||
*/ | |||||
void LCD_IO_WriteMultipleData(uint8_t *pData, uint32_t Size) | |||||
{ | |||||
uint32_t counter = 0; | |||||
__IO uint32_t data = 0; | |||||
/* Reset LCD control line CS */ | |||||
LCD_CS_LOW(); | |||||
/* Set LCD data/command line DC to High */ | |||||
LCD_DC_HIGH(); | |||||
if (Size == 1) | |||||
{ | |||||
/* Only 1 byte to be sent to LCD - general interface can be used */ | |||||
/* Send Data */ | |||||
SPIx_Write(*pData); | |||||
} | |||||
else | |||||
{ | |||||
/* Several data should be sent in a raw */ | |||||
/* Direct SPI accesses for optimization */ | |||||
for (counter = Size; counter != 0; counter--) | |||||
{ | |||||
while(((hnucleo_Spi.Instance->SR) & SPI_FLAG_TXE) != SPI_FLAG_TXE) | |||||
{ | |||||
} | |||||
/* Need to invert bytes for LCD*/ | |||||
*((__IO uint8_t*)&hnucleo_Spi.Instance->DR) = *(pData+1); | |||||
while(((hnucleo_Spi.Instance->SR) & SPI_FLAG_TXE) != SPI_FLAG_TXE) | |||||
{ | |||||
} | |||||
*((__IO uint8_t*)&hnucleo_Spi.Instance->DR) = *pData; | |||||
counter--; | |||||
pData += 2; | |||||
} | |||||
/* Wait until the bus is ready before releasing Chip select */ | |||||
while(((hnucleo_Spi.Instance->SR) & SPI_FLAG_BSY) != RESET) | |||||
{ | |||||
} | |||||
} | |||||
/* Empty the Rx fifo */ | |||||
data = *(&hnucleo_Spi.Instance->DR); | |||||
UNUSED(data); | |||||
/* Deselect : Chip Select high */ | |||||
LCD_CS_HIGH(); | |||||
} | |||||
/** | |||||
* @brief Wait for loop in ms. | |||||
* @param Delay in ms. | |||||
*/ | |||||
void LCD_Delay(uint32_t Delay) | |||||
{ | |||||
HAL_Delay(Delay); | |||||
} | |||||
#endif /* HAL_SPI_MODULE_ENABLED */ | |||||
/******************************* ADC driver ********************************/ | |||||
#ifdef HAL_ADC_MODULE_ENABLED | |||||
/** | |||||
* @brief Initializes ADC MSP. | |||||
*/ | |||||
static void ADCx_MspInit(ADC_HandleTypeDef *hadc) | |||||
{ | |||||
GPIO_InitTypeDef GPIO_InitStruct; | |||||
/*** Configure the GPIOs ***/ | |||||
/* Enable GPIO clock */ | |||||
NUCLEO_ADCx_GPIO_CLK_ENABLE(); | |||||
/* Configure the selected ADC Channel as analog input */ | |||||
GPIO_InitStruct.Pin = NUCLEO_ADCx_GPIO_PIN ; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; | |||||
GPIO_InitStruct.Pull = GPIO_NOPULL; | |||||
HAL_GPIO_Init(NUCLEO_ADCx_GPIO_PORT, &GPIO_InitStruct); | |||||
/*** Configure the ADC peripheral ***/ | |||||
/* Enable ADC clock */ | |||||
NUCLEO_ADCx_CLK_ENABLE(); | |||||
} | |||||
/** | |||||
* @brief DeInitializes ADC MSP. | |||||
* @note ADC DeInit does not disable the GPIO clock | |||||
*/ | |||||
static void ADCx_MspDeInit(ADC_HandleTypeDef *hadc) | |||||
{ | |||||
GPIO_InitTypeDef GPIO_InitStruct; | |||||
/*** DeInit the ADC peripheral ***/ | |||||
/* Disable ADC clock */ | |||||
NUCLEO_ADCx_CLK_DISABLE(); | |||||
/* Configure the selected ADC Channel as analog input */ | |||||
GPIO_InitStruct.Pin = NUCLEO_ADCx_GPIO_PIN ; | |||||
HAL_GPIO_DeInit(NUCLEO_ADCx_GPIO_PORT, GPIO_InitStruct.Pin); | |||||
/* Disable GPIO clock has to be done by the application*/ | |||||
/* NUCLEO_ADCx_GPIO_CLK_DISABLE(); */ | |||||
} | |||||
/** | |||||
* @brief Initializes ADC HAL. | |||||
*/ | |||||
static void ADCx_Init(void) | |||||
{ | |||||
if(HAL_ADC_GetState(&hnucleo_Adc) == HAL_ADC_STATE_RESET) | |||||
{ | |||||
/* ADC Config */ | |||||
hnucleo_Adc.Instance = NUCLEO_ADCx; | |||||
hnucleo_Adc.Init.ClockPrescaler = ADC_CLOCKPRESCALER_PCLK_DIV4; /* (must not exceed 36MHz) */ | |||||
hnucleo_Adc.Init.Resolution = ADC_RESOLUTION12b; | |||||
hnucleo_Adc.Init.DataAlign = ADC_DATAALIGN_RIGHT; | |||||
hnucleo_Adc.Init.ContinuousConvMode = DISABLE; | |||||
hnucleo_Adc.Init.DiscontinuousConvMode = DISABLE; | |||||
hnucleo_Adc.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; | |||||
hnucleo_Adc.Init.EOCSelection = EOC_SINGLE_CONV; | |||||
hnucleo_Adc.Init.NbrOfConversion = 1; | |||||
hnucleo_Adc.Init.DMAContinuousRequests = DISABLE; | |||||
ADCx_MspInit(&hnucleo_Adc); | |||||
HAL_ADC_Init(&hnucleo_Adc); | |||||
} | |||||
} | |||||
/** | |||||
* @brief Initializes ADC HAL. | |||||
*/ | |||||
static void ADCx_DeInit(void) | |||||
{ | |||||
hnucleo_Adc.Instance = NUCLEO_ADCx; | |||||
HAL_ADC_DeInit(&hnucleo_Adc); | |||||
ADCx_MspDeInit(&hnucleo_Adc); | |||||
} | |||||
/******************************* LINK JOYSTICK ********************************/ | |||||
/** | |||||
* @brief Configures joystick available on adafruit 1.8" TFT shield | |||||
* managed through ADC to detect motion. | |||||
* @retval Joystickstatus (0=> success, 1=> fail) | |||||
*/ | |||||
uint8_t BSP_JOY_Init(void) | |||||
{ | |||||
uint8_t status = HAL_ERROR; | |||||
ADCx_Init(); | |||||
/* Select the ADC Channel to be converted */ | |||||
sConfig.Channel = NUCLEO_ADCx_CHANNEL; | |||||
sConfig.SamplingTime = ADC_SAMPLETIME_3CYCLES; | |||||
sConfig.Rank = 1; | |||||
status = HAL_ADC_ConfigChannel(&hnucleo_Adc, &sConfig); | |||||
/* Return Joystick initialization status */ | |||||
return status; | |||||
} | |||||
/** | |||||
* @brief DeInit joystick GPIOs. | |||||
* @note JOY DeInit does not disable the Mfx, just set the Mfx pins in Off modee. | |||||
*/ | |||||
void BSP_JOY_DeInit(void) | |||||
{ | |||||
ADCx_DeInit(); | |||||
} | |||||
/** | |||||
* @brief Returns the Joystick key pressed. | |||||
* @note To know which Joystick key is pressed we need to detect the voltage | |||||
* level on each key output | |||||
* - None : 3.3 V / 4095 | |||||
* - SEL : 1.055 V / 1308 | |||||
* - DOWN : 0.71 V / 88 | |||||
* - LEFT : 3.0 V / 3720 | |||||
* - RIGHT : 0.595 V / 737 | |||||
* - UP : 1.65 V / 2046 | |||||
* @retval JOYState_TypeDef: Code of the Joystick key pressed. | |||||
*/ | |||||
JOYState_TypeDef BSP_JOY_GetState(void) | |||||
{ | |||||
JOYState_TypeDef state; | |||||
uint16_t keyconvertedvalue = 0; | |||||
/* Start the conversion process */ | |||||
HAL_ADC_Start(&hnucleo_Adc); | |||||
/* Wait for the end of conversion */ | |||||
HAL_ADC_PollForConversion(&hnucleo_Adc, 10); | |||||
/* Check if the continuous conversion of regular channel is finished */ | |||||
if(((HAL_ADC_GetState(&hnucleo_Adc) & HAL_ADC_STATE_EOC_REG) == HAL_ADC_STATE_EOC_REG)) | |||||
{ | |||||
/* Get the converted value of regular channel */ | |||||
keyconvertedvalue = HAL_ADC_GetValue(&hnucleo_Adc); | |||||
} | |||||
if((keyconvertedvalue > 2010) && (keyconvertedvalue < 2090)) | |||||
{ | |||||
state = JOY_UP; | |||||
} | |||||
else if((keyconvertedvalue > 680) && (keyconvertedvalue < 780)) | |||||
{ | |||||
state = JOY_RIGHT; | |||||
} | |||||
else if((keyconvertedvalue > 1270) && (keyconvertedvalue < 1350)) | |||||
{ | |||||
state = JOY_SEL; | |||||
} | |||||
else if((keyconvertedvalue > 50) && (keyconvertedvalue < 130)) | |||||
{ | |||||
state = JOY_DOWN; | |||||
} | |||||
else if((keyconvertedvalue > 3680) && (keyconvertedvalue < 3760)) | |||||
{ | |||||
state = JOY_LEFT; | |||||
} | |||||
else | |||||
{ | |||||
state = JOY_NONE; | |||||
} | |||||
/* Loop while a key is pressed */ | |||||
if(state != JOY_NONE) | |||||
{ | |||||
keyconvertedvalue = HAL_ADC_GetValue(&hnucleo_Adc); | |||||
} | |||||
/* Return the code of the Joystick key pressed */ | |||||
return state; | |||||
} | |||||
#endif /* HAL_ADC_MODULE_ENABLED */ | |||||
#endif /* ADAFRUIT_TFT_JOY_SD_ID802 */ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
/** | |||||
****************************************************************************** | |||||
* @file x_nucleo_ihm05a1_stm32f4xx.c | |||||
* @author IPC Rennes | |||||
* @version V1.5.0 | |||||
* @date June 1st, 2018 | |||||
* @brief BSP driver for x-nucleo-ihm05a1 Nucleo extension board | |||||
* (based on L6208) | |||||
****************************************************************************** | |||||
* @attention | |||||
* | |||||
* <h2><center>© 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 "x_nucleo_ihm05a1_stm32f4xx.h" | |||||
#include "motor.h" | |||||
/** @addtogroup BSP | |||||
* @{ | |||||
*/ | |||||
/** @defgroup X_NUCLEO_IHM05A1_STM32F4XX NUCLEO IHM05A1 STM32F4XX | |||||
* @{ | |||||
*/ | |||||
/* Private constants ---------------------------------------------------------*/ | |||||
/** @defgroup IHM05A1_Private_Constants IHM05A1 Private Constants | |||||
* @{ | |||||
*/ | |||||
/// Tick frequency (Hz) | |||||
#define TIMER_TICK_FREQUENCY (10000) | |||||
/// Tick Timer Prescaler | |||||
#define TIMER_TICK_PRESCALER (64) | |||||
/// MCU wait time after power bridges are enabled | |||||
#define BRIDGE_TURN_ON_DELAY (10) | |||||
/** | |||||
* @} | |||||
*/ | |||||
/* Private variables ---------------------------------------------------------*/ | |||||
/** @defgroup IHM05A1_Board_Private_Variables IHM05A1 Board Private Variables | |||||
* @{ | |||||
*/ | |||||
/// L6208 timer handler for VREFA PWM | |||||
TIM_HandleTypeDef hTimVrefaPwm; | |||||
/// L6208 timer handler for VREFB PWM | |||||
TIM_HandleTypeDef hTimVrefbPwm; | |||||
/// L6208 timer handler for the tick | |||||
TIM_HandleTypeDef hTimTick; | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup IHM05A1_Board_Private_Function_Prototypes IHM05A1 Board Private Function Prototypes | |||||
* @{ | |||||
*/ | |||||
void L6208_Board_CLOCK_PIN_Reset(void); //Reset the clock pin | |||||
void L6208_Board_CLOCK_PIN_Set(void); //Set the clock pin | |||||
void L6208_Board_CONTROL_PIN_Reset(void); //Reset the control pin | |||||
void L6208_Board_CONTROL_PIN_Set(void); //Set the control pin | |||||
void L6208_Board_Delay(uint32_t delay); //Delay of the requested number of milliseconds | |||||
void L6208_Board_DIR_PIN_Reset(void); //Reset the dir pin | |||||
void L6208_Board_DIR_PIN_Set(void); //Set the dir pin | |||||
void L6208_Board_Disable(void); //Disable the power bridges (leave the output bridges HiZ) | |||||
void L6208_Board_DisableIrq(void); //Disable Irq | |||||
void L6208_Board_Enable(void); //Enable the power bridges (leave the output bridges HiZ) | |||||
void L6208_Board_EnableIrq(void); //Disable Irq | |||||
uint32_t L6208_Board_FLAG_PIN_GetState(void); //Returns the EN pin state | |||||
void L6208_Board_GpioInit(void); //Initialise GPIOs used for L6208 | |||||
void L6208_Board_HALF_FULL_PIN_Reset(void); //Reset the half full pin | |||||
void L6208_Board_HALF_FULL_PIN_Set(void); //Set the half full pin | |||||
bool L6208_Board_VrefPwmInit(uint8_t bridgeId, uint32_t pwmFreq); //Initialize the VREFA or VREFB PWM | |||||
void L6208_Board_ReleaseReset(void); //Release the reset pin | |||||
void L6208_Board_Reset(void); //Reset the reset pin | |||||
uint32_t L6208_Board_TickGetFreq(void); //Get the tick frequency in Hz | |||||
void L6208_Board_TickInit(void); //Initialize the tick | |||||
void L6208_Board_TickStart(void); //Start the timer for the tick by using the set tick frequency | |||||
void L6208_Board_TickStop(void); //Stop the timer for the tick | |||||
bool L6208_Board_VrefPwmFreqCheck(uint32_t newFreq); //Check that the new VREFA and VREFB PWM frequency is nor too low nor too high | |||||
uint32_t L6208_Board_VrefPwmGetPeriod(void); //Get current VREF PWM period duration | |||||
bool L6208_Board_VrefPwmSetDutyCycle(uint8_t bridgeId,\ | |||||
uint16_t value,\ | |||||
bool valueIsPwmDutyCycle); //Set duty cycle of VREFA or VREFB PWM | |||||
bool L6208_Board_VrefPwmStart(uint8_t bridgeId,\ | |||||
uint32_t pwmFreq); //Start the timer for the VREFA or VREFB PWM | |||||
bool L6208_Board_VrefPwmStop(uint8_t bridgeId); //Stop the timer for the VREFA or VREFB PWM | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** @defgroup IHM05A1_Board_Private_Functions IHM05A1 Board Private Functions | |||||
* @{ | |||||
*/ | |||||
/******************************************************//** | |||||
* @brief This function provides an accurate delay in milliseconds | |||||
* @param[in] delay time length in milliseconds | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_Delay(uint32_t delay) | |||||
{ | |||||
HAL_Delay(delay); | |||||
} | |||||
/******************************************************//** | |||||
* @brief This function disable the interruptions | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_DisableIrq(void) | |||||
{ | |||||
//__disable_irq(); | |||||
} | |||||
/******************************************************//** | |||||
* @brief This function enable the interruptions | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_EnableIrq(void) | |||||
{ | |||||
//__enable_irq(); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Start the L6208 library | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_GpioInit(void) | |||||
{ | |||||
GPIO_InitTypeDef GPIO_InitStruct; | |||||
/* GPIO Ports Clock Enable */ | |||||
__GPIOC_CLK_ENABLE(); | |||||
__GPIOA_CLK_ENABLE(); | |||||
__GPIOB_CLK_ENABLE(); | |||||
/* Configure L6208 - EN pin -------------------------------*/ | |||||
/* When this pin is set low, it is configured just before as */ | |||||
/* GPIO_MODE_OUTPUT_PP with GPIO_NOPULL */ | |||||
/* When this pin is set high, it is just after configured for OCD and OVT */ | |||||
/* as GPIO_MODE_IT_FALLING with GPIO_PULLUP */ | |||||
L6208_Board_Disable(); | |||||
/* Set Priority of External Line Interrupt used for the OCD OVT interrupt*/ | |||||
HAL_NVIC_SetPriority(FLAG_EXTI_LINE_IRQn, BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PRIORITY, 0); | |||||
/* Enable the External Line Interrupt used for the OCD OVT interrupt*/ | |||||
HAL_NVIC_EnableIRQ(FLAG_EXTI_LINE_IRQn); | |||||
/* Configure L6208 - CW/CCW pin ----------------------------*/ | |||||
GPIO_InitStruct.Pin = BSP_MOTOR_CONTROL_BOARD_DIR_PIN; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; | |||||
GPIO_InitStruct.Pull = GPIO_NOPULL; | |||||
GPIO_InitStruct.Speed = GPIO_SPEED_MEDIUM; | |||||
HAL_GPIO_Init(BSP_MOTOR_CONTROL_BOARD_DIR_PORT, &GPIO_InitStruct); | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_DIR_PORT, BSP_MOTOR_CONTROL_BOARD_DIR_PIN, GPIO_PIN_RESET); | |||||
/* Configure L6208 - HALF/FULL pin -------------------------------------------*/ | |||||
GPIO_InitStruct.Pin = BSP_MOTOR_CONTROL_BOARD_HALF_FULL_PIN; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; | |||||
GPIO_InitStruct.Pull = GPIO_NOPULL; | |||||
GPIO_InitStruct.Speed = GPIO_SPEED_MEDIUM; | |||||
HAL_GPIO_Init(BSP_MOTOR_CONTROL_BOARD_HALF_FULL_PORT, &GPIO_InitStruct); | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_HALF_FULL_PORT, BSP_MOTOR_CONTROL_BOARD_HALF_FULL_PIN, GPIO_PIN_RESET); | |||||
/* Configure L6208 - CONTROL pin -------------------------------------------*/ | |||||
GPIO_InitStruct.Pin = BSP_MOTOR_CONTROL_BOARD_CONTROL_PIN; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; | |||||
GPIO_InitStruct.Pull = GPIO_NOPULL; | |||||
GPIO_InitStruct.Speed = GPIO_SPEED_MEDIUM; | |||||
HAL_GPIO_Init(BSP_MOTOR_CONTROL_BOARD_CONTROL_PORT, &GPIO_InitStruct); | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_CONTROL_PORT, BSP_MOTOR_CONTROL_BOARD_CONTROL_PIN, GPIO_PIN_RESET); | |||||
/* Configure L6208 - CLOCK pin -------------------------------------------*/ | |||||
GPIO_InitStruct.Pin = BSP_MOTOR_CONTROL_BOARD_CLOCK_PIN; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; | |||||
GPIO_InitStruct.Pull = GPIO_NOPULL; | |||||
GPIO_InitStruct.Speed = GPIO_SPEED_MEDIUM; | |||||
HAL_GPIO_Init(BSP_MOTOR_CONTROL_BOARD_CLOCK_PORT, &GPIO_InitStruct); | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_CLOCK_PORT, BSP_MOTOR_CONTROL_BOARD_CLOCK_PIN, GPIO_PIN_RESET); | |||||
/* Configure L6208 - STBY/RESET pin -------------------------------------*/ | |||||
GPIO_InitStruct.Pin = BSP_MOTOR_CONTROL_BOARD_RESET_PIN; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; | |||||
GPIO_InitStruct.Pull = GPIO_NOPULL; | |||||
GPIO_InitStruct.Speed = GPIO_SPEED_MEDIUM; | |||||
HAL_GPIO_Init(BSP_MOTOR_CONTROL_BOARD_RESET_PORT, &GPIO_InitStruct); | |||||
L6208_Board_ReleaseReset(); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Initialize the tick | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_TickInit(void) | |||||
{ | |||||
static TIM_OC_InitTypeDef sConfigOC; | |||||
static TIM_MasterConfigTypeDef sMasterConfig; | |||||
static TIM_ClockConfigTypeDef sClockSourceConfig; | |||||
hTimTick.Instance = BSP_MOTOR_CONTROL_BOARD_TIMER_TICK; | |||||
hTimTick.Init.Period = (HAL_RCC_GetSysClockFreq() / (TIMER_TICK_PRESCALER * TIMER_TICK_FREQUENCY)) - 1; | |||||
hTimTick.Init.Prescaler = TIMER_TICK_PRESCALER -1; | |||||
hTimTick.Init.ClockDivision = 0; | |||||
hTimTick.Init.CounterMode = TIM_COUNTERMODE_UP; | |||||
HAL_TIM_PWM_Init(&hTimTick); | |||||
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; | |||||
HAL_TIM_ConfigClockSource(&hTimTick, &sClockSourceConfig); | |||||
sConfigOC.OCMode = TIM_OCMODE_PWM1; | |||||
sConfigOC.Pulse = 0; | |||||
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; | |||||
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; | |||||
HAL_TIM_PWM_ConfigChannel(&hTimTick, &sConfigOC, BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_TICK); | |||||
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; | |||||
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; | |||||
HAL_TIMEx_MasterConfigSynchronization(&hTimTick, &sMasterConfig); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Start the timer for the tick by using the set tick frequency | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_TickStart(void) | |||||
{ | |||||
uint32_t period = (HAL_RCC_GetSysClockFreq() / (TIMER_TICK_PRESCALER * TIMER_TICK_FREQUENCY)) - 1; | |||||
__HAL_TIM_SetAutoreload(&hTimTick, period); | |||||
__HAL_TIM_SetCompare(&hTimTick, BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_TICK, period >> 1); | |||||
HAL_TIM_PWM_Start_IT(&hTimTick, BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_TICK); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Stop the timer for the tick | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_TickStop(void) | |||||
{ | |||||
HAL_TIM_PWM_Stop_IT(&hTimTick, BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_TICK); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Get the tick timer frequency in Hz | |||||
* @retval The tick timer frequency in Hz | |||||
**********************************************************/ | |||||
uint32_t L6208_Board_TickGetFreq(void) | |||||
{ | |||||
return TIMER_TICK_FREQUENCY; | |||||
} | |||||
/******************************************************//** | |||||
* @brief Check that the frequency for the VREFA and VREFB PWM | |||||
* is high enough | |||||
* @param[in] newFreq frequency in Hz of the PWM used to generate | |||||
* the reference voltage for the bridge | |||||
* @retval FALSE if frequency is too low, else TRUE | |||||
**********************************************************/ | |||||
bool L6208_Board_VrefPwmFreqCheck(uint32_t newFreq) | |||||
{ | |||||
if (newFreq<=(HAL_RCC_GetSysClockFreq()>>16)) | |||||
{ | |||||
return FALSE; | |||||
} | |||||
else | |||||
{ | |||||
return TRUE; | |||||
} | |||||
} | |||||
/******************************************************//** | |||||
* @brief Initialize the VREFA or VREFB PWM | |||||
* @param[in] bridgeId | |||||
* 0 for BRIDGE_A | |||||
* 1 for BRIDGE_B | |||||
* @param[in] pwmFreq frequency in Hz of the PWM used to generate the reference | |||||
* voltage for the bridge | |||||
* @retval FALSE if wrong timer handle is used, else TRUE | |||||
* @note None | |||||
**********************************************************/ | |||||
bool L6208_Board_VrefPwmInit(uint8_t bridgeId, uint32_t pwmFreq) | |||||
{ | |||||
static TIM_OC_InitTypeDef sConfigOC; | |||||
static TIM_MasterConfigTypeDef sMasterConfig; | |||||
static TIM_ClockConfigTypeDef sClockSourceConfig; | |||||
TIM_HandleTypeDef *pHTim = NULL; | |||||
uint32_t channel; | |||||
if (bridgeId == 0) | |||||
{ | |||||
pHTim = &hTimVrefaPwm; | |||||
pHTim->Instance = BSP_MOTOR_CONTROL_BOARD_TIMER_VREFA_PWM; | |||||
pHTim->Init.Prescaler = 0; | |||||
pHTim->Init.Period = (HAL_RCC_GetSysClockFreq() / pwmFreq) - 1; | |||||
channel = BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_VREFA_PWM; | |||||
} | |||||
else if (bridgeId == 1) | |||||
{ | |||||
pHTim = &hTimVrefbPwm; | |||||
pHTim->Instance = BSP_MOTOR_CONTROL_BOARD_TIMER_VREFB_PWM; | |||||
pHTim->Init.Prescaler = 0; | |||||
pHTim->Init.Period = (HAL_RCC_GetSysClockFreq() / pwmFreq) - 1; | |||||
channel = BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_VREFB_PWM; | |||||
} | |||||
else | |||||
{ | |||||
return FALSE; | |||||
} | |||||
pHTim->Init.CounterMode = TIM_COUNTERMODE_UP; | |||||
pHTim->Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; | |||||
HAL_TIM_PWM_Init(pHTim); | |||||
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; | |||||
HAL_TIM_ConfigClockSource(pHTim, &sClockSourceConfig); | |||||
sConfigOC.OCMode = TIM_OCMODE_PWM1; | |||||
sConfigOC.Pulse = 0; | |||||
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; | |||||
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; | |||||
HAL_TIM_PWM_ConfigChannel(pHTim, &sConfigOC, channel); | |||||
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; | |||||
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; | |||||
HAL_TIMEx_MasterConfigSynchronization(pHTim, &sMasterConfig); | |||||
return TRUE; | |||||
} | |||||
/******************************************************//** | |||||
* @brief Set duty cycle of VREFA or VREFB PWM | |||||
* @param[in] bridgeId | |||||
* 0 for BRIDGE_A | |||||
* 1 for BRIDGE_B | |||||
* @param[in] value pulse length or PWM duty cycle: 0 - 100 % | |||||
* @param[in] valueIsPwmDutyCycle must be TRUE if value is a PWM duty cycle | |||||
* @retval FALSE if wrong timer handle is used, else TRUE | |||||
**********************************************************/ | |||||
bool L6208_Board_VrefPwmSetDutyCycle(uint8_t bridgeId, uint16_t value, bool valueIsPwmDutyCycle) | |||||
{ | |||||
TIM_HandleTypeDef *pHTim = NULL; | |||||
uint32_t channel; | |||||
if (bridgeId == 0) | |||||
{ | |||||
pHTim = &hTimVrefaPwm; | |||||
channel = BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_VREFA_PWM; | |||||
} | |||||
else if (bridgeId == 1) | |||||
{ | |||||
pHTim = &hTimVrefbPwm; | |||||
channel = BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_VREFB_PWM; | |||||
} | |||||
else | |||||
{ | |||||
return 0; | |||||
} | |||||
// PWM or OC Channel pulse length | |||||
if(valueIsPwmDutyCycle) | |||||
{ | |||||
if (value > 100) value = 100; | |||||
value = (uint16_t)(((uint32_t)pHTim->Init.Period * (uint32_t)value) / 100); | |||||
} | |||||
__HAL_TIM_SetCompare(pHTim, channel, value); | |||||
return 1; | |||||
} | |||||
/******************************************************//** | |||||
* @brief Start the timer for the VREFA or VREFB PWM | |||||
* @param[in] bridgeId | |||||
* 0 for BRIDGE_A | |||||
* 1 for BRIDGE_B | |||||
* @param[in] pwmFreq frequency in Hz of the PWM used to generate the reference | |||||
* voltage for the bridge | |||||
* @retval FALSE if wrong timer handle is used, else TRUE | |||||
**********************************************************/ | |||||
bool L6208_Board_VrefPwmStart(uint8_t bridgeId, uint32_t pwmFreq) | |||||
{ | |||||
TIM_HandleTypeDef *pHTim = NULL; | |||||
uint32_t period; | |||||
uint32_t channel; | |||||
if (bridgeId == 0) | |||||
{ | |||||
pHTim = &hTimVrefaPwm; | |||||
period = (HAL_RCC_GetSysClockFreq() / pwmFreq) - 1; | |||||
channel = BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_VREFA_PWM; | |||||
} | |||||
else if (bridgeId == 1) | |||||
{ | |||||
pHTim = &hTimVrefbPwm; | |||||
period = (HAL_RCC_GetSysClockFreq() / pwmFreq) - 1; | |||||
channel = BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_VREFB_PWM; | |||||
} | |||||
else | |||||
{ | |||||
return FALSE; | |||||
} | |||||
__HAL_TIM_SetAutoreload(pHTim, period); | |||||
HAL_TIM_PWM_Start(pHTim, channel); | |||||
return TRUE; | |||||
} | |||||
/******************************************************//** | |||||
* @brief Stop the VREFA or VREFB PWM | |||||
* @param[in] bridgeId | |||||
* 0 for BRIDGE_A | |||||
* 1 for BRIDGE_B | |||||
* @retval None | |||||
**********************************************************/ | |||||
bool L6208_Board_VrefPwmStop(uint8_t bridgeId) | |||||
{ | |||||
TIM_HandleTypeDef *pHTim = NULL; | |||||
uint32_t channel; | |||||
if (bridgeId == 0) | |||||
{ | |||||
pHTim = &hTimVrefaPwm; | |||||
channel = BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_VREFA_PWM; | |||||
} | |||||
else if (bridgeId == 1) | |||||
{ | |||||
pHTim = &hTimVrefbPwm; | |||||
channel = BSP_MOTOR_CONTROL_BOARD_CHAN_TIMER_VREFB_PWM; | |||||
} | |||||
else | |||||
{ | |||||
return FALSE; | |||||
} | |||||
HAL_TIM_PWM_Stop(pHTim, channel); | |||||
return TRUE; | |||||
} | |||||
/******************************************************//** | |||||
* @brief Get current VREF PWM period duration | |||||
* @retval the current VREF PWM period duration | |||||
* @note hTimVrefbPwm.Init.Period is the same as hTimVrefaPwm.Init.Period | |||||
**********************************************************/ | |||||
uint32_t L6208_Board_VrefPwmGetPeriod(void) | |||||
{ | |||||
return ((uint32_t)hTimVrefaPwm.Init.Period); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Releases the L6208 reset (pin set to High) of all devices | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_ReleaseReset(void) | |||||
{ | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_RESET_PORT, BSP_MOTOR_CONTROL_BOARD_RESET_PIN, GPIO_PIN_SET); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Resets the L6208 (reset pin set to low) of all devices | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_Reset(void) | |||||
{ | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_RESET_PORT, BSP_MOTOR_CONTROL_BOARD_RESET_PIN, GPIO_PIN_RESET); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Set the L6208 CONTROL pin | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_CONTROL_PIN_Set(void) | |||||
{ | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_CONTROL_PORT, BSP_MOTOR_CONTROL_BOARD_CONTROL_PIN, GPIO_PIN_SET); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Reset the L6208 CONTROL pin | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_CONTROL_PIN_Reset(void) | |||||
{ | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_CONTROL_PORT, BSP_MOTOR_CONTROL_BOARD_CONTROL_PIN, GPIO_PIN_RESET); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Set the L6208 CLOCK pin | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_CLOCK_PIN_Set(void) | |||||
{ | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_CLOCK_PORT, BSP_MOTOR_CONTROL_BOARD_CLOCK_PIN, GPIO_PIN_SET); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Reset the L6208 CLOCK pin | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_CLOCK_PIN_Reset(void) | |||||
{ | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_CLOCK_PORT, BSP_MOTOR_CONTROL_BOARD_CLOCK_PIN, GPIO_PIN_RESET); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Set the L6208 HALF_FULL pin | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_HALF_FULL_PIN_Set(void) | |||||
{ | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_HALF_FULL_PORT, BSP_MOTOR_CONTROL_BOARD_HALF_FULL_PIN, GPIO_PIN_SET); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Reset the L6208 HALF_FULL pin | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_HALF_FULL_PIN_Reset(void) | |||||
{ | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_HALF_FULL_PORT, BSP_MOTOR_CONTROL_BOARD_HALF_FULL_PIN, GPIO_PIN_RESET); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Set the L6208 DIR pin | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_DIR_PIN_Set(void) | |||||
{ | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_DIR_PORT, BSP_MOTOR_CONTROL_BOARD_DIR_PIN, GPIO_PIN_SET); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Reset the L6208 DIR pin | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_DIR_PIN_Reset(void) | |||||
{ | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_DIR_PORT, BSP_MOTOR_CONTROL_BOARD_DIR_PIN, GPIO_PIN_RESET); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Returns the FLAG pin state. | |||||
* @retval The FLAG pin value. | |||||
**********************************************************/ | |||||
uint32_t L6208_Board_FLAG_PIN_GetState(void) | |||||
{ | |||||
return HAL_GPIO_ReadPin(BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PORT, BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PIN); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Disable the power bridges (leave the output bridges HiZ) | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_Disable(void) | |||||
{ | |||||
GPIO_InitTypeDef GPIO_InitStruct; | |||||
/* Configure the GPIO connected to EN pin as an output */ | |||||
GPIO_InitStruct.Pin = BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PIN; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; | |||||
GPIO_InitStruct.Pull = GPIO_NOPULL; | |||||
GPIO_InitStruct.Speed = GPIO_SPEED_MEDIUM; | |||||
HAL_GPIO_Init(BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PORT, &GPIO_InitStruct); | |||||
__disable_irq(); | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PORT, BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PIN, GPIO_PIN_RESET); | |||||
__HAL_GPIO_EXTI_CLEAR_IT(BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PIN); | |||||
__enable_irq(); | |||||
} | |||||
/******************************************************//** | |||||
* @brief Enable the power bridges (leave the output bridges HiZ) | |||||
* @retval None | |||||
**********************************************************/ | |||||
void L6208_Board_Enable(void) | |||||
{ | |||||
GPIO_InitTypeDef GPIO_InitStruct; | |||||
HAL_GPIO_WritePin(BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PORT, BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PIN, GPIO_PIN_SET); | |||||
HAL_Delay(BRIDGE_TURN_ON_DELAY); | |||||
/* Configure the GPIO connected to EN pin to take interrupt */ | |||||
GPIO_InitStruct.Pin = BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PIN; | |||||
GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING; | |||||
GPIO_InitStruct.Pull = GPIO_PULLUP; | |||||
GPIO_InitStruct.Speed = GPIO_SPEED_MEDIUM; | |||||
HAL_GPIO_Init(BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PORT, &GPIO_InitStruct); | |||||
__HAL_GPIO_EXTI_CLEAR_IT(BSP_MOTOR_CONTROL_BOARD_EN_AND_FLAG_PIN); | |||||
HAL_NVIC_ClearPendingIRQ(FLAG_EXTI_LINE_IRQn); | |||||
HAL_NVIC_EnableIRQ(FLAG_EXTI_LINE_IRQn); | |||||
} | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/** | |||||
* @} | |||||
*/ | |||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |