Library to handle the X_NUCLEO_IHM02A1 Motor Control Expansion Board based on the L6470 component.
Fork of X_NUCLEO_IHM02A1 by
Components/l6470/l6470_class.h
- Committer:
- Davidroid
- Date:
- 2015-11-20
- Revision:
- 0:92706998571a
- Child:
- 1:b78dab6d2c58
File content as of revision 0:92706998571a:
/** ****************************************************************************** * @file L6470.c * @date 01/10/2014 12:00:00 * @brief This file provides set of firmware functions to manage the * L6470. ****************************************************************************** * * COPYRIGHT(c) 2014 STMicroelectronics * * Redistribution and use in source and binary forms, with or without modification, * are permitted provided that the following conditions are met: * 1. Redistributions of source code must retain the above copyright notice, * this list of conditions and the following disclaimer. * 2. Redistributions in binary form must reproduce the above copyright notice, * this list of conditions and the following disclaimer in the documentation * and/or other materials provided with the distribution. * 3. Neither the name of STMicroelectronics nor the names of its contributors * may be used to endorse or promote products derived from this software * without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * ****************************************************************************** */ /* Generated with Stm32CubeTOO -----------------------------------------------*/ /* Revision ------------------------------------------------------------------*/ /* Repository: http://svn.x-nucleodev.codex.cro.st.com/svnroot/X-NucleoDev Branch/Trunk/Tag: trunk Based on: X-CUBE-SPN2/trunk/Drivers/BSP/Components/L6470/L6470.h Revision: 0 */ /* Define to prevent recursive inclusion -------------------------------------*/ #ifndef __L6470_CLASS_H #define __L6470_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 "l6470.h" /* ACTION 3 ------------------------------------------------------------------* * Include here interface specific header files. * * * * Example: * * #include "../Interfaces/Humidity_class.h" * * #include "../Interfaces/Temperature_class.h" * *----------------------------------------------------------------------------*/ #include "../Interfaces/StepperMotor_class.h" /* Classes -------------------------------------------------------------------*/ /** Class representing a L6470 component. */ class L6470 : public StepperMotor { public: /*** Constructor and Destructor Methods ***/ /** * @brief Constructor. * @param flag_irq pin name of the FLAG pin of the component. * @param standby_reset pin name of the STBY\RST 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. */ L6470(PinName flag_irq, PinName standby_reset, PinName ssel, DevSPI &spi) : StepperMotor(), flag_irq(flag_irq), standby_reset(standby_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; * *--------------------------------------------------------------------*/ L6470_Register = &_L6470_Register[0]; L6470_ApplicationCommand = &_L6470_ApplicationCommand[0]; L6470_Direction = &_L6470_Direction[0]; L6470_ACT = &_L6470_ACT[0]; pL6470_StatusRegister = &L6470_StatusRegister; L6470_Id = number_of_devices++; L6470_DaisyChain_HalfPrepared = ZERO_F; memset(L6470_AppCmdPkg, 0, L6470DAISYCHAINSIZE * sizeof(sL6470_AppCmdPkg_t)); memset(L6470_DaisyChainSpiTxStruct, 0, L6470MAXSPICMDBYTESIZE * L6470DAISYCHAINSIZE * sizeof(uint8_t)); memset(L6470_DaisyChainSpiRxStruct, 0, L6470MAXSPICMDBYTESIZE * L6470DAISYCHAINSIZE * sizeof(uint8_t)); } /** * @brief Destructor. */ virtual ~L6470(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) L6470_Config((MICROSTEPPING_MOTOR_InitTypeDef *) init); } virtual int ReadID(uint8_t *id) { return (int) 0; } virtual unsigned int GetStatus(void) { return (unsigned int) L6470_GetStatus(); } virtual unsigned int GetParameter(unsigned int parameter) { return (unsigned int) L6470_GetParam((eL6470_RegId_t) parameter); } virtual signed int GetPosition(void) { return (signed int) L6470_GetParam((eL6470_RegId_t) L6470_ABS_POS_ID); } virtual signed int GetMark(void) { return (signed int) L6470_GetParam((eL6470_RegId_t) L6470_MARK_ID); } virtual unsigned int GetSpeed(void) { return (unsigned int) L6470_GetParam((eL6470_RegId_t) L6470_SPEED_ID); } virtual unsigned int GetMaxSpeed(void) { return (unsigned int) L6470_GetParam((eL6470_RegId_t) L6470_MAX_SPEED_ID); } virtual unsigned int GetMinSpeed(void) { return (unsigned int) L6470_GetParam((eL6470_RegId_t) L6470_MIN_SPEED_ID); } virtual unsigned int GetAcceleration(void) { return (unsigned int) L6470_GetParam((eL6470_RegId_t) L6470_ACC_ID); } virtual unsigned int GetDeceleration(void) { return (unsigned int) L6470_GetParam((eL6470_RegId_t) L6470_DEC_ID); } virtual direction_t GetDirection(void) { return (direction_t) (L6470_CheckStatusRegisterFlag((eL6470_StatusRegisterFlagId_t) DIR_ID) == 1 ? StepperMotor::FWD : StepperMotor::BWD); } virtual void SetParameter(unsigned int parameter, unsigned int value) { L6470_SetParam((eL6470_RegId_t) parameter, (uint32_t) value); } virtual void SetHome(void) { L6470_ResetPos(); //L6470_SetParam((eL6470_RegId_t) L6470_ABS_POS_ID, (uint32_t) 0); } virtual void SetMark(void) { L6470_SetParam((eL6470_RegId_t) L6470_MARK_ID, (uint32_t) L6470_GetParam((eL6470_RegId_t) L6470_ABS_POS_ID)); //L6470_SetParam((eL6470_RegId_t) L6470_MARK_ID, (uint32_t) 0); } virtual void SetMaxSpeed(unsigned int speed) { L6470_SetParam((eL6470_RegId_t) L6470_MAX_SPEED_ID, (uint32_t) speed); } virtual void SetMinSpeed(unsigned int speed) { L6470_SetParam((eL6470_RegId_t) L6470_MIN_SPEED_ID, (uint32_t) speed); } virtual void SetAcceleration(unsigned int acceleration) { L6470_SetParam((eL6470_RegId_t) L6470_ACC_ID, (uint32_t) acceleration); } virtual void SetDeceleration(unsigned int deceleration) { L6470_SetParam((eL6470_RegId_t) L6470_DEC_ID, (uint32_t) deceleration); } virtual void GoTo(signed int position) { L6470_GoTo((uint32_t) position); } virtual void GoTo(signed int position, direction_t direction) { L6470_GoToDir((eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID), (signed int) position); } virtual void GoHome(void) { L6470_GoHome(); } virtual void GoMark(void) { L6470_GoMark(); } virtual void GoUntil(eL6470_ActId_t L6470_ActId, direction_t direction, unsigned int speed) { L6470_GoUntil((eL6470_ActId_t) L6470_ActId, (eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID), (unsigned int) speed); } virtual void Run(direction_t direction) { L6470_Run((eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID), (unsigned int) L6470_GetParam((eL6470_RegId_t) L6470_MAX_SPEED_ID)); } virtual void Run(direction_t direction, unsigned int speed) { L6470_Run((eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID), (unsigned int) speed); } virtual void Move(direction_t direction, unsigned int steps) { L6470_Move((eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID), (unsigned int) steps); } virtual void SoftStop(void) { L6470_SoftStop(); } virtual void HardStop(void) { L6470_HardStop(); } virtual void WaitWhileActive(void) { while (L6470_CheckStatusRegisterFlag(BUSY_ID) == 0); } virtual void SoftHiZ(void) { L6470_SoftHiZ(); } virtual void HardHiZ(void) { L6470_HardHiZ(); } virtual void StepClock(direction_t direction) { L6470_StepClock((eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID)); } virtual void ReleaseSW(eL6470_ActId_t L6470_ActId, direction_t direction) { L6470_ReleaseSW((eL6470_ActId_t) L6470_ActId, (eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID)); } virtual void ResetDevice(void) { L6470_ResetDevice(); } virtual void PrepareGetStatus(void) { L6470_PrepareGetStatus(); } virtual void PrepareGetParameter(unsigned int parameter) { L6470_PrepareGetParam((eL6470_RegId_t) parameter); } virtual void PrepareGetPosition(void) { L6470_PrepareGetParam((eL6470_RegId_t) L6470_ABS_POS_ID); } virtual void PrepareGetMark(void) { L6470_PrepareGetParam((eL6470_RegId_t) L6470_MARK_ID); } virtual void PrepareGetSpeed(void) { L6470_GetParam((eL6470_RegId_t) L6470_SPEED_ID); } virtual void PrepareGetMaxSpeed(void) { L6470_PrepareGetParam((eL6470_RegId_t) L6470_MAX_SPEED_ID); } virtual void PrepareGetMinSpeed(void) { L6470_PrepareGetParam((eL6470_RegId_t) L6470_MIN_SPEED_ID); } virtual void PrepareGetAcceleration(void) { L6470_PrepareGetParam((eL6470_RegId_t) L6470_ACC_ID); } virtual void PrepareGetDeceleration(void) { L6470_PrepareGetParam((eL6470_RegId_t) L6470_DEC_ID); } virtual direction_t PrepareGetDirection(void) { return (direction_t) (L6470_CheckStatusRegisterFlag((eL6470_StatusRegisterFlagId_t) DIR_ID) == 1 ? StepperMotor::FWD : StepperMotor::BWD); } virtual void PrepareSetParameter(unsigned int parameter, unsigned int value) { L6470_PrepareSetParam((eL6470_RegId_t) parameter, (uint32_t) value); } virtual void PrepareSetHome(void) { L6470_PrepareResetPos(); //L6470_SetParam((eL6470_RegId_t) L6470_ABS_POS_ID, (uint32_t) 0); } virtual void PrepareSetMark(void) { uint32_t mark = L6470_GetParam((eL6470_RegId_t) L6470_ABS_POS_ID); L6470_PrepareSetParam((eL6470_RegId_t) L6470_MARK_ID, mark); } virtual void PrepareSetMaxSpeed(unsigned int speed) { L6470_PrepareSetParam((eL6470_RegId_t) L6470_MAX_SPEED_ID, (uint32_t) speed); } virtual void PrepareSetMinSpeed(unsigned int speed) { L6470_PrepareSetParam((eL6470_RegId_t) L6470_MIN_SPEED_ID, (uint32_t) speed); } virtual void PrepareSetAcceleration(unsigned int acceleration) { L6470_PrepareSetParam((eL6470_RegId_t) L6470_ACC_ID, (uint32_t) acceleration); } virtual void PrepareSetDeceleration(unsigned int deceleration) { L6470_PrepareSetParam((eL6470_RegId_t) L6470_DEC_ID, (uint32_t) deceleration); } virtual void PrepareGoTo(signed int position) { L6470_PrepareGoTo((uint32_t) position); } virtual void PrepareGoTo(signed int position, direction_t direction) { L6470_PrepareGoToDir((eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID), (signed int) position); } virtual void PrepareGoHome(void) { L6470_PrepareGoHome(); } virtual void PrepareGoMark(void) { L6470_PrepareGoMark(); } virtual void PrepareGoUntil(eL6470_ActId_t L6470_ActId, direction_t direction, unsigned int speed) { L6470_PrepareGoUntil((eL6470_ActId_t) L6470_ActId, (eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID), (unsigned int) speed); } virtual void PrepareRun(direction_t direction) { L6470_PrepareRun((eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID), (unsigned int) L6470_GetParam((eL6470_RegId_t) L6470_MAX_SPEED_ID)); } virtual void PrepareRun(direction_t direction, unsigned int speed) { L6470_PrepareRun((eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID), (unsigned int) speed); } virtual void PrepareMove(direction_t direction, unsigned int steps) { L6470_PrepareMove((eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID), (unsigned int) steps); } virtual void PrepareSoftStop(void) { L6470_PrepareSoftStop(); } virtual void PrepareHardStop(void) { L6470_PrepareHardStop(); } virtual void PrepareSoftHiZ(void) { L6470_PrepareSoftHiZ(); } virtual void PrepareHardHiZ(void) { L6470_PrepareHardHiZ(); } virtual void PrepareStepClock(direction_t direction) { L6470_StepClock((eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID)); } virtual void PrepareReleaseSW(eL6470_ActId_t L6470_ActId, direction_t direction) { L6470_ReleaseSW((eL6470_ActId_t) L6470_ActId, (eL6470_DirId_t) (direction == StepperMotor::FWD ? L6470_DIR_FWD_ID : L6470_DIR_REV_ID)); } virtual void PrepareResetDevice(void) { L6470_ResetDevice(); } virtual uint8_t* PerformAction(void) { return (uint8_t*) L6470_PerformPreparedApplicationCommand(); } /*** 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 AttachFeatureIRQ(void (*fptr) (void)) * * { * * feature_irq.rise(fptr); * * } * * * * void EnableFeatureIRQ(void) * * { * * feature_irq.enable_irq(); * * } * * * * void DisableFeatureIRQ(void) * * { * * feature_irq.disable_irq(); * * } * *------------------------------------------------------------------------*/ /** * @brief Attaching a FLAG interrupt handler. * @param fptr an interrupt handler. * @retval None. */ void AttachFlagIRQ(void (*fptr)(void)) { flag_irq.rise(fptr); } /** * @brief Enabling FLAG interrupt handling. * @param None. * @retval None. */ void EnableFlagIRQ(void) { flag_irq.enable_irq(); } /** * @brief Disabling FLAG interrupt handling. * @param None. * @retval None. */ void DisableFlagIRQ(void) { flag_irq.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) * *------------------------------------------------------------------------*/ int32_t L6470_AbsPos_2_Position(uint32_t AbsPos); uint32_t L6470_Position_2_AbsPos(int32_t Position); float L6470_Speed_2_Step_s(uint32_t Speed); uint32_t L6470_Step_s_2_Speed(float Step_s); float L6470_Acc_2_Step_s2(uint16_t Acc); uint16_t L6470_Step_s2_2_Acc(float Step_s2); float L6470_Dec_2_Step_s2(uint16_t Dec); uint16_t L6470_Step_s2_2_Dec(float Step_s2); float L6470_MaxSpeed_2_Step_s(uint16_t MaxSpeed); uint16_t L6470_Step_s_2_MaxSpeed(float Step_s); float L6470_MinSpeed_2_Step_s(uint16_t MinSpeed); uint16_t L6470_Step_s_2_MinSpeed(float Step_s); float L6470_FsSpd_2_Step_s(uint16_t FsSpd); uint16_t L6470_Step_s_2_FsSpd(float Step_s); float L6470_IntSpeed_2_Step_s(uint16_t IntSpeed); uint16_t L6470_Step_s_2_IntSpeed(float Step_s); float L6470_StSlp_2_s_Step(uint8_t StSlp); uint8_t L6470_s_Step_2_StSlp(float s_Step); float L6470_FnSlpAcc_2_s_Step(uint8_t FnSlpAcc); uint8_t L6470_s_Step_2_FnSlpAcc(float s_Step); float L6470_FnSlpDec_2_s_Step(uint8_t FnSlpDec); uint8_t L6470_s_Step_2_FnSlpDec(float s_Step); float L6470_OcdTh_2_mA(uint8_t OcdTh); uint8_t L6470_mA_2_OcdTh(float mA); float L6470_StallTh_2_mA(uint8_t StallTh); uint8_t L6470_mA_2_StallTh(float mA); DrvStatusTypeDef L6470_Config(MICROSTEPPING_MOTOR_InitTypeDef *MotorParameterData); void L6470_SetParam(eL6470_RegId_t L6470_RegId, uint32_t Value); uint32_t L6470_GetParam(eL6470_RegId_t L6470_RegId); void L6470_Run(eL6470_DirId_t L6470_DirId, uint32_t Speed); void L6470_StepClock(eL6470_DirId_t L6470_DirId); void L6470_Move(eL6470_DirId_t L6470_DirId, uint32_t N_Step); void L6470_GoTo(uint32_t AbsPos); void L6470_GoToDir(eL6470_DirId_t L6470_DirId, uint32_t AbsPos); void L6470_GoUntil(eL6470_ActId_t L6470_ActId, eL6470_DirId_t L6470_DirId, uint32_t Speed); void L6470_ReleaseSW(eL6470_ActId_t L6470_ActId, eL6470_DirId_t L6470_DirId); void L6470_GoHome(void); void L6470_GoMark(void); void L6470_ResetPos(void); void L6470_ResetDevice(void); void L6470_SoftStop(void); void L6470_HardStop(void); void L6470_SoftHiZ(void); void L6470_HardHiZ(void); uint16_t L6470_GetStatus(void); void L6470_PrepareSetParam(eL6470_RegId_t L6470_RegId, uint32_t Value); void L6470_PrepareGetParam(eL6470_RegId_t L6470_RegId); void L6470_PrepareRun(eL6470_DirId_t L6470_DirId, uint32_t Speed); void L6470_PrepareStepClock(eL6470_DirId_t L6470_DirId); void L6470_PrepareMove(eL6470_DirId_t L6470_DirId, uint32_t N_Step); void L6470_PrepareGoTo(uint32_t AbsPos); void L6470_PrepareGoToDir(eL6470_DirId_t L6470_DirId, uint32_t AbsPos); void L6470_PrepareGoUntil(eL6470_ActId_t L6470_ActId, eL6470_DirId_t L6470_DirId, uint32_t Speed); void L6470_PrepareReleaseSW(eL6470_ActId_t L6470_ActId, eL6470_DirId_t L6470_DirId); void L6470_PrepareGoHome(void); void L6470_PrepareGoMark(void); void L6470_PrepareResetPos(void); void L6470_PrepareResetDevice(void); void L6470_PrepareSoftStop(void); void L6470_PrepareHardStop(void); void L6470_PrepareSoftHiZ(void); void L6470_PrepareHardHiZ(void); void L6470_PrepareGetStatus(void); uint8_t* L6470_PerformPreparedApplicationCommand(void); void L6470_DaisyChainCommand(uint8_t* pL6470_DaisyChainSpiTxStruct, uint8_t* pL6470_DaisyChainSpiRxStruct); uint32_t L6470_ExtractReturnedData(uint8_t* pL6470_DaisyChainSpiRxStruct, uint8_t LengthByte); uint8_t L6470_CheckStatusRegisterFlag(uint8_t L6470_StatusRegisterFlagId); uint8_t* L6470_GetRegisterName(uint8_t id); void L6470_ResetAppCmdPkg(sL6470_AppCmdPkg_t* pL6470_AppCmdPkg); void L6470_FillAppCmdPkg(sL6470_AppCmdPkg_t* pL6470_AppCmdPkg, eL6470_AppCmdId_t L6470_AppCmdId, uint32_t p1, uint32_t p2, uint32_t p3); void L6470_PrepareAppCmdPkg(sL6470_AppCmdPkg_t* pL6470_AppCmdPkg, eL6470_AppCmdId_t L6470_AppCmdId, uint32_t p1, uint32_t p2, uint32_t p3); void L6470_PrepareDaisyChainCommand(sL6470_AppCmdPkg_t* pL6470_AppCmdPkg, uint8_t* pL6470_DaisyChainSpiTxStruct); /*** Component's I/O Methods ***/ /** * @brief Utility function to read data from L6470. * @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 L6470. * @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 L6470 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. * *------------------------------------------------------------------------*/ /* * Puts the device in standby mode. */ void L6470_ENABLE(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ standby_reset = 1; } /* * Puts the device in reset mode. */ void L6470_DISABLE(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ standby_reset = 0; } /* * Write and read bytes to/from the component through the SPI at the same time. */ void L6470_SPI_Communication(uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, uint32_t Timeout) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ ReadWrite(pRxData, pTxData, Size); } /*** 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; /* Flag Interrupt. */ InterruptIn flag_irq; /* Standby/reset pin. */ DigitalOut standby_reset; /* Configuration. */ DigitalOut ssel; /* 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; * *------------------------------------------------------------------------*/ uint8_t L6470_Id; const sL6470_Register_t *L6470_Register; const sL6470_ApplicationCommand_t *L6470_ApplicationCommand; const sL6470_Direction_t *L6470_Direction; const sL6470_ACT_t *L6470_ACT; sL6470_StatusRegister_t L6470_StatusRegister; sL6470_StatusRegister_t *pL6470_StatusRegister; StepperMotorRegister_t StepperMotorRegister; /* Static data. */ static uint8_t number_of_devices; static const sL6470_Register_t _L6470_Register[L6470REGIDSIZE]; static const sL6470_ApplicationCommand_t _L6470_ApplicationCommand[L6470APPCMDIDSIZE]; static const sL6470_Direction_t _L6470_Direction[L6470DIRIDSIZE]; static const sL6470_ACT_t _L6470_ACT[L6470ACTIDSIZE]; static eFlagStatus_t L6470_DaisyChain_HalfPrepared; static sL6470_AppCmdPkg_t L6470_AppCmdPkg[L6470DAISYCHAINSIZE]; static uint8_t L6470_DaisyChainSpiTxStruct[L6470MAXSPICMDBYTESIZE][L6470DAISYCHAINSIZE]; static uint8_t L6470_DaisyChainSpiRxStruct[L6470MAXSPICMDBYTESIZE][L6470DAISYCHAINSIZE]; }; #endif // __L6470_CLASS_H /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/