ST Expansion SW Team / X_NUCLEO_IHM14A1

Dependencies:   ST_INTERFACES

Dependents:   HelloWorld_IHM14A1

Fork of X_NUCLEO_IHM14A1 by Davide Aliprandi

Revision:
2:4fd08b67958c
Parent:
1:bc265521eb00
--- a/Components/STSPIN820/STSPIN820.h	Fri Apr 27 17:02:08 2018 +0000
+++ b/Components/STSPIN820/STSPIN820.h	Thu Sep 27 14:05:44 2018 +0000
@@ -1,40 +1,41 @@
 /**
-  ******************************************************************************
-  * @file    STSPIN820.h
-  * @author  STM
-  * @version V1.0.0
-  * @date    August 7th, 2017
-  * @brief   STSPIN820 driver (fully integrated microstepping motor driver)
-  * @note    (C) COPYRIGHT 2017 STMicroelectronics
-  ******************************************************************************
-  * @attention
-  *
-  * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
-  *
-  * Redistribution and use in source and binary forms, with or without modification,
-  * are permitted provided that the following conditions are met:
-  *   1. Redistributions of source code must retain the above copyright notice,
-  *      this list of conditions and the following disclaimer.
-  *   2. Redistributions in binary form must reproduce the above copyright notice,
-  *      this list of conditions and the following disclaimer in the documentation
-  *      and/or other materials provided with the distribution.
-  *   3. Neither the name of STMicroelectronics nor the names of its contributors
-  *      may be used to endorse or promote products derived from this software
-  *      without specific prior written permission.
-  *
-  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
-  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
-  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
-  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
-  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
-  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
-  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
-  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
-  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
-  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-  *
-  ******************************************************************************
-  */
+ *******************************************************************************
+ * @file    STSPIN820.h
+ * @author  Davide Aliprandi, STMicroelectronics
+ * @version V1.0.0
+ * @date    May 3rd, 2018
+ * @brief   This file contains the class definition of an STSPIN820 Motor
+ *          Control component.
+ * @note    (C) COPYRIGHT 2018 STMicroelectronics
+ *******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; COPYRIGHT(c) 2018 STMicroelectronics</center></h2>
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *   1. Redistributions of source code must retain the above copyright notice,
+ *      this list of conditions and the following disclaimer.
+ *   2. Redistributions in binary form must reproduce the above copyright notice,
+ *      this list of conditions and the following disclaimer in the documentation
+ *      and/or other materials provided with the distribution.
+ *   3. Neither the name of STMicroelectronics nor the names of its contributors
+ *      may be used to endorse or promote products derived from this software
+ *      without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ *******************************************************************************
+ */
 
 
 /* Generated with STM32CubeTOO -----------------------------------------------*/
@@ -61,7 +62,6 @@
  * Include here platform specific header files.                               *
  *----------------------------------------------------------------------------*/        
 #include "mbed.h"
-#include "DevSPI.h"
 /* ACTION 2 ------------------------------------------------------------------*
  * Include here component specific header files.                              *
  *----------------------------------------------------------------------------*/        
@@ -70,18 +70,18 @@
  * Include here interface specific header files.                              *
  *                                                                            *
  * Example:                                                                   *
- *   #include "../Interfaces/Humidity.h"                                *
- *   #include "../Interfaces/Temperature.h"                             *
+ *   #include "../Interfaces/Humidity.h"                                      *
+ *   #include "../Interfaces/Temperature.h"                                   *
  *----------------------------------------------------------------------------*/
-#include "../Interfaces/Motor.h"
+#include "StepperMotor.h"
 
 
 /* Classes -------------------------------------------------------------------*/
 
 /**
- * @brief Class representing a STSPIN820 component.
+ * @brief Class representing an STSPIN820 component.
  */
