Personal fork of the library for direct control instead of library control

Dependencies:   X_NUCLEO_COMMON

Dependents:   Thesis_Rotating_Platform

Fork of X_NUCLEO_IHM01A1 by Arkadi Rafalovich

Components/l6474/l6474_class.h

Committer:
Davidroid
Date:
2015-10-16
Revision:
1:b38ebb8ea286
Parent:
0:2887415a46cd
Child:
4:83a1eb397a65

File content as of revision 1:b38ebb8ea286:

/**
  ******************************************************************************
  * @file    l6474_class.h
  * @author  IPC Rennes
  * @version V1.5.0
  * @date    November 12, 2014
  * @brief   L6474 driver (fully integrated microstepping motor driver)
  * @note    (C) COPYRIGHT 2014 STMicroelectronics
  ******************************************************************************
  * @attention
  *
  * <h2><center>&copy; COPYRIGHT(c) 2014 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 -----------------------------------------------*/


/* Revision ------------------------------------------------------------------*/
/*
    Repository:       http://svn.x-nucleodev.codex.cro.st.com/svnroot/X-NucleoDev
    Branch/Trunk/Tag: trunk
    Based on:         X-CUBE-SPN1/trunk/Drivers/BSP/Components/l6474/l6474.h
    Revision:         0
*/


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

#ifndef __L6474_CLASS_H
#define __L6474_CLASS_H


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

/* ACTION 1 ------------------------------------------------------------------*
 * Include here platform specific header files.                               *
 *----------------------------------------------------------------------------*/        
#include "mbed.h"
#include "DevSPI.h"
/* ACTION 2 ------------------------------------------------------------------*
 * Include here component specific header files.                              *
 *----------------------------------------------------------------------------*/        
#include "l6474.h"
/* ACTION 3 ------------------------------------------------------------------*
 * Include here interface specific header files.                              *
 *                                                                            *
 * Example:                                                                   *
 *   #include "../Interfaces/Humidity_class.h"                                *
 *   #include "../Interfaces/Temperature_class.h"                             *
 *----------------------------------------------------------------------------*/
#include "../Interfaces/Motor_class.h"


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

/** Class representing a L6474 component.
 */
class L6474 : public Motor
{
public:

    /*** Constructor and Destructor Methods ***/

    /**
     * @brief Constructor.
     * @param reset     pin name of the STBY\RST pin of the component.
     * @param direction pin name of the DIR pin of the component.
     * @param pwm       pin name of the PWM pin of the component.
     * @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.
     */
    L6474(PinName reset, PinName direction, PinName pwm, PinName ssel, DevSPI &spi) : Motor(), direction(direction), pwm(pwm), reset(reset), ssel(ssel), dev_spi(spi)
    {
        /* ACTION 4 ----------------------------------------------------------*
         * Initialize here the component's member variables, one variable per *
         * line.                                                              *
         *                                                                    *
         * Example:                                                           *
         *   T0_out = 0;                                                      *
         *   T1_out = 0;                                                      *
         *   T0_degC = 0;                                                     *
         *   T1_degC = 0;                                                     *
         *--------------------------------------------------------------------*/
        flagInterruptCallback = 0;
        errorHandlerCallback = 0;
        memset(spiTxBursts, 0, L6474_CMD_ARG_MAX_NB_BYTES);
        memset(spiRxBursts, 0, L6474_CMD_ARG_MAX_NB_BYTES);
        spiPreemtionByIsr = 0;
        isrFlag = 0;
        //devicePrm = 0;
        deviceInstance = numberOfDevices;
        numberOfDevices++;
    }
    
