Library to handle the X-NUCLEO-IHM06A1 Motor Control Expansion Board based on the STSPIN220 component.

Dependencies:   ST_INTERFACES

Dependents:   HelloWorld_IHM06A1

Fork of X-NUCLEO-IHM06A1 by ST Expansion SW Team

Motor Control Library

Library to handle the X-NUCLEO-IHM06A1 Motor Control Expansion Board based on the STSPIN220 component.

It features the:

  • Read and write of the device parameters; GPIO, PWM and IRQ configuration; microstepping, direction position, speed, acceleration, deceleration and torque controls
  • Automatic full-step switch management; high impedance or hold stop mode selection; enable and standby management
  • Fault interrupts handling (over current, short-circuit and over temperature)
  • Command locking until the device completes movement

The API allows to easily:

  • perform various positioning, moves and stops
  • get/set or monitor the motor positions
  • set the home position and mark another position
  • get/set the minimum and maximum speed
  • get the current speed
  • get/set the acceleration and deceleration
  • get/set the stop mode (hold, hiz or standby)
  • get/set the torque
  • get/set the torque boost
  • get/set the step mode (up to 1/256)

Platform compatibility

Compatible platforms have been tested with the configurations provided by the HelloWorld_IHM06A1 example.

Components/STSpin220/STSpin220.h

Committer:
Davidroid
Date:
2017-07-28
Revision:
5:fd1315beea32
Parent:
4:265c30b9112a

File content as of revision 5:fd1315beea32:

/**
 ******************************************************************************
 * @file    STSpin220.h
 * @author  IPC Rennes
 * @version V1.0.0
 * @date    July 27th, 2016
 * @brief   This file contains the class of a STSpin220 Motor Control component.
 * @note    (C) COPYRIGHT 2016 STMicroelectronics
 ******************************************************************************
 * @attention
 *
 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
 *
 * Redistribution and use in source and binary forms, with or without modification,
 * are permitted provided that the following conditions are met:
 *   1. Redistributions of source code must retain the above copyright notice,
 *      this list of conditions and the following disclaimer.
 *   2. Redistributions in binary form must reproduce the above copyright notice,
 *      this list of conditions and the following disclaimer in the documentation
 *      and/or other materials provided with the distribution.
 *   3. Neither the name of STMicroelectronics nor the names of its contributors
 *      may be used to endorse or promote products derived from this software
 *      without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 *
 ******************************************************************************
 */


/* Define to prevent recursive inclusion -------------------------------------*/

#ifndef __STSPIN220_CLASS_H
#define __STSPIN220_CLASS_H


/* Includes ------------------------------------------------------------------*/

/* ACTION 1 ------------------------------------------------------------------*
 * Include here platform specific header files.                               *
 *----------------------------------------------------------------------------*/        
#include "mbed.h"

/* ACTION 2 ------------------------------------------------------------------*
 * Include here component specific header files.                              *
 *----------------------------------------------------------------------------*/        
#include "STSpin220_def.h"
/* ACTION 3 ------------------------------------------------------------------*
 * Include here interface specific header files.                              *
 *                                                                            *
 * Example:                                                                   *
 *   #include "HumiditySensor.h"                                              *
 *   #include "TemperatureSensor.h"                                           *
 *----------------------------------------------------------------------------*/
#include "StepperMotor.h"


/* Classes -------------------------------------------------------------------*/

/**
 * @brief Class representing a STSpin220 component.
 */
class STSpin220 : public StepperMotor
{
public:
    /*** Constructor and Destructor Methods ***/
    /**
     * @brief Constructor.
     * @param fault_and_enable_pin  pin name of the EN\FAULT pin of the component.
     * @param stby_reset_pin        pin name of the STBY\RESET pin of the component.
     * @param direction_mode4_pin   pin name of the MODE4\DIR pin of the component.
     * @param mode1_pin             pin name of the MODE1 pin of the component.
     * @param mode2_pin             pin name of the MODE2 pin of the component.
     * @param stck_mode3_pin        pin name of the MODE3\STCK pin of the component.
     * @param pwm_ref_pin           pin name of the PWM connected to the REF pin of the component.
     * @param Monitor_pin           pin name for the step clock handler duration Monitoring.
     */
    STSpin220(PinName fault_and_enable_pin,
              PinName stby_reset_pin,
              PinName direction_mode4_pin,
              PinName mode1_pin,
              PinName mode2_pin,
              PinName stck_mode3_pin,
              PinName pwm_ref_pin,
              PinName monitor_pin = NC) : StepperMotor(),
                                     fault_and_enable(fault_and_enable_pin),
                                     stby_reset(stby_reset_pin),
                                     direction_mode4(direction_mode4_pin),
                                     mode1(mode1_pin),
                                     mode2(mode2_pin),
                                     stck_mode3(stck_mode3_pin),
                                     pwm_ref(pwm_ref_pin),
                                     monitor(monitor_pin)
    {
        /* Checking stackability. */
        if (numberOfDevices!=0)
        {
            error("Instantiation of the STSpin220 component failed: it can't be stacked on itself.\r\n");
        }

        /* ACTION 4 ----------------------------------------------------------*
         * Initialize here the component's member variables, one variable per *
         * line.                                                              *
         *                                                                    *
         * Example:                                                           *
         *   measure = 0;                                                     *
         *   instance_id = number_of_instances++;                             *
         *--------------------------------------------------------------------*/
        errorHandlerCallback = 0;
        memset(&devicePrm, 0, sizeof(devicePrm));
        deviceInstance = numberOfDevices++;
        
        fault_and_enable_pinName = fault_and_enable_pin;
    }
    