-class STSPIN820 : public Motor
+class STSPIN820 : public StepperMotor
 {
 public:
 
@@ -89,11 +89,35 @@
 
     /**
      * @brief Constructor.
-     * @param ssel pin name of the SSEL pin of the SPI device to be used for communication.
-     * @param spi  SPI device to be used for communication.
+     * @param en_fault_irq  pin name of the EN_FAULT pin of the component.
+     * @param standby_reset pin name of the STBY\RST pin of the component.
+     * @param direction     pin name of the DIR pin of the component.
+     * @param ref_pwm       pin name of the REF_PWM pin of the component.
+     * @param decay         pin name of the DECAY pin of the component.
+     * @param step_clock    pin name of the STCK pin of the component.
+     * @param mode1         pin name of the MODE1 pin of the component.
+     * @param mode2         pin name of the MODE2 pin of the component.
+     * @param mode3         pin name of the MODE3 pin of the component.
      */
-    STSPIN820(PinName ssel, DevSPI &spi) : Motor(), ssel(ssel), dev_spi(spi)
+    STSPIN820(PinName en_fault_irq, PinName standby_reset, PinName direction,
+              PinName ref_pwm, PinName decay, PinName step_clock,
+              PinName mode1, PinName mode2, PinName mode3) :
+              StepperMotor(),
+              en_fault_irq(en_fault_irq),
+              standby_reset(standby_reset),
+              direction(direction),
+              ref_pwm(ref_pwm),
+              decay(decay),
+              step_clock(step_clock),
+              mode1(mode1),
+              mode2(mode2),
+              mode3(mode3)
     {
+        /* Checking stackability. */
+        if (!(number_of_devices < MAX_NUMBER_OF_DEVICES)) {
+            error("Instantiation of the STSPIN820 component failed: it can be stacked up to %d times.\r\n", MAX_NUMBER_OF_DEVICES);
+        }
+
         /* ACTION 4 ----------------------------------------------------------*
          * Initialize here the component's member variables, one variable per *
          * line.                                                              *
@@ -105,9 +129,9 @@
         flag_interrupt_callback = 0;
         error_handler_callback = 0;
         toggle_odd = 0;
-        device_prm = 0;
-        number_of_devices = 0;
-        device_instance = 0;
+        pwm_period = 1;
+        pwm_duty_cycle = 0;
+        device_instance = number_of_devices++;
     }
     
     /**
@@ -163,24 +187,24 @@
         STSPIN820_FlagInterruptHandler();
     }
 
-    virtual uint16_t get_acceleration(uint8_t deviceId)
+    virtual unsigned int get_acceleration(void)
     {
-        return (uint16_t) STSPIN820_GetAcceleration((uint8_t) deviceId);
+        return (unsigned int) STSPIN820_GetAcceleration();
     }
 
-    virtual uint16_t get_current_speed(uint8_t deviceId)
+    virtual unsigned int get_speed(void)
     {
-        return (uint16_t) STSPIN820_GetCurrentSpeed((uint8_t) deviceId);
+        return (unsigned int) STSPIN820_GetCurrentSpeed();
     }
 
-    virtual uint16_t get_deceleration(uint8_t deviceId)
+    virtual unsigned int get_deceleration(void)
     {
-        return (uint16_t) STSPIN820_GetDeceleration((uint8_t) deviceId);
+        return (unsigned int) STSPIN820_GetDeceleration();
     }
 
-    virtual motor_state_t get_device_state(uint8_t deviceId)
+    virtual motor_state_t get_device_state(void)
     {
-        return (motor_state_t) STSPIN820_GetDeviceState((uint8_t) deviceId);
+        return (motor_state_t) STSPIN820_GetDeviceState();
     }
 
     virtual uint32_t get_fw_version(void)
@@ -188,134 +212,156 @@
         return (uint32_t) STSPIN820_GetFwVersion();
     }
 
-    virtual int32_t get_mark(uint8_t deviceId)
+    virtual signed int get_mark(void)
     {
-        return (int32_t) STSPIN820_GetMark((uint8_t) deviceId);
+        return (signed int) STSPIN820_GetMark();
     }
 
-    virtual uint16_t get_max_speed(uint8_t deviceId)
+    virtual unsigned int get_max_speed(void)
     {
-        return (uint16_t) STSPIN820_GetMaxSpeed((uint8_t) deviceId);
+        return (unsigned int) STSPIN820_GetMaxSpeed();
+    }
+
+    virtual unsigned int get_min_speed(void)
+    {
+        return (unsigned int) STSPIN820_GetMinSpeed();
     }
 
-    virtual uint16_t get_min_speed(uint8_t deviceId)
+    virtual signed int get_position(void)
     {
-        return (uint16_t) STSPIN820_GetMinSpeed((uint8_t) deviceId);
+        return (signed int) STSPIN820_GetPosition();
     }
 
-    virtual int32_t get_position(uint8_t deviceId)
+    virtual void go_home(void)
     {
-        return (int32_t) STSPIN820_GetPosition((uint8_t) deviceId);
+        STSPIN820_GoHome();
     }
 
-    virtual void go_home(uint8_t deviceId)
+    virtual void go_mark(void)
     {
-        STSPIN820_GoHome((uint8_t) deviceId);
+        STSPIN820_GoMark();
+    }
+
+    virtual void go_to(signed int position)
+    {
+        STSPIN820_GoTo((signed int) position);
     }
 
-    virtual void go_mark(uint8_t deviceId)
-    {
-        STSPIN820_GoMark((uint8_t) deviceId);
-    }
-
-    virtual void go_to(uint8_t deviceId, int32_t targetPosition)
+    /**
+     * @brief  Stopping the motor through an immediate deceleration up to zero speed.
+     * @param  None.
+     * @retval None.
+     */
+    virtual void soft_stop(void)
     {
-        STSPIN820_GoTo((uint8_t) deviceId, (int32_t) targetPosition);
-    }
-
-    virtual void hard_stop(uint8_t deviceId)
-    {
-        STSPIN820_HardStop((uint8_t) deviceId);
+        STSPIN820_SoftStop();
     }
 
-    virtual void move(uint8_t deviceId, motor_direction_t direction, uint32_t stepCount)
+    /**
+     * @brief  Stopping the motor through an immediate infinite deceleration.
+     * @param  None.
+     * @retval None.
+     */
+    virtual void hard_stop(void)
     {
-        STSPIN820_Move((uint8_t) deviceId, (motor_direction_t) direction, (uint32_t) stepCount);
+        STSPIN820_HardStop();
     }
 
-    virtual void run(uint8_t deviceId, motor_direction_t direction)
-    {
-        STSPIN820_Run((uint8_t) deviceId, (motor_direction_t) direction);
-    }
+    /**
+     * @brief  Disabling the power bridge after performing a deceleration to zero.
+     * @param  None.
+     * @retval None.
+     */
+    virtual void soft_hiz(void) {}
 
-    virtual bool set_acceleration(uint8_t deviceId, uint16_t newAcc)
+    /**
+     * @brief  Disabling the power bridge immediately.
+     * @param  None.
+     * @retval None.
+     */
+    virtual void hard_hiz(void)
     {
-        return (bool) STSPIN820_SetAcceleration((uint8_t) deviceId, (uint16_t) newAcc);
-    }
-
-    virtual bool set_deceleration(uint8_t deviceId, uint16_t newDec)
-    {
-        return (bool) STSPIN820_SetDeceleration((uint8_t) deviceId, (uint16_t) newDec);
+        STSPIN820_HardHiZ();
     }
 
-    virtual void set_home(uint8_t deviceId)
+    virtual void move(direction_t direction, unsigned int steps)
     {
-        STSPIN820_SetHome((uint8_t) deviceId);
+        STSPIN820_Move((motor_direction_t) (direction == StepperMotor::FWD ? FORWARD : BACKWARD), (unsigned int) steps);
     }
 
-    virtual void set_mark(uint8_t deviceId)
+    virtual void run(direction_t direction)
     {
-        STSPIN820_SetMark((uint8_t) deviceId);
+        STSPIN820_Run((motor_direction_t) direction);
+    }
+
+    virtual bool set_acceleration(unsigned int acceleration)
+    {
+        return (bool) STSPIN820_SetAcceleration((unsigned int) acceleration);
     }
 
-    virtual bool set_max_speed(uint8_t deviceId, uint16_t newMaxSpeed)
+    virtual bool set_deceleration(unsigned int deceleration)
     {
-        return (bool) STSPIN820_SetMaxSpeed((uint8_t) deviceId, (uint16_t) newMaxSpeed);
+        return (bool) STSPIN820_SetDeceleration((unsigned int) deceleration);
     }
 
-    virtual bool set_min_speed(uint8_t deviceId, uint16_t newMinSpeed)
+    virtual void set_home(void)
     {
-        return (bool) STSPIN820_SetMinSpeed((uint8_t) deviceId, (uint16_t) newMinSpeed);
+        STSPIN820_SetHome();
     }
 
-    virtual bool soft_stop(uint8_t deviceId)
+    virtual void set_mark(void)
     {
-        return (bool) STSPIN820_SoftStop((uint8_t) deviceId);
+        STSPIN820_SetMark();
     }
 
-    virtual void step_clock_handler(uint8_t deviceId)
+    virtual bool set_max_speed(unsigned int speed)
     {
-        STSPIN820_StepClockHandler((uint8_t) deviceId);
+        return (bool) STSPIN820_SetMaxSpeed((unsigned int) speed);
     }
 
-    virtual void wait_while_active(uint8_t deviceId)
+    virtual bool set_min_speed(unsigned int speed)
     {
-        STSPIN820_WaitWhileActive((uint8_t) deviceId);
+        return (bool) STSPIN820_SetMinSpeed((unsigned int) speed);
     }
 
-    virtual void cmd_disable(uint8_t deviceId)
+    virtual void wait_while_active(void)
     {
-        STSPIN820_Disable((uint8_t) deviceId);
+        STSPIN820_WaitWhileActive();
     }
 
-    virtual void cmd_enable(uint8_t deviceId)
+    virtual void cmd_disable(void)
     {
-        STSPIN820_Enable((uint8_t) deviceId);
+        STSPIN820_Disable();
+    }
+
+    virtual void cmd_enable(void)
+    {
+        STSPIN820_Enable();
     }
 
-    virtual bool select_step_mode(uint8_t deviceId, motor_step_mode_t stepMode)
+    virtual bool set_step_mode(step_mode_t step_mode)
     {
-        return (bool) STSPIN820_SetStepMode((uint8_t) deviceId, (motor_step_mode_t) stepMode);
+        return (bool) STSPIN820_SetStepMode((motor_step_mode_t) step_mode);
     }
 
-    virtual void set_direction(uint8_t deviceId, motor_direction_t direction)
+    virtual void set_direction(direction_t direction)
     {
-        STSPIN820_SetDirection((uint8_t) deviceId, (motor_direction_t) direction);
+        STSPIN820_SetDirection((motor_direction_t) direction);
     }
 
-    virtual void cmd_go_to_dir(uint8_t deviceId, motor_direction_t direction, int32_t targetPosition)
+    virtual void go_to_dir(direction_t direction, int32_t targetPosition)
     {
-        STSPIN820_GoToDir((uint8_t) deviceId, (motor_direction_t) direction, (int32_t) targetPosition);
+        STSPIN820_GoToDir((motor_direction_t) direction, (int32_t) targetPosition);
     }
 
-    virtual uint8_t check_status_hw(void)
+    virtual unsigned int get_status(void)
     {
-        return (uint8_t) STSPIN820_CheckStatusHw();
+        return (unsigned int) STSPIN820_CheckStatusHw();
     }
 
-    virtual void cmd_reset_device(uint8_t deviceId)
+    virtual void cmd_reset_device(void)
     {
-        STSPIN820_PutDeviceInStandby((uint8_t) deviceId);
+        STSPIN820_PutDeviceInStandby();
     }
 
     virtual uint8_t get_nb_devices(void)
@@ -323,89 +369,79 @@
         return (uint8_t) STSPIN820_GetNbDevices();
     }
 
-    virtual void error_handler(uint16_t error)
+    virtual uint32_t get_bridge_input_pwm_freq(void)
     {
-        STSPIN820_ErrorHandler((uint16_t) error);
+        return (uint32_t) STSPIN820_VrefPwmGetFreq();
     }
 
-    virtual uint32_t get_bridge_input_pwm_freq(uint8_t deviceId)
+    virtual void set_bridge_input_pwm_freq(uint32_t newFreq)
     {
-        return (uint32_t) STSPIN820_VrefPwmGetFreq((uint8_t) deviceId);
+        STSPIN820_VrefPwmSetFreq((uint32_t) newFreq);
     }
 
-    virtual void set_bridge_input_pwm_freq(uint8_t deviceId, uint32_t newFreq)
+    virtual void set_stop_mode(motor_stop_mode_t stopMode)
     {
-        STSPIN820_VrefPwmSetFreq((uint8_t) deviceId, (uint32_t) newFreq);
+        STSPIN820_SetStopMode((motor_stop_mode_t) stopMode);
     }
 
-    virtual void set_stop_mode(uint8_t deviceId, motor_stop_mode_t stopMode)
+    virtual motor_stop_mode_t get_stop_mode(void)
     {
-        STSPIN820_SetStopMode((uint8_t) deviceId, (motor_stop_mode_t) stopMode);
-    }
-
-    virtual motor_stop_mode_t get_stop_mode(uint8_t deviceId)
-    {
-        return (motor_stop_mode_t) STSPIN820_GetStopMode((uint8_t) deviceId);
+        return (motor_stop_mode_t) STSPIN820_GetStopMode();
     }
 
-    virtual void set_decay_mode(uint8_t deviceId, motor_decay_mode_t decayMode)
+    virtual void set_decay_mode(motor_decay_mode_t decayMode)
     {
-        STSPIN820_SetDecayMode((uint8_t) deviceId, (motor_decay_mode_t) decayMode);
+        STSPIN820_SetDecayMode((motor_decay_mode_t) decayMode);
     }
 
-    virtual motor_decay_mode_t get_decay_mode(uint8_t deviceId)
+    virtual motor_decay_mode_t get_decay_mode(void)
     {
-        return (motor_decay_mode_t) STSPIN820_GetDecayMode((uint8_t) deviceId);
+        return (motor_decay_mode_t) STSPIN820_GetDecayMode();
     }
 
-    virtual motor_step_mode_t get_step_mode(uint8_t deviceId)
+    virtual motor_step_mode_t get_step_mode(void)
     {
-        return (motor_step_mode_t) STSPIN820_GetStepMode((uint8_t) deviceId);
+        return (motor_step_mode_t) STSPIN820_GetStepMode();
     }
 
-    virtual motor_direction_t get_direction(uint8_t deviceId)
+    virtual direction_t get_direction(void)
     {
-        return (motor_direction_t) STSPIN820_GetDirection((uint8_t) deviceId);
+        return (direction_t) (STSPIN820_GetDirection() == FORWARD ? StepperMotor::FWD : StepperMotor::BWD);
     }
 
-    virtual void exit_device_from_reset(uint8_t deviceId)
+    virtual void exit_device_from_reset(void)
     {
-        STSPIN820_ExitDeviceFromStandby((uint8_t) deviceId);
+        STSPIN820_ExitDeviceFromStandby();
     }
 
-    virtual void set_torque(uint8_t deviceId, motor_torque_mode_t torqueMode, uint8_t torqueValue)
+    virtual void set_torque(motor_torque_mode_t torqueMode, uint8_t torqueValue)
     {
-        STSPIN820_SetTorque((uint8_t) deviceId, (motor_torque_mode_t) torqueMode, (uint8_t) torqueValue);
-    }
-
-    virtual uint8_t get_torque(uint8_t deviceId, motor_torque_mode_t torqueMode)
-    {
-        return (uint8_t) STSPIN820_GetTorque((uint8_t) deviceId, (motor_torque_mode_t) torqueMode);
+        STSPIN820_SetTorque((motor_torque_mode_t) torqueMode, (uint8_t) torqueValue);
     }
 
-    virtual bool set_nb_devices(uint8_t deviceId)
+    virtual uint8_t get_torque(motor_torque_mode_t torqueMode)
     {
-        return (bool) STSPIN820_SetNbDevices((uint8_t) deviceId);
+        return (uint8_t) STSPIN820_GetTorque((motor_torque_mode_t) torqueMode);
     }
 
-    virtual void set_torque_boost_enable(uint8_t deviceId, bool enable)
+    virtual void set_torque_boost_enable(bool enable)
     {
-        STSPIN820_SetTorqueBoostEnable((uint8_t) deviceId, (bool) enable);
+        STSPIN820_SetTorqueBoostEnable((bool) enable);
     }
 
-    virtual bool get_torque_boost_enable(uint8_t deviceId)
+    virtual bool get_torque_boost_enable(void)
     {
-        return (bool) STSPIN820_GetTorqueBoostEnable((uint8_t) deviceId);
+        return (bool) STSPIN820_GetTorqueBoostEnable();
     }
 
-    virtual void set_torque_boost_threshold(uint8_t deviceId, uint16_t speedThreshold)
+    virtual void set_torque_boost_threshold(uint16_t speedThreshold)
     {
-        STSPIN820_SetTorqueBoostThreshold((uint8_t) deviceId, (uint16_t) speedThreshold);
+        STSPIN820_SetTorqueBoostThreshold((uint16_t) speedThreshold);
     }
 
-    virtual uint16_t get_torque_boost_threshold(uint8_t deviceId)
+    virtual uint16_t get_torque_boost_threshold(void)
     {
-        return (uint16_t) STSPIN820_GetTorqueBoostThreshold((uint8_t) deviceId);
+        return (uint16_t) STSPIN820_GetTorqueBoostThreshold();
     }
 
 
@@ -440,6 +476,36 @@
      *     feature_irq.disable_irq();                                         *
      *   }                                                                    *
      *------------------------------------------------------------------------*/
