diff --git a/RTC/Core/Inc/l6208.h b/RTC/Core/Inc/l6208.h
new file mode 100644
index 0000000..c602b03
--- /dev/null
+++ b/RTC/Core/Inc/l6208.h
@@ -0,0 +1,383 @@
+/******************************************************//**
+ * @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
+ *
+ *
© COPYRIGHT(c) 2016 STMicroelectronics
+ *
+ * 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****/
diff --git a/RTC/Core/Inc/l6208_target_config.h b/RTC/Core/Inc/l6208_target_config.h
new file mode 100644
index 0000000..e2f9c17
--- /dev/null
+++ b/RTC/Core/Inc/l6208_target_config.h
@@ -0,0 +1,120 @@
+/******************************************************//**
+ * @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
+ *
+ * © COPYRIGHT(c) 2016 STMicroelectronics
+ *
+ * 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****/
diff --git a/RTC/Core/Inc/motor.h b/RTC/Core/Inc/motor.h
new file mode 100644
index 0000000..bf37d4c
--- /dev/null
+++ b/RTC/Core/Inc/motor.h
@@ -0,0 +1,441 @@
+/**
+ ******************************************************************************
+ * @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
+ *
+ * © COPYRIGHT(c) 2016 STMicroelectronics
+ *
+ * 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
+
+/** @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****/
diff --git a/RTC/Core/Inc/stm32f4xx_nucleo.h b/RTC/Core/Inc/stm32f4xx_nucleo.h
new file mode 100644
index 0000000..1fc66d0
--- /dev/null
+++ b/RTC/Core/Inc/stm32f4xx_nucleo.h
@@ -0,0 +1,302 @@
+/**
+ ******************************************************************************
+ * @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
+ *
+ * © COPYRIGHT(c) 2017 STMicroelectronics
+ *
+ * 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****/
diff --git a/RTC/Core/Inc/x_nucleo_ihm05a1_stm32f4xx.h b/RTC/Core/Inc/x_nucleo_ihm05a1_stm32f4xx.h
new file mode 100644
index 0000000..0c5a163
--- /dev/null
+++ b/RTC/Core/Inc/x_nucleo_ihm05a1_stm32f4xx.h
@@ -0,0 +1,209 @@
+/**
+ ******************************************************************************
+ * @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
+ *
+ * © COPYRIGHT(c) 2018 STMicroelectronics
+ *
+ * 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****/
diff --git a/RTC/Core/Inc/x_nucleo_ihmxx.h b/RTC/Core/Inc/x_nucleo_ihmxx.h
new file mode 100644
index 0000000..cb1e0bc
--- /dev/null
+++ b/RTC/Core/Inc/x_nucleo_ihmxx.h
@@ -0,0 +1,241 @@
+/**
+ ******************************************************************************
+ * @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
+ *
+ * © COPYRIGHT(c) 2018 STMicroelectronics
+ *
+ * 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****/
diff --git a/RTC/Core/Src/l6208.c b/RTC/Core/Src/l6208.c
new file mode 100644
index 0000000..f41f524
--- /dev/null
+++ b/RTC/Core/Src/l6208.c
@@ -0,0 +1,2183 @@
+/**
+ ******************************************************************************
+ * @file l6208.c
+ * @author IPC Rennes
+ * @version V1.5.0
+ * @date June 1st, 2018
+ * @brief L6208 product related routines
+ * @note (C) COPYRIGHT 2016 STMicroelectronics
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2016 STMicroelectronics
+ *
+ * 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.
+ *
+ ******************************************************************************
+ */
+
+#include "l6208.h"
+#include "string.h"
+
+/** @addtogroup BSP
+ * @{
+ */
+
+/** @addtogroup L6208
+ * @{
+ */
+
+/* Private constants ---------------------------------------------------------*/
+
+/** @addtogroup L6208_Private_Constants
+ * @{
+ */
+
+/// The maximum number of devices
+#define MAX_NUMBER_OF_DEVICES (1)
+
+/// Bridge A
+#define BRIDGE_A (0)
+/// Bridge B
+#define BRIDGE_B (1)
+
+/// Bitmaps for system flags
+#define EN_A_set 0x00000001 ///< EN_A pin status
+#define HiZstop 0x00000002 ///< motor has to be left in HiZ after stopping
+#define busy 0x00000004 ///< stepper position command executing flag
+#define running 0x00000008 ///< running motor flag
+#define velocitymode 0x00000010 ///< velocity controlled stepper motor
+#define positionmode 0x00000020 ///< position controlled stepper motor
+#define fullstep 0x00000040 ///< full step mode controlled
+#define halfstep 0x00000080 ///< half step mode controlled
+#define microstep 0x00000100 ///< micro step mode controlled
+#define forward 0x00000200 ///< forward running motor
+#define dir2change 0x00000400 ///< direction has to be changed while the motor is running
+#define fastdecaymode 0x00000800 ///< decay mode is fast
+#define wavestep 0x00001000 ///< wave step mode controlled
+
+/**
+ * @}
+ */
+
+/* Private variables ---------------------------------------------------------*/
+
+/** @addtogroup L6208_Private_Variables
+ * @{
+ */
+
+/// Function pointer to flag interrupt call back
+void (*flagInterruptCallback)(void);
+/// Function pointer to error handler call back
+void (*errorHandlerCallback)(uint16_t);
+static volatile bool isrFlag = FALSE;
+static uint16_t l6208DriverInstance = 0;
+
+/// L6208 Device Paramaters structure
+deviceParams_t devicePrm;
+
+/// Exponent used to scale the sine function for the RefMicroTable
+#define L6208_SINE_WAVEFORM_POWER_OF_TWO_MAX_VALUE (15)
+
+/// RefMicroTable values are 2^L6208_SINE_WAVEFORM_POWER_OF_TWO_MAX_VALUE*|sin(n/16*PI/2)|
+/// where n is the index in the table
+const uint16_t RefMicroTable[L6208_USTEPS_PER_QUARTER_PERIOD*3] =
+{
+ 0,3212,6393,9512,12540,15447,18205,20788,23170,25330,27246,28899,30274,31357,32138,32610,
+ 32768,32610,32138,31357,30274,28899,27246,25330,23170,20788,18205,15447,12540,9512,6393,3212,
+ 0,3212,6393,9512,12540,15447,18205,20788,23170,25330,27246,28899,30274,31357,32138,32610
+};
+
+/// microstepping PWM period and torque scaled waveform samples array
+uint16_t updatedMicroTable[L6208_USTEPS_PER_QUARTER_PERIOD+1];
+/// waveform microstepping PWM period sample arrays for VREFA wave
+uint16_t microTable1[L6208_USTEPS_PER_QUARTER_PERIOD*3+1];
+/// waveform microstepping PWM period sample array for VREFB wave, 90 deg shifted
+uint16_t *pMicroTable2 = &(microTable1[16]);
+
+/**
+ * @}
+ */
+
+/* Private function prototypes -----------------------------------------------*/
+
+/** @addtogroup L6208_Private_functions
+ * @{
+ */
+void L6208_ClearSysFlag(uint32_t mask);
+uint32_t L6208_ComputeNbAccOrDecSteps(uint16_t accOrDecRate);
+uint16_t L6208_ConvertAcceDecelRateValue(uint16_t newAccOrDecRate);
+void L6208_DoAccel(void);
+void L6208_DoDecel(void);
+void L6208_DoRun(void);
+uint8_t L6208_GetMicrostepSample2Scale(void);
+void L6208_Indexmodeinit(void);
+bool L6208_IsSysFlag(uint32_t mask);
+void L6208_ResetSteps(void);
+uint32_t L6208_ScaleWaveformSample(uint8_t sampleIndex);
+void L6208_ScaleWaveformTable(void);
+void L6208_SetDeviceParamsToGivenValues(l6208_Init_t* pInitDevicePrm);
+void L6208_SetDeviceParamsToPredefinedValues(void);
+void L6208_SetMicrostepSample2Scale(uint8_t value);
+void L6208_SetMicrostepSample2Update(uint8_t value);
+void L6208_SetMotionState(motorState_t newMotionState);
+bool L6208_SetSpeed(uint16_t newSpeed, uint32_t volatile *pSpeed);
+void L6208_SetSysFlag(uint32_t mask);
+bool L6208_StartMovement(void);
+void L6208_UpdateScanWaveformTable(void);
+void L6208_UstepWaveformHandling(void);
+bool L6208_VectorCalc(uint8_t newTorque);
+/**
+ * @}
+ */
+
+/** @defgroup L6208_Exported_Variables L6208 Exported Variables
+ * @{
+ */
+
+/// L6208 motor driver functions pointer structure
+motorDrv_t l6208Drv =
+{
+ L6208_Init, //void (*Init)(void*);
+ L6208_ReadId, //uint16_t (*ReadID)(void);
+ L6208_AttachErrorHandler, //void (*AttachErrorHandler)(void (*callback)(uint16_t));
+ L6208_AttachFlagInterrupt, //void (*AttachFlagInterrupt)(void (*callback)(void));
+ 0, //void (*AttachBusyInterrupt)(void (*callback)(void));
+ L6208_FlagInterruptHandler, //void (*FlagInterruptHandler)(void);
+ L6208_GetAcceleration, //uint16_t (*GetAcceleration)(uint8_t);
+ L6208_GetCurrentSpeed, //uint16_t (*GetCurrentSpeed)(uint8_t);
+ L6208_GetDeceleration, //uint16_t (*GetDeceleration)(uint8_t);
+ L6208_GetMotionState, //motorState_t(*GetDeviceState)(uint8_t);
+ L6208_GetFwVersion, //uint32_t (*GetFwVersion)(void);
+ L6208_GetMark, //int32_t (*GetMark)(uint8_t);
+ L6208_GetMaxSpeed, //uint16_t (*GetMaxSpeed)(uint8_t);
+ L6208_GetMinSpeed, //uint16_t (*GetMinSpeed)(uint8_t);
+ L6208_GetPosition, //int32_t (*GetPosition)(uint8_t);
+ L6208_GoHome, //void (*GoHome)(uint8_t);
+ L6208_GoMark, //void (*GoMark)(uint8_t);
+ L6208_GoTo, //void (*GoTo)(uint8_t, int32_t);
+ L6208_HardStop, //void (*HardStop)(uint8_t);
+ L6208_Move, //void (*Move)(uint8_t, motorDir_t, uint32_t );
+ 0, //void (*ResetAllDevices)(void);
+ L6208_Run, //void (*Run)(uint8_t, motorDir_t);
+ L6208_SetAcceleration, //bool(*SetAcceleration)(uint8_t ,uint16_t );
+ L6208_SetDeceleration, //bool(*SetDeceleration)(uint8_t , uint16_t );
+ L6208_SetHome, //void (*SetHome)(uint8_t, int32_t);
+ L6208_SetMark, //void (*SetMark)(uint8_t, int32_t);
+ L6208_SetMaxSpeed, //bool (*SetMaxSpeed)(uint8_t, uint16_t );
+ L6208_SetMinSpeed, //bool (*SetMinSpeed)(uint8_t, uint16_t );
+ L6208_SoftStop, //bool (*SoftStop)(uint8_t);
+ L6208_TickHandler, //void (*StepClockHandler)(uint8_t deviceId);
+ L6208_WaitWhileActive, //void (*WaitWhileActive)(uint8_t);
+ L6208_Disable, //void (*CmdDisable)(uint8_t);
+ L6208_Enable, //void (*CmdEnable)(uint8_t);
+ 0, //uint32_t (*CmdGetParam)(uint8_t, uint32_t);
+ 0, //uint16_t (*CmdGetStatus)(uint8_t);
+ 0, //void (*CmdNop)(uint8_t);
+ 0, //void (*CmdSetParam)(uint8_t, uint32_t, uint32_t);
+ 0, //uint16_t (*ReadStatusRegister)(uint8_t);
+ L6208_ReleaseReset, //void (*ReleaseReset)(uint8_t);
+ L6208_Reset, //void (*Reset)(uint8_t);
+ L6208_SetStepMode, //bool (*SelectStepMode)(uint8_t deviceId, motorStepMode_t);
+ L6208_SetDirection, //void (*SetDirection)(uint8_t, motorDir_t);
+ L6208_GoToDir, //void (*CmdGoToDir)(uint8_t, motorDir_t, int32_t);
+ 0, //uint8_t (*CheckBusyHw)(void);
+ L6208_CheckStatusHw, //uint8_t (*CheckStatusHw)(void);
+ 0, //void (*CmdGoUntil)(uint8_t, motorAction_t, motorDir_t, uint32_t);
+ 0, //void (*CmdHardHiZ)(uint8_t);
+ 0, //void (*CmdReleaseSw)(uint8_t, motorAction_t, motorDir_t);
+ 0, //void (*CmdResetDevice)(uint8_t);
+ 0, //void (*CmdResetPos)(uint8_t);
+ 0, //void (*CmdRun)(uint8_t, motorDir_t, uint32_t);
+ 0, //void (*CmdSoftHiZ)(uint8_t);
+ 0, //void (*CmdStepClock)(uint8_t, motorDir_t);
+ 0, //void (*FetchAndClearAllStatus)(void);
+ 0, //uint16_t (*GetFetchedStatus)(uint8_t);
+ 0, //uint8_t (*GetNbDevices)(void);
+ 0, //bool (*IsDeviceBusy)(uint8_t);
+ 0, //void (*SendQueuedCommands)(void);
+ 0, //void (*QueueCommands)(uint8_t, uint8_t, int32_t);
+ 0, //void (*WaitForAllDevicesNotBusy)(void);
+ L6208_ErrorHandler, //void (*ErrorHandler)(uint16_t);
+ 0, //void (*BusyInterruptHandler)(void);
+ 0, //void (*CmdSoftStop)(uint8_t);
+ 0, //void (*StartStepClock)(uint16_t);
+ 0, //void (*StopStepClock)(void);
+ 0, //void (*SetDualFullBridgeConfig)(uint8_t);
+ L6208_VrefPwmGetFreq, //uint32_t (*GetBridgeInputPwmFreq)(uint8_t);
+ L6208_VrefPwmSetFreq, //void (*SetBridgeInputPwmFreq)(uint8_t, uint32_t);
+ L6208_SetStopMode, //void (*SetStopMode)(uint8_t, motorStopMode_t);
+ L6208_GetStopMode, //motorStopMode_t (*GetStopMode)(uint8_t);
+ L6208_SetDecayMode, //void (*SetDecayMode)(uint8_t, motorDecayMode_t);
+ L6208_GetDecayMode, //motorDecayMode_t (*GetDecayMode)(uint8_t);
+ L6208_GetStepMode, //motorStepMode_t (*GetStepMode)(uint8_t);
+ L6208_GetDirection, //motorDir_t (*GetDirection)(uint8_t);
+ 0, //void (*ExitDeviceFromReset)(uint8_t);
+ L6208_SetTorque, //void (*SetTorque)(uint8_t, motorTorqueMode_t, uint8_t);
+ L6208_GetTorque, //uint8_t (*GetTorque)(uint8_t, motorTorqueMode_t);
+ 0, //void (*SetRefFreq)(uint8_t, uint32_t);
+ 0, //uint32_t (*GetRefFreq)(uint8_t);
+ 0, //void (*SetRefDc)(uint8_t, uint8_t);
+ 0, //uint8_t (*GetRefDc)(uint8_t);
+ L6208_SetNbDevices, //bool (*SetNbDevices)(uint8_t);
+ 0, //bool (*SetAnalogValue)(uint8_t, uint32_t, float);
+ 0 //float (*GetAnalogValue)(uint8_t, uint32_t);
+};
+
+/**
+ * @}
+ */
+
+/** @defgroup L6208_library_Functions L6208 library Functions
+ * @{
+ */
+
+/******************************************************//**
+ * @brief Return motor handle (pointer to the L6208 motor driver structure)
+ * @retval Pointer to the motorDrv_t structure
+ **********************************************************/
+motorDrv_t* L6208_GetMotorHandle(void)
+{
+ return (&l6208Drv);
+}
+
+/******************************************************//**
+ * @brief Start the L6208 library
+ * @param[in] pInit pointer to the initialization data
+ * @retval None
+ **********************************************************/
+void L6208_Init(void* pInit)
+{
+
+ l6208DriverInstance++;
+
+ /* Initialise the GPIOs */
+ L6208_Board_GpioInit();
+
+ if (pInit == NULL)
+ {
+ /* Set context variables to the predefined values from l6208_target_config.h */
+ /* Set GPIO according to these values */
+ L6208_SetDeviceParamsToPredefinedValues();
+ }
+ else
+ {
+ L6208_SetDeviceParamsToGivenValues((l6208_Init_t*) pInit);
+ }
+
+ /* Initialise the PWMs */
+ L6208_Board_VrefPwmInit(BRIDGE_A, devicePrm.vrefPwmFreq);
+ L6208_Board_VrefPwmInit(BRIDGE_B, devicePrm.vrefPwmFreq);
+
+ /* Initialise the tick */
+ L6208_Board_TickInit();
+
+ /* Reset L6208 */
+ L6208_ResetDevice();
+
+ /* Align motor mechanical position to driver position */
+ L6208_Board_VrefPwmStart(BRIDGE_A, devicePrm.vrefPwmFreq);
+ L6208_Board_VrefPwmStart(BRIDGE_B, devicePrm.vrefPwmFreq);
+ L6208_Enable(0);
+ }
+
+/******************************************************//**
+ * @brief Read id
+ * @retval Id of the l6208 Driver Instance
+ **********************************************************/
+uint16_t L6208_ReadId(void)
+ {
+ return(l6208DriverInstance);
+ }
+
+/******************************************************//**
+ * @brief Attaches a user callback to the error Handler.
+ * The call back will be then called each time the library
+ * detects an error
+ * @param[in] callback Name of the callback to attach
+ * to the error Hanlder
+ * @retval None
+ **********************************************************/
+void L6208_AttachErrorHandler(void (*callback)(uint16_t error))
+ {
+ errorHandlerCallback = (void (*)(uint16_t error)) callback;
+}
+
+/******************************************************//**
+ * @brief Attach a user callback to the flag Interrupt
+ * The call back will be then called each time the EN
+ * pin will be pulled down due to the occurrence of
+ * OCD or OVT
+ * @param[in] callback Name of the callback to attach
+ * to the Flag Interrupt
+ * @retval None
+ **********************************************************/
+void L6208_AttachFlagInterrupt(void (*callback)(void))
+{
+ flagInterruptCallback = (void (*)())callback;
+}
+
+/******************************************************//**
+ * @brief Check if L6208 has a fault by reading EN pin position.
+ * @retval One if L6208 has EN pin down, otherwise zero
+ **********************************************************/
+uint8_t L6208_CheckStatusHw(void)
+{
+ if(!L6208_Board_FLAG_PIN_GetState())
+ {
+ return 0x01;
+ }
+ else
+ {
+ return 0x00;
+ }
+}
+
+/******************************************************//**
+ * @brief Disable the power bridges (leave the output bridges HiZ)
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void L6208_Disable(uint8_t deviceId)
+ {
+ L6208_Board_Disable();
+ L6208_ClearSysFlag(EN_A_set);
+}
+
+/******************************************************//**
+ * @brief Error handler which calls the user callback (if defined)
+ * @param[in] error Number of the error
+ * @retval None
+ **********************************************************/
+void L6208_ErrorHandler(uint16_t error)
+ {
+ if (errorHandlerCallback != 0)
+ {
+ errorHandlerCallback(error);
+ }
+ else
+ {
+ while(1)
+ {
+ /* Infinite loop */
+ }
+ }
+ }
+
+/******************************************************//**
+ * @brief Enable the power bridges
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void L6208_Enable(uint8_t deviceId)
+ {
+ L6208_Board_Enable();
+ L6208_SetSysFlag(EN_A_set);
+ }
+
+/******************************************************//**
+ * @brief Handler of the flag interrupt which calls the user callback (if defined)
+ * @retval None
+ **********************************************************/
+void L6208_FlagInterruptHandler(void)
+ {
+ if (flagInterruptCallback != 0)
+ {
+ /* Set isr flag */
+ isrFlag = TRUE;
+
+ flagInterruptCallback();
+
+ /* Reset isr flag */
+ isrFlag = FALSE;
+ }
+ }
+
+/******************************************************//**
+ * @brief Get the stepper acceleration rate
+ * in step/s^2 for full, half and wave modes
+ * in microsteps/s^2 for microstep modes
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval the stepper acceleration rate in step/s^2 or microstep/s^2
+ * @note
+ **********************************************************/
+uint16_t L6208_GetAcceleration(uint8_t deviceId)
+ {
+ return devicePrm.accelerationSps2;
+ }
+
+/******************************************************//**
+ * @brief Get the current speed
+ * in step/s for full, half and wave modes
+ * in microsteps/s for microstep modes
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval return the current speed in step/s or microstep/s
+ * @note
+ **********************************************************/
+uint16_t L6208_GetCurrentSpeed(uint8_t deviceId)
+ {
+ uint64_t tmp64 = (uint64_t) devicePrm.speedSpt * L6208_Board_TickGetFreq();
+
+ devicePrm.speedSps = (uint16_t)(tmp64 >> 23);
+ if (devicePrm.speedSps & 0x1)
+ {
+ devicePrm.speedSps = (devicePrm.speedSps >> 1) + 1;
+ }
+ else
+ {
+ devicePrm.speedSps = devicePrm.speedSps >> 1;
+ }
+ return devicePrm.speedSps;
+ }
+
+/******************************************************//**
+ * @brief Get the motor decay mode
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval decay mode
+ **********************************************************/
+motorDecayMode_t L6208_GetDecayMode(uint8_t deviceId)
+ {
+ if (L6208_IsSysFlag(fastdecaymode)) return (FAST_DECAY);
+ else return (SLOW_DECAY);
+ }
+
+/******************************************************//**
+ * @brief Get the stepper deceleration rate
+ * in step/s^2 for full, half and wave modes
+ * in microsteps/s^2 for microstep modes
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval the stepper deceleration rate in step/s^2 or microstep/s^2
+ * @note
+ **********************************************************/
+uint16_t L6208_GetDeceleration(uint8_t deviceId)
+ {
+ return devicePrm.decelerationSps2;
+ }
+
+/******************************************************//**
+ * @brief Get the motor current direction
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval direction
+ **********************************************************/
+motorDir_t L6208_GetDirection(uint8_t deviceId)
+ {
+ if (L6208_IsSysFlag(forward))
+ {
+ return FORWARD;
+ }
+ else
+ {
+ return BACKWARD;
+ }
+ }
+
+/******************************************************//**
+ * @brief Return the FW version.
+ * @retval FW version
+ **********************************************************/
+uint32_t L6208_GetFwVersion(void)
+ {
+ return L6208_FW_VERSION;
+ }
+
+/******************************************************//**
+ * @brief Get the mark position (32b signed)
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval mark position
+ **********************************************************/
+int32_t L6208_GetMark(uint8_t deviceId)
+{
+ return devicePrm.markPos;
+ }
+
+/******************************************************//**
+ * @brief Get the max speed
+ * in step/s for full, half and wave modes
+ * in microsteps/s for microstep modes
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval return the max speed in step/s or microstep/s
+ * @note
+ **********************************************************/
+uint16_t L6208_GetMaxSpeed(uint8_t deviceId)
+ {
+ return devicePrm.maxSpeedSps;
+ }
+
+/******************************************************//**
+ * @brief Get the min speed
+ * in step/s for full, half and wave modes
+ * in microsteps/s for microstep modes
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval return the min speed in step/s or microstep/s
+ * @note
+ **********************************************************/
+uint16_t L6208_GetMinSpeed(uint8_t deviceId)
+{
+ return devicePrm.minSpeedSps;
+ }
+
+/******************************************************//**
+ * @brief Get the stepper state machine index
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval one of the stepper state machine index in the motorState_t enum
+ **********************************************************/
+motorState_t L6208_GetMotionState(uint8_t deviceId)
+ {
+ // gets the new stepper state machine index
+ return devicePrm.motionState;
+}
+
+/******************************************************//**
+ * @brief Get the current position (32b signed)
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval current absoulte position
+ **********************************************************/
+int32_t L6208_GetPosition(uint8_t deviceId)
+ {
+ return devicePrm.absolutePos;
+ }
+
+/******************************************************//**
+ * @brief Get the motor step mode
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval step mode
+ **********************************************************/
+motorStepMode_t L6208_GetStepMode(uint8_t deviceId)
+ {
+ return devicePrm.stepMode;
+ }
+
+/******************************************************//**
+ * @brief Get the selected stop mode
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval the selected stop mode
+ **********************************************************/
+motorStopMode_t L6208_GetStopMode(uint8_t deviceId)
+ {
+ if (L6208_IsSysFlag(HiZstop) == FALSE)
+ {
+ return (HOLD_MODE);
+ }
+ else
+ {
+ return (HIZ_MODE);
+ }
+}
+
+/******************************************************//**
+ * @brief Get the torque of the specified device
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] torqueMode torque mode
+ * @retval the torqueValue in % (from 0 to 100)
+ * @note
+ **********************************************************/
+uint8_t L6208_GetTorque(uint8_t deviceId, motorTorqueMode_t torqueMode)
+{
+ uint8_t torqueValue = 0;
+ switch(torqueMode)
+ {
+ case ACC_TORQUE:
+ torqueValue = devicePrm.accelTorque;
+ break;
+ case DEC_TORQUE:
+ torqueValue = devicePrm.decelTorque;
+ break;
+ case RUN_TORQUE:
+ torqueValue = devicePrm.runTorque;
+ break;
+ case HOLD_TORQUE:
+ torqueValue = devicePrm.holdTorque;
+ break;
+ case CURRENT_TORQUE:
+ torqueValue = devicePrm.curTorqueScaler;
+ break;
+ default:
+ break;
+ }
+ return torqueValue;
+}
+
+/******************************************************//**
+ * @brief Go to the home position
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void L6208_GoHome(uint8_t deviceId)
+{
+ L6208_GoTo(deviceId, 0);
+}
+
+/******************************************************//**
+ * @brief Go to the Mark position
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void L6208_GoMark(uint8_t deviceId)
+{
+ L6208_GoTo(deviceId, devicePrm.markPos);
+}
+
+/******************************************************//**
+ * @brief Move the motor to the absolute position using the shortest path
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] abs_pos 32 bit signed value position
+ * @retval None
+ * @note The position is at the resolution corresponding to the
+ * selected step mode.
+ * STEP_MODE_FULL or STEP_MODE_WAVE : step
+ * STEP_MODE_HALF : 1/2 step
+ * STEP_MODE_1_4 : 1/4 step
+ * STEP_MODE_1_8 : 1/8 step
+ * STEP_MODE_1_16 : 1/16 step
+ **********************************************************/
+void L6208_GoTo(uint8_t deviceId, int32_t abs_pos)
+{
+ uint32_t steps = 0;
+
+ if(L6208_IsSysFlag(running))
+ {
+ L6208_HardStop(0);
+ }
+
+ if (abs_pos > devicePrm.absolutePos)
+ {
+ steps = abs_pos - devicePrm.absolutePos;
+ if (steps < (L6208_POSITION_RANGE>>1))
+ {
+ L6208_Move(0, FORWARD, steps);
+}
+ else
+ {
+ L6208_Move(0, BACKWARD, (L6208_POSITION_RANGE - steps));
+ }
+}
+ else
+{
+ steps = devicePrm.absolutePos - abs_pos;
+ if (steps < (L6208_POSITION_RANGE>>1))
+ {
+ L6208_Move(0, BACKWARD, steps);
+ }
+ else
+ {
+ L6208_Move(0, FORWARD, (L6208_POSITION_RANGE - steps));
+ }
+}
+}
+
+/******************************************************//**
+ * @brief Move the motor to the absolute position
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] direction FORWARD or BACKWARD
+ * @param[in] abs_pos 32 bit signed value position
+ * @retval None
+ * @note The position is at the resolution corresponding to the
+ * selected step mode.
+ * STEP_MODE_FULL or STEP_MODE_WAVE : step
+ * STEP_MODE_HALF : 1/2 step
+ * STEP_MODE_1_4 : 1/4 step
+ * STEP_MODE_1_8 : 1/8 step
+ * STEP_MODE_1_16 : 1/16 step
+ **********************************************************/
+void L6208_GoToDir(uint8_t deviceId, motorDir_t direction, int32_t abs_pos)
+{
+ uint32_t steps = 0;
+
+ if(L6208_IsSysFlag(running))
+ {
+ L6208_HardStop(0);
+ }
+
+ if (direction != BACKWARD)
+ {
+ if (abs_pos > devicePrm.absolutePos)
+ {
+ steps = abs_pos - devicePrm.absolutePos;
+ }
+ else
+ {
+ steps = L6208_POSITION_RANGE + (abs_pos - devicePrm.absolutePos);
+ }
+}
+ else
+{
+ if (abs_pos > devicePrm.absolutePos)
+ {
+ steps = L6208_POSITION_RANGE + (devicePrm.absolutePos - abs_pos);
+}
+ else
+{
+ steps = devicePrm.absolutePos - abs_pos;
+ }
+ }
+ L6208_Move(0, direction, steps);
+}
+
+/******************************************************//**
+ * @brief Immediately stop the motor and disables the power bridges
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void L6208_HardHiZ(uint8_t deviceId)
+{
+ /* Disables power stage */
+ L6208_Disable(0);
+
+ /* Sets inactive state */
+ L6208_SetMotionState(INACTIVE);
+
+ /* Clears the running motor and the position */
+ L6208_ClearSysFlag(running);
+
+ /* Disables PWMs */
+ L6208_Board_VrefPwmStop(BRIDGE_A);
+ L6208_Board_VrefPwmStop(BRIDGE_B);
+
+ /* Disables tick timer */
+ L6208_Board_TickStop();
+}
+
+/******************************************************//**
+ * @brief Immediately stop the motor and keeps holding torque
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void L6208_HardStop(uint8_t deviceId)
+{
+ /* Sets inactive state */
+ L6208_SetMotionState(INACTIVE);
+
+ /* Clears the running motor and the position */
+ L6208_ClearSysFlag(running);
+ L6208_VectorCalc(devicePrm.holdTorque);
+
+ /* Disables tick timer */
+ L6208_Board_TickStop();
+}
+
+/******************************************************//**
+ * @brief Move the motor by the specified number of steps
+ * in the specified direction
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] direction FORWARD or BACKWARD
+ * @param[in] stepCount 32 bit unsigned step count
+ * @retval None
+ * @note The step count resolution is corresponding to the
+ * selected step mode.
+ * STEP_MODE_FULL or STEP_MODE_WAVE : step
+ * STEP_MODE_HALF : 1/2 step
+ * STEP_MODE_1_4 : 1/4 step
+ * STEP_MODE_1_8 : 1/8 step
+ * STEP_MODE_1_16 : 1/16 step
+ **********************************************************/
+void L6208_Move(uint8_t deviceId, motorDir_t direction, uint32_t stepCount)
+{
+ if(L6208_IsSysFlag(running))
+ {
+ L6208_HardStop(0);
+ }
+
+ /* clear the velocity driving mode flag */
+ L6208_ClearSysFlag(velocitymode);
+
+ /* Set the indexing driving mode flag */
+ /* and the user command executing flag */
+ L6208_SetSysFlag(positionmode);
+
+ /* store relative number of steps to move */
+ devicePrm.positionTarget = stepCount;
+
+ L6208_SetDirection(0, direction);
+
+ /* Motor activation */
+ L6208_StartMovement();
+}
+
+/******************************************************//**
+ * @brief Release the L6208 reset (Reset pin set to high level)
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void L6208_ReleaseReset(uint8_t deviceId)
+ {
+ L6208_Board_ReleaseReset();
+}
+
+/******************************************************//**
+ * @brief Reset the L6208 (Reset pin set to low level)
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void L6208_Reset(uint8_t deviceId)
+ {
+ L6208_Board_Reset();
+ }
+
+/******************************************************//**
+ * @brief Reset the device with current step mode, resets current speed,
+ * positions and microstep variables.
+ * @retval None
+ **********************************************************/
+void L6208_ResetDevice(void)
+ {
+ L6208_SetStepMode(0, L6208_GetStepMode(0));
+}
+
+/******************************************************//**
+ * @brief Run the motor in the specified direction
+ * according to the speed profile defined by the minimum speed,
+ * maximum speed, and acceleration parameters.
+ * The device accelerates from the minimum speed up to the maximum
+ * speed by using the device acceleration.
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] direction FORWARD or BACKWARD
+ * @retval None
+ **********************************************************/
+void L6208_Run(uint8_t deviceId, motorDir_t direction)
+{
+ if(L6208_IsSysFlag(running))
+ {
+ L6208_HardStop(0);
+ }
+ L6208_SetDirection(0, direction);
+ /* Clear the indexing driving mode flag */
+ L6208_ClearSysFlag(positionmode);
+ /* Set the velocity driving mode flag */
+ L6208_SetSysFlag(velocitymode);
+ /* Motor activation */
+ L6208_StartMovement();
+}
+
+/******************************************************//**
+ * @brief Set the stepper acceleration rate
+ * in step/s^2 and step/tick^2 for full, half and wave modes
+ * in microsteps/s^2 and microsteps/tick^2 for microstep modes
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] newAcc new acceleration rate in step/s^2 or microstep/s^2
+ * @retval TRUE
+ * @note
+ **********************************************************/
+bool L6208_SetAcceleration(uint8_t deviceId, uint16_t newAcc)
+{
+ uint16_t newAccSpt2 = L6208_ConvertAcceDecelRateValue(newAcc);
+ if (newAccSpt2)
+ {
+ devicePrm.accelerationSps2 = newAcc;
+ devicePrm.accelerationSpt2 = newAccSpt2;
+ }
+ else
+ {
+ L6208_ErrorHandler(L6208_ERROR_SET_ACCELERATION);
+ }
+ return TRUE;
+}
+
+/******************************************************//**
+ * @brief Select the motor decay mode
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] decayMode (SLOW_DECAY or FAST_DECAY)
+ * @retval None
+ **********************************************************/
+void L6208_SetDecayMode(uint8_t deviceId, motorDecayMode_t decayMode)
+{
+ if ((decayMode & L6208_FAST_DECAY_MODE_MASK) == L6208_FAST_DECAY_MODE_MASK)
+ {
+ L6208_Board_CONTROL_PIN_Set();
+ L6208_SetSysFlag(fastdecaymode);
+ }
+ else
+ {
+ L6208_Board_CONTROL_PIN_Reset();
+ L6208_ClearSysFlag(fastdecaymode);
+ }
+}
+
+/******************************************************//**
+ * @brief Set the stepper deceleration rate
+ * in step/s^2 and step/tick^2 for full, half and wave modes
+ * in microsteps/s^2 and microsteps/tick^2 for microstep modes
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] newDec new deceleration rate in step/s^2 or microstep/s^2
+ * @retval TRUE
+ * @note
+ **********************************************************/
+bool L6208_SetDeceleration(uint8_t deviceId, uint16_t newDec)
+{
+ uint16_t newDecSpt2 = L6208_ConvertAcceDecelRateValue(newDec);
+ if (newDecSpt2)
+ {
+ devicePrm.decelerationSps2 = newDec;
+ devicePrm.decelerationSpt2 = newDecSpt2;
+ }
+ else
+ {
+ L6208_ErrorHandler(L6208_ERROR_SET_DECELERATION);
+ }
+ return TRUE;
+}
+
+/******************************************************//**
+ * @brief Specify the direction
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] dir FORWARD or BACKWARD
+ * @note In velocity mode a direction change forces the device to stop and
+ * then run in the new direction. In position mode, if the device is
+ * running, a direction change will generate an error.
+ * @retval None
+ **********************************************************/
+void L6208_SetDirection(uint8_t deviceId, motorDir_t dir)
+{
+ L6208_ClearSysFlag(dir2change);
+ if (dir == FORWARD)
+ {
+ if (!L6208_IsSysFlag(forward))
+ {
+ if (L6208_IsSysFlag(running))
+ {
+ /* motor is running */
+ if (L6208_IsSysFlag(positionmode))
+ {
+ L6208_ErrorHandler(L6208_ERROR_SET_DIRECTION);
+ }
+ else
+ {
+ /* set the rotation direction to change flag */
+ L6208_SetSysFlag(dir2change);
+ }
+ }
+ else /* the motor is stopped, cw direction selected */
+ {
+ L6208_SetSysFlag(forward);
+ L6208_Board_DIR_PIN_Set();
+ }
+ }
+ }
+ else
+ {
+ if (L6208_IsSysFlag(forward))
+ {
+ if (L6208_IsSysFlag(running))
+ {
+ /* motor is running */
+ if (L6208_IsSysFlag(positionmode))
+ {
+ L6208_ErrorHandler(L6208_ERROR_SET_DIRECTION);
+ }
+ else
+ {
+ /* set the rotation direction to change flag */
+ L6208_SetSysFlag(dir2change);
+ }
+ }
+ else /* the motor is stopped, ccw direction selected */
+ {
+ L6208_ClearSysFlag(forward);
+ L6208_Board_DIR_PIN_Reset();
+ }
+ }
+ }
+ if(L6208_IsSysFlag(dir2change))
+ {
+ L6208_VectorCalc(devicePrm.decelTorque);
+ L6208_SetMotionState(DECELERATINGTOSTOP);
+ }
+}
+
+/******************************************************//**
+ * @brief Set home position
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] homePos new home position
+ * @retval None
+ **********************************************************/
+void L6208_SetHome(uint8_t deviceId, int32_t homePos)
+{
+ if (!L6208_IsSysFlag(running))
+ {
+ devicePrm.absolutePos -= homePos;
+ }
+ else
+ {
+ L6208_ErrorHandler(L6208_ERROR_SET_HOME);
+ }
+}
+
+/******************************************************//**
+ * @brief Set mark position
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] markPos new mark position
+ * @retval None
+ **********************************************************/
+void L6208_SetMark(uint8_t deviceId, int32_t markPos)
+{
+ devicePrm.markPos = markPos;
+}
+
+/******************************************************//**
+ * @brief Set the user selected maximum speed
+ * in step/s and step/tick for full, half and wave modes
+ * in microsteps/s and microsteps/tick for microstep modes
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] newSpeed speed value (step/s or microstep/s)
+ * @retval TRUE
+ * @note One microstep is 1/16 step
+ **********************************************************/
+bool L6208_SetMaxSpeed(uint8_t deviceId, uint16_t newSpeed)
+{
+ if (L6208_SetSpeed(newSpeed, &devicePrm.maxSpeedSpt))
+ {
+ devicePrm.maxSpeedSps = newSpeed;
+ }
+ else
+ {
+ L6208_ErrorHandler(L6208_ERROR_SET_MAX_SPEED);
+ }
+ return TRUE;
+}
+
+/******************************************************//**
+ * @brief Set the user selected minimum speed
+ * in step/s and step/tick for full, half and wave modes
+ * in microsteps/s and microsteps/tick for microstep modes
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] newSpeed speed value (step/s or microstep/s)
+ * @retval TRUE
+ * @note One microstep is 1/16 step
+ **********************************************************/
+bool L6208_SetMinSpeed(uint8_t deviceId, uint16_t newSpeed)
+{
+ if (L6208_SetSpeed(newSpeed, &devicePrm.minSpeedSpt))
+ {
+ devicePrm.minSpeedSps = newSpeed;
+ }
+ else
+ {
+ L6208_ErrorHandler(L6208_ERROR_SET_MIN_SPEED);
+ }
+ return TRUE;
+}
+
+/******************************************************//**
+ * @brief Sets the number of devices to be used
+ * @param[in] nbDevices (from 1 to MAX_NUMBER_OF_DEVICES)
+ * @retval TRUE if successfull, FALSE if failure, attempt to set a number of
+ * devices greater than MAX_NUMBER_OF_DEVICES
+ **********************************************************/
+bool L6208_SetNbDevices(uint8_t nbDevices)
+{
+ if (nbDevices <= MAX_NUMBER_OF_DEVICES)
+ {
+ return TRUE;
+ }
+ else
+ {
+ return FALSE;
+ }
+}
+
+/******************************************************//**
+ * @brief Set the step mode
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] stepMode
+ * @retval true if the command is successfully executed, else false
+ * @note Every time the step mode is changed, the step state machine is reset
+ **********************************************************/
+bool L6208_SetStepMode(uint8_t deviceId, motorStepMode_t stepMode)
+{
+ devicePrm.stepMode = stepMode;
+ L6208_ClearSysFlag(fullstep | halfstep | microstep | wavestep);
+ switch (stepMode)
+ {
+ case STEP_MODE_HALF:
+ /* Set the Half/Full pin low and Reset and the set the Half/Full pin high*/
+ L6208_Board_HALF_FULL_PIN_Reset();
+ L6208_Board_Reset();
+ L6208_Board_HALF_FULL_PIN_Set();
+ /* Set system flag */
+ L6208_SetSysFlag(halfstep);
+ break;
+ case STEP_MODE_FULL:
+ /* Set the Half/Full pin low and Reset */
+ L6208_Board_HALF_FULL_PIN_Reset();
+ L6208_Board_Reset();
+ /* Set system flag */
+ L6208_SetSysFlag(fullstep);
+ break;
+ case STEP_MODE_WAVE:
+ /* Set the Half/Full pin low and Reset and the set the Half/Full pin high*/
+ L6208_Board_CLOCK_PIN_Reset();
+ L6208_Board_HALF_FULL_PIN_Reset();
+ L6208_Board_Reset();
+ L6208_Board_CLOCK_PIN_Set();
+ L6208_Board_HALF_FULL_PIN_Set();
+ L6208_Board_Delay(2);
+ L6208_Board_CLOCK_PIN_Reset();
+ L6208_Board_Delay(2);
+ L6208_Board_HALF_FULL_PIN_Reset();
+ /* Set system flag */
+ L6208_SetSysFlag(wavestep);
+ break;
+ case STEP_MODE_1_4:
+ /* Set the Half/Full pin low and Reset */
+ L6208_Board_HALF_FULL_PIN_Reset();
+ L6208_Board_Reset();
+ /* Set system flag */
+ L6208_SetSysFlag(microstep);
+ devicePrm.uStepInc = 4;
+ break;
+ case STEP_MODE_1_8:
+ /* Set the Half/Full pin low and Reset */
+ L6208_Board_HALF_FULL_PIN_Reset();
+ L6208_Board_Reset();
+ /* Set system flag */
+ L6208_SetSysFlag(microstep);
+ devicePrm.uStepInc = 2;
+ break;
+ case STEP_MODE_1_16:
+ /* Set the Half/Full pin low and Reset */
+ L6208_Board_HALF_FULL_PIN_Reset();
+ L6208_Board_Reset();
+ /* Set system flag */
+ L6208_SetSysFlag(microstep);
+ devicePrm.uStepInc = 1;
+ break;
+ default:
+ return FALSE;
+ }
+ L6208_Board_Delay(2);
+ L6208_Board_ReleaseReset();
+ L6208_ResetSteps();
+ return TRUE;
+}
+
+/******************************************************//**
+ * @brief Select the mode to stop the motor. When the motor
+ * is stopped, if autoHiZ is TRUE, the power bridges are disabled
+ * if autoHiZ is FALSE, the power bridges are kept enabled.
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] stopMode HOLD_MODE to let power bridge enabled
+ * @retval None
+ **********************************************************/
+void L6208_SetStopMode(uint8_t deviceId, motorStopMode_t stopMode)
+{
+ if (stopMode == HOLD_MODE)
+ {
+ L6208_ClearSysFlag(HiZstop);
+ }
+ else
+ {
+ L6208_SetSysFlag(HiZstop);
+ }
+}
+
+/******************************************************//**
+ * @brief Set the torque of the specified device
+ * @param[in] deviceId Unused parameter
+ * @param[in] torqueMode Torque mode as specified in enum motorTorqueMode_t
+ * @param[in] torqueValue in % (from 0 to 100)
+ * @retval None
+ * @note
+ **********************************************************/
+void L6208_SetTorque(uint8_t deviceId, motorTorqueMode_t torqueMode, uint8_t torqueValue)
+{
+ if (torqueValue>100) torqueValue = 100;
+ switch(torqueMode)
+ {
+ case ACC_TORQUE:
+ devicePrm.accelTorque = torqueValue;
+ break;
+ case DEC_TORQUE:
+ devicePrm.decelTorque = torqueValue;
+ break;
+ case RUN_TORQUE:
+ devicePrm.runTorque = torqueValue;
+ break;
+ case HOLD_TORQUE:
+ devicePrm.holdTorque = torqueValue;
+ if (devicePrm.motionState != INACTIVE)
+ {
+ break;
+ }
+ L6208_VectorCalc(devicePrm.holdTorque);
+ break;
+ case CURRENT_TORQUE:
+ devicePrm.curTorqueScaler = torqueValue;
+ L6208_SetMicrostepSample2Scale(L6208_USTEPS_PER_QUARTER_PERIOD);
+ default:
+ break; //ignore error
+ }
+}
+
+/******************************************************//**
+ * @brief Stop the motor by using the device deceleration and set deceleration torque
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval true if the command is successfully executed, else false
+ * @note .
+ **********************************************************/
+bool L6208_SoftStop(uint8_t deviceId)
+{
+ L6208_VectorCalc(devicePrm.decelTorque);
+ L6208_SetMotionState(DECELERATINGTOSTOP);
+ return TRUE;
+}
+
+/******************************************************//**
+ * @brief Handle the device state machine at each tick timer pulse end.
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void L6208_TickHandler(uint8_t deviceId)
+{
+ uint32_t locMaxSpeedSpt = devicePrm.maxSpeedSpt;
+ uint32_t locMinSpeedSpt = devicePrm.minSpeedSpt;
+
+ /* Update state, target speed, acceleration and deceleration rates */
+ L6208_Board_CLOCK_PIN_Reset();
+
+ switch(L6208_GetMotionState(0))
+ {
+ /* ============ Velocity control mode states ======================== */
+ case ACCELERATING:
+ /* velocity mode: acceleration phase */
+ /* Increase Speed and update position */
+ L6208_DoAccel();
+ if(locMaxSpeedSpt < devicePrm.speedSpt)
+ {
+ /*Target speed reached */
+ devicePrm.speedSpt = locMaxSpeedSpt;
+ L6208_VectorCalc(devicePrm.runTorque);
+ L6208_SetMotionState(STEADY);
+ }
+ break;
+ case STEADY:
+ /* velocity mode: constant speed phase */
+ /* Update position */
+ L6208_DoRun();
+ if(locMaxSpeedSpt != devicePrm.speedSpt)
+ {
+ /* targeted speed has changed */
+ if(locMaxSpeedSpt< devicePrm.speedSpt)
+ {
+ /* Slow down the motor */
+ L6208_VectorCalc(devicePrm.decelTorque);
+ L6208_SetMotionState(DECELERATING);
+ }
+ else
+ {
+ /* speed up the motor */
+ L6208_VectorCalc(devicePrm.accelTorque);
+ L6208_SetMotionState(ACCELERATING);
+ }
+ }
+ break;
+ case DECELERATING:
+ /* velocity mode: running motor deceleration phase */
+ /* Decrease Speed and update position */
+ L6208_DoDecel();
+ if(locMaxSpeedSpt > devicePrm.speedSpt)
+ {
+ /*Target speed reached but motor has still to be run*/
+ devicePrm.speedSpt = locMaxSpeedSpt;
+ L6208_VectorCalc(devicePrm.runTorque);
+ L6208_SetMotionState(STEADY);
+ }
+ break;
+ case DECELERATINGTOSTOP:
+ /* velocity mode: decelerate to stopped phase */
+ /* Decrease current speed */
+ L6208_DoDecel();
+ if(devicePrm.speedSpt == locMinSpeedSpt)
+ {
+ if (L6208_IsSysFlag(dir2change))
+ {
+ L6208_ClearSysFlag(running);
+ /* Change direction */
+ if (L6208_IsSysFlag(forward))
+ {
+ /* switch to reverse rotation */
+ L6208_SetDirection(0, BACKWARD);
+ }
+ else
+ {
+ /* switch to forward rotation */
+ L6208_SetDirection(0, FORWARD);
+ }
+ L6208_SetSysFlag(running);
+ L6208_SetMotionState(ACCELERATING);
+ /* Set VRefA and VRefB to the selected acceleration torque */
+ L6208_VectorCalc(devicePrm.accelTorque);
+ }
+ else
+ {
+ if (L6208_IsSysFlag(HiZstop))
+ {
+ L6208_HardHiZ(0);
+ }
+ else
+ {
+ L6208_HardStop(0);
+ }
+ }
+ }
+ break;
+
+ /* ============ Position (indexed) control mode states ======================== */
+
+ case INDEX_ACCEL:
+ /* position mode: acceleration state*/
+
+ /* Increase Speed and update position */
+ L6208_DoAccel();
+
+ if(devicePrm.positionTarget1 <= devicePrm.step)
+ {
+ /* End of acceleration phase */
+ L6208_VectorCalc(devicePrm.runTorque);
+ L6208_SetMotionState(INDEX_RUN);
+ }
+ break;
+
+ case INDEX_RUN:
+ /* position mode: constant speed phase */
+
+ /* Update position */
+ L6208_DoRun();
+
+ if(devicePrm.positionTarget2 <= devicePrm.step)
+ {
+ /* reach position targeted for constant speed */
+ L6208_VectorCalc(devicePrm.decelTorque);
+ L6208_SetMotionState(INDEX_DECEL);
+ }
+ break;
+
+ case INDEX_DECEL:
+ /* position mode: deceleration phase */
+
+ /* Decrease Speed and update position */
+ L6208_DoDecel();
+
+ if(devicePrm.positionTarget3 <= devicePrm.step)
+ {
+ /* reach position targeted for deceleration phase */
+ /* the motor terminated its run */
+ /* the torque will be the deceleration one */
+ devicePrm.step = devicePrm.positionTarget3;
+ L6208_SetMotionState(INDEX_DWELL);
+ }
+ break;
+
+ case INDEX_DWELL:
+ /* position mode: dwelling state */
+ if(devicePrm.dwellCounter > 0)
+ {
+ /* decrease the dwelling wait tick counter */
+ devicePrm.dwellCounter--;
+ }
+ if(devicePrm.dwellCounter == 0)
+ {
+ /* dwelling wait time is elapsed */
+ /* so stop the motor */
+ if (L6208_IsSysFlag(HiZstop))
+ {
+ L6208_HardHiZ(0);
+ }
+ else
+ {
+ L6208_HardStop(0);
+ }
+ }
+ break;
+
+ /* ============ stopped state ======================== */
+ case INACTIVE:
+ {
+ if(L6208_IsSysFlag(running))
+ {
+ /* clear the user move command executing */
+ /* and the motor running flags */
+ L6208_ClearSysFlag(running);
+ }
+ break;
+ }
+ default:
+ break;
+ } /* switch(L6208_GetMotionState(0)) */
+ if(L6208_GetMotionState(0) != INACTIVE)
+ {
+ if (L6208_IsSysFlag(microstep))
+ {
+ /* Microstep handling */
+ switch(devicePrm.uStepInc)
+ {
+ default:
+ case 1:
+ /* 1 microstep increment */
+ devicePrm.lsbTicks = (uint8_t)(devicePrm.ticks>>16);
+ break;
+
+ case 2:
+ /* 2 microsteps increment */
+ devicePrm.lsbTicks = (uint8_t)(devicePrm.ticks>>17);
+ break;
+
+ case 4:
+ /* 4 microsteps increment */
+ devicePrm.lsbTicks = (uint8_t)(devicePrm.ticks>>18);
+ break;
+ }
+ devicePrm.lsbTicks &= 0x01;
+ if(devicePrm.lsbOldUSteppingTicks != devicePrm.lsbTicks)
+ {
+ /* waveform sample to update */
+ devicePrm.lsbOldUSteppingTicks = devicePrm.lsbTicks;
+ devicePrm.step++;
+ if (L6208_IsSysFlag(forward))
+ {
+ /* the motor is going forward */
+ devicePrm.absolutePos++;
+ /* Reset the absolute motor position in step/microsteps */
+ /* Get next microstep sample */
+ devicePrm.uStepSample += devicePrm.uStepInc;
+ if(devicePrm.uStepSample > 31)
+ {
+ devicePrm.uStepSample = 0;
+ }
+ }
+ else
+ {
+ /* the motor is going backward */
+ devicePrm.absolutePos--;
+ if(devicePrm.uStepSample >= devicePrm.uStepInc)
+ {
+ /* Get previous microstep sample */
+ devicePrm.uStepSample -= devicePrm.uStepInc;
+ }
+ else
+ {
+ devicePrm.uStepSample = 32 - devicePrm.uStepInc;
+ }
+ }
+ /* set the PWM to update VRefs */
+ L6208_Board_VrefPwmSetDutyCycle(BRIDGE_A, pMicroTable2[devicePrm.uStepSample], FALSE);
+ L6208_Board_VrefPwmSetDutyCycle(BRIDGE_B, microTable1[devicePrm.uStepSample], FALSE);
+ if(devicePrm.uStepsample2update > 0)
+ {
+ /* the waveform samples table has been recalculated
+ so update the waveform scanning table */
+ L6208_UpdateScanWaveformTable();
+ devicePrm.uStepsample2update = 0;
+ }
+ }
+ /* Microstep: use the bit4 toggling as step clock */
+ /* this bit is used because there are 16 microstep samples per quarter period */
+ devicePrm.lsbTicks = (uint8_t)((devicePrm.uStepSample>>4) & 0x01);
+ if(devicePrm.lsbOldTicks != devicePrm.lsbTicks)
+ {
+ /* the selected bit status changed ==> get the next motor step
+ save the current masked motor tick position for step setting scope ... */
+ devicePrm.lsbOldTicks = devicePrm.lsbTicks;
+ L6208_Board_CLOCK_PIN_Set();
+ }
+ }
+ else
+ {
+ /* Full and half step handling code */
+ if(!L6208_IsSysFlag(halfstep))
+ {
+ /* Full step: use the bit 16 toggling as step clock */
+ devicePrm.lsbTicks = (uint8_t)((devicePrm.ticks>>16) & 0x00000001);
+ }
+ else
+ {
+ /* half step: use the bit 15 toggling as step clock */
+ devicePrm.lsbTicks = (uint8_t)((devicePrm.ticks>>15) & 0x00000001);
+ }
+ if(devicePrm.lsbOldTicks != devicePrm.lsbTicks)
+ {
+ /* the selected bit status changed ==> get the next motor step */
+ devicePrm.step++;
+ if(L6208_IsSysFlag(forward))
+ {
+ /* the motor is going forward */
+ devicePrm.absolutePos++;
+ }
+ else
+ {
+ /* the motor is going backward */
+ devicePrm.absolutePos--;
+ }
+ /* save the current masked motor tick position for step setting scope ... */
+ devicePrm.lsbOldTicks = devicePrm.lsbTicks;
+ L6208_Board_CLOCK_PIN_Set();
+ }
+ }
+ }
+ L6208_UstepWaveformHandling();
+}
+
+/******************************************************//**
+ * @brief Get the frequency of VREFA and VREFB PWM
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval the frequency of VREFA and VREFB PWM in Hz
+ * @note
+ **********************************************************/
+uint32_t L6208_VrefPwmGetFreq(uint8_t deviceId)
+ {
+ return devicePrm.vrefPwmFreq;
+}
+
+/******************************************************//**
+ * @brief Set the frequency of the VREFA and VREFB PWM
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @param[in] newFreq in Hz
+ * @retval None
+ * @note
+ **********************************************************/
+void L6208_VrefPwmSetFreq(uint8_t deviceId, uint32_t newFreq)
+{
+ if (!L6208_Board_VrefPwmFreqCheck(newFreq)) L6208_ErrorHandler(L6208_ERROR_SET_PWM);
+ devicePrm.vrefPwmFreq = newFreq;
+ /* Re-Initialise the PWMs -----------------------------------------------------*/
+ L6208_Board_VrefPwmInit(BRIDGE_A, devicePrm.vrefPwmFreq);
+ L6208_Board_VrefPwmInit(BRIDGE_B, devicePrm.vrefPwmFreq);
+ /* Recompute the waveform samples according to the new PWM frequency */
+ L6208_ScaleWaveformTable();
+ /* Update the waveform scanning table */
+ L6208_UpdateScanWaveformTable();
+ if (L6208_IsSysFlag(running))
+ {
+ L6208_Board_VrefPwmStart(BRIDGE_A, devicePrm.vrefPwmFreq);
+ L6208_Board_VrefPwmStart(BRIDGE_B, devicePrm.vrefPwmFreq);
+ }
+}
+
+/******************************************************//**
+ * @brief Lock while motor is running
+ * @param[in] deviceId dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void L6208_WaitWhileActive(uint8_t deviceId)
+{
+ /* Wait while motor is running */
+ while (L6208_IsSysFlag(running));
+}
+
+/**
+ * @}
+ */
+
+/* ------------------------------------------------------------------------- */
+/* Private functions ------------------------------------------------------- */
+/* ------------------------------------------------------------------------- */
+/******************************************************//**
+ * @brief Clear the bit/s of flags according to the specified mask
+ * @param[in] mask flag bit mask
+ * @retval None
+ **********************************************************/
+inline void L6208_ClearSysFlag(uint32_t mask)
+ {
+ devicePrm.flags &= ~mask;
+}
+
+/******************************************************//**
+ * @brief Compute the number of steps at the end of the accereration/deceleration phase
+ * P = position in steps at the end of the acceleration/deceleration phase
+ * T = acceleration/deceleration time in seconds
+ * A = acceleration/deceleration rate in steps per second per second (steps/sec^2)
+ * V = peak velocity during acceleration/deceleration phase
+ * V1 = average velocity during acceleration/deceleration phase
+ * T = V/A
+ * V1 = V/2
+ * P = V1*T
+ * P = V^2/2A
+ * @param accOrDecRate acceleration/deceleration rate in steps per second per second (steps/sec^2)
+ * @retval end position or 0xFFFFFFFF on error
+ **********************************************************/
+uint32_t L6208_ComputeNbAccOrDecSteps(uint16_t accOrDecRate)
+ {
+ uint32_t nbAccOrDecSteps;
+ uint32_t locMaxSpeedSps = (uint32_t)devicePrm.maxSpeedSps;
+
+ if (L6208_IsSysFlag(microstep))
+ {
+ switch(devicePrm.uStepInc)
+ {
+ case 1:
+ locMaxSpeedSps = (uint32_t)devicePrm.maxSpeedSps;
+ break;
+ case 2:
+ locMaxSpeedSps = ((uint32_t)devicePrm.maxSpeedSps)>>1;
+ accOrDecRate >>= 1;
+ break;
+ case 4:
+ locMaxSpeedSps = ((uint32_t)devicePrm.maxSpeedSps)>>2;
+ accOrDecRate >>= 2;
+ break;
+ default:
+ break;
+ }
+ }
+ else if (L6208_IsSysFlag(halfstep))
+ {
+ locMaxSpeedSps = ((uint32_t)devicePrm.maxSpeedSps)<<1;
+ accOrDecRate <<= 1;
+ }
+
+ if(accOrDecRate == 0)
+ {
+ /* division by 0 error */
+ return 0xFFFFFFFF;
+ }
+ nbAccOrDecSteps = locMaxSpeedSps * locMaxSpeedSps;
+ nbAccOrDecSteps /= (uint32_t)accOrDecRate;
+ nbAccOrDecSteps /= 2;
+
+ return nbAccOrDecSteps;
+ }
+
+/******************************************************//**
+ * @brief Compute the acceleration/deceleration speed increment value
+ * @param[in] newAccOrDecRate acceleration or deceleration value (steps/s^2) greater or equal than 24
+ * @retval the speed (step/tick) increment value
+ * LSB = 2^-24 step/tick^2 or 2^-20 microstep/tick^2
+ * @note return 0 if the rate is too low or if the tick frequency is too small
+ * or if the device is running in position mode
+ **********************************************************/
+uint16_t L6208_ConvertAcceDecelRateValue(uint16_t newAccOrDecRate)
+{
+ uint64_t tmp64;
+ uint32_t tmp32;
+
+ if (((L6208_IsSysFlag(running))&&(L6208_IsSysFlag(positionmode)))||\
+ (newAccOrDecRate < L6208_MIN_ACC_DEC_RATE))
+ {
+ return 0;
+ }
+ /* Compute (tick frequency)^2 */
+ tmp32 = (uint32_t)L6208_Board_TickGetFreq();
+ tmp32 *= tmp32;
+ /* Return 0 if the (tick frequency)^2 is too small */
+ if ( tmp32 < (uint32_t)newAccOrDecRate )
+ {
+ return 0;
+}
+ /* Compute the decimal number of microstep or step per tick^2 */
+ /* Decimal part is on 32 bits */
+ tmp64 = (uint64_t)newAccOrDecRate << 32;
+ tmp64 /= ((uint64_t)tmp32);
+
+ return (uint16_t)((tmp64 & 0x00000000FFFFFFFF)>>8);
+}
+
+/******************************************************//**
+ * @brief Compute next position and speed according to the acceleration rate
+ * @retval None
+ **********************************************************/
+void L6208_DoAccel(void)
+{
+ /* Increase speed by acceleration rate */
+ uint32_t locAccelerationSpt2 = (uint32_t)devicePrm.accelerationSpt2;
+ uint32_t locMinSpeedSpt = devicePrm.minSpeedSpt;
+ if ((devicePrm.speedSpt + locAccelerationSpt2) < locMinSpeedSpt)
+ {
+ devicePrm.speedSpt = locMinSpeedSpt;
+ }
+ else
+ {
+ devicePrm.speedSpt += locAccelerationSpt2;
+ }
+ /* Compute next position */
+ L6208_DoRun();
+}
+
+/******************************************************//**
+ * @brief Compute next position and speed according to the deceleration rate
+ * @retval None
+ **********************************************************/
+void L6208_DoDecel(void)
+{
+ /* Decrease current speed by deceleration rate */
+ uint32_t locDecelerationSpt2 = (uint32_t)devicePrm.decelerationSpt2;
+ uint32_t locMinSpeedSpt = devicePrm.minSpeedSpt;
+ if((devicePrm.speedSpt - locMinSpeedSpt) > (uint32_t)locDecelerationSpt2)
+ {
+ devicePrm.speedSpt -= (uint32_t)locDecelerationSpt2;
+ }
+ else
+ {
+ /* Set minimum speed */
+ devicePrm.speedSpt = locMinSpeedSpt;
+ }
+ /* Compute next position */
+ L6208_DoRun();
+}
+
+/******************************************************//**
+ * @brief Compute next position by adding current speed
+ * @retval None
+ **********************************************************/
+void L6208_DoRun(void)
+{
+ devicePrm.ticks += (devicePrm.speedSpt >> 8) & 0x0000FFFF;
+}
+
+/******************************************************//**
+ * @brief Get number of samples to rescale
+ * @retval uStepsample2scale the number of micro stepping waveform samples to rescale
+ **********************************************************/
+uint8_t L6208_GetMicrostepSample2Scale(void)
+{
+ return devicePrm.uStepsample2scale;
+}
+
+/******************************************************//**
+ * @brief Initialize the system for position mode motor moving command
+ * P = total move distance in steps
+ * P1 = steps required to accel from 0 to V
+ * P2 = steps required to decel from V to 0
+ * V = peak velocity in steps per second (steps/sec)
+ * V1 = average velocity during accel or decel*
+ * A = required accel rate in steps per second per second (steps/sec2)
+ * D = required decel rate in steps per second per second (steps/sec2)
+ * T1 = acceleration time in seconds
+ * T2 = deceleration time in seconds*
+ *
+ * 1) T1 = V / A
+ * 2) V1 = V / 2
+ * 3) P1 = V1 T1
+ * Substituting 1 and 2 into 3 yields:
+ * 4) P1 = V2 / 2A
+ * In the same manner we have:
+ * 5) P2 = V2 / 2D
+ *
+ * P1 = PD/(D+A)
+ *
+ * \sa Application Note: AN2044
+ * @retval None
+ **********************************************************/
+void L6208_Indexmodeinit(void)
+ {
+ uint32_t tmpVal0;
+ uint32_t tmpVal1;
+ uint32_t locAccelSteps;
+ uint32_t locDecSteps;
+
+ /* calculate the number of steps to get the running speed */
+ locAccelSteps = L6208_ComputeNbAccOrDecSteps(devicePrm.accelerationSps2);
+ /* calculate the number of steps to get the motor stopped */
+ locDecSteps = L6208_ComputeNbAccOrDecSteps(devicePrm.decelerationSps2);
+ if(( locAccelSteps + locDecSteps ) > devicePrm.positionTarget)
+ {
+ /* Triangular move needed */
+ /* accelsteps = P1 = PD/(D+A) */
+ tmpVal0 = devicePrm.positionTarget * devicePrm.decelerationSps2;
+ tmpVal1 = (uint32_t)devicePrm.decelerationSps2;
+ tmpVal1 += (uint32_t)devicePrm.accelerationSps2;
+ locAccelSteps = tmpVal0 / tmpVal1;
+ devicePrm.positionTarget1 = locAccelSteps;
+ devicePrm.positionTarget2 = devicePrm.positionTarget1 + 1;
+ devicePrm.positionTarget3 = devicePrm.positionTarget;
+ if(devicePrm.positionTarget1 == 0)
+ {
+ devicePrm.positionTarget1 = 1;
+ }
+ }
+ else
+ {
+ /* trapezoidal move needed */
+ /* P1 = V^2/2A */
+ /* P2 = P - V^2/2D */
+ devicePrm.positionTarget1 = locAccelSteps;
+ devicePrm.positionTarget2 = devicePrm.positionTarget - locDecSteps;
+ devicePrm.positionTarget3 = devicePrm.positionTarget;
+ }
+ L6208_SetMotionState(INDEX_ACCEL);
+}
+
+/******************************************************//**
+ * @brief Check the bit/s of flags according to the specified mask
+ * @param[in] mask flag bit mask
+ * @retval TRUE if the bit of the mask are set
+ **********************************************************/
+inline bool L6208_IsSysFlag(uint32_t mask)
+ {
+ return (bool)((devicePrm.flags & mask) == mask);
+ }
+
+/******************************************************//**
+ * @brief Stepper driver device step state reset subroutine
+ * @retval None
+ **********************************************************/
+void L6208_ResetSteps(void)
+ {
+ devicePrm.speedSpt = 0; // reset the current speed value
+ devicePrm.ticks = 0; // reset the current ticks counter value
+ devicePrm.step = 0; // reset the current step counter value
+ devicePrm.lsbOldTicks = 0; // reset copy of the previous position (tick)
+ devicePrm.lsbOldUSteppingTicks = 0; // reset copy of the previous position (tick) ( micro stepping )
+ devicePrm.lsbTicks = 0; // reset copy of the current position (tick)
+ devicePrm.absolutePos = 0; // reset the absolute motor position in step/microsteps
+ devicePrm.uStepSample = 0; // reset the microstepping waveform sample index
+}
+
+/******************************************************//**
+ * @brief Compute the specified micro stepping waveform sample with the
+ * current selected torque and pwm period
+ * @param[in] sampleIndex sample Index
+ * @retval scaled sample value
+ **********************************************************/
+uint32_t L6208_ScaleWaveformSample(uint8_t sampleIndex)
+{
+ uint32_t sample;
+
+ sample = (uint32_t)RefMicroTable[sampleIndex];
+ sample *= L6208_Board_VrefPwmGetPeriod();
+ sample >>= (uint32_t)L6208_SINE_WAVEFORM_POWER_OF_TWO_MAX_VALUE;
+
+ sample *= (uint32_t)devicePrm.curTorqueScaler; // torque val (%)
+ sample /= (uint32_t)100;
+
+ return sample;
+ }
+
+/******************************************************//**
+ * @brief Compute the micro stepping waveform sample table samples with the
+ * current selected torque and pwm period
+ * @retval None
+ **********************************************************/
+void L6208_ScaleWaveformTable(void)
+{
+ uint8_t index;
+ for(index=0; index<=L6208_USTEPS_PER_QUARTER_PERIOD; index++)
+ {
+ /* Calculate the scaled sample and save its value into the waveform to update table */
+ updatedMicroTable[index] = (uint16_t)L6208_ScaleWaveformSample(index);
+ }
+}
+
+/******************************************************//**
+ * @brief Set the parameters of the device to values of the structure pointed
+ * by pInitDevicePrm. Set GPIO according to these values.
+ * @param pInitDevicePrm pointer onto the structure containing values to
+ * initialize the device parameters.
+ * @retval None
+ **********************************************************/
+void L6208_SetDeviceParamsToGivenValues(l6208_Init_t* pInitDevicePrm)
+{
+ memset(&devicePrm, 0, sizeof(devicePrm));
+ L6208_SetAcceleration(0, pInitDevicePrm->accelerationSps2);
+ L6208_SetDeceleration(0, pInitDevicePrm->decelerationSps2);
+ L6208_SetMaxSpeed(0, pInitDevicePrm->maxSpeedSps);
+ L6208_SetMinSpeed(0, L6208_MIN_SPEED);
+ devicePrm.accelTorque = pInitDevicePrm->accelTorque;
+ devicePrm.decelTorque = pInitDevicePrm->decelTorque;
+ devicePrm.runTorque = pInitDevicePrm->runTorque;
+ devicePrm.holdTorque = pInitDevicePrm->holdTorque;
+ /* Only once acceleration, deceleration, min speed and max speed have been */
+ /* initialized, set the step mode */
+ devicePrm.stepMode = pInitDevicePrm->stepMode;
+ L6208_SetDecayMode(0, pInitDevicePrm->decayMode);
+ devicePrm.moveDwellTime = pInitDevicePrm->moveDwellTime;
+ if (L6208_CONF_PARAM_AUTO_HIZ_STOP) L6208_SetSysFlag(pInitDevicePrm->autoHiZstop);
+ if (!L6208_Board_VrefPwmFreqCheck(pInitDevicePrm->vrefPwmFreq))
+ L6208_ErrorHandler(L6208_ERROR_SET_PWM);
+ devicePrm.vrefPwmFreq = pInitDevicePrm->vrefPwmFreq;
+ /* Initialize current stepper state machine index */
+ L6208_SetMotionState(INACTIVE);
+}
+
+/******************************************************//**
+ * @brief Set the parameters of the device to predefined values
+ * Set GPIO according to these values
+ * from l6208_target_config.h
+ * @retval None
+ **********************************************************/
+void L6208_SetDeviceParamsToPredefinedValues(void)
+ {
+ memset(&devicePrm, 0, sizeof(devicePrm));
+ L6208_SetAcceleration(0, L6208_CONF_PARAM_ACC_RATE);
+ L6208_SetDeceleration(0, L6208_CONF_PARAM_DEC_RATE);
+ L6208_SetMaxSpeed(0, L6208_CONF_PARAM_RUNNING_SPEED);
+ L6208_SetMinSpeed(0, L6208_MIN_SPEED);
+ devicePrm.accelTorque = L6208_CONF_PARAM_ACC_CURRENT;
+ devicePrm.decelTorque = L6208_CONF_PARAM_DEC_CURRENT;
+ devicePrm.runTorque = L6208_CONF_PARAM_RUNNING_CURRENT;
+ devicePrm.holdTorque = L6208_CONF_PARAM_HOLDING_CURRENT;
+ /* Only once acceleration, deceleration, min speed and max speed have been */
+ /* initialized, set the step mode */
+ devicePrm.stepMode = L6208_CONF_PARAM_STEP_MODE;
+ L6208_SetDecayMode(0, L6208_CONF_PARAM_DECAY_MODE);
+ devicePrm.moveDwellTime = L6208_CONF_PARAM_DWELL_TIME;
+ if (L6208_CONF_PARAM_AUTO_HIZ_STOP) L6208_SetSysFlag(HiZstop);
+ if (!L6208_Board_VrefPwmFreqCheck(L6208_CONF_VREF_PWM_FREQUENCY))
+ L6208_ErrorHandler(L6208_ERROR_SET_PWM);
+ devicePrm.vrefPwmFreq = L6208_CONF_VREF_PWM_FREQUENCY;
+ /* Initialize current stepper state machine index */
+ L6208_SetMotionState(INACTIVE);
+ }
+
+/******************************************************//**
+ * @brief Set the number of micro stepping waveform samples to rescale
+ * @param[in] value number of micro stepping waveform samples
+ * @retval None
+ **********************************************************/
+void L6208_SetMicrostepSample2Scale(uint8_t value)
+{
+ // clamp to maximum number of samples per period/4
+ if(value > L6208_USTEPS_PER_QUARTER_PERIOD)
+ {
+ value = L6208_USTEPS_PER_QUARTER_PERIOD;
+ }
+ devicePrm.uStepsample2scale = value;
+}
+
+/******************************************************//**
+ * @brief Set the number of micro stepping waveform samples to update into scanning
+ * @param[in] value number of micro stepping waveform samples
+ * @retval None
+ **********************************************************/
+void L6208_SetMicrostepSample2Update(uint8_t value)
+{
+ // clamp to maximum number of samples per period/4
+ if(value > L6208_USTEPS_PER_QUARTER_PERIOD)
+ {
+ value = L6208_USTEPS_PER_QUARTER_PERIOD;
+ }
+ devicePrm.uStepsample2update = value;
+ }
+
+/******************************************************//**
+ * @brief Set the stepper state machine index
+ * @param[in] newMotionState
+ * @retval None
+ **********************************************************/
+void L6208_SetMotionState(motorState_t newMotionState)
+{
+ // sets the new stepper state machine index
+ devicePrm.motionState = newMotionState;
+}
+
+/******************************************************//**
+ * @brief Set the user selected speed in step/tick
+ * @param[in] newSpeed speed value (step/s)
+ * @param[in] pSpeed pointer to the selected speed field
+ * @retval return FALSE if the speed is too low or too high
+ * or if the device is running in position mode, else TRUE
+ **********************************************************/
+bool L6208_SetSpeed(uint16_t newSpeed, uint32_t volatile *pSpeed)
+{
+ uint64_t tmp64;
+ uint32_t tmp32;
+
+ if (((L6208_IsSysFlag(running))&&(L6208_IsSysFlag(positionmode)))||\
+ (newSpeed < L6208_MIN_SPEED))
+ {
+ return FALSE;
+ }
+ tmp32 = (uint32_t)L6208_Board_TickGetFreq();
+ if (tmp32 < newSpeed)
+ {
+ return FALSE;
+ }
+ /* Compute the decimal number of microstep or step per tick */
+ /* Decimal part is on 32 bits */
+ tmp64 = (uint64_t)newSpeed << 32;
+ tmp64 /= ((uint64_t)tmp32);
+ /* set the running constant speed value (step/tick) */
+ *pSpeed = (uint32_t)((tmp64 & 0x00000000FFFFFFFF)>>8);
+
+ return TRUE;
+}
+
+/******************************************************//**
+ * @brief Set the bit/s of flags according to the specified mask
+ * @param[in] mask flag bit mask
+ * @retval None
+ **********************************************************/
+inline void L6208_SetSysFlag(uint32_t mask)
+ {
+ devicePrm.flags |= mask;
+}
+
+/******************************************************//**
+ * @brief Stepper motor start command
+ * @retval true on correct command execution
+ **********************************************************/
+bool L6208_StartMovement(void)
+{
+ uint32_t tmp;
+ if (L6208_IsSysFlag(running))
+ {
+ /* Motor is already running ==> quit */
+ return FALSE;
+ }
+ if (!L6208_IsSysFlag(positionmode))
+ {
+ /* Set the VREFA and VREFB to the selected acc. torque */
+ L6208_VectorCalc(devicePrm.accelTorque);
+
+ /* If the speed control mode is selected */
+ /* setup the motor acceleration for velocity mode driving */
+ L6208_SetMotionState(ACCELERATING);
+ }
+ else
+ {
+ /* if position control mode is selected, reset the current step counter */
+ devicePrm.step = 0;
+ if(devicePrm.uStepSample > 31)
+ {
+ /* check the micro stepping waveform sample index */
+ devicePrm.uStepSample = 0;
+ }
+ /* Set the position dwelling wait time */
+ /* compute number of ticks per millisecond */
+ tmp = (uint32_t)L6208_Board_TickGetFreq() / 1000;
+ /* Compute the dwelling time in ticks => dwellCounter (ticks) */
+ devicePrm.dwellCounter = tmp * (uint32_t)devicePrm.moveDwellTime;
+ if (devicePrm.positionTarget == 0)
+ {
+ /* if the position to go is 0 (no move) */
+ /* Set the deceleration torque */
+ L6208_VectorCalc(devicePrm.decelTorque);
+ /* Set the dwelling delay state index */
+ L6208_SetMotionState(INDEX_DWELL);
+ }
+ else
+ {
+ /* Set the VREFA and VREFB to the selected acc. torque */
+ L6208_VectorCalc(devicePrm.accelTorque);
+ /* go to the selected position */
+ L6208_Indexmodeinit();
+ L6208_SetMotionState(INDEX_ACCEL);
+ }
+ }
+ /* Sets the motor running flag */
+ L6208_SetSysFlag(running);
+ /* Start the VREFA and VREFB PWMs */
+ L6208_Board_VrefPwmStart(BRIDGE_A, devicePrm.vrefPwmFreq);
+ L6208_Board_VrefPwmStart(BRIDGE_B, devicePrm.vrefPwmFreq);
+ if (!(L6208_IsSysFlag(EN_A_set)))
+ {
+ /* Enable power bridges */
+ L6208_Enable(0);
+ }
+ /* Start the tick */
+ L6208_Board_TickStart();
+
+ return TRUE;
+}
+
+/******************************************************//**
+ * @brief Update the micro stepping waveform samples table with the
+ * values previously scaled with current selected torque and tick period
+ * @retval None
+ **********************************************************/
+void L6208_UpdateScanWaveformTable(void)
+{
+ uint8_t index;
+
+ for(index=0; index<=L6208_USTEPS_PER_QUARTER_PERIOD; index++)
+ {
+ microTable1[index] = updatedMicroTable[index];
+ microTable1[L6208_USTEPS_PER_QUARTER_PERIOD*2 - index] = microTable1[index];
+ microTable1[index + L6208_USTEPS_PER_QUARTER_PERIOD*2] = updatedMicroTable[index];
+ }
+ /* clear the number of samples to update */
+ L6208_SetMicrostepSample2Update(0);
+}
+
+/******************************************************//**
+ * @brief Check if there are waveform samples to rescale and if so, perform the rescaling
+ * @retval None
+ **********************************************************/
+void L6208_UstepWaveformHandling(void)
+{
+ /* micro stepper waveform samples rescaling ... and updating */
+ if(L6208_GetMicrostepSample2Scale() > 0)
+ {
+ /* Current torque value has been changed, so recalculate the waveform table */
+ L6208_ScaleWaveformTable();
+
+ /* Set the number of samples to update */
+ L6208_SetMicrostepSample2Update(L6208_USTEPS_PER_QUARTER_PERIOD);
+
+ /* Reset the number of samples to rescaled afer rescaling */
+ L6208_SetMicrostepSample2Scale(0);
+ }
+}
+
+/******************************************************//**
+ * @brief Set the current torque value (Vref)
+ * @param[in] newTorque Selected torque value
+ * @retval always TRUE
+ **********************************************************/
+bool L6208_VectorCalc(uint8_t newTorque)
+{
+ /* save current selected torque value */
+ devicePrm.curTorqueScaler = newTorque;
+
+ if(!L6208_IsSysFlag(microstep))
+ {
+ /* full/half step mode or the motor is not running */
+ /* set the PWM duty cycle according to the current torque value (%). */
+ /* The TON value will be calculated inside the TIMx_PWM_duty_setup f(). */
+ L6208_Board_VrefPwmSetDutyCycle(BRIDGE_A, devicePrm.curTorqueScaler, TRUE);
+ L6208_Board_VrefPwmSetDutyCycle(BRIDGE_B, devicePrm.curTorqueScaler, TRUE);
+ }
+ else
+ {
+ /* microstep mode */
+ if(L6208_IsSysFlag(running))
+ {
+ /* set the number of waveform sample to rescale according current selected */
+ /* torque value */
+ L6208_SetMicrostepSample2Scale(L6208_USTEPS_PER_QUARTER_PERIOD);
+ }
+ else
+ {
+ /* micro stepping mode motor stopped */
+ /* Recompute the waveform samples according to the new PWM frequency */
+ L6208_ScaleWaveformTable();
+ /* Update the waveform scanning table */
+ L6208_UpdateScanWaveformTable();
+ /* Set the VREF timer PWM TON to update VREFA and VREFB */
+ L6208_Board_VrefPwmSetDutyCycle(BRIDGE_A, pMicroTable2[devicePrm.uStepSample], FALSE);
+ L6208_Board_VrefPwmSetDutyCycle(BRIDGE_B, microTable1[devicePrm.uStepSample], FALSE);
+ }
+ }
+ return TRUE;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/******************* (C) COPYRIGHT 2016 STMicroelectronics *****END OF FILE****/
diff --git a/RTC/Core/Src/stm32f4xx_nucleo.c b/RTC/Core/Src/stm32f4xx_nucleo.c
new file mode 100644
index 0000000..2fda2ae
--- /dev/null
+++ b/RTC/Core/Src/stm32f4xx_nucleo.c
@@ -0,0 +1,863 @@
+/**
+ ******************************************************************************
+ * @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
+ *
+ * © COPYRIGHT(c) 2017 STMicroelectronics
+ *
+ * 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; /*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****/
diff --git a/RTC/Core/Src/x_nucleo_ihm05a1_stm32f4xx.c b/RTC/Core/Src/x_nucleo_ihm05a1_stm32f4xx.c
new file mode 100644
index 0000000..178cade
--- /dev/null
+++ b/RTC/Core/Src/x_nucleo_ihm05a1_stm32f4xx.c
@@ -0,0 +1,631 @@
+/**
+ ******************************************************************************
+ * @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
+ *
+ * © COPYRIGHT(c) 2018 STMicroelectronics
+ *
+ * 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****/
diff --git a/RTC/Core/Src/x_nucleo_ihmxx.c b/RTC/Core/Src/x_nucleo_ihmxx.c
new file mode 100644
index 0000000..e59439e
--- /dev/null
+++ b/RTC/Core/Src/x_nucleo_ihmxx.c
@@ -0,0 +1,1943 @@
+ /**
+ ******************************************************************************
+ * @file x_nucleo_ihmxx.c
+ * @author IPC Rennes
+ * @version V1.7.0
+ * @date March 16th, 2018
+ * @brief This file provides common functions for motor control
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2018 STMicroelectronics
+ *
+ * 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_ihmxx.h"
+
+/** @addtogroup BSP
+ * @{
+ */
+
+/** @defgroup MOTOR_CONTROL MOTOR CONTROL
+ * @{
+ */
+
+/** @defgroup MOTOR_CONTROL_Private_Types_Definitions MOTOR CONTROL Private Types Definitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup MOTOR_CONTROL_Private_Defines MOTOR CONTROL Private Defines
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup MOTOR_CONTROL_Private_Constants MOTOR CONTROL Private Constants
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup MOTOR_CONTROL_Private_Macros MOTOR CONTROL Private Macros
+ * @{
+ */
+/// Error when trying to call undefined functions via motorDrvHandle
+#define MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(errorNb) (BSP_MotorControl_ErrorHandler(MOTOR_CONTROL_ERROR_TAG|(errorNb)))
+
+/**
+ * @}
+ */
+
+/** @defgroup MOTOR_CONTROL_Private_Variables MOTOR CONTROL Private Variables
+ * @{
+ */
+
+static motorDrv_t *motorDrvHandle = 0;
+static uint16_t MotorControlBoardId;
+
+/**
+ * @}
+ */
+
+/** @defgroup MOTOR_CONTROL_Weak_Private_Functions MOTOR CONTROL Weak Private Functions
+ * @{
+ */
+/// Get motor handle for L6474
+__weak motorDrv_t* L6474_GetMotorHandle(void){return ((motorDrv_t* )0);}
+/// Get motor handle for L647x
+__weak motorDrv_t* l647x_GetMotorHandle(void){return ((motorDrv_t* )0);}
+/// Get motor handle for L648x
+__weak motorDrv_t* l648x_GetMotorHandle(void){return ((motorDrv_t* )0);}
+/// Get motor handle for Powerstep
+__weak motorDrv_t* Powerstep01_GetMotorHandle(void){return ((motorDrv_t* )0);}
+/// Get motor handle for L6206
+__weak motorDrv_t* L6206_GetMotorHandle(void){return ((motorDrv_t* )0);}
+/// Get motor handle for L6208
+__weak motorDrv_t* L6208_GetMotorHandle(void){return ((motorDrv_t* )0);}
+/// Get motor handle for STSPIN220
+__weak motorDrv_t* Stspin220_GetMotorHandle(void){return ((motorDrv_t* )0);}
+/// Get motor handle for STSPIN240
+__weak motorDrv_t* Stspin240_250_GetMotorHandle(void){return ((motorDrv_t* )0);}
+/**
+ * @}
+ */
+
+/** @defgroup MOTOR_CONTROL_Private_Functions MOTOR CONTROL Private Functions
+ * @{
+ */
+
+/******************************************************//**
+ * @brief Attaches a user callback to the error Handler.
+ * The call back will be then called each time the library
+ * detects an error
+ * @param[in] callback Name of the callback to attach
+ * to the error Hanlder
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_AttachErrorHandler(void (*callback)(uint16_t))
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->AttachErrorHandler != 0))
+ {
+ motorDrvHandle->AttachErrorHandler(callback);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(2);
+ }
+}
+
+/******************************************************//**
+ * @brief Attaches a user callback to the Flag interrupt Handler.
+ * The call back will be then called each time the library
+ * detects a FLAG signal falling edge.
+ * @param[in] callback Name of the callback to attach
+ * to the Flag interrupt Hanlder
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_AttachFlagInterrupt(void (*callback)(void))
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->AttachFlagInterrupt != 0))
+ {
+ motorDrvHandle->AttachFlagInterrupt(callback);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(3);
+ }
+}
+
+/******************************************************//**
+ * @brief Attaches a user callback to the Busy interrupt Handler.
+ * The call back will be then called each time the library
+ * detects a BUSY signal falling edge.
+ * @param[in] callback Name of the callback to attach
+ * to the Busy interrupt Hanlder
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_AttachBusyInterrupt(void (*callback)(void))
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->AttachBusyInterrupt != 0))
+ {
+ motorDrvHandle->AttachBusyInterrupt(callback);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(4);
+ }
+}
+
+/******************************************************//**
+ * @brief Motor control error handler
+ * @param[in] error number of the error
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_ErrorHandler(uint16_t error)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->ErrorHandler != 0))
+ {
+ motorDrvHandle->ErrorHandler(error);
+ }
+ else
+ {
+ while(1)
+ {
+ /* Infinite loop as Error handler must be defined*/
+ }
+ }
+}
+/******************************************************//**
+ * @brief Initialises the motor driver. This function has to be called one time
+ * for each device. The number of devices is incremented in the driver up to
+ * the maximum allowed. Calling this function a number of times greater than the
+ * maximum number triggers an error in the driver.
+ * @param[in] id Component Id (L6474, Powerstep01,...)
+ * @param[in] initDeviceParameters Initialization structure for one device
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_Init(uint16_t id, void* initDeviceParameters)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->Init != 0))
+ {
+ motorDrvHandle->Init(initDeviceParameters);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(0);
+ }
+}
+
+/******************************************************//**
+ * @brief Handlers of the flag interrupt which calls the user callback (if defined)
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_FlagInterruptHandler(void)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->FlagInterruptHandler != 0))
+ {
+ motorDrvHandle->FlagInterruptHandler();
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(5);
+ }
+}
+/******************************************************//**
+ * @brief Returns the acceleration of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval Acceleration in pps^2
+ **********************************************************/
+uint16_t BSP_MotorControl_GetAcceleration(uint8_t deviceId)
+{
+ uint16_t acceleration = 0;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetAcceleration != 0))
+ {
+ acceleration = motorDrvHandle->GetAcceleration(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(6);
+ }
+ return(acceleration);
+}
+
+/******************************************************//**
+ * @brief Get board Id the motor driver
+ * @retval Motor control board Id
+ **********************************************************/
+uint16_t BSP_MotorControl_GetBoardId(void)
+{
+ return (MotorControlBoardId);
+}
+/******************************************************//**
+ * @brief Returns the current speed of the specified device
+ * @param[in] deviceId from 0 to (MAX_NUMBER_OF_DEVICES - 1) for stepper motor
+ * For L6208: dummy parameter for compatibility with motor.h
+ * motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS for Brush DC motor
+ * @retval Speed in pps for stepper motor
+ * in % for Brush DC motor (0-100)
+ **********************************************************/
+uint16_t BSP_MotorControl_GetCurrentSpeed(uint8_t deviceId)
+{
+ uint16_t currentSpeed = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetCurrentSpeed != 0))
+ {
+ currentSpeed = motorDrvHandle->GetCurrentSpeed(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(7);
+ }
+ return(currentSpeed);
+}
+
+/******************************************************//**
+ * @brief Returns the deceleration of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval Deceleration in pps^2
+ **********************************************************/
+uint16_t BSP_MotorControl_GetDeceleration(uint8_t deviceId)
+{
+ uint16_t deceleration = 0;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetDeceleration != 0))
+ {
+ deceleration = motorDrvHandle->GetDeceleration(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(8);
+ }
+ return(deceleration);
+}
+
+/******************************************************//**
+ * @brief Returns the device state
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1) for stepper motor
+ * For L6208: dummy parameter for compatibility with motor.h
+ * motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS for Brush DC motor
+ * @retval State ACCELERATING, DECELERATING, STEADY or INACTIVE for stepper motor,
+ STEADY or INACTIVE for Brush DC motor
+ **********************************************************/
+motorState_t BSP_MotorControl_GetDeviceState(uint8_t deviceId)
+{
+ motorState_t state = INACTIVE;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetDeviceState != 0))
+ {
+ state = motorDrvHandle->GetDeviceState(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(9);
+ }
+ return(state);
+}
+
+/******************************************************//**
+ * @brief Returns the FW version of the library
+ * @retval BSP_MotorControl_FW_VERSION
+ * @note the format is (MAJOR_VERSION<<16)|(MINOR_VERSION<<8)|(PATCH_VERSION)
+ * with major, minor and patch versions coded on 8 bits.
+ **********************************************************/
+uint32_t BSP_MotorControl_GetFwVersion(void)
+{
+ uint32_t version = 0;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetFwVersion != 0))
+ {
+ version = motorDrvHandle->GetFwVersion();
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(10);
+ }
+ return(version);
+}
+
+/******************************************************//**
+ * @brief Returns the mark position of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval Mark register value converted in a 32b signed integer
+ **********************************************************/
+int32_t BSP_MotorControl_GetMark(uint8_t deviceId)
+{
+ int32_t mark = 0;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetMark != 0))
+ {
+ mark = motorDrvHandle->GetMark(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(11);
+ }
+ return(mark);
+}
+
+/******************************************************//**
+ * @brief Returns the max speed of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1) for stepper motor
+ * For L6208: dummy parameter for compatibility with motor.h
+ * motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS for Brush DC motor
+ * @retval maxSpeed in pps for stepper motor
+ * in % for Brush DC motor (0-100)
+ **********************************************************/
+uint16_t BSP_MotorControl_GetMaxSpeed(uint8_t deviceId)
+{
+ uint16_t maxSpeed = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetMaxSpeed != 0))
+ {
+ maxSpeed = motorDrvHandle->GetMaxSpeed(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(12);
+ }
+ return(maxSpeed);
+}
+
+/******************************************************//**
+ * @brief Returns the min speed of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval minSpeed in pps
+ **********************************************************/
+uint16_t BSP_MotorControl_GetMinSpeed(uint8_t deviceId)
+{
+ uint16_t minSpeed = 0;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetMinSpeed != 0))
+ {
+ minSpeed = motorDrvHandle->GetMinSpeed(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(13);
+ }
+ return(minSpeed);
+}
+
+/******************************************************//**
+ * @brief Returns the ABS_POSITION of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval ABS_POSITION register value converted in a 32b signed integer
+ **********************************************************/
+int32_t BSP_MotorControl_GetPosition(uint8_t deviceId)
+{
+ int32_t pos = 0;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetPosition != 0))
+ {
+ pos = motorDrvHandle->GetPosition(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(14);
+ }
+ return(pos);
+}
+
+/******************************************************//**
+ * @brief Requests the motor to move to the home position (ABS_POSITION = 0)
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_GoHome(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GoHome != 0))
+ {
+ motorDrvHandle->GoHome(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(15);
+ }
+}
+
+/******************************************************//**
+ * @brief Requests the motor to move to the mark position
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_GoMark(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GoMark != 0))
+ {
+ motorDrvHandle->GoMark(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(16);
+ }
+}
+
+/******************************************************//**
+ * @brief Requests the motor to move to the specified position
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @param[in] targetPosition absolute position in steps
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_GoTo(uint8_t deviceId, int32_t targetPosition)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GoTo != 0))
+ {
+ motorDrvHandle->GoTo(deviceId, targetPosition);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(17);
+ }
+}
+
+/******************************************************//**
+ * @brief Immediatly stops the motor.
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1) for stepper motor
+ * For L6208: dummy parameter for compatibility with motor.h
+ * motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS for Brush DC motor
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_HardStop(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->HardStop != 0))
+ {
+ motorDrvHandle->HardStop(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(18);
+ }
+}
+
+/******************************************************//**
+ * @brief Moves the motor of the specified number of steps
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @param[in] direction FORWARD or BACKWARD
+ * @param[in] stepCount Number of steps to perform
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_Move(uint8_t deviceId, motorDir_t direction, uint32_t stepCount)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->Move != 0))
+ {
+ motorDrvHandle->Move(deviceId, direction, stepCount);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(19);
+ }
+}
+
+/******************************************************//**
+ * @brief Resets all motor driver devices
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_ResetAllDevices(void)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->ResetAllDevices != 0))
+ {
+ motorDrvHandle->ResetAllDevices();
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(20);
+ }
+}
+
+/******************************************************//**
+ * @brief Runs the motor. It will accelerate from the min
+ * speed up to the max speed by using the device acceleration.
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1) for stepper motor
+ * For L6208: dummy parameter for compatibility with motor.h
+ * motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS for Brush DC motor
+ * @param[in] direction FORWARD or BACKWARD
+ * @retval None
+ * @note For unidirectionnal brush DC motor, direction parameter
+ * has no effect
+ **********************************************************/
+void BSP_MotorControl_Run(uint8_t deviceId, motorDir_t direction)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->Run != 0))
+ {
+ motorDrvHandle->Run(deviceId, direction);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(21);
+ }
+}
+/******************************************************//**
+ * @brief Changes the acceleration of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @param[in] newAcc New acceleration to apply in pps^2
+ * @retval true if the command is successfully executed, else false
+ * @note The command is not performed is the device is executing
+ * a MOVE or GOTO command (but it can be used during a RUN command)
+ **********************************************************/
+bool BSP_MotorControl_SetAcceleration(uint8_t deviceId,uint16_t newAcc)
+{
+ bool status = FALSE;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetAcceleration != 0))
+ {
+ status = motorDrvHandle->SetAcceleration(deviceId, newAcc);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(22);
+ }
+ return (status);
+}
+
+/******************************************************//**
+ * @brief Changes the deceleration of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @param[in] newDec New deceleration to apply in pps^2
+ * @retval true if the command is successfully executed, else false
+ * @note The command is not performed is the device is executing
+ * a MOVE or GOTO command (but it can be used during a RUN command)
+ **********************************************************/
+bool BSP_MotorControl_SetDeceleration(uint8_t deviceId, uint16_t newDec)
+{
+ bool status = FALSE;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetDeceleration != 0))
+ {
+ status = motorDrvHandle->SetDeceleration(deviceId, newDec);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(23);
+ }
+ return (status);
+}
+
+/******************************************************//**
+ * @brief Set current position to be the Home position (ABS pos set to 0)
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @param[in] homePosition new absolute home position
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_SetHome(uint8_t deviceId, int32_t homePosition)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetHome != 0))
+ {
+ motorDrvHandle->SetHome(deviceId, homePosition);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(24);
+ }
+}
+
+/******************************************************//**
+ * @brief Sets current position to be the Mark position
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @param[in] markPosition new absolute mark position
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_SetMark(uint8_t deviceId, int32_t markPosition)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetMark != 0))
+ {
+ motorDrvHandle->SetMark(deviceId, markPosition);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(25);
+ }
+}
+
+/******************************************************//**
+ * @brief Changes the max speed of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1) for stepper motor
+ * For L6208: dummy parameter for compatibility with motor.h
+ * motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS for Brush DC motor
+ * @param[in] newMaxSpeed New max speed to apply in pps for stepper motor,
+ in % for Brush DC motor (0-100)
+ * @retval true if the command is successfully executed, else false
+ * @note For a stepper motor, the command is not performed if the device
+ * is executing a MOVE or GOTO command (but it can be used during a RUN command).
+ **********************************************************/
+bool BSP_MotorControl_SetMaxSpeed(uint8_t deviceId, uint16_t newMaxSpeed)
+{
+ bool status = FALSE;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetMaxSpeed != 0))
+ {
+ status = motorDrvHandle->SetMaxSpeed(deviceId, newMaxSpeed);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(26);
+ }
+ return (status);
+}
+
+/******************************************************//**
+ * @brief Changes the min speed of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @param[in] newMinSpeed New min speed to apply in pps
+ * @retval true if the command is successfully executed, else false
+ * @note The command is not performed is the device is executing
+ * a MOVE or GOTO command (but it can be used during a RUN command).
+ **********************************************************/
+bool BSP_MotorControl_SetMinSpeed(uint8_t deviceId, uint16_t newMinSpeed)
+{
+ bool status = FALSE;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetMinSpeed != 0))
+ {
+ status = motorDrvHandle->SetMinSpeed(deviceId, newMinSpeed);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(27);
+ }
+
+ return (status);
+}
+
+/******************************************************//**
+ * @brief Stops the motor by using the device deceleration
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1) for stepper motor
+ * For L6208: dummy parameter for compatibility with motor.h
+ * motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS for Brush DC motor
+ * @retval true if the command is successfully executed, else false
+ * @note The command is not performed is the device is in INACTIVE state.
+ **********************************************************/
+bool BSP_MotorControl_SoftStop(uint8_t deviceId)
+{
+ bool status = FALSE;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SoftStop != 0))
+ {
+ status = motorDrvHandle->SoftStop(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(28);
+ }
+ return (status);
+}
+
+/******************************************************//**
+ * @brief Handles the device state machine at each step
+ * or at each tick
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval None
+ * @note Must only be called by the timer ISR
+ **********************************************************/
+void BSP_MotorControl_StepClockHandler(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->StepClockHandler != 0))
+ {
+ motorDrvHandle->StepClockHandler(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(29);
+ }
+}
+/******************************************************//**
+ * @brief Locks until the device state becomes Inactive
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_WaitWhileActive(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->WaitWhileActive != 0))
+ {
+ motorDrvHandle->WaitWhileActive(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(30);
+ }
+}
+
+/**
+ * @}
+ */
+
+/** @defgroup BSP_MotorControl_Control_Functions BSP MotorControl Control Functions
+ * @{
+ */
+
+/******************************************************//**
+ * @brief Issue the Disable command to the motor driver of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1) for stepper motor
+ * For L6208: dummy parameter for compatibility with motor.h
+ * motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS for Brush DC motor
+ * @retval None
+ * @note For brush DC motor, when input of different brigdes are parallelized
+ * together, the disabling of one bridge leads to the disabling
+ * of the second one
+ **********************************************************/
+void BSP_MotorControl_CmdDisable(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdDisable != 0))
+ {
+ motorDrvHandle->CmdDisable(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(31);
+ }
+}
+
+/******************************************************//**
+ * @brief Issues the Enable command to the motor driver of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1) for stepper motor
+ * For L6208: dummy parameter for compatibility with motor.h
+ * motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS for Brush DC motor
+ * @retval None
+ * @note For brush DC motor, when input of different brigdes are parallelized
+ * together, the enabling of one bridge leads to the enabling
+ * of the second one
+ **********************************************************/
+void BSP_MotorControl_CmdEnable(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdEnable != 0))
+ {
+ motorDrvHandle->CmdEnable(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(32);
+ }
+}
+
+/******************************************************//**
+ * @brief Issues the GetParam command to the motor driver of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @param[in] param Register adress (BSP_MotorControl_ABS_POS, BSP_MotorControl_MARK,...)
+ * @retval Register value
+ **********************************************************/
+uint32_t BSP_MotorControl_CmdGetParam(uint8_t deviceId,
+ uint32_t param)
+{
+ uint32_t value = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdGetParam != 0))
+ {
+ value = motorDrvHandle->CmdGetParam(deviceId, param);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(33);
+ }
+ return (value);
+}
+
+/******************************************************//**
+ * @brief Issues the GetStatus command to the motor driver of the specified
+ * device for stepper motor,
+ * Get bridge status for Brush DC motor
+ * @param[in] deviceId from 0 to MAX_NUMBER_OF_DEVICES - 1 for stepper motor,
+ bridgeId from 0 for bridge A, 1 for bridge B for brush DC motor
+ * @retval Status Register value for stepper motor,
+ * Bridge state for brush DC motor
+ * @note For stepper motor, once the GetStatus command is performed,
+ * the flags of the status register are reset.
+ * This is not the case when the status register is read with the
+ * GetParam command (via the functions ReadStatusRegister or CmdGetParam).
+ **********************************************************/
+uint16_t BSP_MotorControl_CmdGetStatus(uint8_t deviceId)
+{
+ uint16_t status = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdGetStatus != 0))
+ {
+ status = motorDrvHandle->CmdGetStatus(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(34);
+ }
+ return (status);
+}
+
+/******************************************************//**
+ * @brief Issues the Nop command to the motor driver of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_CmdNop(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdNop != 0))
+ {
+ motorDrvHandle->CmdNop(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(35);
+ }
+}
+
+/******************************************************//**
+ * @brief Issues the SetParam command to the motor driver of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @param[in] param Register adress (BSP_MotorControl_ABS_POS, BSP_MotorControl_MARK,...)
+ * @param[in] value Value to set in the register
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_CmdSetParam(uint8_t deviceId,
+ uint32_t param,
+ uint32_t value)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdSetParam != 0))
+ {
+ motorDrvHandle->CmdSetParam(deviceId, param, value);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(36);
+ }
+}
+
+/******************************************************//**
+ * @brief Reads the Status Register value
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @retval Status register valued
+ * @note The status register flags are not cleared
+ * at the difference with CmdGetStatus()
+ **********************************************************/
+uint16_t BSP_MotorControl_ReadStatusRegister(uint8_t deviceId)
+{
+ uint16_t status = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->ReadStatusRegister != 0))
+ {
+ status = motorDrvHandle->ReadStatusRegister(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(37);
+ }
+ return (status);
+}
+
+/******************************************************//**
+ * @brief Releases the motor driver (pin set to High) of all devices
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_ReleaseReset(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->ReleaseReset != 0))
+ {
+ motorDrvHandle->ReleaseReset(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(38);
+ }
+}
+
+/******************************************************//**
+ * @brief Resets the motor driver (reset pin set to low) of all devices
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_Reset(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->Reset != 0))
+ {
+ motorDrvHandle->Reset(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(39);
+ }
+}
+
+/******************************************************//**
+ * @brief Set the stepping mode
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @param[in] stepMode from full step to 1/16 microstep as specified in
+ * enum BSP_MotorControl_STEP_SEL_t
+ * @retval true if the command is successfully executed, else false
+ **********************************************************/
+bool BSP_MotorControl_SelectStepMode(uint8_t deviceId, motorStepMode_t stepMode)
+{
+ bool value = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SelectStepMode != 0))
+ {
+ value = motorDrvHandle->SelectStepMode(deviceId, stepMode);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(40);
+ }
+ return (value);
+}
+
+/******************************************************//**
+ * @brief Specifies the direction
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @param[in] dir FORWARD or BACKWARD
+ * @note The direction change is only applied if the device
+ * is in INACTIVE state
+ * For L6208: In velocity mode a direction change forces the device to stop and
+ * then run in the new direction. In position mode, if the device is
+ * running, a direction change will generate an error.
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_SetDirection(uint8_t deviceId, motorDir_t dir)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetDirection != 0))
+ {
+ motorDrvHandle->SetDirection(deviceId, dir);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(41);
+ }
+}
+
+/******************************************************//**
+ * @brief Issues Go To Dir command
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @param[in] dir movement direction
+ * @param[in] abs_pos absolute position where requested to move
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_CmdGoToDir(uint8_t deviceId, motorDir_t dir, int32_t abs_pos)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdGoToDir != 0))
+ {
+ motorDrvHandle->CmdGoToDir(deviceId, dir, abs_pos);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(42);
+ }
+}
+
+/******************************************************//**
+ * @brief Checks if at least one device is busy by checking
+ * busy pin position.
+ * The busy pin is shared between all devices.
+ * @retval One if at least one device is busy, otherwise zero
+ **********************************************************/
+uint8_t BSP_MotorControl_CheckBusyHw(void)
+{
+ uint8_t value = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CheckBusyHw != 0))
+ {
+ value = motorDrvHandle->CheckBusyHw();
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(43);
+ }
+ return (value);
+}
+
+/******************************************************//**
+ * @brief Checks if at least one device has an alarm flag set
+ * by reading flag pin position.
+ * The flag pin is shared between all devices.
+ * @retval One if at least one device has an alarm flag set ,
+ * otherwise zero
+ **********************************************************/
+uint8_t BSP_MotorControl_CheckStatusHw(void)
+{
+ uint8_t value = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CheckStatusHw != 0))
+ {
+ value = motorDrvHandle->CheckStatusHw();
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(44);
+ }
+ return (value);
+}
+
+/******************************************************//**
+ * @brief Issues Go Until command
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * @param[in] action ACTION_RESET or ACTION_COPY
+ * @param[in] dir movement direction
+ * @param[in] speed in 2^-28 step/tick
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_CmdGoUntil(uint8_t deviceId, motorAction_t action, motorDir_t dir, uint32_t speed)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdGoUntil != 0))
+ {
+ motorDrvHandle->CmdGoUntil(deviceId, action, dir, speed);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(45);
+ }
+}
+
+/******************************************************//**
+ * @brief Immediately stops the motor and disable the power bridge.
+ * @param[in] deviceId from 0 to MAX_NUMBER_OF_DEVICES-1 for stepper motor
+ * motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS for Brush DC motor
+ * @retval None
+ * @note if two Brush DC motors use the same power bridge, the
+ * power bridge will be disable only if the two motors are
+ * stopped
+ **********************************************************/
+void BSP_MotorControl_CmdHardHiZ(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdHardHiZ != 0))
+ {
+ motorDrvHandle->CmdHardHiZ(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(46);
+ }
+}
+
+/******************************************************//**
+ * @brief Issues Release SW command
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * @param[in] action
+ * @param[in] dir movement direction
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_CmdReleaseSw(uint8_t deviceId, motorAction_t action, motorDir_t dir)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdReleaseSw != 0))
+ {
+ motorDrvHandle->CmdReleaseSw(deviceId, action, dir);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(47);
+ }
+}
+
+/******************************************************//**
+ * @brief Issues Reset Device command
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_CmdResetDevice(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdResetDevice != 0))
+ {
+ motorDrvHandle->CmdResetDevice(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(48);
+ }
+}
+
+/******************************************************//**
+ * @brief Issues Reset Pos command
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_CmdResetPos(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdResetPos != 0))
+ {
+ motorDrvHandle->CmdResetPos(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(49);
+ }
+}
+
+/******************************************************//**
+ * @brief Issues Run command
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * @param[in] dir Movement direction (FORWARD, BACKWARD)
+ * @param[in] speed in 2^-28 step/tick
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_CmdRun(uint8_t deviceId, motorDir_t dir, uint32_t speed)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdRun != 0))
+ {
+ motorDrvHandle->CmdRun(deviceId, dir, speed);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(50);
+ }
+}
+
+/******************************************************//**
+ * @brief Issues Soft HiZ command
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_CmdSoftHiZ(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdSoftHiZ != 0))
+ {
+ motorDrvHandle->CmdSoftHiZ(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(51);
+ }
+}
+
+/******************************************************//**
+ * @brief Issues Step Clock command
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * @param[in] dir Movement direction (FORWARD, BACKWARD)
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_CmdStepClock(uint8_t deviceId, motorDir_t dir)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdStepClock != 0))
+ {
+ motorDrvHandle->CmdStepClock(deviceId, dir);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(52);
+ }
+}
+
+/******************************************************//**
+ * @brief Fetch and clear status flags of all devices
+ * by issuing a GET_STATUS command simultaneously
+ * to all devices.
+ * Then, the fetched status of each device can be retrieved
+ * by using the BSP_MotorControl_GetFetchedStatus function
+ * provided there is no other calls to functions which
+ * use the SPI in between.
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_FetchAndClearAllStatus(void)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->FetchAndClearAllStatus != 0))
+ {
+ motorDrvHandle->FetchAndClearAllStatus();
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(53);
+ }
+}
+
+/******************************************************//**
+ * @brief Get the value of the STATUS register which was
+ * fetched by using BSP_MotorControl_FetchAndClearAllStatus.
+ * The fetched values are available as long as there is
+ * no other calls to functions which use the SPI.
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * @retval Last fetched value of the STATUS register
+ **********************************************************/
+uint16_t BSP_MotorControl_GetFetchedStatus(uint8_t deviceId)
+{
+ uint16_t value = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetFetchedStatus != 0))
+ {
+ value = motorDrvHandle->GetFetchedStatus(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(54);
+ }
+ return (value);
+}
+
+/******************************************************//**
+ * @brief Return the number of devices in the daisy chain
+ * @retval number of devices from 1 to MAX_NUMBER_OF_DEVICES
+ **********************************************************/
+uint8_t BSP_MotorControl_GetNbDevices(void)
+{
+ uint8_t value = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetNbDevices != 0))
+ {
+ value = motorDrvHandle->GetNbDevices();
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(55);
+ }
+ return (value);
+}
+
+/******************************************************//**
+ * @brief Checks if the specified device is busy
+ * by reading the Busy bit of its status Register
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * @retval true if device is busy, else false
+ **********************************************************/
+bool BSP_MotorControl_IsDeviceBusy(uint8_t deviceId)
+{
+ bool value = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->IsDeviceBusy != 0))
+ {
+ value = motorDrvHandle->IsDeviceBusy(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(56);
+ }
+ return (value);
+}
+
+/******************************************************//**
+ * @brief Sends commands stored in the queue by previously
+ * BSP_MotorControl_QueueCommands
+ * @retval None
+ *********************************************************/
+void BSP_MotorControl_SendQueuedCommands(void)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SendQueuedCommands != 0))
+ {
+ motorDrvHandle->SendQueuedCommands();
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(57);
+ }
+}
+
+/******************************************************//**
+ * @brief Put commands in queue before synchronous sending
+ * done by calling BSP_MotorControl_SendQueuedCommands.
+ * Any call to functions that use the SPI between the calls of
+ * BSP_MotorControl_QueueCommands and BSP_MotorControl_SendQueuedCommands
+ * will corrupt the queue.
+ * A command for each device of the daisy chain must be
+ * specified before calling BSP_MotorControl_SendQueuedCommands.
+ * @param[in] deviceId deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * @param[in] command Command to queue (all BSP_MotorControl commmands
+ * except SET_PARAM, GET_PARAM, GET_STATUS)
+ * @param[in] value argument of the command to queue
+ * @retval None
+ *********************************************************/
+void BSP_MotorControl_QueueCommands(uint8_t deviceId, uint8_t command, int32_t value)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->QueueCommands != 0))
+ {
+ motorDrvHandle->QueueCommands(deviceId, command, value);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(58);
+ }
+}
+
+/******************************************************//**
+ * @brief Locks until all devices become not busy
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_WaitForAllDevicesNotBusy(void)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->WaitForAllDevicesNotBusy != 0))
+ {
+ motorDrvHandle->WaitForAllDevicesNotBusy();
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(59);
+ }
+}
+
+/******************************************************//**
+ * @brief Handler of the busy interrupt which calls the user callback (if defined)
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_BusyInterruptHandler(void)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->BusyInterruptHandler != 0))
+ {
+ motorDrvHandle->BusyInterruptHandler();
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(61);
+ }
+}
+
+/******************************************************//**
+ * @brief Issues Soft Stop command
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_CmdSoftStop(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdSoftStop != 0))
+ {
+ motorDrvHandle->CmdSoftStop(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(62);
+ }
+}
+
+/******************************************************//**
+ * @brief Start the step clock by using the given frequency
+ * @param[in] newFreq in Hz of the step clock
+ * @retval None
+ * @note The frequency is directly the current speed of the device
+ **********************************************************/
+void BSP_MotorControl_StartStepClock(uint16_t newFreq)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->StartStepClock != 0))
+ {
+ motorDrvHandle->StartStepClock(newFreq);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(63);
+ }
+}
+
+/******************************************************//**
+ * @brief Stops the PWM uses for the step clock
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_StopStepClock(void)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->StopStepClock != 0))
+ {
+ motorDrvHandle->StopStepClock();
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(64);
+ }
+}
+
+/******************************************************//**
+ * @brief Set the dual full bridge configuration
+ * @param[in] config bridge configuration to apply
+ * for L6206, see dualFullBridgeConfig_t enum
+ * for Stspin240, 0 for a mono brush DC configuration, 1 for a dual brush DC configuration
+ * for Stspin250, 0 only as no dual brush DC configuration is supported
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_SetDualFullBridgeConfig(uint8_t config)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetDualFullBridgeConfig != 0))
+ {
+ motorDrvHandle->SetDualFullBridgeConfig(config);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(65);
+ }
+}
+
+/******************************************************//**
+ * @brief Get the PWM frequency of the bridge input
+ * @param[in] bridgeId from 0 for bridge A to 1 for bridge B for brush DC motor
+ * bridgeId must be 0 for L6208 (both bridges are set with the same frequency)
+ * @retval Freq in Hz
+ **********************************************************/
+uint32_t BSP_MotorControl_GetBridgeInputPwmFreq(uint8_t bridgeId)
+{
+ uint32_t pwmFreq = 0;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetBridgeInputPwmFreq != 0))
+ {
+ pwmFreq = motorDrvHandle->GetBridgeInputPwmFreq(bridgeId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(66);
+ }
+ return (pwmFreq);
+}
+
+/******************************************************//**
+ * @brief Changes the PWM frequency of the bridge input
+ * @param[in] bridgeId from 0 for bridge A to 1 for bridge B for brush DC motor
+ * bridgeId must be 0 for L6208 (both bridges are set with the same frequency)
+ * @param[in] newFreq in Hz up to 100000Hz
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_SetBridgeInputPwmFreq(uint8_t bridgeId, uint32_t newFreq)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetBridgeInputPwmFreq != 0))
+ {
+ motorDrvHandle->SetBridgeInputPwmFreq(bridgeId, newFreq);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(67);
+ }
+}
+
+/******************************************************//**
+ * @brief Select the mode to stop the motor. When the motor
+ * is stopped, if autoHiZ is TRUE, the power bridges are disabled
+ * if autoHiZ is FALSE, the power bridges are kept enabled.
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * deviceId dummy parameter for compatibility with motor.h
+ * @param[in] stopMode selected stop mode
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_SetStopMode(uint8_t deviceId, motorStopMode_t stopMode)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetStopMode != 0))
+ {
+ motorDrvHandle->SetStopMode(deviceId, stopMode);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(68);
+ }
+}
+
+/******************************************************//**
+ * @brief Get the selected stop mode
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval the selected stop mode
+ **********************************************************/
+motorStopMode_t BSP_MotorControl_GetStopMode(uint8_t deviceId)
+{
+ motorStopMode_t stopMode = UNKNOW_STOP_MODE;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetStopMode != 0))
+ {
+ stopMode = motorDrvHandle->GetStopMode(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(69);
+ }
+ return (stopMode);
+}
+
+/******************************************************//**
+ * @brief Select the motor decay mode
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @param[in] decayMode (SLOW_DECAY or FAST_DECAY)
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_SetDecayMode(uint8_t deviceId, motorDecayMode_t decayMode)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetDecayMode != 0))
+ {
+ motorDrvHandle->SetDecayMode(deviceId, decayMode);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(70);
+ }
+}
+
+/******************************************************//**
+ * @brief Get the motor decay mode
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval decay mode
+ **********************************************************/
+motorDecayMode_t BSP_MotorControl_GetDecayMode(uint8_t deviceId)
+{
+ motorDecayMode_t decayMode = UNKNOW_DECAY;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetDecayMode != 0))
+ {
+ decayMode = motorDrvHandle->GetDecayMode(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(71);
+ }
+ return (decayMode);
+}
+
+/******************************************************//**
+ * @brief Get the motor step mode
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval step mode
+ **********************************************************/
+motorStepMode_t BSP_MotorControl_GetStepMode(uint8_t deviceId)
+{
+ motorStepMode_t stepMode = STEP_MODE_UNKNOW;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetStepMode != 0))
+ {
+ stepMode = motorDrvHandle->GetStepMode(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(72);
+ }
+ return (stepMode);
+}
+
+/******************************************************//**
+ * @brief Get the motor direction
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * For L6208: dummy parameter for compatibility with motor.h
+ * @retval direction
+ **********************************************************/
+motorDir_t BSP_MotorControl_GetDirection(uint8_t deviceId)
+{
+ motorDir_t dir = UNKNOW_DIR;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetDirection != 0))
+ {
+ dir = motorDrvHandle->GetDirection(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(73);
+ }
+ return (dir);
+}
+
+/******************************************************//**
+ * @brief Exit specified device from reset
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES-1 )
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_ExitDeviceFromReset(uint8_t deviceId)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->ExitDeviceFromReset != 0))
+ {
+ motorDrvHandle->ExitDeviceFromReset(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(74);
+ }
+}
+
+/******************************************************//**
+ * @brief Get the motor torque
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @param[in] torqueMode Torque mode as specified in enum motorTorqueMode_t
+ * @retval torque value in % (from 0 to 100)
+ **********************************************************/
+uint8_t BSP_MotorControl_GetTorque(uint8_t deviceId, motorTorqueMode_t torqueMode)
+{
+ uint8_t torqueValue = 0;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetTorque != 0))
+ {
+ torqueValue = motorDrvHandle->GetTorque(deviceId, torqueMode);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(76);
+ }
+ return (torqueValue);
+}
+
+/******************************************************//**
+ * @brief Set the motor torque
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @param[in] torqueMode Torque mode as specified in enum motorTorqueMode_t
+ * @param[in] torqueValue in % (from 0 to 100)
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_SetTorque(uint8_t deviceId, motorTorqueMode_t torqueMode, uint8_t torqueValue)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetTorque != 0))
+ {
+ motorDrvHandle->SetTorque(deviceId, torqueMode, torqueValue);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(75);
+ }
+}
+
+/******************************************************//**
+ * @brief Set the PWM frequency of Ref
+ * @param[in] refId Id of the targeted Ref
+ * @param[in] newFreq frequency in Hz
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_SetRefFreq(uint8_t refId, uint32_t newFreq)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetRefFreq != 0))
+ {
+ motorDrvHandle->SetRefFreq(refId, newFreq);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(77);
+ }
+}
+
+/******************************************************//**
+ * @brief Return the PWM frequency of Ref
+ * @param[in] refId Id of the targeted Ref
+ * @retval frequency in Hz
+ **********************************************************/
+uint32_t BSP_MotorControl_GetRefFreq(uint8_t refId)
+{
+ uint32_t value = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetRefFreq != 0))
+ {
+ value = motorDrvHandle->GetRefFreq(refId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(78);
+ }
+ return (value);
+}
+
+/******************************************************//**
+ * @brief Set the PWM duty cycle of Ref
+ * @param[in] refId Id of the targeted Ref
+ * @param[in] newDc duty cycle in % (from 0 to 100)
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_SetRefDc(uint8_t refId, uint8_t newDc)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetRefDc != 0))
+ {
+ motorDrvHandle->SetRefDc(refId, newDc);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(79);
+ }
+}
+
+/******************************************************//**
+ * @brief Return the PWM duty cycle of Ref
+ * @param[in] refId Id of the targeted Ref
+ * @retval duty cycle in % (from 0 to 100)
+ **********************************************************/
+uint8_t BSP_MotorControl_GetRefDc(uint8_t refId)
+{
+ uint8_t value = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetRefDc != 0))
+ {
+ value = motorDrvHandle->GetRefDc(refId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(80);
+ }
+ return (value);
+}
+
+/******************************************************//**
+ * @brief Set the number of devices in the daisy chain
+ * @param[in] id Component Id (L6474, Powerstep01,...)
+ * @param[in] nbDevices the number of devices to be used
+ * from 1 to MAX_NUMBER_OF_DEVICES
+ * @retval TRUE if successfull, FALSE if failure, attempt
+ * to set a number of devices greater than MAX_NUMBER_OF_DEVICES
+ **********************************************************/
+bool BSP_MotorControl_SetNbDevices(uint16_t id, uint8_t nbDevices)
+{
+ MotorControlBoardId = id;
+ bool status = FALSE;
+ if (id == BSP_MOTOR_CONTROL_BOARD_ID_L6474)
+ {
+ motorDrvHandle = L6474_GetMotorHandle();
+ }
+ else if (id == BSP_MOTOR_CONTROL_BOARD_ID_POWERSTEP01)
+ {
+ motorDrvHandle = Powerstep01_GetMotorHandle();
+ }
+ else if (id == BSP_MOTOR_CONTROL_BOARD_ID_L6206)
+ {
+ motorDrvHandle = L6206_GetMotorHandle();
+ }
+ else if (id == BSP_MOTOR_CONTROL_BOARD_ID_L6208)
+ {
+ motorDrvHandle = L6208_GetMotorHandle();
+ }
+ else if (id == BSP_MOTOR_CONTROL_BOARD_ID_STSPIN220)
+ {
+ motorDrvHandle = Stspin220_GetMotorHandle();
+ }
+ else if ( (id == BSP_MOTOR_CONTROL_BOARD_ID_L6470) ||
+ (id == BSP_MOTOR_CONTROL_BOARD_ID_L6472) )
+ {
+ motorDrvHandle = l647x_GetMotorHandle();
+ }
+ else if ( (id == BSP_MOTOR_CONTROL_BOARD_ID_L6480) ||
+ (id == BSP_MOTOR_CONTROL_BOARD_ID_L6482) )
+ {
+ motorDrvHandle = l648x_GetMotorHandle();
+ }
+ else if ((id == BSP_MOTOR_CONTROL_BOARD_ID_STSPIN240)||
+ (id == BSP_MOTOR_CONTROL_BOARD_ID_STSPIN250))
+ {
+ motorDrvHandle = Stspin240_250_GetMotorHandle();
+ }
+ else
+ {
+ motorDrvHandle = 0;
+ }
+ if ((motorDrvHandle != 0)&&
+ (motorDrvHandle->SetNbDevices != 0)&&
+ (nbDevices !=0))
+ {
+ status = motorDrvHandle->SetNbDevices(nbDevices);
+ }
+ return (status);
+}
+
+/******************************************************//**
+ * @brief Set the parameter param in the motor driver of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @param[in] param Register adress (BSP_MotorControl_ABS_POS, BSP_MotorControl_MARK,...)
+ * @param[in] value Floating point value to convert and set into the register
+ * @retval None
+ **********************************************************/
+bool BSP_MotorControl_SetAnalogValue(uint8_t deviceId, uint32_t param, float value)
+{
+ bool status = FALSE;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->CmdSetParam != 0))
+ {
+ status = motorDrvHandle->SetAnalogValue(deviceId, param, value);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(82);
+ }
+ return (status);
+}
+
+/******************************************************//**
+ * @brief Get the parameter param in the motor driver of the specified device
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @param[in] param Register adress (BSP_MotorControl_ABS_POS, BSP_MotorControl_MARK,...)
+ * @retval Floating point value corresponding to the register value
+ **********************************************************/
+float BSP_MotorControl_GetAnalogValue(uint8_t deviceId, uint32_t param)
+{
+ float value = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetAnalogValue != 0))
+ {
+ value = motorDrvHandle->GetAnalogValue(deviceId, param);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(83);
+ }
+ return (value);
+}
+
+/******************************************************//**
+ * @brief Enable or disable the torque boost
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @param[in] enable true to enable torque boost, false to disable
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_SetTorqueBoostEnable(uint8_t deviceId, bool enable)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetTorqueBoostEnable != 0))
+ {
+ motorDrvHandle->SetTorqueBoostEnable(deviceId, enable);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(84);
+ }
+}
+
+/******************************************************//**
+ * @brief Get the torque boost feature status
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @retval TRUE if enabled, FALSE if disabled
+ **********************************************************/
+bool BSP_MotorControl_GetTorqueBoostEnable(uint8_t deviceId)
+{
+ bool status = FALSE;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetTorqueBoostEnable != 0))
+ {
+ status = motorDrvHandle->GetTorqueBoostEnable(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(85);
+ }
+ return status;
+}
+
+/******************************************************//**
+ * @brief Set the torque boost threshold
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @param[in] speedThreshold speed threshold above which the step mode is
+ * changed to full step
+ * @retval None
+ **********************************************************/
+void BSP_MotorControl_SetTorqueBoostThreshold(uint8_t deviceId, uint16_t speedThreshold)
+{
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->SetTorqueBoostThreshold != 0))
+ {
+ motorDrvHandle->SetTorqueBoostThreshold(deviceId, speedThreshold);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(86);
+ }
+}
+
+/******************************************************//**
+ * @brief Get the torque boost threshold
+ * @param[in] deviceId (from 0 to MAX_NUMBER_OF_DEVICES - 1)
+ * @retval the torque boost threshold above which the step mode is
+ * changed to full step
+ **********************************************************/
+uint16_t BSP_MotorControl_GetTorqueBoostThreshold(uint8_t deviceId)
+{
+ uint16_t value = 0;
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetTorqueBoostThreshold != 0))
+ {
+ value = motorDrvHandle->GetTorqueBoostThreshold(deviceId);
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(87);
+ }
+ return value;
+}
+
+/******************************************************//**
+ * @brief Get the dual full bridge configuration
+ * return config bridge configuration to apply
+ * for L6206, see dualFullBridgeConfig_t enum
+ * for Stspin240, 0 for a mono brush DC configuration, 1 for a dual brush DC configuration
+ * for Stspin250, 0 only as no dual brush DC configuration is supported
+ **********************************************************/
+uint8_t BSP_MotorControl_GetDualFullBridgeConfig(void)
+{
+ uint8_t value = 0;
+
+ if ((motorDrvHandle != 0)&&(motorDrvHandle->GetDualFullBridgeConfig != 0))
+ {
+ value = motorDrvHandle->GetDualFullBridgeConfig();
+ }
+ else
+ {
+ MOTOR_CONTROL_ERROR_UNDEFINED_FUNCTION(88);
+ }
+
+ return value;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/