    /**
     * @brief Destructor.
     */
    virtual ~STSpin220(void) {}
    

    /*** Public Component Related Methods ***/

    /* ACTION 5 --------------------------------------------------------------*
     * Implement here the component's public methods, as wrappers of the C    *
     * component's functions.                                                 *
     * They should be:                                                        *
     *   + Methods with the same name of the C component's virtual table's    *
     *     functions (1);                                                     *
     *   + Methods with the same name of the C component's extended virtual   *
     *     table's functions, if any (2).                                     *
     *                                                                        *
     * Example:                                                               *
     *   virtual int get_value(float *pData) //(1)                            *
     *   {                                                                    *
     *     return COMPONENT_get_value(float *pfData);                         *
     *   }                                                                    *
     *                                                                        *
     *   virtual int enable_feature(void) //(2)                               *
     *   {                                                                    *
     *     return COMPONENT_enable_feature();                                 *
     *   }                                                                    *
     *------------------------------------------------------------------------*/

    /**
     * @brief Public functions inherited from the Component Class
     */

    /**
     * @brief  Initialize the component.
     * @param  init Pointer to device specific initalization structure.
     * @retval "0" in case of success, an error code otherwise.
     */
    virtual int init(void *init = NULL)
    {
        return (int) STSpin220_Init((void *) init);
    }

    /**
     * @brief  Getting the ID of the component.
     * @param  id Pointer to an allocated variable to store the ID into.
     * @retval "0" in case of success, an error code otherwise.
     */
    virtual int read_id(uint8_t *id = NULL)
    {
        return (int) STSpin220_ReadID((uint8_t *) id);
    }

    /**
     * @brief Public functions inherited from the StepperMotor Class
     */

    /**
     * @brief  Getting the value of the motor state .
     * @param  None.
     * @retval The motor state accoring to motorState_t in motor.h
     */
    virtual unsigned int get_status(void)
    {
        return (unsigned int) STSpin220_get_device_state();
    }

    /**
     * @brief  Getting the position.
     * @param  None.
     * @retval The position.
     */
    virtual signed int get_position(void)
    {
        return (signed int)STSpin220_GetPosition();
    }

    /**
     * @brief  Getting the marked position.
     * @param  None.
     * @retval The marked position.
     */
    virtual signed int get_mark(void)
    {
        return (signed int)STSpin220_GetMark();
    }

    /**
     * @brief  Getting the current speed in pps.
     * @param  None.
     * @retval The current speed in pps.
     */
    virtual unsigned int get_speed(void)
    {
        return (unsigned int)STSpin220_GetCurrentSpeed();
    }

    /**
     * @brief  Getting the maximum speed in pps.
     * @param  None.
     * @retval The maximum speed in pps.
     */
    virtual unsigned int get_max_speed(void)
    {
        return (unsigned int)STSpin220_GetMaxSpeed();
    }

    /**
     * @brief  Getting the minimum speed in pps.
     * @param  None.
     * @retval The minimum speed in pps.
     */
    virtual unsigned int get_min_speed(void)
    {
        return (unsigned int)STSpin220_GetMinSpeed();
    }

    /**
     * @brief  Getting the acceleration in pps^2.
     * @param  None.
     * @retval The acceleration in pps^2.
     */
    virtual unsigned int get_acceleration(void)
    {
        return (unsigned int)STSpin220_GetAcceleration();
    }

    /**
     * @brief  Getting the deceleration in pps^2.
     * @param  None.
     * @retval The deceleration in pps^2.
     */
    virtual unsigned int get_deceleration(void)
    {
        return (unsigned int)STSpin220_GetDeceleration();
    }
    
    /**
     * @brief  Getting the direction of rotation.
     * @param  None.
     * @retval The direction of rotation.
     */
    virtual direction_t get_direction(void)
    {
        if (STSpin220_GetDirection()!=BACKWARD)
        {
            return FWD;
        }
        else
        {
            return BWD;
        }
    }
    