+    /**
+     * @brief  Attaching an interrupt handler to the FLAG interrupt.
+     * @param  fptr An interrupt handler.
+     * @retval None.
+     */
+    void attach_en_fault_irq(void (*fptr)(void))
+    {
+        en_fault_irq.mode(PullUp);
+        en_fault_irq.fall(fptr);
+    }
+    
+    /**
+     * @brief  Enabling the FLAG interrupt handling.
+     * @param  None.
+     * @retval None.
+     */
+    void enable_en_fault_irq(void)
+    {
+        en_fault_irq.enable_irq();
+    }
+    
+    /**
+     * @brief  Disabling the FLAG interrupt handling.
+     * @param  None.
+     * @retval None.
+     */
+    void disable_en_fault_irq(void)
+    {
+        en_fault_irq.disable_irq();
+    }
 
 
 protected:
@@ -461,244 +527,396 @@
      *   status_t COMPONENT_enable_feature(void);  //(2)                      *
      *   status_t COMPONENT_compute_average(void); //(3)                      *
      *------------------------------------------------------------------------*/
-    void STSPIN820_ApplySpeed(uint8_t pwmId, uint16_t newSpeed);
-    void STSPIN820_ApplyTorque(uint8_t deviceId, motor_torque_mode_t torqueMode);
-    void STSPIN820_ComputeSpeedProfile(uint8_t deviceId, uint32_t nbSteps);
+    //Apply speed
+    void STSPIN820_ApplySpeed(uint16_t newSpeed);
+    //Apply torque
+    void STSPIN820_ApplyTorque(motor_torque_mode_t torqueMode);
+    //Compute speed profile
+    void STSPIN820_ComputeSpeedProfile(uint32_t nbSteps);
+    //Handler for the flag interrupt
     void STSPIN820_FlagInterruptHandler(void);
