Davide Aliprandi / X_NUCLEO_IHM03A1

Dependencies:   ST_INTERFACES X_NUCLEO_COMMON

Fork of X_NUCLEO_IHM03A1 by ST

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers powerstep01_class.h Source File

powerstep01_class.h

Go to the documentation of this file.
00001 /**
00002  ******************************************************************************
00003  * @file    powerstep01_class.h
00004  * @author  IPC Rennes
00005  * @version V1.0.0
00006  * @date    March 18th, 2016
00007  * @brief   This file contains the class of a Powerstep01 Motor Control component.
00008  * @note    (C) COPYRIGHT 2016 STMicroelectronics
00009  ******************************************************************************
00010  * @attention
00011  *
00012  * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
00013  *
00014  * Redistribution and use in source and binary forms, with or without modification,
00015  * are permitted provided that the following conditions are met:
00016  *   1. Redistributions of source code must retain the above copyright notice,
00017  *      this list of conditions and the following disclaimer.
00018  *   2. Redistributions in binary form must reproduce the above copyright notice,
00019  *      this list of conditions and the following disclaimer in the documentation
00020  *      and/or other materials provided with the distribution.
00021  *   3. Neither the name of STMicroelectronics nor the names of its contributors
00022  *      may be used to endorse or promote products derived from this software
00023  *      without specific prior written permission.
00024  *
00025  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00026  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00027  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00028  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00029  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00030  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00031  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00033  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00034  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  ******************************************************************************
00037  */
00038 
00039 
00040 /* Define to prevent recursive inclusion -------------------------------------*/
00041 
00042 #ifndef __POWERSTEP01_CLASS_H
00043 #define __POWERSTEP01_CLASS_H
00044 
00045 
00046 /* Includes ------------------------------------------------------------------*/
00047 
00048 /* ACTION 1 ------------------------------------------------------------------*
00049  * Include here platform specific header files.                               *
00050  *----------------------------------------------------------------------------*/
00051 #include "mbed.h"
00052 #include "DevSPI.h"
00053 /* ACTION 2 ------------------------------------------------------------------*
00054  * Include here component specific header files.                              *
00055  *----------------------------------------------------------------------------*/
00056 #include "powerstep01.h"
00057 /* ACTION 3 ------------------------------------------------------------------*
00058  * Include here interface specific header files.                              *
00059  *                                                                            *
00060  * Example:                                                                   *
00061  *   #include "HumiditySensor.h"                                              *
00062  *   #include "TemperatureSensor.h"                                           *
00063  *----------------------------------------------------------------------------*/
00064 #include "StepperMotor.h"
00065 
00066 
00067 /* Classes -------------------------------------------------------------------*/
00068 
00069 /**
00070  * @brief Class representing a Powerstep01 component.
00071  */
00072 class POWERSTEP01 : public StepperMotor
00073 {
00074 public:
00075 
00076     /*** Constructor and Destructor Methods ***/
00077 
00078     /**
00079      * @brief Constructor.
00080      * @param flag_irq      pin name of the FLAG pin of the component.
00081      * @param busy_irq      pin name of the BUSY pin of the component.
00082      * @param standby_reset pin name of the STBY\RST pin of the component.
00083      * @param pwm           pin name of the PWM pin of the component.
00084      * @param ssel          pin name of the SSEL pin of the SPI device to be used for communication.
00085      * @param spi           SPI device to be used for communication.
00086      */
00087     POWERSTEP01(PinName flag_irq, PinName busy_irq, PinName standby_reset, PinName pwm, PinName ssel, DevSPI &spi) : StepperMotor(), flag_irq(flag_irq), busy_irq(busy_irq), standby_reset(standby_reset), pwm(pwm), ssel(ssel), dev_spi(spi)
00088     {
00089         /* Checking stackability. */
00090         if (!(numberOfDevices < MAX_NUMBER_OF_DEVICES))
00091             error("Instantiation of the powerstep01 component failed: it can be stacked up to %d times.\r\n", MAX_NUMBER_OF_DEVICES);
00092 
00093         /* ACTION 4 ----------------------------------------------------------*
00094          * Initialize here the component's member variables, one variable per *
00095          * line.                                                              *
00096          *                                                                    *
00097          * Example:                                                           *
00098          *   measure = 0;                                                     *
00099          *   instance_id = number_of_instances++;                             *
00100          *--------------------------------------------------------------------*/
00101         errorHandlerCallback = 0;
00102         deviceInstance = numberOfDevices++;
00103         memset(spiTxBursts, 0, POWERSTEP01_CMD_ARG_MAX_NB_BYTES * MAX_NUMBER_OF_DEVICES * sizeof(uint8_t));
00104         memset(spiRxBursts, 0, POWERSTEP01_CMD_ARG_MAX_NB_BYTES * MAX_NUMBER_OF_DEVICES * sizeof(uint8_t));
00105     }
00106     
00107     /**
00108      * @brief Destructor.
00109      */
00110     virtual ~POWERSTEP01(void) {}
00111     
00112 
00113     /*** Public Component Related Methods ***/
00114 
00115     /* ACTION 5 --------------------------------------------------------------*
00116      * Implement here the component's public methods, as wrappers of the C    *
00117      * component's functions.                                                 *
00118      * They should be:                                                        *
00119      *   + Methods with the same name of the C component's virtual table's    *
00120      *     functions (1);                                                     *
00121      *   + Methods with the same name of the C component's extended virtual   *
00122      *     table's functions, if any (2).                                     *
00123      *                                                                        *
00124      * Example:                                                               *
00125      *   virtual int GetValue(float *pData) //(1)                             *
00126      *   {                                                                    *
00127      *     return COMPONENT_GetValue(float *pfData);                          *
00128      *   }                                                                    *
00129      *                                                                        *
00130      *   virtual int EnableFeature(void) //(2)                                *
00131      *   {                                                                    *
00132      *     return COMPONENT_EnableFeature();                                  *
00133      *   }                                                                    *
00134      *------------------------------------------------------------------------*/
00135 
00136     /**
00137      * @brief Public functions inherited from the Component Class
00138      */
00139 
00140     /**
00141      * @brief  Initialize the component.
00142      * @param  init Pointer to device specific initalization structure.
00143      * @retval "0" in case of success, an error code otherwise.
00144      */
00145     virtual int Init(void *init = NULL)
00146     {
00147         return (int) Powerstep01_Init((void *) init);
00148     }
00149 
00150     /**
00151      * @brief  Getting the ID of the component.
00152      * @param  id Pointer to an allocated variable to store the ID into.
00153      * @retval "0" in case of success, an error code otherwise.
00154      */
00155     virtual int ReadID(uint8_t *id = NULL)
00156     {
00157         return (int) Powerstep01_ReadID((uint8_t *) id);
00158     }
00159 
00160     /**
00161      * @brief Public functions inherited from the StepperMotor Class
00162      */
00163 
00164     /**
00165      * @brief  Getting the value of the Status Register.
00166      * @param  None.
00167      * @retval None.
00168      * @note   The Status Register's flags are cleared, contrary to ReadStatusRegister().
00169      */
00170     virtual unsigned int GetStatus(void)
00171     {
00172         return (unsigned int) Powerstep01_CmdGetStatus();
00173     }
00174 
00175     /**
00176      * @brief  Getting the position.
00177      * @param  None.
00178      * @retval The position.
00179      */
00180     virtual signed int GetPosition(void)
00181     {
00182         return (signed int)Powerstep01_GetPosition();
00183     }
00184 
00185     /**
00186      * @brief  Getting the marked position.
00187      * @param  None.
00188      * @retval The marked position.
00189      */
00190     virtual signed int GetMark(void)
00191     {
00192         return (signed int)Powerstep01_GetMark();
00193     }
00194 
00195     /**
00196      * @brief  Getting the current speed in pps.
00197      * @param  None.
00198      * @retval The current speed in pps.
00199      */
00200     virtual unsigned int GetSpeed(void)
00201     {
00202         return (unsigned int)round(Powerstep01_GetAnalogValue(POWERSTEP01_SPEED));
00203     }
00204 
00205     /**
00206      * @brief  Getting the maximum speed in pps.
00207      * @param  None.
00208      * @retval The maximum speed in pps.
00209      */
00210     virtual unsigned int GetMaxSpeed(void)
00211     {
00212         return (unsigned int)round(Powerstep01_GetAnalogValue(POWERSTEP01_MAX_SPEED));
00213     }
00214 
00215     /**
00216      * @brief  Getting the minimum speed in pps.
00217      * @param  None.
00218      * @retval The minimum speed in pps.
00219      */
00220     virtual unsigned int GetMinSpeed(void)
00221     {
00222         return (unsigned int)round(Powerstep01_GetAnalogValue(POWERSTEP01_MIN_SPEED));
00223     }
00224 
00225     /**
00226      * @brief  Getting the acceleration in pps^2.
00227      * @param  None.
00228      * @retval The acceleration in pps^2.
00229      */
00230     virtual unsigned int GetAcceleration(void)
00231     {
00232         return (unsigned int)round(Powerstep01_GetAnalogValue(POWERSTEP01_ACC));
00233     }
00234 
00235     /**
00236      * @brief  Getting the deceleration in pps^2.
00237      * @param  None.
00238      * @retval The deceleration in pps^2.
00239      */
00240     virtual unsigned int GetDeceleration(void)
00241     {
00242         return (unsigned int)round(Powerstep01_GetAnalogValue(POWERSTEP01_DEC));
00243     }
00244     
00245     /**
00246      * @brief  Getting the direction of rotation.
00247      * @param  None.
00248      * @retval The direction of rotation.
00249      */
00250     virtual direction_t GetDirection(void)
00251     {
00252         if ((POWERSTEP01_STATUS_DIR&Powerstep01_ReadStatusRegister())!=0)
00253         {
00254             return FWD;
00255         }
00256         else
00257         {
00258             return BWD;
00259         }
00260     }
00261     
00262     /**
00263      * @brief  Setting the current position to be the home position.
00264      * @param  None.
00265      * @retval None.
00266      */
00267     virtual void SetHome(void)
00268     {
00269         Powerstep01_SetHome();
00270     }
00271 
00272     /**
00273      * @brief  Setting the current position to be the marked position.
00274      * @param  None.
00275      * @retval None.
00276      */
00277     virtual void SetMark(void)
00278     {
00279         Powerstep01_SetMark();
00280     }
00281 
00282     /**
00283      * @brief  Setting the maximum speed in steps/s.
00284      * @param  speed The maximum speed in steps/s.
00285      * @retval TRUE if value is valid, FALSE otherwise.
00286      */
00287     virtual bool SetMaxSpeed(unsigned int speed)
00288     {
00289         return Powerstep01_SetAnalogValue(POWERSTEP01_MAX_SPEED, (float)speed);
00290     }
00291 
00292     /**
00293      * @brief  Setting the minimum speed in steps/s.
00294      * @param  speed The minimum speed in steps/s.
00295      * @retval TRUE if value is valid, FALSE otherwise.
00296      */
00297     virtual bool SetMinSpeed(unsigned int speed)
00298     {
00299         return Powerstep01_SetAnalogValue(POWERSTEP01_MIN_SPEED, (float)speed);
00300     }
00301 
00302     /**
00303      * @brief  Setting the acceleration in steps/s^2.
00304      * @param  acceleration The acceleration in steps/s^2.
00305      * @retval None.
00306      */
00307     virtual bool SetAcceleration(unsigned int acceleration)
00308     {
00309         return Powerstep01_SetAnalogValue(POWERSTEP01_ACC, (float)acceleration);
00310     }
00311 
00312     /**
00313      * @brief  Setting the deceleration in steps/s^2.
00314      * @param  deceleration The deceleration in steps/s^2.
00315      * @retval None.
00316      */
00317     virtual bool SetDeceleration(unsigned int deceleration)
00318     {
00319         return Powerstep01_SetAnalogValue(POWERSTEP01_DEC, (float)deceleration);
00320     }
00321 
00322     /**
00323      * @brief  Setting the Step Mode.
00324      * @param  step_mode The Step Mode.
00325      * @retval None.
00326      * @note   step_mode can be one of the following:
00327      *           + STEP_MODE_FULL
00328      *           + STEP_MODE_HALF
00329      *           + STEP_MODE_1_4
00330      *           + STEP_MODE_1_8
00331      *           + STEP_MODE_1_16
00332      *           + STEP_MODE_1_32
00333      *           + STEP_MODE_1_64
00334      *           + STEP_MODE_1_128
00335      */
00336     virtual bool SetStepMode(step_mode_t step_mode)
00337     {
00338         return Powerstep01_SelectStepMode((motorStepMode_t) step_mode);
00339     }
00340 
00341     /**
00342      * @brief  Going to a specified position.
00343      * @param  position The desired position.
00344      * @retval None.
00345      */
00346     virtual void GoTo(signed int position)
00347     {
00348         Powerstep01_CmdGoTo((int32_t)position);
00349     }
00350 
00351     virtual void GoTo(direction_t direction, signed int position)
00352     {
00353         Powerstep01_CmdGoToDir((motorDir_t) (direction == StepperMotor::FWD ? FORWARD : BACKWARD),(int32_t)position);
00354     }
00355 
00356     /**
00357      * @brief  Going to the home position.
00358      * @param  None.
00359      * @retval None.
00360      */
00361     virtual void GoHome(void)
00362     {
00363         Powerstep01_CmdGoHome();
00364     }
00365 
00366     /**
00367      * @brief  Going to the marked position.
00368      * @param  None.
00369      * @retval None.
00370      */
00371     virtual void GoMark(void)
00372     {
00373         Powerstep01_CmdGoMark();
00374     }
00375 
00376     /**
00377      * @brief  Running the motor towards a specified direction.
00378      * @param  direction The direction of rotation.
00379      * @retval None.
00380      */
00381     virtual void Run(direction_t direction)
00382     {
00383         Powerstep01_CmdRun((motorDir_t) (direction == StepperMotor::FWD ? FORWARD : BACKWARD), Powerstep01_CmdGetParam((powerstep01_Registers_t) POWERSTEP01_MAX_SPEED));
00384     }
00385 
00386     /**
00387      * @brief  Moving the motor towards a specified direction for a certain number of steps.
00388      * @param  direction The direction of rotation.
00389      * @param  steps The desired number of steps.
00390      * @retval None.
00391      */
00392     virtual void Move(direction_t direction, unsigned int steps)
00393     {
00394         Powerstep01_CmdMove((motorDir_t) (direction == StepperMotor::FWD ? FORWARD : BACKWARD), (uint32_t)steps);
00395     }
00396 
00397     /**
00398      * @brief  Stopping the motor through an immediate deceleration up to zero speed.
00399      * @param  None.
00400      * @retval None.
00401      */
00402     virtual void SoftStop(void)
00403     {
00404         Powerstep01_CmdSoftStop();
00405     }
00406 
00407     /**
00408      * @brief  Stopping the motor through an immediate infinite deceleration.
00409      * @param  None.
00410      * @retval None.
00411      */
00412     virtual void HardStop(void)
00413     {
00414         Powerstep01_CmdHardStop();
00415     }
00416 
00417     /**
00418      * @brief  Disabling the power bridge after performing a deceleration to zero.
00419      * @param  None.
00420      * @retval None.
00421      */
00422     virtual void SoftHiZ(void)
00423     {
00424         Powerstep01_CmdSoftHiZ();
00425     }
00426 
00427     /**
00428      * @brief  Disabling the power bridge immediately.
00429      * @param  None.
00430      * @retval None.
00431      */
00432     virtual void HardHiZ(void)
00433     {
00434         Powerstep01_CmdHardHiZ();
00435     }
00436 
00437     /**
00438      * @brief  Waiting while the motor is active.
00439      * @param  None.
00440      * @retval None.
00441      */
00442     virtual void WaitWhileActive(void)
00443     {
00444         Powerstep01_WaitWhileActive();
00445     }  
00446 
00447     /**
00448      * @brief Public functions NOT inherited
00449      */
00450      
00451     /**
00452      * @brief  Attaching an error handler.
00453      * @param  fptr An error handler.
00454      * @retval None.
00455      */
00456     virtual void AttachErrorHandler(void (*fptr)(uint16_t error))
00457     {
00458         Powerstep01_AttachErrorHandler((void (*)(uint16_t error)) fptr);
00459     }
00460     
00461     /**
00462      * @brief  Checks if the device is busy by reading the busy pin position.
00463      * @param  None.
00464      * @retval One if the device his busy (low logic level on busy output),
00465      * otherwise zero
00466      */
00467     virtual int CheckBusyHw(void)
00468     {
00469         if (busy_irq!=0) return 0x01;
00470         else return 0x00;
00471     }
00472 
00473     /**
00474      * @brief  Checks if the device has an alarm flag set by reading the flag pin position.
00475      * @param  None.
00476      * @retval One if the device has an alarm flag set (low logic level on flag output),
00477      * otherwise zero
00478      */
00479     virtual unsigned int CheckStatusHw(void)
00480     {
00481         if (flag_irq!=0) return 0x01;
00482         else return 0x00;
00483     }
00484     
00485     /**
00486      * @brief Fetch and clear status flags of all devices 
00487      * by issuing a GET_STATUS command simultaneously  
00488      * to all devices.
00489      * Then, the fetched status of each device can be retrieved
00490      * by using the Powerstep01_GetFetchedStatus function
00491      * provided there is no other calls to functions which 
00492      * use the SPI in between.
00493      * @retval None
00494      */
00495     virtual void FetchAndClearAllStatus(void)
00496     {
00497         Powerstep01_FetchAndClearAllStatus();
00498     }
00499 
00500     /**
00501      * @brief  Getting a parameter float value.
00502      * @param  parameter A parameter's register adress.
00503      * @retval The parameter's float value.
00504      *         parameter can be one of the following:
00505      *           + POWERSTEP01_ABS_POS
00506      *           + POWERSTEP01_MARK
00507      *           + POWERSTEP01_ACC
00508      *           + POWERSTEP01_DEC
00509      *           + POWERSTEP01_SPEED     
00510      *           + POWERSTEP01_MAX_SPEED
00511      *           + POWERSTEP01_MIN_SPEED
00512      *           + POWERSTEP01_FS_SPD
00513      *           (voltage mode) + POWERSTEP01_INT_SPD
00514      *           (voltage mode) + POWERSTEP01_K_THERM
00515      *           + POWERSTEP01_OCD_TH
00516      *           (voltage mode) + POWERSTEP01_STALL_TH
00517      *           (voltage mode) + POWERSTEP01_KVAL_HOLD : value in %
00518      *           (current mode) + POWERSTEP01_TVAL_HOLD : value in mV
00519      *           (voltage mode) + POWERSTEP01_KVAL_RUN  : value in %
00520      *           (current mode) + POWERSTEP01_TVAL_RUN  : value in mV
00521      *           (voltage mode) + POWERSTEP01_KVAL_ACC  : value in %
00522      *           (current mode) + POWERSTEP01_TVAL_ACC  : value in mV
00523      *           (voltage mode) + POWERSTEP01_KVAL_DEC  : value in %
00524      *           (current mode) + POWERSTEP01_TVAL_DEC  : value in mV
00525      *           (voltage mode) + POWERSTEP01_ST_SLP
00526      *           (voltage mode) + POWERSTEP01_FN_SLP_ACC
00527      *           (voltage mode) + POWERSTEP01_FN_SLP_DEC
00528      */
00529     virtual float GetAnalogValue(unsigned int parameter)
00530     {
00531       return Powerstep01_GetAnalogValue((powerstep01_Registers_t)parameter);
00532     }
00533 
00534     /**
00535      * @brief Get the value of the STATUS register which was 
00536      * fetched by using Powerstep01_FetchAndClearAllStatus.
00537      * The fetched values are available  as long as there
00538      * no other calls to functions which use the SPI.
00539      * @retval Last fetched value of the STATUS register.
00540      */ 
00541     virtual uint16_t GetFetchedStatus(void)
00542     {
00543         return Powerstep01_GetFetchedStatus();
00544     }
00545 
00546     /**
00547      * @brief  Getting the version of the firmware.
00548      * @param  None.
00549      * @retval The version of the firmware.
00550      */
00551     virtual unsigned int GetFwVersion(void)
00552     {
00553         return (unsigned int) Powerstep01_GetFwVersion();
00554     }
00555 
00556     /**
00557      * @brief  Getting a parameter register value.
00558      * @param  parameter A parameter's register adress.
00559      * @retval The parameter's register value.
00560      *         parameter can be one of the following:
00561      *           + POWERSTEP01_ABS_POS
00562      *           + POWERSTEP01_EL_POS
00563      *           + POWERSTEP01_MARK
00564      *           + POWERSTEP01_SPEED
00565      *           + POWERSTEP01_ACC
00566      *           + POWERSTEP01_DEC
00567      *           + POWERSTEP01_MAX_SPEED
00568      *           + POWERSTEP01_MIN_SPEED
00569      *           (voltage mode) + POWERSTEP01_KVAL_HOLD : value in %
00570      *           (current mode) + POWERSTEP01_TVAL_HOLD : value in mV
00571      *           (voltage mode) + POWERSTEP01_KVAL_RUN  : value in %
00572      *           (current mode) + POWERSTEP01_TVAL_RUN  : value in mV
00573      *           (voltage mode) + POWERSTEP01_KVAL_ACC  : value in %
00574      *           (current mode) + POWERSTEP01_TVAL_ACC  : value in mV
00575      *           (voltage mode) + POWERSTEP01_KVAL_DEC  : value in %
00576      *           (current mode) + POWERSTEP01_TVAL_DEC  : value in mV
00577      *           (voltage mode) + POWERSTEP01_INT_SPD
00578      *           (voltage mode) + POWERSTEP01_ST_SLP
00579      *           (current mode) + POWERSTEP01_T_FAST
00580      *           (voltage mode) + POWERSTEP01_FN_SLP_ACC
00581      *           (current mode) + POWERSTEP01_TON_MIN
00582      *           (voltage mode) + POWERSTEP01_FN_SLP_DEC
00583      *           (current mode) + POWERSTEP01_TOFF_MIN
00584      *           (voltage mode) + POWERSTEP01_K_THERM
00585      *           + POWERSTEP01_ADC_OUT
00586      *           + POWERSTEP01_OCD_TH
00587      *           (voltage mode) + POWERSTEP01_STALL_TH
00588      *           + POWERSTEP01_FS_SPD
00589      *           + POWERSTEP01_STEP_MODE
00590      *           + POWERSTEP01_ALARM_EN
00591      *           + POWERSTEP01_GATECFG1
00592      *           + POWERSTEP01_GATECFG2
00593      *           + POWERSTEP01_CONFIG
00594      *           + POWERSTEP01_STATUS
00595      */
00596     virtual unsigned int GetRawParameter(unsigned int parameter)
00597     {
00598       return (unsigned int) Powerstep01_CmdGetParam((powerstep01_Registers_t)parameter);
00599     }
00600     
00601     /**
00602      * @brief  Issues PowerStep01 Go Until command.
00603      * @param  action type of action to undertake when the SW
00604      * input is forced high (ACTION_RESET or ACTION_COPY).
00605      * @param  direction The direction of rotation.
00606      * @param  speed in steps/s.
00607      * @retval One if the device has an alarm flag set (low logic level on flag output),
00608      * otherwise zero
00609      */    
00610     virtual void GoUntil(motorAction_t action, direction_t direction, float speed)
00611     {
00612         Powerstep01_CmdGoUntil(action,
00613                                (motorDir_t) (direction == StepperMotor::FWD ? FORWARD : BACKWARD),
00614                                Speed_Steps_s_to_RegVal(speed));
00615     }
00616     
00617     /**
00618      * @brief Checks if the device is busy
00619      * by reading the Busy flag bit ot its status Register
00620      * This operation clears the status register
00621      * @retval true if device is busy, false zero  
00622      */
00623     virtual bool IsDeviceBusy(void)
00624     {
00625         return Powerstep01_IsDeviceBusy();
00626     }
00627 
00628     /**
00629      * @brief Put commands in queue before synchronous sending
00630      * done by calling SendQueuedCommands.
00631      * Any call to functions that use the SPI between the calls of 
00632      * QueueCommands and SendQueuedCommands 
00633      * will corrupt the queue.
00634      * A command for each device of the daisy chain must be 
00635      * specified before calling SendQueuedCommands.
00636      * @param command Command to queue (all Powerstep01 commmands 
00637      * except POWERSTEP01_SET_PARAM, POWERSTEP01_GET_PARAM, 
00638      * POWERSTEP01_GET_STATUS).
00639      * @param value argument of the command to queue.
00640      * @retval None.
00641      */
00642     virtual void QueueCommands(uint8_t command, int32_t value)
00643     {
00644         Powerstep01_QueueCommands(command, value);
00645     }
00646     
00647     /**
00648      * @brief  Reading the Status Register.
00649      * @param  None.
00650      * @retval None.
00651      * @note   The Status Register's flags are not cleared, contrary to GetStatus().
00652      */
00653     virtual uint16_t ReadStatusRegister(void)
00654     {
00655         return Powerstep01_ReadStatusRegister();
00656     }
00657     
00658     /**
00659      * @brief  Issues PowerStep01 Release SW command.
00660      * @param  action type of action to undertake when the SW
00661      * input is forced high (ACTION_RESET or ACTION_COPY).
00662      * @param  direction The direction of rotation.
00663      * @param  speed in steps/s.
00664      * @retval One if the device has an alarm flag set (low logic level on flag output),
00665      * otherwise zero
00666      */  
00667     virtual void ReleaseSw(motorAction_t action, direction_t direction)
00668     {
00669         Powerstep01_CmdReleaseSw(action,
00670                                  (motorDir_t) (direction == StepperMotor::FWD ? FORWARD : BACKWARD));
00671     }
00672     
00673     /**
00674      * @brief  Issues PowerStep01 Reset Device command.
00675      * @param  None.
00676      * @retval None.
00677      */
00678     virtual void ResetCommand(void)
00679     {
00680         Powerstep01_CmdResetDevice();
00681     }
00682 
00683     /**
00684      * @brief  Issues PowerStep01 ResetPos command.
00685      * @param  None.
00686      * @retval None.
00687      * @note   Same effect as SetHome().
00688      */
00689     virtual void ResetPosition(void)
00690     {
00691         Powerstep01_CmdResetPos();
00692     }
00693 
00694     /**
00695      * @brief  Running the motor towards a specified direction.
00696      * @param  direction The direction of rotation.
00697      * @param  speed in steps/s.
00698      * @retval None.
00699      */
00700     virtual void Run(direction_t direction, float speed)
00701     {
00702         Powerstep01_CmdRun((motorDir_t) (direction == StepperMotor::FWD ? FORWARD : BACKWARD), Speed_Steps_s_to_RegVal(speed));
00703     }
00704         
00705     /**
00706      * @brief Sends commands stored previously in the queue by QueueCommands.
00707      * @param  None.
00708      * @retval None.
00709      */ 
00710     virtual void SendQueuedCommands(void)
00711     {
00712         Powerstep01_SendQueuedCommands();
00713     }
00714     
00715     /**
00716      * @brief  Setting a parameter with an input float value.
00717      * @param  param Register adress.
00718      * @param  value Float value to convert and set into the register.
00719      * @retval TRUE if param and value are valid, FALSE otherwise
00720      * @note   parameter can be one of the following:
00721      *           + POWERSTEP01_EL_POS
00722      *           + POWERSTEP01_ABS_POS
00723      *           + POWERSTEP01_MARK
00724      *           + POWERSTEP01_ACC
00725      *           + POWERSTEP01_DEC
00726      *           + POWERSTEP01_MAX_SPEED
00727      *           + POWERSTEP01_MIN_SPEED
00728      *           + POWERSTEP01_FS_SPD
00729      *           + POWERSTEP01_INT_SPD
00730      *           + POWERSTEP01_K_THERM
00731      *           + POWERSTEP01_OCD_TH
00732      *           + POWERSTEP01_STALL_TH
00733      *           + POWERSTEP01_KVAL_HOLD
00734      *           + POWERSTEP01_KVAL_RUN
00735      *           + POWERSTEP01_KVAL_ACC
00736      *           + POWERSTEP01_KVAL_DEC
00737      *           + POWERSTEP01_ST_SLP
00738      *           + POWERSTEP01_FN_SLP_ACC
00739      *           + POWERSTEP01_FN_SLP_DEC
00740      *           + POWERSTEP01_TVAL_HOLD
00741      *           + POWERSTEP01_TVAL_RUN
00742      *           + POWERSTEP01_TVAL_ACC
00743      *           + POWERSTEP01_TVAL_DEC
00744      *           + POWERSTEP01_TON_MIN
00745      *           + POWERSTEP01_TOFF_MIN
00746      */
00747     virtual bool SetAnalogValue(unsigned int param, float value)
00748     {
00749       return Powerstep01_SetAnalogValue((powerstep01_Registers_t)param, value);
00750     }
00751     
00752     /**
00753      * @brief  Setting a parameter.
00754      * @param  parameter A parameter's register adress.
00755      * @param  value The parameter's value.
00756      * @retval None.
00757      *         parameter can be one of the following:
00758      *           + POWERSTEP01_ABS_POS
00759      *           + POWERSTEP01_EL_POS
00760      *           + POWERSTEP01_MARK
00761      *           + POWERSTEP01_ACC
00762      *           + POWERSTEP01_DEC
00763      *           + POWERSTEP01_MAX_SPEED
00764      *           + POWERSTEP01_MIN_SPEED
00765      *           (voltage mode) + POWERSTEP01_KVAL_HOLD : value in %
00766      *           (current mode) + POWERSTEP01_TVAL_HOLD : value in mV
00767      *           (voltage mode) + POWERSTEP01_KVAL_RUN  : value in %
00768      *           (current mode) + POWERSTEP01_TVAL_RUN  : value in mV
00769      *           (voltage mode) + POWERSTEP01_KVAL_ACC  : value in %
00770      *           (current mode) + POWERSTEP01_TVAL_ACC  : value in mV
00771      *           (voltage mode) + POWERSTEP01_KVAL_DEC  : value in %
00772      *           (current mode) + POWERSTEP01_TVAL_DEC  : value in mV
00773      *           (voltage mode) + POWERSTEP01_INT_SPD
00774      *           (voltage mode) + POWERSTEP01_ST_SLP
00775      *           (current mode) + POWERSTEP01_T_FAST
00776      *           (voltage mode) + POWERSTEP01_FN_SLP_ACC
00777      *           (current mode) + POWERSTEP01_TON_MIN
00778      *           (voltage mode) + POWERSTEP01_FN_SLP_DEC
00779      *           (current mode) + POWERSTEP01_TOFF_MIN
00780      *           (voltage mode) + POWERSTEP01_K_THERM
00781      *           + POWERSTEP01_ADC_OUT
00782      *           + POWERSTEP01_OCD_TH
00783      *           (voltage mode) + POWERSTEP01_STALL_TH
00784      *           + POWERSTEP01_FS_SPD
00785      *           + POWERSTEP01_STEP_MODE
00786      *           + POWERSTEP01_ALARM_EN
00787      *           + POWERSTEP01_GATECFG1
00788      *           + POWERSTEP01_GATECFG2
00789      *           + POWERSTEP01_CONFIG
00790      */
00791     virtual void SetRawParameter(unsigned int parameter, unsigned int value)
00792     {
00793         Powerstep01_CmdSetParam((powerstep01_Registers_t)parameter, (uint32_t)value);
00794     }
00795     
00796     /**
00797      * @brief  Enable the step clock mode.
00798      * @param  frequency the frequency of PWM.
00799      * @retval None.
00800      */
00801     virtual void StepClockModeEnable(direction_t direction)
00802     {
00803         Powerstep01_CmdStepClock((motorDir_t) (direction == StepperMotor::FWD ? FORWARD : BACKWARD));
00804     }
00805     
00806     /**
00807      * @brief  Setting the frequency of PWM.
00808      *         The frequency controls directly the speed of the device.
00809      * @param  frequency the frequency of PWM.
00810      * @retval None.
00811      */
00812     virtual void StepClockStart(uint16_t frequency)
00813     {
00814         /* Computing the period of PWM. */
00815         double period = 1.0f / frequency;
00816         
00817         /* Setting the period and the duty-cycle of PWM. */
00818         pwm.period(period);
00819         pwm.write(0.5f);
00820     }
00821 
00822     /**
00823      * @brief  Stopping the PWM.
00824      * @param  None.
00825      * @retval None.
00826      */
00827     virtual void StepClockStop(void)
00828     {
00829         pwm.write(0.0f);
00830     }
00831     
00832     /**
00833      * @brief Public static functions
00834      */    
00835 
00836     static uint8_t GetNbDevices(void)
00837     {
00838         return numberOfDevices;
00839     }
00840 
00841     /**
00842      * @brief To and from register parameter conversion functions
00843      */
00844      
00845     /**********************************************************
00846      * @brief Convert the float formatted acceleration or
00847      * deceleration into respectively an ACC or DEC register value
00848      * @param[in] steps_s2 the acceleration or deceleration as
00849      * steps/s^2, range 14.55 to 59590 steps/s^2
00850      * @retval The acceleration or deceleration as steps/tick^2
00851      **********************************************************/
00852     static uint16_t AccDec_Steps_s2_to_RegVal(float steps_s2)
00853     {
00854         return ((uint16_t)(((float)(steps_s2)*0.068719476736f)+0.5f));
00855     }
00856     
00857     /**********************************************************
00858      * @brief Convert the ACC or DEC register value into step/s^2
00859      * @param[in] regVal The ACC or DEC register value
00860      * @retval The speed as steps/s
00861      **********************************************************/
00862     static float AccDec_RegVal_to_Steps_s2(uint32_t regVal)
00863     {
00864         return (((float)(regVal))*14.5519152283f);
00865     }
00866     
00867     /**********************************************************
00868      * @brief Converts BEMF compensation slope to values for ST_SLP,
00869      * FN_SLP_ACC or FN_SLP_DEC register
00870      * @param[in] percentage BEMF compensation slope percentage,
00871      * range 0 to 0.4% (0.004) s/step
00872      * @retval value for ST_SLP, FN_SLP_ACC or FN_SLP_DEC register
00873      **********************************************************/
00874     static uint8_t BEMFslope_Perc_to_RegVal(float percentage)
00875     {
00876         return ((uint8_t)(((float)(percentage)*637.5f)+0.5f));
00877     }
00878     
00879     /**********************************************************
00880      * @brief Converts values from ST_SLP, FN_SLP_ACC or
00881      * FN_SLP_DEC register to BEMF compensation slope percentage
00882      * @param[in] regVal The ST_SLP, FN_SLP_ACC or FN_SLP_DEC
00883      * register value
00884      * @retval BEMF compensation slope percentage
00885      **********************************************************/
00886     static float BEMFslope_RegVal_to_Perc(uint32_t regVal)
00887     {
00888         return (((float)(regVal))*0.00156862745098f);
00889     }
00890           
00891     /**********************************************************
00892      * @brief Convert the float formatted speed into a FS_SPD 
00893      * register value
00894      * @param[in] steps_s the speed as steps/s, range 15.25 to 15610 steps/s
00895      * @retval The speed as steps/tick
00896      **********************************************************/
00897     static uint16_t FSSpd_Steps_s_to_RegVal(float steps_s)
00898     {
00899         return ((uint16_t)((float)(steps_s)*0.065536f));
00900     }
00901     
00902     /**********************************************************
00903      * @brief Convert the FS_SPD register value into step/s
00904      * @param[in] regVal The FS_SPD register value
00905      * @retval The full Step speed as steps/s
00906      **********************************************************/
00907     static float FSSpd_RegVal_to_Steps_s(uint32_t regVal)
00908     {
00909         return (((float)regVal+0.999f)*15.258789f);
00910     }
00911     
00912     /**********************************************************
00913      * @brief Convert the float formatted speed into a INT_SPEED 
00914      * register value
00915      * @param[in] steps_s the speed as steps/s, range 0 to 976.5 steps/s
00916      * @retval The intersect speed as steps/tick
00917      **********************************************************/
00918     static uint16_t IntSpd_Steps_s_to_RegVal(float steps_s)
00919     {
00920         return ((uint16_t)(((float)(steps_s)*16.777216f)+0.5f));
00921     }
00922     
00923     /**********************************************************
00924      * @brief Convert the INT_SPEED register value into step/s
00925      * @param[in] regVal The INT_SPEED register value
00926      * @retval The speed as steps/s
00927      **********************************************************/
00928     static float IntSpd_RegVal_to_Steps_s(uint32_t regVal)
00929     {
00930         return (((float)(regVal))*0.0596045f);
00931     }
00932     
00933     /**********************************************************
00934      * @brief Convert the float formatted thermal compensation
00935      * factor into a K_THEM register value
00936      * @param[in] compFactor the float formatted thermal 
00937      * compensation factor, range 1 to 1.46875
00938      * @retval value for K_THERM register
00939      **********************************************************/
00940     static uint8_t KTherm_Comp_to_RegVal(float compFactor)
00941     {
00942         return ((uint8_t)((((float)(compFactor)-1.0f)*32.0f)+0.5f));
00943     }
00944     
00945     /**********************************************************
00946      * @brief Convert the K_THERM register value into a float 
00947      * formatted thermal compensation factor
00948      * @param[in] regVal The K_THERM register value
00949      * @retval The float formatted thermal compensation factor
00950      **********************************************************/
00951     static float KTherm_RegVal_to_Comp(uint32_t regVal)
00952     {
00953         return (((float)(regVal))*0.03125f+1);
00954     }
00955     
00956     /**********************************************************
00957      * @brief Converts voltage in percentage to values for KVAL_RUN,
00958      * KVAL_HOLD, KVAL_ACC or KVAL_DEC register
00959      * @param[in] percentage percentage of the power supply voltage
00960      * applied to the motor windings, range 0.4% to 99.6%
00961      * @retval value for KVAL_RUN, KVAL_HOLD, KVAL_ACC or
00962      * KVAL_DEC register
00963      * @note The voltage applied is sinusoidal
00964      **********************************************************/
00965     static uint8_t Kval_Perc_to_RegVal(float percentage)
00966     {
00967         return ((uint8_t)(((float)(percentage)*2.56f)+0.5f));
00968     }
00969     
00970     /**********************************************************
00971      * @brief Converts values from KVAL_RUN, KVAL_HOLD, KVAL_ACC
00972      * or KVAL_DEC register to percentage
00973      * @param[in] regVal The KVAL_RUN, KVAL_HOLD, KVAL_ACC
00974      * or KVAL_DEC register value
00975      * @retval percentage of the power supply voltage applied to
00976      * the motor windings
00977      * @note The voltage applied is sinusoidal
00978      **********************************************************/
00979     static float Kval_RegVal_to_Perc(uint32_t regVal)
00980     {
00981         return (((float)(regVal))*0.390625f);
00982     }
00983     
00984     /**********************************************************
00985      * @brief Convert the float formatted speed into a MAX_SPEED 
00986      * register value
00987      * @param[in] steps_s the speed as steps/s, range 15.25 to 15610 steps/s
00988      * @retval The speed as steps/tick
00989      **********************************************************/
00990     static uint16_t MaxSpd_Steps_s_to_RegVal(float steps_s)
00991     {
00992         return ((uint16_t)(((float)(steps_s)*0.065536f)+0.5f));
00993     }
00994     
00995     /**********************************************************
00996      * @brief Convert the MAX_SPEED register value into step/s
00997      * @param[in] regVal The MAX_SPEED register value
00998      * @retval The speed as steps/s
00999      **********************************************************/
01000     static float MaxSpd_RegVal_to_Steps_s(uint32_t regVal)
01001     {
01002         return (((float)(regVal))*15.258789f);
01003     }
01004     
01005     /**********************************************************
01006      * @brief Convert the float formatted speed into a MIN_SPEED 
01007      * register value
01008      * @param[in] steps_s the speed as steps/s, range 0 to 976.3 steps/s
01009      * @retval The speed as steps/tick
01010      **********************************************************/
01011     static uint16_t MinSpd_Steps_s_to_RegVal(float steps_s)
01012     {
01013         return ((uint16_t)(((float)(steps_s)*4.194304f)+0.5f));
01014     }
01015     
01016     /**********************************************************
01017      * @brief Convert the MIN_SPEED register value into step/s
01018      * @param[in] regVal The MIN_SPEED register value
01019      * @retval The speed as steps/s
01020      **********************************************************/
01021     static float MinSpd_RegVal_to_Steps_s(uint32_t regVal)
01022     {
01023         return (((float)(regVal))*0.238418579f);
01024     }
01025     
01026     /**********************************************************
01027      * @brief Convert the float formatted speed into a SPEED 
01028      * register value
01029      * @param[in] steps_s the speed as steps/s, range 0 to 15625 steps/s
01030      * @retval The speed as steps/tick
01031      **********************************************************/
01032     static uint32_t Speed_Steps_s_to_RegVal(float steps_s)
01033     {
01034         return ((uint32_t)(((float)(steps_s)*67.108864f)+0.5f));
01035     }
01036     
01037     /**********************************************************
01038      * @brief Convert the SPEED register value into step/s
01039      * @param[in] regVal The SPEED register value
01040      * @retval The speed as steps/s
01041      **********************************************************/
01042     static float Speed_RegVal_to_Steps_s(uint32_t regVal)
01043     {
01044         return (((float)(regVal))*0.01490116119f);
01045     }
01046     
01047     /**********************************************************
01048      * @brief Converts STALL or OCD Threshold voltage in mV to 
01049      * values for STALL_TH or OCD_TH register
01050      * @param[in] mV voltage in mV, range 31.25mV to 1000mV
01051      * @retval value for STALL_TH or OCD_TH register
01052      **********************************************************/
01053     static uint8_t StallOcd_Th_to_RegVal(float mV)
01054     {
01055         return ((uint8_t)((((float)(mV)-31.25f)*0.032f)+0.5f));
01056     }
01057     
01058     /**********************************************************
01059      * @brief Converts values from STALL_TH or OCD_TH register 
01060      * to mV
01061      * @param[in] regVal The STALL_TH or OCD_TH register value
01062      * @retval voltage in mV
01063      **********************************************************/
01064     static float StallOcd_RegVal_to_Th(uint32_t regVal)
01065     {
01066         return (((float)(regVal+1))*31.25f);
01067     }
01068     
01069     /**********************************************************
01070      * @brief Converts voltage in mV to values for TVAL_RUN,
01071      * TVAL_HOLD, TVAL_ACC or TVAL_DEC register
01072      * @param[in] voltage_mV voltage in mV, range 7.8mV to 1000mV
01073      * @retval value for TVAL_RUN, TVAL_HOLD, TVAL_ACC or
01074      * TVAL_DEC register
01075      * @note The voltage corresponds to a peak output current
01076      * accross the external sense power resistor
01077      **********************************************************/
01078     static uint8_t Tval_RefVoltage_to_RegVal(float voltage_mV)
01079     {
01080         return ((uint8_t)((((float)(voltage_mV)-7.8125f)*0.128f)+0.5f));
01081     }
01082     
01083     /**********************************************************
01084      * @brief Converts values from TVAL_RUN, TVAL_HOLD, TVAL_ACC
01085      * or TVAL_DEC register to mV
01086      * @param[in] regVal The TVAL_RUN, TVAL_HOLD, TVAL_ACC
01087      * or TVAL_DEC register value
01088      * @retval voltage in mV
01089      * @note The voltage corresponds to a peak output current
01090      * accross the external sense power resistor
01091      **********************************************************/
01092     static float Tval_RegVal_to_RefVoltage(uint32_t regVal)
01093     {
01094         return (((float)(regVal+1))*7.8125f);
01095     }
01096     
01097     /**********************************************************
01098      * @brief Convert time in us to values for TON_MIN register
01099      * @param[in] tmin_us time in us, range 0.5us to 64us
01100      * @retval value for TON_MIN register
01101      **********************************************************/
01102     static uint8_t Tmin_Time_to_RegVal(float tmin_us)
01103     {
01104         return ((uint8_t)((((float)(tmin_us)-0.5f)*2.0f)+0.5f));
01105     }
01106     
01107     /**********************************************************
01108      * @brief Convert values for TON_MIN or TOFF_MIN register to time in us
01109      * @param[in] regVal The TON_MIN or TOFF_MIN register value
01110      * @retval time in us
01111      **********************************************************/
01112     static float Tmin_RegVal_to_Time(uint32_t regVal)
01113     {
01114         return (((float)(regVal+1))*0.5f);
01115     }
01116     
01117     /*** Public Interrupt Related Methods ***/
01118 
01119     /* ACTION 6 --------------------------------------------------------------*
01120      * Implement here interrupt related methods, if any.                      *
01121      * Note that interrupt handling is platform dependent, e.g.:              *
01122      *   + mbed:                                                              *
01123      *     InterruptIn feature_irq(pin); //Interrupt object.                  *
01124      *     feature_irq.rise(callback);   //Attach a callback.                 *
01125      *     feature_irq.mode(PullNone);   //Set interrupt mode.                *
01126      *     feature_irq.enable_irq();     //Enable interrupt.                  *
01127      *     feature_irq.disable_irq();    //Disable interrupt.                 *
01128      *   + Arduino:                                                           *
01129      *     attachInterrupt(pin, callback, RISING); //Attach a callback.       *
01130      *     detachInterrupt(pin);                   //Detach a callback.       *
01131      *                                                                        *
01132      * Example (mbed):                                                        *
01133      *   void AttachFeatureIRQ(void (*fptr) (void))                           *
01134      *   {                                                                    *
01135      *     feature_irq.rise(fptr);                                            *
01136      *   }                                                                    *
01137      *                                                                        *
01138      *   void EnableFeatureIRQ(void)                                          *
01139      *   {                                                                    *
01140      *     feature_irq.enable_irq();                                          *
01141      *   }                                                                    *
01142      *                                                                        *
01143      *   void DisableFeatureIRQ(void)                                         *
01144      *   {                                                                    *
01145      *     feature_irq.disable_irq();                                         *
01146      *   }                                                                    *
01147      *------------------------------------------------------------------------*/
01148     /**
01149      * @brief  Attaching an interrupt handler to the FLAG interrupt.
01150      * @param  fptr An interrupt handler.
01151      * @retval None.
01152      */
01153     void AttachFlagIRQ(void (*fptr)(void))
01154     {
01155         flag_irq.fall(fptr);
01156     }
01157     
01158     /**
01159      * @brief  Enabling the FLAG interrupt handling.
01160      * @param  None.
01161      * @retval None.
01162      */
01163     void EnableFlagIRQ(void)
01164     {
01165         flag_irq.enable_irq();
01166     }
01167     
01168     /**
01169      * @brief  Disabling the FLAG interrupt handling.
01170      * @param  None.
01171      * @retval None.
01172      */
01173     void DisableFlagIRQ(void)
01174     {
01175         flag_irq.disable_irq();
01176     }
01177 
01178     /**
01179      * @brief  Attaching an interrupt handler to the BUSY interrupt.
01180      * @param  fptr An interrupt handler.
01181      * @retval None.
01182      */
01183     void AttachBusyIRQ(void (*fptr)(void))
01184     {
01185         busy_irq.fall(fptr);
01186     }
01187     
01188     /**
01189      * @brief  Enabling the BUSY interrupt handling.
01190      * @param  None.
01191      * @retval None.
01192      */
01193     void EnableBusyIRQ(void)
01194     {
01195         busy_irq.enable_irq();
01196     }
01197 
01198     /**
01199      * @brief  Disabling the BUSY interrupt handling.
01200      * @param  None.
01201      * @retval None.
01202      */
01203     void DisableBusyIRQ(void)
01204     {
01205         busy_irq.disable_irq();
01206     }
01207     
01208 protected:
01209 
01210     /*** Protected Component Related Methods ***/
01211 
01212     /* ACTION 7 --------------------------------------------------------------*
01213      * Declare here the component's specific methods.                         *
01214      * They should be:                                                        *
01215      *   + Methods with the same name of the C component's virtual table's    *
01216      *     functions (1);                                                     *
01217      *   + Methods with the same name of the C component's extended virtual   *
01218      *     table's functions, if any (2);                                     *
01219      *   + Helper methods, if any, like functions declared in the component's *
01220      *     source files but not pointed by the component's virtual table (3). *
01221      *                                                                        *
01222      * Example:                                                               *
01223      *   Status_t COMPONENT_GetValue(float *f);   //(1)                       *
01224      *   Status_t COMPONENT_EnableFeature(void);  //(2)                       *
01225      *   Status_t COMPONENT_ComputeAverage(void); //(3)                       *
01226      *------------------------------------------------------------------------*/
01227     Status_t Powerstep01_Init(void *init);
01228     Status_t Powerstep01_ReadID(uint8_t *id);
01229     void Powerstep01_AttachErrorHandler(void (*callback)(uint16_t error));
01230     uint8_t Powerstep01_CheckBusyHw(void);
01231     uint8_t Powerstep01_CheckStatusHw(void);
01232     uint16_t Powerstep01_CmdGetStatus(void);
01233     void Powerstep01_CmdGoHome(void);
01234     void Powerstep01_CmdGoMark(void);
01235     void Powerstep01_CmdGoTo(int32_t targetPosition);
01236     void Powerstep01_CmdGoToDir(motorDir_t direction, int32_t targetPosition);
01237     void Powerstep01_CmdGoUntil(motorAction_t action, motorDir_t direction, uint32_t speed);
01238     void Powerstep01_CmdHardHiZ(void);
01239     void Powerstep01_CmdHardStop(void);
01240     void Powerstep01_CmdMove(motorDir_t direction, uint32_t stepCount);
01241     void Powerstep01_CmdNop(void);
01242     void Powerstep01_CmdReleaseSw(motorAction_t action, motorDir_t direction);
01243     void Powerstep01_CmdResetDevice(void);
01244     void Powerstep01_CmdResetPos(void);
01245     void Powerstep01_CmdRun(motorDir_t direction, uint32_t speed);
01246     void Powerstep01_CmdSoftHiZ(void);
01247     void Powerstep01_CmdSoftStop(void);
01248     void Powerstep01_CmdStepClock(motorDir_t direction);
01249     void Powerstep01_ErrorHandler(uint16_t error);
01250     void Powerstep01_FetchAndClearAllStatus(void); 
01251     uint16_t Powerstep01_GetFetchedStatus(void);
01252     uint32_t Powerstep01_GetFwVersion(void);
01253     int32_t Powerstep01_GetMark(void);
01254     int32_t Powerstep01_GetPosition(void);
01255     bool Powerstep01_IsDeviceBusy(void);
01256     uint16_t Powerstep01_ReadStatusRegister(void);
01257     bool Powerstep01_SelectStepMode(motorStepMode_t stepMode);
01258     void Powerstep01_SetHome(void);
01259     void Powerstep01_SetMark(void);
01260     void Powerstep01_WaitForAllDevicesNotBusy(void);
01261     void Powerstep01_WaitWhileActive(void);
01262 
01263     /**
01264      * @brief To and from register parameter conversion functions
01265      */
01266     int32_t Powerstep01_ConvertPosition(uint32_t abs_position_reg);
01267 
01268     /**
01269      * @brief Functions to initialize the registers
01270      */
01271     void Powerstep01_SetDeviceParamsToGivenValues(powerstep01_Init_u_t *initPrm);
01272     void Powerstep01_SetRegisterToPredefinedValues(void);
01273     
01274     /**
01275      * @brief Functions to get and set parameters using digital or analog values
01276      */
01277     uint32_t Powerstep01_CmdGetParam(powerstep01_Registers_t param);
01278     void Powerstep01_CmdSetParam(powerstep01_Registers_t param, uint32_t value);
01279     float Powerstep01_GetAnalogValue(powerstep01_Registers_t param);
01280     void Powerstep01_QueueCommands(uint8_t command, int32_t value);
01281     void Powerstep01_SendCommand(uint8_t command, uint32_t value);
01282     void Powerstep01_SendQueuedCommands(void);
01283     bool Powerstep01_SetAnalogValue(powerstep01_Registers_t param, float value);
01284     void Powerstep01_WriteBytes(uint8_t *pByteToTransmit, uint8_t *pReceivedByte);    
01285     
01286     /**
01287      * @brief      Rounding a floating point number to the nearest unsigned integer number.
01288      * @param  f The floating point number.
01289      * @retval     The nearest unsigned integer number.
01290      */
01291     int round(float f)
01292     {
01293         if (f >= 0)
01294             return (int) f + (f - (int) f < 0.5f ? 0 : 1);
01295         else
01296             return (int) f - (f - (int) f < -0.5f ? 1 : 0);
01297     }
01298     
01299     /*** Component's I/O Methods ***/
01300 
01301     /**
01302      * @brief      Utility function to read data from Powerstep01.
01303      * @param[out] pBuffer pointer to the buffer to read data into.
01304      * @param  NumBytesToRead number of bytes to read.
01305      * @retval     COMPONENT_OK in case of success, COMPONENT_ERROR otherwise.
01306      */
01307     Status_t Read(uint8_t* pBuffer, uint16_t NumBytesToRead)
01308     {
01309         if (dev_spi.spi_read(pBuffer, ssel, NumBytesToRead) != 0)
01310             return COMPONENT_ERROR;
01311         return COMPONENT_OK;
01312     }
01313     
01314     /**
01315      * @brief      Utility function to write data to Powerstep01.
01316      * @param  pBuffer pointer to the buffer of data to send.
01317      * @param  NumBytesToWrite number of bytes to write.
01318      * @retval     COMPONENT_OK in case of success, COMPONENT_ERROR otherwise.
01319      */
01320     Status_t Write(uint8_t* pBuffer, uint16_t NumBytesToWrite)
01321     {
01322         if (dev_spi.spi_write(pBuffer, ssel, NumBytesToWrite) != 0)
01323             return COMPONENT_ERROR;
01324         return COMPONENT_OK;
01325     }
01326 
01327     /**
01328      * @brief      Utility function to read and write data from/to Powerstep01 at the same time.
01329      * @param[out] pBufferToRead pointer to the buffer to read data into.
01330      * @param  pBufferToWrite pointer to the buffer of data to send.
01331      * @param  NumBytes number of bytes to read and write.
01332      * @retval     COMPONENT_OK in case of success, COMPONENT_ERROR otherwise.
01333      */
01334     Status_t ReadWrite(uint8_t* pBufferToRead, uint8_t* pBufferToWrite, uint16_t NumBytes)
01335     {
01336         if (dev_spi.spi_read_write(pBufferToRead, pBufferToWrite, ssel, NumBytes) != 0)
01337             return COMPONENT_ERROR;
01338         return COMPONENT_OK;
01339     }
01340 
01341     /* ACTION 8 --------------------------------------------------------------*
01342      * Implement here other I/O methods beyond those already implemented      *
01343      * above, which are declared extern within the component's header file.   *
01344      *------------------------------------------------------------------------*/
01345     /**
01346      * @brief  Making the CPU wait.
01347      * @param  None.
01348      * @retval None.
01349      */
01350     void Powerstep01_Board_Delay(uint32_t delay)
01351     {
01352         wait_ms(delay);
01353     }
01354 
01355     /**
01356      * @brief  Enabling interrupts.
01357      * @param  None.
01358      * @retval None.
01359      */
01360     void Powerstep01_Board_EnableIrq(void)
01361     {
01362         __enable_irq();
01363     }
01364 
01365     /**
01366      * @brief  Disabling interrupts.
01367      * @param  None.
01368      * @retval None.
01369      */
01370     void Powerstep01_Board_DisableIrq(void)
01371     {
01372         __disable_irq();
01373     }
01374 
01375     /**
01376      * @brief  Initialising the PWM.
01377      * @param  None.
01378      * @retval None.
01379      */
01380     void Powerstep01_Board_StepClockInit(void) {}
01381 
01382     /**
01383      * @brief  Exit the device from reset mode.
01384      * @param  None.
01385      * @retval None.
01386      */
01387     void Powerstep01_Board_ReleaseReset(void)
01388     {
01389         standby_reset = 1;
01390     }
01391 
01392     /**
01393      * @brief  Put the device in reset mode.
01394      * @param  None.
01395      * @retval None.
01396      */
01397     void Powerstep01_Board_Reset(void)
01398     {
01399         standby_reset = 0;
01400     }
01401 
01402     /**
01403      * @brief      Writing and reading bytes to/from the component through the SPI at the same time.
01404      * @param  pByteToTransmit pointer to the buffer of data to send.
01405      * @param[out] pReceivedByte pointer to the buffer to read data into.
01406      * @retval     "0" in case of success, "1" otherwise.
01407      */
01408     uint8_t Powerstep01_Board_SpiWriteBytes(uint8_t *pByteToTransmit, uint8_t *pReceivedByte)
01409     {
01410         return (uint8_t) (ReadWrite(pReceivedByte, pByteToTransmit, numberOfDevices) == COMPONENT_OK ? 0 : 1);
01411     }
01412 
01413 
01414     /*** Component's Instance Variables ***/
01415 
01416     /* ACTION 9 --------------------------------------------------------------*
01417      * Declare here interrupt related variables, if needed.                   *
01418      * Note that interrupt handling is platform dependent, see                *
01419      * "Interrupt Related Methods" above.                                     *
01420      *                                                                        *
01421      * Example:                                                               *
01422      *   + mbed:                                                              *
01423      *     InterruptIn feature_irq;                                           *
01424      *------------------------------------------------------------------------*/
01425     /* Flag Interrupt. */
01426     InterruptIn flag_irq;
01427     
01428     /* Busy Interrupt. */
01429     InterruptIn busy_irq;
01430 
01431     /* ACTION 10 -------------------------------------------------------------*
01432      * Declare here other pin related variables, if needed.                   *
01433      *                                                                        *
01434      * Example:                                                               *
01435      *   + mbed:                                                              *
01436      *     DigitalOut standby_reset;                                          *
01437      *------------------------------------------------------------------------*/
01438     /* Standby/reset pin. */
01439     DigitalOut standby_reset;
01440 
01441     /* Pulse Width Modulation pin. */
01442     PwmOut pwm;
01443 
01444     /* ACTION 11 -------------------------------------------------------------*
01445      * Declare here communication related variables, if needed.               *
01446      *                                                                        *
01447      * Example:                                                               *
01448      *   + mbed:                                                              *
01449      *     DigitalOut ssel;                                                   *
01450      *     DevSPI &dev_spi;                                                   *
01451      *------------------------------------------------------------------------*/
01452     /* Configuration. */
01453     DigitalOut ssel;
01454 
01455     /* IO Device. */
01456     DevSPI &dev_spi;
01457 
01458     /* ACTION 12 -------------------------------------------------------------*
01459      * Declare here identity related variables, if needed.                    *
01460      * Note that there should be only a unique identifier for each component, *
01461      * which should be the "who_am_i" parameter.                              *
01462      *------------------------------------------------------------------------*/
01463     /* Identity */
01464     uint8_t who_am_i;
01465 
01466     /* ACTION 13 -------------------------------------------------------------*
01467      * Declare here the component's static and non-static data, one variable  *
01468      * per line.                                                              *
01469      *                                                                        *
01470      * Example:                                                               *
01471      *   float measure;                                                       *
01472      *   int instance_id;                                                     *
01473      *   static int number_of_instances;                                      *
01474      *------------------------------------------------------------------------*/
01475     /* Data. */
01476     void (*errorHandlerCallback)(uint16_t error);
01477     uint8_t deviceInstance;
01478 
01479     /* Static data. */
01480     static uint8_t numberOfDevices;
01481     static uint8_t spiTxBursts[POWERSTEP01_CMD_ARG_MAX_NB_BYTES][MAX_NUMBER_OF_DEVICES];
01482     static uint8_t spiRxBursts[POWERSTEP01_CMD_ARG_MAX_NB_BYTES][MAX_NUMBER_OF_DEVICES];
01483 
01484 
01485 public:
01486 
01487     /* Static data. */
01488     static bool spiPreemptionByIsr;
01489     static bool isrFlag;
01490     
01491 };
01492 
01493 #endif // __POWERSTEP01_CLASS_H
01494 
01495 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/