    /**
     * @brief  Setting the current position to be the home position.
     * @param  None.
     * @retval None.
     */
    virtual void set_home(void)
    {
        STSpin220_SetHome();
    }

    /**
     * @brief  Setting the current position to be the marked position.
     * @param  None.
     * @retval None.
     */
    virtual void set_mark(void)
    {
        STSpin220_SetMark();
    }

    /**
     * @brief  Setting the maximum speed in pps.
     * @param  speed The maximum speed in pps.
     * @retval "true" in case of success, "false" otherwise.
     */
    virtual bool set_max_speed(unsigned int speed)
    {
        if (speed <= 0xFFFF)
        {
            return STSpin220_SetMaxSpeed((uint16_t) speed);
        }
        else
        {
            return false;
        }
    }

    /**
     * @brief  Setting the minimum speed in pps.
     * @param  speed The minimum speed in pps.
     * @retval "true" in case of success, "false" otherwise.
     */
    virtual bool set_min_speed(unsigned int speed)
    {
        if (speed <= 0xFFFF)
        {
            return STSpin220_SetMinSpeed((uint16_t) speed);
        }
        else
        {
            return false;
        }
    }

    /**
     * @brief  Setting the acceleration in pps^2.
     * @param  acceleration The acceleration in pps/s^2.
     * @retval "true" in case of success, "false" otherwise.
     */
    virtual bool set_acceleration(unsigned int acceleration)
    {
        if (acceleration <= 0xFFFF)
        {
            return STSpin220_SetAcceleration((uint16_t) acceleration);
        }
        else
        {
            return false;
        }
    }

    /**
     * @brief  Setting the deceleration in pps^2.
     * @param  deceleration The deceleration in pps^2.
     * @retval "true" in case of success, "false" otherwise.
     */
    virtual bool set_deceleration(unsigned int deceleration)
    {
        if (deceleration <= 0xFFFF)
        {
            return STSpin220_SetDeceleration((uint16_t) deceleration);
        }
        else
        {
            return false;
        }
    }

    /**
     * @brief  Setting the Step Mode.
     * @param  step_mode The Step Mode.
     * @retval "true" in case of success, "false" otherwise.
     * @note   step_mode can be one of the following:
     *           + STEP_MODE_FULL
     *           + STEP_MODE_WAVE
     *           + STEP_MODE_HALF
     *           + STEP_MODE_1_4
     *           + STEP_MODE_1_8
     *           + STEP_MODE_1_16
     */
    virtual bool set_step_mode(step_mode_t step_mode)
    {
        return STSpin220_SetStepMode((motorStepMode_t) step_mode);
    }

    /**
     * @brief  Going to a specified position.
     * @param  position The desired position.
     * @retval None.
     */
    virtual void go_to(signed int position)
    {
        STSpin220_GoTo((int32_t)position);
    }

    /**
     * @brief  Going to the home position.
     * @param  None.
     * @retval None.
     */
    virtual void go_home(void)
    {
        STSpin220_GoHome();
    }

    /**
     * @brief  Going to the marked position.
     * @param  None.
     * @retval None.
     */
    virtual void go_mark(void)
    {
        STSpin220_GoMark();
    }

    /**
     * @brief  Running the motor towards a specified direction.
     * @param  direction The direction of rotation.
     * @retval None.
     */
    virtual void run(direction_t direction)
    {
        STSpin220_Run((motorDir_t) (direction == StepperMotor::FWD ? FORWARD : BACKWARD));
    }

    /**
     * @brief  Moving the motor towards a specified direction for a certain number of steps.
     * @param  direction The direction of rotation.
     * @param  steps The desired number of steps.
     * @retval None.
     */
    virtual void move(direction_t direction, unsigned int steps)
    {
        STSpin220_Move((motorDir_t) (direction == StepperMotor::FWD ? FORWARD : BACKWARD), (uint32_t)steps);
    }

    /**
     * @brief  Stopping the motor through an immediate deceleration up to zero speed.
     * @param  None.
     * @retval None.
     */
    virtual void soft_stop(void)
    {
        STSpin220_SoftStop();
    }

    /**
     * @brief  Stopping the motor through an immediate infinite deceleration.
     * @param  None.
     * @retval None.
     */
    virtual void hard_stop(void)
    {
        STSpin220_HardStop();
    }

    /**
     * @brief  Disabling the power bridge after performing a deceleration to zero.
     * @param  None.
     * @retval None.
     */
    virtual void soft_hiz(void)
    {
        STSpin220_SetStopMode(HIZ_MODE);
        STSpin220_SoftStop();
    }