+    //Set device paramenters to other values
     void STSPIN820_SetDeviceParamsOtherValues(void);
+    //Set device paramenters to given values
     void STSPIN820_SetDeviceParamsToGivenValues(STSPIN820_init_t* initDevicePrm);
+    //Set device paramenters to predefined values
     void STSPIN820_SetDeviceParamsToPredefinedValues(void);
-    void STSPIN820_StartMovement(uint8_t deviceId);
-    void STSPIN820_StepClockHandler(uint8_t deviceId);
-    MOTOR_vt_t* STSPIN820_GetMotorHandle(void);                                    //Return handle of the motor driver handle
-    void STSPIN820_Init(void* pInit);                                //Start the STSPIN820 library
-    uint16_t STSPIN820_ReadId(void);                                       //Read Id to get driver instance
-    void STSPIN820_AttachErrorHandler(void (*callback)(uint16_t));   //Attach a user callback to the error handler
-    void STSPIN820_AttachFlagInterrupt(void (*callback)(void));      //Attach a user callback to the flag Interrupt
-    uint8_t STSPIN820_CheckStatusHw(void);                                 //Check if STSPIN820 has a fault by reading EN pin position
-    void STSPIN820_Disable(uint8_t deviceId);                        //Disable the power stage of the specified device
-    void STSPIN820_Enable(uint8_t deviceId);                         //Enable the power stage of the specified device
-    void STSPIN820_ErrorHandler(uint16_t error);                     //Error handler which calls the user callback
-    void STSPIN820_ExitDeviceFromStandby(uint8_t deviceId);          //Exit STSPIN820 device from standby 
-    uint16_t STSPIN820_GetAcceleration(uint8_t deviceId);            //Return the acceleration in pps^2
-    uint16_t STSPIN820_GetCurrentSpeed(uint8_t deviceId);            //Return the current speed in pps
-    motor_decay_mode_t STSPIN820_GetDecayMode(uint8_t deviceId);     //Return the device decay mode
-    uint16_t STSPIN820_GetDeceleration(uint8_t deviceId);            //Return the deceleration in pps^2
-    motor_state_t STSPIN820_GetDeviceState(uint8_t deviceId);        //Return the device state
-    motor_direction_t STSPIN820_GetDirection(uint8_t deviceId);      //Get the motor current direction
-    uint32_t STSPIN820_GetFwVersion(void);                                 //Return the FW version
-    int32_t STSPIN820_GetMark(uint8_t deviceId);                     //Return the mark position 
-    uint16_t STSPIN820_GetMaxSpeed(uint8_t deviceId);                //Return the max speed in pps
-    uint16_t STSPIN820_GetMinSpeed(uint8_t deviceId);                //Return the min speed in pps
-    uint8_t STSPIN820_GetNbDevices(void);                                  //Return the nupber of devices
-    int32_t STSPIN820_GetPosition(uint8_t deviceId);                 //Return the ABS_POSITION (32b signed)
-    motor_step_mode_t STSPIN820_GetStepMode(uint8_t deviceId);       //Get the motor step mode
-    motor_stop_mode_t STSPIN820_GetStopMode(uint8_t deviceId);       //Get the selected mode to stop the motor
-    uint8_t STSPIN820_GetTorque(uint8_t deviceId, motor_torque_mode_t torqueMode);
-    bool STSPIN820_GetTorqueBoostEnable(uint8_t deviceId);           //Get the torque boost feature status
-    uint16_t STSPIN820_GetTorqueBoostThreshold(uint8_t deviceId);    //Get the torque boost threshold
-    void STSPIN820_GoHome(uint8_t deviceId);                         //Move to the home position
-    void STSPIN820_GoMark(uint8_t deviceId);                         //Move to the Mark position
-    void STSPIN820_GoTo(uint8_t deviceId, int32_t targetPosition);   //Go to the specified position
-    void STSPIN820_GoToDir(uint8_t deviceId, motor_direction_t direction, int32_t targetPosition); //Go to the specified position using the specified direction
-    void STSPIN820_HardStop(uint8_t deviceId);                       //Stop the motor and keep holding torque
-    void STSPIN820_HardHiZ(uint8_t deviceId);                        //Stop the motor and disable the power bridge
-    void STSPIN820_Move(uint8_t deviceId, motor_direction_t direction, uint32_t stepCount); //Move the motor of the specified number of steps
-    void STSPIN820_PutDeviceInStandby(uint8_t deviceId);              //Put STSPIN820 device in standby (low power consumption)
-    void STSPIN820_Run(uint8_t deviceId, motor_direction_t direction);       //Run the motor 
-    bool STSPIN820_SetAcceleration(uint8_t deviceId,uint16_t newAcc); //Set the acceleration in pps^2
-    bool STSPIN820_SetDeceleration(uint8_t deviceId,uint16_t newDec); //Set the deceleration in pps^2
-    void STSPIN820_SetDecayMode(uint8_t deviceId, motor_decay_mode_t decay); //Set the STSPIN820 decay mode pin
-    void STSPIN820_SetDirection(uint8_t deviceId, motor_direction_t direction); //Set the STSPIN820 direction pin
-    void STSPIN820_SetHome(uint8_t deviceId);                         //Set current position to be the home position
-    void STSPIN820_SetMark(uint8_t deviceId);                         //Set current position to be the Markposition
-    bool STSPIN820_SetMaxSpeed(uint8_t deviceId,uint16_t newMaxSpeed);//Set the max speed in pps
-    bool STSPIN820_SetMinSpeed(uint8_t deviceId,uint16_t newMinSpeed);//Set the min speed in pps
+    //Start moving
+    void STSPIN820_StartMovement(void);
+    //Handle the step clock
+    void STSPIN820_StepClockHandler(void);
+    //Start the STSPIN820 library
+    status_t STSPIN820_Init(void *init);
+    //Read Id to get driver instance
+    status_t STSPIN820_ReadId(uint8_t *id);
+    //Attach a user callback to the error handler
+    void STSPIN820_AttachErrorHandler(void (*callback)(uint16_t));
+    //Attach a user callback to the flag Interrupt
+    void STSPIN820_AttachFlagInterrupt(void (*callback)(void));
+    //Check if STSPIN820 has a fault by reading EN pin position
+    uint8_t STSPIN820_CheckStatusHw(void);
+    //Disable the power stage of the specified device
+    void STSPIN820_Disable(void);
+    //Enable the power stage of the specified device
+    void STSPIN820_Enable(void);
+    //Error handler which calls the user callback
+    void STSPIN820_ErrorHandler(uint16_t error);
+    //Exit STSPIN820 device from standby 
+    void STSPIN820_ExitDeviceFromStandby(void);
+    //Return the acceleration in pps^2
+    uint16_t STSPIN820_GetAcceleration(void);
+    //Return the current speed in pps
+    uint16_t STSPIN820_GetCurrentSpeed(void);
+    //Return the device decay mode
+    motor_decay_mode_t STSPIN820_GetDecayMode(void);
+    //Return the deceleration in pps^2
+    uint16_t STSPIN820_GetDeceleration(void);
+    //Return the device state
+    motor_state_t STSPIN820_GetDeviceState(void);
+    //Get the motor current direction
+    motor_direction_t STSPIN820_GetDirection(void);
+    //Return the FW version
+    uint32_t STSPIN820_GetFwVersion(void);
+    //Return the mark position 
+    int32_t STSPIN820_GetMark(void);
+    //Return the max speed in pps
+    uint16_t STSPIN820_GetMaxSpeed(void);
+    //Return the min speed in pps
+    uint16_t STSPIN820_GetMinSpeed(void);
+    //Return the nupber of devices
+    uint8_t STSPIN820_GetNbDevices(void);
+    //Return the ABS_POSITION (32b signed)
+    int32_t STSPIN820_GetPosition(void);
+    //Get the motor step mode
+    motor_step_mode_t STSPIN820_GetStepMode(void);
+    //Get the selected mode to stop the motor
+    motor_stop_mode_t STSPIN820_GetStopMode(void);
+    //Get the torque
+    uint8_t STSPIN820_GetTorque(motor_torque_mode_t torqueMode);
+    //Get the torque boost feature status
+    bool STSPIN820_GetTorqueBoostEnable(void);
+    //Get the torque boost threshold
+    uint16_t STSPIN820_GetTorqueBoostThreshold(void);
+    //Move to the home position
+    void STSPIN820_GoHome(void);
+    //Move to the Mark position
+    void STSPIN820_GoMark(void);
+    //Go to the specified position
+    void STSPIN820_GoTo(int32_t targetPosition);
+    //Go to the specified position using the specified direction
+    void STSPIN820_GoToDir(motor_direction_t direction, int32_t targetPosition);
+    //Stop the motor and keep holding torque
+    void STSPIN820_HardStop(void);
+    //Stop the motor and disable the power bridge
+    void STSPIN820_HardHiZ(void);
+    //Move the motor of the specified number of steps
+    void STSPIN820_Move(motor_direction_t direction, uint32_t stepCount);
+    //Put STSPIN820 device in standby (low power consumption)
+    void STSPIN820_PutDeviceInStandby(void);
+    //Run the motor 
+    void STSPIN820_Run(motor_direction_t direction);
+    //Set the acceleration in pps^2
+    bool STSPIN820_SetAcceleration(uint16_t newAcc);
+    //Set the deceleration in pps^2
+    bool STSPIN820_SetDeceleration(uint16_t newDec);
+    //Set the STSPIN820 decay mode pin
+    void STSPIN820_SetDecayMode(motor_decay_mode_t decay);
+    //Set the STSPIN820 direction pin
+    void STSPIN820_SetDirection(motor_direction_t direction);
+    //Set current position to be the home position
+    void STSPIN820_SetHome(void);
+    //Set current position to be the mark position
+    void STSPIN820_SetMark(void);
+    //Set the max speed in pps
+    bool STSPIN820_SetMaxSpeed(uint16_t newMaxSpeed);
+    //Set the min speed in pps
+    bool STSPIN820_SetMinSpeed(uint16_t newMinSpeed);
+    //Set the number of devices
     bool STSPIN820_SetNbDevices(uint8_t nbDevices);