    /**
     * @brief Destructor.
     */
    virtual ~L6474(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 GetValue(float *pData) //(1)                             *
     *   {                                                                    *
     *     return COMPONENT_GetValue(float *pfData);                          *
     *   }                                                                    *
     *                                                                        *
     *   virtual int EnableFeature(void) //(2)                                *
     *   {                                                                    *
     *     return COMPONENT_EnableFeature();                                  *
     *   }                                                                    *
     *------------------------------------------------------------------------*/
    virtual int Init(void *init)
    {
        return (int) L6474_Init((MOTOR_InitTypeDef *) init);
    }

    virtual int ReadID(uint8_t *id)
    {
        return (int) L6474_ReadID((uint8_t *) id);
    }

    virtual void AttachErrorHandler(void (*callback)(uint16_t error))
    {
        L6474_AttachErrorHandler((void (*)(uint16_t error)) callback);
    }

    virtual void AttachFlagInterrupt(void (*callback)(void))
    {
        L6474_AttachFlagInterrupt((void (*)(void)) callback);
    }

    virtual void FlagInterruptHandler(void)
    {
        L6474_FlagInterruptHandler();
    }

    virtual uint16_t GetAcceleration(void)
    {
        return (uint16_t) L6474_GetAcceleration();
    }

    virtual uint16_t GetCurrentSpeed(void)
    {
        return (uint16_t) L6474_GetCurrentSpeed();
    }

    virtual uint16_t GetDeceleration(void)
    {
        return (uint16_t) L6474_GetDeceleration();
    }

    virtual motorState_t GetDeviceState(void)
    {
        return (motorState_t) L6474_GetDeviceState();
    }

    virtual uint8_t GetFwVersion(void)
    {
        return (uint8_t) L6474_GetFwVersion();
    }

    virtual int32_t GetMark(void)
    {
        return (int32_t) L6474_GetMark();
    }

    virtual uint16_t GetMaxSpeed(void)
    {
        return (uint16_t) L6474_GetMaxSpeed();
    }

    virtual uint16_t GetMinSpeed(void)
    {
        return (uint16_t) L6474_GetMinSpeed();
    }

    virtual int32_t GetPosition(void)
    {
        return (int32_t) L6474_GetPosition();
    }

    virtual void GoHome(void)
    {
        L6474_GoHome();
    }

    virtual void GoMark(void)
    {
        L6474_GoMark();
    }

    virtual void GoTo(int32_t targetPosition)
    {
        L6474_GoTo((int32_t) targetPosition);
    }

    virtual void HardStop(void)
    {
        L6474_HardStop();
    }

    virtual void Move(motorDir_t direction, uint32_t stepCount)
    {
        L6474_Move((motorDir_t) direction, (uint32_t) stepCount);
    }

    virtual void Run(motorDir_t direction)
    {
        L6474_Run((motorDir_t) direction);
    }

    virtual bool SetAcceleration(uint16_t newAcc)
    {
        return (bool) L6474_SetAcceleration((uint16_t) newAcc);
    }

    virtual bool SetDeceleration(uint16_t newDec)
    {
        return (bool) L6474_SetDeceleration((uint16_t) newDec);
    }

    virtual void SetHome(void)
    {
        L6474_SetHome();
    }

    virtual void SetMark(void)
    {
        L6474_SetMark();
    }

    virtual bool SetMaxSpeed(uint16_t newMaxSpeed)
    {
        return (bool) L6474_SetMaxSpeed((uint16_t) newMaxSpeed);
    }

    virtual bool SetMinSpeed(uint16_t newMinSpeed)
    {
        return (bool) L6474_SetMinSpeed((uint16_t) newMinSpeed);
    }

    virtual bool SoftStop(void)
    {
        return (bool) L6474_SoftStop();
    }

    virtual void StepClockHandler(void)
    {
        L6474_StepClockHandler();
    }

    virtual void WaitWhileActive(void)
    {
        L6474_WaitWhileActive();
    }

    virtual void CmdDisable(void)
    {
        L6474_CmdDisable();
    }

    virtual void CmdEnable(void)
    {
        L6474_CmdEnable();
    }

    virtual uint32_t CmdGetParam(uint32_t param)
    {
        return (uint32_t) L6474_CmdGetParam((uint32_t) param);
    }

    virtual uint16_t CmdGetStatus(void)
    {
        return (uint16_t) L6474_CmdGetStatus();
    }

    virtual void CmdNop(void)
    {
        L6474_CmdNop();
    }

    virtual void CmdSetParam(uint32_t param, uint32_t value)
    {
        L6474_CmdSetParam((uint32_t) param, (uint32_t) value);
    }

    virtual uint16_t ReadStatusRegister(void)
    {
        return (uint16_t) L6474_ReadStatusRegister();
    }

    virtual void ReleaseReset(void)
    {
        L6474_ReleaseReset();
    }

    virtual void Reset(void)
    {
        L6474_Reset();
    }

    virtual void SelectStepMode(motorStepMode_t stepMod)
    {
        L6474_SelectStepMode((motorStepMode_t) stepMod);
    }

    virtual void SetDirection(motorDir_t direction)
    {
        L6474_SetDirection((motorDir_t) direction);
    }

    virtual void ErrorHandler(uint16_t error)
    {
        L6474_ErrorHandler((uint16_t) error);
    }


    /*** 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_int(pin); //Interrupt object.                  *
     *     feature_int.rise(callback);   //Attach a callback.                 *
     *     feature_int.mode(PullNone);   //Set interrupt mode.                *
     *     feature_int.enable_irq();     //Enable interrupt.                  *
     *     feature_int.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_int.rise(fptr);                                            *
     *   }                                                                    *
     *                                                                        *
     *   void Enable_Feature_IRQ(void)                                        *
     *   {                                                                    *
     *     feature_int.enable_irq();                                          *
     *   }                                                                    *
     *                                                                        *
     *   void Disable_Feature_IRQ(void)                                       *
     *   {                                                                    *
     *     feature_int.disable_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:                                                               *
     *   DrvStatusTypeDef COMPONENT_GetValue(float* pfData); //(1)            *
     *   DrvStatusTypeDef COMPONENT_EnableFeature(void);     //(2)            *
     *   DrvStatusTypeDef COMPONENT_ComputeAverage(void);    //(3)            *
     *------------------------------------------------------------------------*/
    void L6474_AttachErrorHandler(void (*callback)(uint16_t error)); //Attach a user callback to the error handler
    void L6474_AttachFlagInterrupt(void (*callback)(void));          //Attach a user callback to the flag Interrupt
    DrvStatusTypeDef L6474_Init(MOTOR_InitTypeDef *init);            //Start the L6474 library
    DrvStatusTypeDef L6474_ReadID(uint8_t *id);                      //Read Id to get driver instance
    uint16_t L6474_GetAcceleration(void);                            //Return the acceleration in pps^2
    uint16_t L6474_GetCurrentSpeed(void);                            //Return the current speed in pps
    uint16_t L6474_GetDeceleration(void);                            //Return the deceleration in pps^2
    motorState_t L6474_GetDeviceState(void);                         //Return the device state
    uint8_t L6474_GetFwVersion(void);                                //Return the FW version
    int32_t L6474_GetMark(void);                                     //Return the mark position 
    uint16_t L6474_GetMaxSpeed(void);                                //Return the max speed in pps
    uint16_t L6474_GetMinSpeed(void);                                //Return the min speed in pps
    int32_t L6474_GetPosition(void);                                 //Return the ABS_POSITION (32b signed)
    void L6474_GoHome(void);                                         //Move to the home position
    void L6474_GoMark(void);                                         //Move to the Mark position
    void L6474_GoTo(int32_t targetPosition);                         //Go to the specified position
    void L6474_HardStop(void);                                       //Stop the motor and disable the power bridge
    void L6474_Move(motorDir_t direction, uint32_t stepCount);       //Move the motor of the specified number of steps
    void L6474_Run(motorDir_t direction);                            //Run the motor 
    bool L6474_SetAcceleration(uint16_t newAcc);                     //Set the acceleration in pps^2
    bool L6474_SetDeceleration(uint16_t newDec);                     //Set the deceleration in pps^2
    void L6474_SetHome(void);                                        //Set current position to be the home position
    void L6474_SetMark(void);                                        //Set current position to be the Markposition
    bool L6474_SetMaxSpeed(uint16_t newMaxSpeed);                    //Set the max speed in pps
    bool L6474_SetMinSpeed(uint16_t newMinSpeed);                    //Set the min speed in pps   
    bool L6474_SoftStop(void);                                       //Progressively stops the motor 
    void L6474_WaitWhileActive(void);                                //Wait for the device state becomes Inactive
    void L6474_CmdDisable(void);                                     //Send the L6474_DISABLE command
    void L6474_CmdEnable(void);                                      //Send the L6474_ENABLE command
    uint32_t L6474_CmdGetParam(uint32_t param);                      //Send the L6474_GET_PARAM command
    uint16_t L6474_CmdGetStatus(void);                               //Send the L6474_GET_STATUS command
    void L6474_CmdNop(void);                                         //Send the L6474_NOP command
    void L6474_CmdSetParam(uint32_t param, uint32_t value);          //Send the L6474_SET_PARAM command
    uint16_t L6474_ReadStatusRegister(void);                         //Read the L6474_STATUS register without clearing the flags
    void L6474_SelectStepMode(motorStepMode_t stepMod);              //Step mode selection
    void L6474_SetDirection(motorDir_t direction);                   //Set the L6474 direction pin
    void L6474_ApplySpeed(uint16_t newSpeed);
    void L6474_ComputeSpeedProfile(uint32_t nbSteps);
    int32_t L6474_ConvertPosition(uint32_t abs_position_reg); 
    void L6474_ErrorHandler(uint16_t error);
    void L6474_FlagInterruptHandler(void);
    void L6474_SendCommand(uint8_t param);
    void L6474_SetRegisterToPredefinedValues(void);
    void L6474_WriteBytes(uint8_t *pByteToTransmit, uint8_t *pReceivedByte);    
    void L6474_SetDeviceParamsToPredefinedValues(void);
    void L6474_StartMovement(void);
    void L6474_StepClockHandler(void);  
    uint8_t L6474_Tval_Current_to_Par(double Tval);
    uint8_t L6474_Tmin_Time_to_Par(double Tmin);


    /*** Component's I/O Methods ***/

    /**
     * @brief      Utility function to read data from L6474.
     * @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.
     */
    DrvStatusTypeDef 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 L6474.
     * @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.
     */
    DrvStatusTypeDef 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 L6474 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.
     */
    DrvStatusTypeDef ReadWrite(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.   *
     *------------------------------------------------------------------------*/
    /*
     * System call to make the CPU wait.
     */
    void L6474_Delay(uint32_t delay)
    {
        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs */
        wait_ms(delay);
    }

    /*
     * System call to enable interrupts.
     */
    void L6474_EnableIrq(void)
    {
        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs */
        __enable_irq();
    }

    /*
     * System call to disable interrupts.
     */
    void L6474_DisableIrq(void)
    {
        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs */
        __disable_irq();
    }

    /*
     * Sets the frequency of PWM.
     * The frequency is directly the current speed of the device.
     */
    void L6474_PwmSetFreq(uint16_t newFreq)
    {
        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs */
        double period = 1.0f / newFreq;
        pwm.period(period);
        pwm.write(0.5f);
        ticker.attach(this, &L6474::L6474_StepClockHandler, period);
    }

    /*
     * Initialises the PWM uses by the specified device.
     *  + Device 0 uses PWM1 based on timer 1;
     *  + Device 1 uses PWM2 based on timer 2;
     *  + Device 2 uses PWM3 based on timer 3.
     */
    void L6474_PwmInit(void)
    {
        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs */
    }

    /*
     * Stops the PWM.
     */
    void L6474_PwmStop(void)
    {
        /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs */
        pwm.write(0.0f);
        ticker.detach();
    }

    /*
     * Setting the standby/reset pin to high.
     */
    void L6474_ReleaseReset(void)
    {
        reset = 1;
    }

    /*
     * Resetting the standby/reset pin to put the device in standby mode.
     */
    void L6474_Reset(void)
    {
        reset = 0;
    }

    /*
     * Set the direction of rotation.
     */
    void L6474_SetDirectionGpio(uint8_t gpioState)
    {
        direction = gpioState;
    }

    /*
     * Write and read bytes to/from the component through the SPI at the same time.
     */
    uint8_t L6474_SpiWriteBytes(uint8_t *pByteToTransmit, uint8_t *pReceivedByte)
    {
        return (uint8_t) ReadWrite(pReceivedByte, pByteToTransmit, numberOfDevices);
    }


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

    /* Identity */
    uint8_t who_am_i;

    /* ACTION 9 --------------------------------------------------------------*
     * There should be only a unique identifier for each component, which     *
     * should be the "who_am_i" parameter, hence this parameter is optional.  *
     *------------------------------------------------------------------------*/
    /* Type. */
    uint8_t type;

    /* Configuration. */
    DigitalOut ssel;

    /* Standby and reset pin. */
    DigitalOut reset;

    /* Direction of rotation pin. */
    DigitalOut direction;

    /* Pulse Width Modulation pin. */
    PwmOut pwm;

    /* Timer to trigger the PWM callback at each PWM pulse. */
    Ticker ticker;

    /* IO Device. */
    DevSPI &dev_spi;

    /* Interrupts. */
    /* ACTION 10 -------------------------------------------------------------*
     * Put here interrupt related objects, if needed.                         *
     * Note that interrupt handling is platform dependent, see                *
     * "Interrupt Related Methods" above.                                     *
     *                                                                        *
     * Example:                                                               *
     *   + mbed:                                                              *
     *     InterruptIn feature_int;                                           *
     *------------------------------------------------------------------------*/

    /* Data. */
    /* ACTION 11 -------------------------------------------------------------*
     * Declare here the component's data, one variable per line.              *
     *                                                                        *
     * Example:                                                               *
     *   int T0_out;                                                          *
     *   int T1_out;                                                          *
     *   float T0_degC;                                                       *
     *   float T1_degC;                                                       *
     *------------------------------------------------------------------------*/
    void (*flagInterruptCallback)(void);
    void (*errorHandlerCallback)(uint16_t error);
    uint8_t spiTxBursts[L6474_CMD_ARG_MAX_NB_BYTES];
    uint8_t spiRxBursts[L6474_CMD_ARG_MAX_NB_BYTES];
    bool spiPreemtionByIsr;
    bool isrFlag;
    deviceParams_t devicePrm;
    static uint8_t numberOfDevices;
    uint8_t deviceInstance;
};

#endif // __L6474_CLASS_H

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