    /**
     * @brief  Disabling the power bridge immediately.
     * @param  None.
     * @retval None.
     */
    virtual void hard_hiz(void)
    {
        STSpin220_HardHiZ();
    }

    /**
     * @brief  Waiting while the motor is active.
     * @param  None.
     * @retval None.
     */
    virtual void wait_while_active(void)
    {
        STSpin220_WaitWhileActive();
    }  

    /**
     * @brief Public functions NOT inherited
     */
     
    /**
     * @brief  Attaching an error handler.
     * @param  fptr An error handler.
     * @retval None.
     */
    virtual void attach_error_handler(void (*fptr)(uint16_t error))
    {
        STSpin220_AttachErrorHandler((void (*)(uint16_t error)) fptr);
    }

    /**
     * @brief  Checks if the device is disabled or/and has an alarm flag set 
     * by reading the EN FAULT pin position.
     * @param  None.
     * @retval One if the EN FAULT pin is low (the device is disabled or/and 
     * has an alarm flag set), otherwise zero.
     */
    virtual unsigned int check_status_hw(void)
    {
        if (!fault_and_enable.read()) return 0x01;
        else return 0x00;
    }
    
    /**
     * @brief  Disabling the device.
     * @param  None.
     * @retval None.
     */
    virtual void disable(void)
    {
        STSpin220_Disable();
    }
    
    /**
     * @brief  Enabling the device.
     * @param  None.
     * @retval None.
     */
    virtual void enable(void)
    {
        STSpin220_Enable();
    }
    
    /**
     * @brief  Exit STSpin220 device from standby (low power consumption) by
     * setting STBY\RESET pin to high level and changing the motion state to
     * INACTIVE.
     * @param  None.
     * @retval None.
     */    
    virtual void exit_device_from_standby(void)
    {
        STSpin220_ExitDeviceFromStandby();
    }
    
    /**
     * @brief  Set the frequency of the VREFA and VREFB PWM
     * @param  frequency in Hz
     * @retval None.
     */  
    virtual uint32_t get_freq_vref_pwm(void)
    {
        return STSpin220_VrefPwmGetFreq();
    }    
    
    /**
     * @brief  Getting the version of the firmware.
     * @param  None.
     * @retval The version of the firmware.
     */
    virtual unsigned int get_fw_version(void)
    {
        return (unsigned int) STSpin220_GetFwVersion();
    }
    
    /**
     * @brief  Getting the motor step mode.
     * @param  None.
     * @retval The motor step mode.
     */
    virtual step_mode_t get_step_mode(void)
    {
      return (step_mode_t) STSpin220_GetStepMode();
    }
    
    /**
     * @brief  Getting the motor stop mode.
     * @param  None.
     * @retval The motor stop mode.
     */  
    virtual motorStopMode_t get_stop_mode(void)
    {
      return STSpin220_GetStopMode();
    }
    
    /**
     * @brief  Get the motor torque.
     * @param  torqueMode Torque mode as specified in enum motorTorqueMode_t
     * @retval the torqueValue in % (from 0 to 100)
     */       
    virtual uint8_t get_torque(motorTorqueMode_t torqueMode)
    {
        return STSpin220_GetTorque(torqueMode);
    }
    
    /**
     * @brief  Get the torque boost feature status.
     * @param  None.
     * @retval true if enabled, false if disabled
     */       
    virtual bool get_torque_boost_enable(void)
    {
        return STSpin220_GetTorqueBoostEnable();
    }
    
    /**
     * @brief  Get the torque boost threshold
     * @retval The torque boost threshold above which the step mode is
     * changed to full step
     */       
    virtual uint16_t get_torque_boost_threshold(void)
    {
        return STSpin220_GetTorqueBoostThreshold();
    }
    
    /**
     * @brief  Going to a specified position with a specificied direction.
     * @param  direction The desired direction.
     * @param  position The desired position.
     * @retval None.
     */
    virtual void go_to(direction_t direction, signed int position)
    {
        STSpin220_GoToDir((motorDir_t) (direction == StepperMotor::FWD ? FORWARD : BACKWARD),(int32_t)position);
    }

    /**
     * @brief  Put STSpin220 device in standby (low power consumption) by 
     * setting STBY\RESET pin to low level and changing the motion state to
     * STANDBY.
     * @param  None.
     * @retval None.
     */    
    virtual void put_device_in_standby(void)
    {
        STSpin220_PutDeviceInStandby();
    }

    /**
     * @brief  Release the STSpin220 reset (Reset pin set to high level).
     * @param  None.
     * @retval None.
     */    
    virtual void release_reset(void)
    {
        STSpin220_Board_ReleaseReset();
    }
    
    /**
     * @brief  Reset the STSpin220 (Reset pin set to low level).
     * @param  None.
     * @retval None.
     */    
    virtual void reset(void)
    {
        STSpin220_Board_Reset();
    }