-    bool STSPIN820_SetStepMode(uint8_t deviceId, motor_step_mode_t stepMode); // Step mode selection
-    void STSPIN820_SetStopMode(uint8_t deviceId, motor_stop_mode_t stopMode); //Select the mode to stop the motor
-    void STSPIN820_SetTorque(uint8_t deviceId, motor_torque_mode_t torqueMode, uint8_t torqueValue);
-    void STSPIN820_SetTorqueBoostEnable(uint8_t deviceId, bool enable); // Enable or disable the torque boost feature
-    void STSPIN820_SetTorqueBoostThreshold(uint8_t deviceId, uint16_t speedThreshold); //Set the torque boost threshold
-    bool STSPIN820_SoftStop(uint8_t deviceId);                        //Progressively stop the motor by using the device deceleration and set deceleration torque
-    uint32_t STSPIN820_VrefPwmGetFreq(uint8_t deviceId);              //Get the frequency of REF PWM of the specified device
-    void STSPIN820_VrefPwmSetFreq(uint8_t deviceId, uint32_t newFreq);//Set the frequency of REF PWM of the specified device
-    void STSPIN820_WaitWhileActive(uint8_t deviceId);                 //Wait for the device state becomes Inactive
-
-
-    /*** Component's I/O Methods ***/
+    //Step mode selection
+    bool STSPIN820_SetStepMode(motor_step_mode_t stepMode);
+    //Select the mode to stop the motor
+    void STSPIN820_SetStopMode(motor_stop_mode_t stopMode);
+    //Set the torque
+    void STSPIN820_SetTorque(motor_torque_mode_t torqueMode, uint8_t torqueValue);
+    //Enable or disable the torque boost feature
+    void STSPIN820_SetTorqueBoostEnable(bool enable);
+    //Set the torque boost threshold
+    void STSPIN820_SetTorqueBoostThreshold(uint16_t speedThreshold);
+    //Progressively stop the motor by using the device deceleration and set deceleration torque
+    bool STSPIN820_SoftStop(void);
+    //Get the frequency of REF PWM of the specified device
+    uint32_t STSPIN820_VrefPwmGetFreq(void);
+    //Set the frequency of REF PWM of the specified device
+    void STSPIN820_VrefPwmSetFreq(uint32_t newFreq);
+    //Wait for the device state becomes Inactive
+    void STSPIN820_WaitWhileActive(void);
 