    /**
     * @brief  Set the motor direction.
     * @param  direction The desired direction.
     * @retval None.
     */
    virtual void set_direction(direction_t direction)
    { 
        STSpin220_SetDirection((motorDir_t) (direction == StepperMotor::FWD ? FORWARD : BACKWARD));
    }

    /**
     * @brief  Set the frequency of the PWM for REF pin
     * @param  frequency in Hz
     * @retval None.
     */  
    virtual void set_freq_vref_pwm(uint32_t frequency)
    {
        STSpin220_VrefPwmSetFreq(frequency);
    }

    /**
     * @brief  Set the motor stop mode.
     * @param  stopMode The desired stop mode (HOLD_MODE, HIZ_MODE or
     * STANDBY_MODE).
     * @retval None.
     */       
    virtual void set_stop_mode(motorStopMode_t stopMode)
    {
        STSpin220_SetStopMode(stopMode);
    }

    /**
     * @brief  Set the motor torque.
     * @param  torqueMode Torque mode as specified in enum motorTorqueMode_t
     * @param  torqueValue in % (from 0 to 100)
     * @retval None.
     */       
    virtual void set_torque(motorTorqueMode_t torqueMode, uint8_t torqueValue)
    {
        STSpin220_SetTorque(torqueMode, torqueValue);
    }

    /**
     * @brief  Enable or disable the motor torque boost feature.
     * @param  enable enable true to enable torque boost, false to disable
     * @retval None.
     */       
    virtual void set_torque_boost_enable(bool enable)
    {
        STSpin220_SetTorqueBoostEnable(enable);
    }
    
    /**
     * @brief Set the torque boost threshold
     * @param[in] speedThreshold speed threshold above which the step mode is
     * changed to full step
     * @retval None.
     */       
    virtual void set_torque_boost_threshold(uint16_t speedThreshold)
    {
        STSpin220_SetTorqueBoostThreshold(speedThreshold);
    }

    /*** Public Interrupt Related Methods ***/

    /* ACTION 6 --------------------------------------------------------------*
     * Implement here interrupt related methods, if any.                      *
     * Note that interrupt handling is platform dependent, e.g.:              *
     *   + mbed:                                                              *
     *     InterruptIn feature_irq(pin); //Interrupt object.                  *
     *     feature_irq.rise(callback);   //Attach a callback.                 *
     *     feature_irq.mode(PullNone);   //Set interrupt mode.                *
     *     feature_irq.enable_irq();     //Enable interrupt.                  *
     *     feature_irq.disable_irq();    //Disable interrupt.                 *
     *   + Arduino:                                                           *
     *     attachInterrupt(pin, callback, RISING); //Attach a callback.       *
     *     detachInterrupt(pin);                   //Detach a callback.       *
     *                                                                        *
     * Example (mbed):                                                        *
     *   void attach_feature_irq(void (*fptr) (void))                         *
     *   {                                                                    *
     *     feature_irq.rise(fptr);                                            *
     *   }                                                                    *
     *                                                                        *
     *   void enable_feature_irq(void)                                        *
     *   {                                                                    *
     *     feature_irq.enable_irq();                                          *
     *   }                                                                    *
     *                                                                        *
     *   void disable_feature_irq(void)                                       *
     *   {                                                                    *
     *     feature_irq.disable_irq();                                         *
     *   }                                                                    *
     *------------------------------------------------------------------------*/
    /**
     * @brief  Attaching an interrupt handler to the FLAG interrupt.
     * @param  fptr An interrupt handler.
     * @retval None.
     */
     
    void attach_flag_irq(void (*fptr)(void))
    {
        fault_and_enable_irqFunctionPointer = &(*fptr);
        fault_and_enable.fall(fptr);
        fault_and_enable.mode(PullDown);
        wait_ms(1);
    }
    
    /**
     * @brief  Enabling the FLAG interrupt handling.
     * @param  None.
     * @retval None.
     */
    void enable_flag_irq(void)
    {
        fault_and_enable.enable_irq();
    }
    
protected:

    /*** Protected Component Related Methods ***/