-    /**
-     * @brief      Utility function to read data from STSPIN820.
-     * @param[out] pBuffer pointer to the buffer to read data into.
-     * @param[in]  NumBytesToRead number of bytes to read.
-     * @retval     COMPONENT_OK in case of success, COMPONENT_ERROR otherwise.
-     */
-    status_t read(uint8_t* pBuffer, uint16_t NumBytesToRead)
-    {
-        if (dev_spi.spi_read(pBuffer, ssel, NumBytesToRead) != 0)
-            return COMPONENT_ERROR;
-        return COMPONENT_OK;
-    }
-    
-    /**
-     * @brief      Utility function to write data to STSPIN820.
-     * @param[in]  pBuffer pointer to the buffer of data to send.
-     * @param[in]  NumBytesToWrite number of bytes to write.
-     * @retval     COMPONENT_OK in case of success, COMPONENT_ERROR otherwise.
-     */
-    status_t write(uint8_t* pBuffer, uint16_t NumBytesToWrite)
-    {
-        if (dev_spi.spi_write(pBuffer, ssel, NumBytesToWrite) != 0)
-            return COMPONENT_ERROR;
-        return COMPONENT_OK;
-    }
-
-    /**
-     * @brief      Utility function to read and write data from/to STSPIN820 at the same time.
-     * @param[out] pBufferToRead pointer to the buffer to read data into.
-     * @param[in]  pBufferToWrite pointer to the buffer of data to send.
-     * @param[in]  NumBytes number of bytes to read and write.
-     * @retval     COMPONENT_OK in case of success, COMPONENT_ERROR otherwise.
-     */
-    status_t read_write(uint8_t* pBufferToRead, uint8_t* pBufferToWrite, uint16_t NumBytes)
-    {
-        if (dev_spi.spi_read_write(pBufferToRead, pBufferToWrite, ssel, NumBytes) != 0)
-            return COMPONENT_ERROR;
-        return COMPONENT_OK;
-    }
 
     /* ACTION 8 --------------------------------------------------------------*
      * Implement here other I/O methods beyond those already implemented      *
      * above, which are declared extern within the component's header file.   *
      *------------------------------------------------------------------------*/