    /* ACTION 7 --------------------------------------------------------------*
     * Declare here the component's specific methods.                         *
     * They should be:                                                        *
     *   + Methods with the same name of the C component's virtual table's    *
     *     functions (1);                                                     *
     *   + Methods with the same name of the C component's extended virtual   *
     *     table's functions, if any (2);                                     *
     *   + Helper methods, if any, like functions declared in the component's *
     *     source files but not pointed by the component's virtual table (3). *
     *                                                                        *
     * Example:                                                               *
     *   status_t COMPONENT_get_value(float *f);   //(1)                      *
     *   status_t COMPONENT_enable_feature(void);  //(2)                      *
     *   status_t COMPONENT_compute_average(void); //(3)                      *
     *------------------------------------------------------------------------*/
    status_t STSpin220_Init(void *init);
    status_t STSpin220_ReadID(uint8_t *id);
    void STSpin220_AttachErrorHandler(void (*callback)(uint16_t error));
    void STSpin220_ApplyTorque(motorTorqueMode_t torqueMode);
    void STSpin220_Disable(void);
    void STSpin220_ErrorHandler(uint16_t error);
    void STSpin220_Enable(void);
    void STSpin220_ExitDeviceFromStandby(void);
    uint16_t STSpin220_GetAcceleration(void);
    uint16_t STSpin220_GetCurrentSpeed(void);
    uint16_t STSpin220_GetDeceleration(void);
    motorState_t STSpin220_get_device_state(void);
    motorDir_t STSpin220_GetDirection(void);
    uint32_t STSpin220_GetFwVersion(void);
    int32_t STSpin220_GetMark(void);
    uint16_t STSpin220_GetMaxSpeed(void);
    uint16_t STSpin220_GetMinSpeed(void);
    int32_t STSpin220_GetPosition(void);
    motorStepMode_t STSpin220_GetStepMode(void);
    motorStopMode_t STSpin220_GetStopMode(void);
    uint8_t STSpin220_GetTorque(motorTorqueMode_t torqueMode);
    bool STSpin220_GetTorqueBoostEnable(void);
    uint16_t STSpin220_GetTorqueBoostThreshold(void);
    void STSpin220_GoHome(void);  
    void STSpin220_GoMark(void);
    void STSpin220_GoTo(int32_t targetPosition);
    void STSpin220_GoToDir(motorDir_t direction, int32_t targetPosition);   
    void STSpin220_HardHiZ(void);
    void STSpin220_HardStop(void);
    void STSpin220_Move(motorDir_t direction, uint32_t stepCount);
    void STSpin220_PutDeviceInStandby(void);
    void STSpin220_Run(motorDir_t direction);
    bool STSpin220_SetAcceleration(uint16_t newAcc);
    bool STSpin220_SetDeceleration(uint16_t newDec);
    void STSpin220_SetDirection(motorDir_t direction);
    void STSpin220_SetHome(void);
    void STSpin220_SetMark(void);
    bool STSpin220_SetMaxSpeed(uint16_t volatile newSpeed);
    bool STSpin220_SetMinSpeed(uint16_t volatile newSpeed);    
    bool STSpin220_SetStepMode(motorStepMode_t stepMode);
    void STSpin220_SetStopMode(motorStopMode_t stopMode);
    bool STSpin220_SoftStop(void);
    void STSpin220_SetTorque(motorTorqueMode_t torqueMode, uint8_t torqueValue);
    void STSpin220_SetTorqueBoostEnable(bool enable);
    void STSpin220_SetTorqueBoostThreshold(uint16_t speedThreshold);
    uint32_t STSpin220_VrefPwmGetFreq(void);
    void STSpin220_VrefPwmSetFreq(uint32_t newFreq);
    void STSpin220_WaitWhileActive(void);
    
    /*** Functions intended to be used only internally ***/
    void STSpin220_ApplySpeed(uint16_t newSpeed);
    void STSpin220_ComputeSpeedProfile(uint32_t nbSteps);    
    void STSpin220_SetDeviceParamsToGivenValues(STSpin220_init_t* pInitDevicePrm);
    void STSpin220_SetDeviceParamsOtherValues(void);    
    void STSpin220_SetDeviceParamsToPredefinedValues(void);
    bool STSpin220_SetStepModeWithoutReset(motorStepMode_t stepMode);
    void STSpin220_StartMovement(void);
    void STSpin220_StepClockHandler(void);
    
    /*** Component's I/O Methods ***/

    /* ACTION 8 --------------------------------------------------------------*
     * Implement here other I/O methods beyond those already implemented      *
     * above, which are declared extern within the component's header file.   *
     *------------------------------------------------------------------------*/
    /**
     * @brief  Making the CPU wait.
     * @param  None.
     * @retval None.
     */
    void STSpin220_Board_Delay(uint32_t delay)
    {
        wait_ms(delay);
    }
    
    /**
     * @brief  Disable the power bridges (leave the output bridges HiZ).
     * @param  None.
     * @retval None.
     */
    void STSpin220_Board_Disable(void)
    {
        fault_and_enable.disable_irq();
        DigitalOut fault_and_enable(fault_and_enable_pinName);
        fault_and_enable.write(0);
    }

    /**
     * @brief  Disabling interrupts.
     * @param  None.
     * @retval None.
     */
    void STSpin220_Board_DisableIrq(void)
    {
        __disable_irq();
    }
    
    /**
     * @brief  Enable the power bridges (leave the output bridges HiZ).
     * @param  None.
     * @retval None.
     */
    void STSpin220_Board_Enable(void)
    {
        DigitalOut fault_and_enable_do(fault_and_enable_pinName);
        fault_and_enable_do.write(1);
        fault_and_enable.fall(fault_and_enable_irqFunctionPointer);
        fault_and_enable.mode(PullUp);
        wait_ms(1);
        fault_and_enable.enable_irq();
    }
    
    /**
     * @brief  Enabling interrupts.
     * @param  None.
     * @retval None.
     */
    void STSpin220_Board_EnableIrq(void)
    {
        __enable_irq();
    }

    /**
     * @brief  Set the duty cycle of the PwmOut used for the REF
     * reference voltage generation and actually start the pwm if the duty cycle
     * is not zero.
     * @param[in] dutyCycle 0 - 100%
     * @retval None
     */
    void STSpin220_Board_PwmRefSetDutyCycle(uint8_t dutyCycle)
    {
        pwm_ref.write(((float)(100-dutyCycle))/100);
    }

    /**
     * @brief  Set the frequency of the PwmOut used for the REF
     * reference voltage generation.
     * @param[in] newFreq in Hz.
     * @retval None.
     */
    void STSpin220_Board_PwmRefSetFreq(uint32_t newFreq)
    {
        pwm_ref.period_us(1000000.0f/newFreq);
    }
    
    /**
     * @brief  Start the PwmOut for the REF pin.
     * @param[in] frequency frequency of the PwmOut used to generate the REF
     * reference voltage for the bridges.
     * @param[in] torqueMode Torque mode as specified in enum motorTorqueMode_t    
     * @retval None.
     */ 
    void STSpin220_Board_PwmRefStart(uint32_t frequency, motorTorqueMode_t torqueMode)
    { 
        /* Setting the period of the PwmOut. */
        pwm_ref.period_us(1000000.0f/frequency);
        /* Setting the duty cycle and actually starting the of the PwmOut. */
        STSpin220_ApplyTorque(torqueMode);
        wait_ms(5*PWM_FILTER_TIME_CONSTANT);
    }

    /**
     * @brief  Exit the device from standby reset mode.
     * @param  None.
     * @retval None.
     */
    void STSpin220_Board_ReleaseReset(void)
    {
        stby_reset = 1;
    }

    /**
     * @brief  Put the device in standby reset mode.
     * @param  None.
     * @retval None.
     */
    void STSpin220_Board_Reset(void)
    {
        stby_reset = 0;
    }

    /**
     * @brief  Set the DIR\MODE4 pin.
     * @param  dir motor direction FORWARD or BACKWARD.
     * @retval None.
     */
    void STSpin220_Board_SetDirectionGpio(motorDir_t dir)
    {
        if (dir==BACKWARD)
        {
            direction_mode4 = 0;
        }
        else
        {
            direction_mode4 = 1;
        }
    }
 
    /**
     * @brief Select Full Step mode
     * @param  None.
     * @retval None
     */
    void STSpin220_Board_SetFullStep(void)
    {
        mode1 = 0;
        mode2 = 0;
    }
    
    /**
     * @brief Select the STSpin220 mode1, mode2, mode3 and mode4 pins levels.
     * @param[in] modePin1Level level of the mode1 gpio (0 low, 1+ high)
     * @param[in] modePin2Level level of the mode2 gpio (0 low, 1+ high)
     * @param[in] modePin3Level level of the mode3 gpio (0 low, 1+ high)
     * @param[in] modePin4Level level of the mode4 gpio (0 low, 1+ high)
     * @retval 1
     */
    uint8_t STSpin220_Board_SetModePins(uint8_t modePin1Level,\
        uint8_t modePin2Level,\
        uint8_t modePin3Level,\
        uint8_t modePin4Level)
    {
        mode1 = modePin1Level;
        mode2 = modePin2Level;
        stck_mode3 = modePin3Level;
        direction_mode4 = modePin4Level;
        return 1;
    }

    /**
     * @brief  Reset the STCK\MODE3 pin.
     * @param  None.
     * @retval None.
     */
    void STSpin220_Board_StckMode3_Reset(void)
    {
        stck_mode3 = 0;
    }

    /**
     * @brief  Set the STCK\MODE3 pin.
     * @param  None.
     * @retval None.
     */
    void STSpin220_Board_StckMode3_Set(void)
    {
        stck_mode3 = 1;
    }

    /**
     * @brief Initialises the step clock pin level
     * @param  None.
     * @retval None
     */
    void STSpin220_Board_TimStckInit(bool check)
    {
        if (monitor.is_connected())
        {
            monitor = 0;
        }
        if (check==false)
        {
            stck_mode3 = 0;
        }
        else
        {
            if (stck_mode3==1)
            {
                STSpin220_ErrorHandler(STSPIN220_ERROR_STEP_CLOCK);
            }
        }
    }