-    void STSPIN820_Board_Delay(uint32_t delay)
+    /**
+     * @brief  Making the CPU wait.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_Delay(uint32_t delay)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        wait_ms(delay);
     }
 
-    void STSPIN820_Board_Disable(void)
+    /**
+     * @brief  Enabling the power bridges (leaving the output bridges at HiZ).
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_Enable_Power_Bridges(void)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        if (en_fault_irq.read() == 0)
+        {
+            //en_fault_irq.write(1);
+            wait_ms(BRIDGE_TURN_ON_DELAY_ms);
+            enable_en_fault_irq();
+        }
     }
 
-    void STSPIN820_Board_DisableIrq(void)
+    /**
+     * @brief  Disabling the power bridges (forcing the output bridges at HiZ).
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_Disable_Power_Bridges(void)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        disable_en_fault_irq();
+        //en_fault_irq.write(0);
     }
 
-    uint32_t STSPIN820_Board_EN_AND_FAULT_PIN_GetState(void)
+    /**
+     * @brief  Enabling interrupts.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_EnableIrq(void)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
-        return (uint32_t) 0;
+        __enable_irq();
     }
 
-    void STSPIN820_Board_Enable(void)
+    /**
+     * @brief  Disabling interrupts.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_DisableIrq(void)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        __disable_irq();
     }
 
-    void STSPIN820_Board_EnableIrq(void)
+    /**
+     * @brief  Getting the state of the EN_FAULT pin.
+     * @param  None.
+     * @retval None.
+     */
+    uint32_t STSPIN820_EN_FAULT_PIN_GetState(void)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        return (uint32_t) en_fault_irq;
     }
 
-    void STSPIN820_Board_GpioInit(void)
+    /**
+     * @brief  Initialising the GPIOs.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_GpioInit(void)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
-    }
-
-    void STSPIN820_Board_PwmRefInit(void)
-    {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        disable_en_fault_irq();
+        enable_en_fault_irq();
+        STSPIN820_Reset();
     }
 
-    void STSPIN820_Board_PwmRefSetFreqAndDutyCycle(uint32_t newFreq, uint8_t dutyCycle)
+    /**
+     * @brief  Initialising the PWM.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_PwmRefInit(void) {}
+
+    /**
+     * @brief  Setting the frequency and the duty-cycle of PWM.
+     *         The frequency controls directly the speed of the device.
+     *         The duty-cycle controls the torque of the device.
+     * @param  frequency  The frequency of PWM in Hz.
+     * @param  duty_cycle The duty-cycle of PWM in [0..100]%.
+     * @retval None.
+     */
+    void STSPIN820_PwmRefSetFreqAndDutyCycle(uint32_t frequency, uint8_t duty_cycle)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        pwm_period = (double) (1.0f / frequency);
+        pwm_duty_cycle = (double) duty_cycle;
     }
 
-    void STSPIN820_Board_PwmRefStart(void)
+    /**
+     * @brief  Starting the PWM.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_PwmRefStart(void)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        /* Setting the period and the duty-cycle of PWM. */
+        ref_pwm.period(pwm_period);
+        ref_pwm.write(pwm_duty_cycle);
+
+        /* Setting a callback with the same period of PWM's, to update the state machine. */
+        ticker.attach(Callback<void()>(this, &STSPIN820::STSPIN820_StepClockHandler), pwm_period);
     }
 
-    void STSPIN820_Board_PwmRefStop(void)
+    /**
+     * @brief  Stopping the PWM.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_PwmRefStop(void)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
-    }
-
-    void STSPIN820_Board_ReleaseReset(void)
-    {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        ref_pwm.write(0.0f);
+        ticker.detach();
     }
 
-    void STSPIN820_Board_Reset(void)
+    /**
+     * @brief  Putting the device in standby mode.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_ReleaseReset(void)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        standby_reset = 1;
     }
 
-    void STSPIN820_Board_SetDecayGpio(uint8_t gpioState)
+    /**
+     * @brief  Putting the device in reset mode.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_Reset(void)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        standby_reset = 0;
     }
 
-    uint8_t STSPIN820_Board_GetDecayGpio(void)
+    /**
+     * @brief  Setting the decay mode pin state.
+     * @param  gpio_state State of the decay mode pin ("0" to reset, "1" to set).
+     * @retval None.
+     */
+    void STSPIN820_SetDecayGpio(uint8_t gpio_state)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
-        return (uint8_t) 0;
+        decay = gpio_state;
     }
 
-    void STSPIN820_Board_SetDirectionGpio(uint8_t gpioState)
+    /**
+     * @brief  Getting the decay mode pin state.
+     * @param  None.
+     * @retval None.
+     */
+    uint8_t STSPIN820_GetDecayGpio(void)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        return (decay != 0 ? 1 : 0);
     }
 