    /**
     * @brief  Setting the Stck Timeout delay
     * and attaching a callback function to it.
     * @param  frequency The frequency corresponding to the delay.
     * @retval None.
     */
    void STSpin220_Board_TimStckSetFreq(uint16_t newFreq)
    {
        /* Computing the delay of the Timeout. */
        float delay_us = (1000000.0f / 2 )/ newFreq;
        
        /* Attaching a function which updates */
        /* the state machine after the elapsed period_us time. */
        tim_stck.attach_us(this, &STSpin220::STSpin220_StepClockHandler, delay_us);
    }

    void STSpin220_Board_Monitor_Set(void)
    {
        if (monitor.is_connected())
        {
            monitor = 1;
        }
    }
    
    void STSpin220_Board_Monitor_Reset(void)
    {
        if (monitor.is_connected())
        {
            monitor = 0;
        }
    }

    /**
     * @brief  Stopping the Timeout.
     * @param  None.
     * @retval None.
     */
    uint8_t STSpin220_Board_TimStckStop(volatile uint8_t *pToggleOdd)
    {
        __disable_irq();
        if (*pToggleOdd == 1)
        {
            __enable_irq();
            return 1;
        }
        if (stck_mode3 != 0)
        {
            __enable_irq();
            return 0;
        }
        tim_stck.detach();
        __enable_irq();
        return 1;
    }

    /**
     * @brief Unselect Full Step mode
     * @param  None.
     * @retval None
     */
    void STSpin220_Board_UnsetFullStep(void)
    {
        mode1 = 1;
    }

protected:

    /*** Component's Instance Variables ***/

    /* ACTION 9 --------------------------------------------------------------*
     * Declare here interrupt related variables, if needed.                   *
     * Note that interrupt handling is platform dependent, see                *
     * "Interrupt Related Methods" above.                                     *
     *                                                                        *
     * Example:                                                               *
     *   + mbed:                                                              *
     *     InterruptIn feature_irq;                                           *
     *------------------------------------------------------------------------*/
    /* Fault Interrupt and chip enable. */
    InterruptIn fault_and_enable;
    
    /* Interrupt to toggle the MODE3\STCK pin */
    Timeout tim_stck;

    /* ACTION 10 -------------------------------------------------------------*
     * Declare here other pin related variables, if needed.                   *
     *                                                                        *
     * Example:                                                               *
     *   + mbed:                                                              *
     *     DigitalOut standby_reset;                                          *
     *------------------------------------------------------------------------*/
    /* STBY\RESET pin. */
    DigitalOut stby_reset;
    /* MODE4\DIR pin. */
    DigitalOut direction_mode4;
    /* MODE1 pin */
    DigitalOut mode1;
    /* MODE2 pin */
    DigitalOut mode2;
    /* MODE3\STCK pin. */
    DigitalOut stck_mode3;

    /* Pulse Width Modulation pin for REF pin */
    PwmOut pwm_ref;
 
    /* Monitoring of step clock handler duration */
    DigitalOut monitor;

    /* fault and enable pin */
    PinName fault_and_enable_pinName;
    
    /* ACTION 11 -------------------------------------------------------------*
     * Declare here communication related variables, if needed.               *
     *                                                                        *
     * Example:                                                               *
     *   + mbed:                                                              *
     *     DigitalOut ssel;                                                   *
     *     DevSPI &dev_spi;                                                   *
     *------------------------------------------------------------------------*/
    /* Configuration. */

    /* IO Device. */

    /* ACTION 12 -------------------------------------------------------------*
     * Declare here identity related variables, if needed.                    *
     * Note that there should be only a unique identifier for each component, *
     * which should be the "who_am_i" parameter.                              *
     *------------------------------------------------------------------------*/
    /* Identity */
    uint8_t who_am_i;

    /* ACTION 13 -------------------------------------------------------------*
     * Declare here the component's static and non-static data, one variable  *
     * per line.                                                              *
     *                                                                        *
     * Example:                                                               *
     *   float measure;                                                       *
     *   int instance_id;                                                     *
     *   static int number_of_instances;                                      *
     *------------------------------------------------------------------------*/
    /* Data. */
    void (*fault_and_enable_irqFunctionPointer)(void);
    void (*errorHandlerCallback)(uint16_t error);
    deviceParams_t devicePrm;
    uint8_t deviceInstance;
    volatile uint8_t toggleOdd;

    /* Static data. */
    static uint8_t numberOfDevices;

public:

    /* Static data. */
    
};

#endif // __STSPIN220_CLASS_H

/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/