-    void STSPIN820_Board_SetFullStep(void)
+    /**
+     * @brief  Setting the direction pin state.
+     * @param  gpio_state State of the direction pin ("0" to reset, "1" to set).
+     * @retval None.
+     */
+    void STSPIN820_SetDirectionGpio(uint8_t gpio_state)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        direction = gpio_state;
     }
 
-    bool STSPIN820_Board_SetModePins(uint8_t modePin1Level, uint8_t modePin2Level, uint8_t modePin3Level)
+    /**
+     * @brief  Setting the full step mode.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_SetFullStep(void)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
-        return (bool) 0;
+        mode1 = mode2 = mode3 = 0;
     }
 
-    void STSPIN820_Board_TimStckCompareInit(void)
-    {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
-    }
-
-    void STSPIN820_Board_TimStckDeInit(void)
+    /**
+     * @brief  Selecting the STSPIN820 mode1, mode2 and mode3 pins levels.
+     * @param  mode1_level Level of the mode1 gpio (0 low, 1+ high).
+     * @param  mode2_level Level of the mode2 gpio (0 low, 1+ high).
+     * @param  mode3_level Level of the mode3 gpio (0 low, 1+ high).
+     * @retval None.
+     */
+    void STSPIN820_SetModePins(uint8_t mode1_level, uint8_t mode2_level, uint8_t mode3_level)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
-    }
-
-    void STSPIN820_Board_TimStckInit(void)
-    {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        mode1 = (mode1_level != 0 ? 1 : 0);
+        mode2 = (mode2_level != 0 ? 1 : 0);
+        mode3 = (mode3_level != 0 ? 1 : 0);
     }
 
-    void STSPIN820_Board_TimStckSetFreq(uint16_t newFreq)
+    /**
+     * @brief  Initializing step clock compare value.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_TimStckCompareInit(void) {}
+
+    /**
+     * @brief  Deinitializing the timer used for the step clock.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_TimStckDeInit(void) {}
+
+    /**
+     * @brief  Initializing the timer used for the step clock.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_TimStckInit(void) {}
+
+    /**
+     * @brief  Setting the frequency of PWM.
+     *         The frequency controls directly the speed of the device.
+     * @param  frequency  The frequency of PWM in Hz.
+     * @retval None.
+     */
+    void STSPIN820_TimStckSetFreq(uint32_t frequency)
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
-    }
-
-    void STSPIN820_Board_TimStckStart(void)
-    {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        pwm_period = (double) (1.0f / frequency);
     }
 
-    uint8_t STSPIN820_Board_TimStckStop(uint8_t *pToggleOdd)
+    /**
+     * @brief  Starting the step clock.
+     * @param  None.
+     * @retval None.
+     */
+    void STSPIN820_TimStckStart(void) {}
+
+    /**
+     * @brief  Stopping the step clock.
+     * @param  p_toggle_odd Pointer to the volatile toggleOdd variable.
+     * @retval "1" if OK, "0" if the STCK pin is High (forbidden configuration).
+     */
+    uint8_t STSPIN820_TimStckStop(volatile uint8_t *p_toggle_odd )
     {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
-        return (uint8_t) 0;
-    }
-
-    void STSPIN820_Board_UnsetFullStep(void)
-    {
-        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */
+        __disable_irq();
+        if (*p_toggle_odd == 1)
+        {
+            __enable_irq();
+            return 1;
+        }
+        if (step_clock != 0)
+        {
+            __enable_irq();
+            return 0;
+        }
+        //HAL_TIM_OC_Stop_IT(&hTimerStepClock, BSP_MOTOR_CONTROL_BOARD_CHAN_TIM_STCK);
+        __enable_irq();
+        STSPIN820_TimStckDeInit();
+        return 1;
     }
 
 
@@ -713,6 +931,8 @@
      *   + mbed:                                                              *
      *     InterruptIn feature_irq;                                           *
      *------------------------------------------------------------------------*/
+    /* En Fault Interrupt. */
+    InterruptIn en_fault_irq;
 
     /* ACTION 10 -------------------------------------------------------------*
      * Declare here other pin related variables, if needed.                   *
@@ -721,6 +941,32 @@
      *   + mbed:                                                              *
      *     DigitalOut standby_reset;                                          *
      *------------------------------------------------------------------------*/
+    /* Standby/reset pin. */
+    DigitalOut standby_reset;
+
+    /* Direction of rotation pin. */
+    DigitalOut direction;
+
+    /* Pulse Width Modulation pin. */
+    PwmOut ref_pwm;
+
+    /* Decay pin. */
+    DigitalOut decay;
+    
+    /* Step clock pin. */
+    DigitalOut step_clock;
+    
+    /* Mode1 pin. */
+    DigitalOut mode1;
+    
+    /* Mode2 pin. */
+    DigitalOut mode2;
+    
+    /* Mode3 pin. */
+    DigitalOut mode3;
+
+    /* Timer to trigger the PWM callback at each PWM pulse. */
+    Ticker ticker;
 
     /* ACTION 11 -------------------------------------------------------------*
      * Declare here communication related variables, if needed.               *
@@ -730,11 +976,6 @@
      *     DigitalOut ssel;                                                   *
      *     DevSPI &dev_spi;                                                   *
      *------------------------------------------------------------------------*/
-    /* Configuration. */
-    DigitalOut ssel;
-
-    /* IO Device. */
-    DevSPI &dev_spi;
 
     /* ACTION 12 -------------------------------------------------------------*
      * Declare here identity related variables, if needed.                    *
@@ -753,12 +994,17 @@
      *   int instance_id;                                                     *
      *   static int number_of_instances;                                      *
      *------------------------------------------------------------------------*/
+    /* Data. */
     void (*flag_interrupt_callback)(void);
     void (*error_handler_callback)(uint16_t error);
-    uint8_t toggle_odd;
+    volatile uint8_t toggle_odd;
     device_params_t device_prm;
-    uint8_t number_of_devices;
+    double pwm_period;
+    double pwm_duty_cycle;
     uint8_t device_instance;
+    
+    /* Static data. */
+    static uint8_t number_of_devices;
 };
 
 #endif /* __STSPIN820_CLASS_H */