Library used to control ST Nucleo Evaluation board IHM12A1, based on STSPIN240 low voltage dual brush DC motor control driver.

Dependencies:   ST_INTERFACES

Dependents:   motori prova_motore SchedamotoriIHM12A1 prova_motore_duck ... more

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

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers STSpin240_250.h Source File

STSpin240_250.h

Go to the documentation of this file.
00001 /**
00002  ******************************************************************************
00003  * @file    STSpin240_250.h
00004  * @author  IPC Rennes
00005  * @version V1.0.0
00006  * @date    April 20th, 2016
00007  * @brief   This file contains the class of a STSpin240_250 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 /* Define to prevent recursive inclusion -------------------------------------*/
00040 
00041 #ifndef __STSPIN240_250_CLASS_H
00042 #define __STSPIN240_250_CLASS_H
00043 
00044 
00045 /* Includes ------------------------------------------------------------------*/
00046 
00047 /* ACTION 1 ------------------------------------------------------------------*
00048  * Include here platform specific header files.                               *
00049  *----------------------------------------------------------------------------*/        
00050 #include "mbed.h"
00051 /* ACTION 2 ------------------------------------------------------------------*
00052  * Include here component specific header files.                              *
00053  *----------------------------------------------------------------------------*/        
00054 #include "STSpin240_250_def.h"
00055 /* ACTION 3 ------------------------------------------------------------------*
00056  * Include here interface specific header files.                              *
00057  *                                                                            *
00058  * Example:                                                                   *
00059  *   #include "HumiditySensor.h"                                              *
00060  *   #include "TemperatureSensor.h"                                           *
00061  *----------------------------------------------------------------------------*/
00062 #include "BDCMotor.h"
00063 
00064 /* Defines -------------------------------------------------------------------*/
00065 
00066 /* MCU wait time in ms after power bridges are enabled */
00067 #define BRIDGE_TURN_ON_DELAY    (1)
00068 
00069 /* MCU wait time in ms after exit standby mode */
00070 #define EXIT_STANDBY_MODE_DELAY    (1)
00071 
00072 /* Classes -------------------------------------------------------------------*/
00073 
00074 
00075 /**
00076  * @brief Class representing a STSpin240_250 component.
00077  */
00078 class STSpin240_250 : public BDCMotor
00079 {
00080 public:
00081 
00082     /*** Constructor and Destructor Methods ***/
00083 
00084     /**
00085      * @brief Constructor.
00086      * @param flag_and_enable_pin   pin name of the EN pin of the component.
00087      * @param standby_reset_pin     pin name of the STBY\RST pin of the component.
00088      * @param dirA_pin              pin name for the direction pin for bridge A.
00089      * @param dirB_pin              pin name for the direction pin for bridge B.
00090      * @param pwmA_pin              pin name for the PWM input for bridge A.
00091      * @param pwmB_pin              pin name for the PWM input for bridge B.
00092      * @param pwmRef_pin            pin name for the REF pin of the component.
00093      */
00094     STSpin240_250(PinName flag_and_enable_pin, PinName standby_reset_pin, PinName dirA_pin, PinName dirB_pin, PinName pwmA_pin, PinName pwmB_pin, PinName pwmRef_pin) :
00095         BDCMotor(),
00096         flag_and_enable(flag_and_enable_pin),
00097         standby_reset(standby_reset_pin),
00098         dirA(dirA_pin),
00099         dirB(dirB_pin),
00100         pwmA(pwmA_pin),
00101         pwmB(pwmB_pin),
00102         pwmRef(pwmRef_pin)
00103     { 
00104         /* Checking stackability. */
00105         if (!(numberOfDevices < MAX_NUMBER_OF_DEVICES))
00106         {
00107             error("Instantiation of the Stpin240_250 component failed: it can be stacked up to %d times.\r\n", MAX_NUMBER_OF_DEVICES);
00108         }
00109 
00110         /* ACTION 4 ----------------------------------------------------------*
00111          * Initialize here the component's member variables, one variable per *
00112          * line.                                                              *
00113          *                                                                    *
00114          * Example:                                                           *
00115          *   measure = 0;                                                     *
00116          *   instance_id = number_of_instances++;                             *
00117          *--------------------------------------------------------------------*/
00118         errorHandlerCallback = 0;
00119         deviceInstance = numberOfDevices++;
00120     }
00121     
00122     /**
00123      * @brief Destructor.
00124      */
00125     virtual ~STSpin240_250(void) {}
00126     
00127 
00128     /*** Public Component Related Methods ***/
00129 
00130     /* ACTION 5 --------------------------------------------------------------*
00131      * Implement here the component's public methods, as wrappers of the C    *
00132      * component's functions.                                                 *
00133      * They should be:                                                        *
00134      *   + Methods with the same name of the C component's virtual table's    *
00135      *     functions (1);                                                     *
00136      *   + Methods with the same name of the C component's extended virtual   *
00137      *     table's functions, if any (2).                                     *
00138      *                                                                        *
00139      * Example:                                                               *
00140      *   virtual int get_value(float *p_data) //(1)                           *
00141      *   {                                                                    *
00142      *     return COMPONENT_get_value(float *pf_data);                        *
00143      *   }                                                                    *
00144      *                                                                        *
00145      *   virtual int enable_feature(void) //(2)                               *
00146      *   {                                                                    *
00147      *     return COMPONENT_enable_feature();                                 *
00148      *   }                                                                    *
00149      *------------------------------------------------------------------------*/
00150 
00151     /**
00152      * @brief Public functions inherited from the Component Class
00153      */
00154 
00155     /**
00156      * @brief  Initialize the component.
00157      * @param  init Pointer to device specific initalization structure.
00158      * @retval "0" in case of success, an error code otherwise.
00159      */
00160     virtual int init(void *init = NULL)
00161     {
00162         return (int) STSpin240_250_Init((void *) init);
00163     }
00164 
00165     /**
00166      * @brief  Getting the ID of the component.
00167      * @param  id Pointer to an allocated variable to store the ID into.
00168      * @retval "0" in case of success, an error code otherwise.
00169      */
00170     virtual int read_id(uint8_t *id = NULL)
00171     {
00172         return (int) STSpin240_250_ReadId((uint8_t *) id);
00173     }
00174 
00175     /**
00176      * @brief Public functions inherited from the BCDMotor Class
00177      */
00178 
00179     /**
00180      * @brief  Disabling the specified bridge.
00181      * @param  bridgeId from 0 for bridge A to 1 for bridge B.
00182      * @retval None.
00183      */
00184     virtual void disable_bridge(unsigned int bridgeId) 
00185     {
00186         STSpin240_250_DisableBridge(bridgeId);
00187     }
00188      
00189     /**
00190      * @brief  Enabling the specified bridge.
00191      * @param  bridgeId from 0 for bridge A to 1 for bridge B
00192      * @retval None.
00193      */
00194     virtual void enable_bridge(unsigned int bridgeId)
00195     {
00196         STSpin240_250_EnableBridge(bridgeId);
00197     }
00198      
00199     /**
00200      * @brief  Getting the PWM frequency of the specified bridge;
00201      * @param  bridgeId from 0 for bridge A to 1 for bridge B.
00202      * @retval The frequency in Hz of the specified bridge input PWM.
00203      */
00204     virtual unsigned int get_bridge_input_pwm_freq(unsigned int bridgeId)
00205     {
00206         return (unsigned int) STSpin240_250_GetBridgeInputPwmFreq(bridgeId);
00207     }
00208     
00209     /**
00210      * @brief  Getting the bridge status.
00211      * @param  bridgeId from 0 for bridge A to 1 for bridge B.
00212      * @retval The status.
00213      */
00214     virtual unsigned int get_bridge_status(unsigned int bridgeId)
00215     {
00216         return (unsigned int) STSpin240_250_GetBridgeStatus();
00217     }
00218 
00219     /**
00220      * @brief  Getting the device State. 
00221      * @param  motorId from 0 to (MAX_NUMBER_OF_BRUSH_DC_MOTORS - 1). 
00222      * @retval The device state (STEADY or INACTIVE)
00223      */
00224     virtual unsigned int get_device_state(unsigned int motorId)
00225     {
00226         return (motorState_t) STSpin240_250_GetDeviceState(motorId);
00227     }
00228    
00229     /**
00230      * @brief  Getting the current speed in % of the specified motor.
00231      * @param  motorId from 0 to (MAX_NUMBER_OF_BRUSH_DC_MOTORS - 1). 
00232      * @retval The current speed in %.
00233      */
00234     virtual unsigned int get_speed(unsigned int motorId)
00235     {
00236         return (unsigned int) STSpin240_250_GetCurrentSpeed(motorId);
00237     }
00238     
00239     /**
00240      * @brief  Stopping the motor and disabling the power bridge immediately.
00241      * @param  motorId from 0 to (MAX_NUMBER_OF_BRUSH_DC_MOTORS - 1). 
00242      * @retval None.
00243      */
00244     virtual void hard_hiz(unsigned int motorId)
00245     {
00246        STSpin240_250_HardHiz(motorId);
00247     }
00248     
00249     /**
00250      * @brief  Stopping the motor immediately.
00251      * @param  motorId from 0 to (MAX_NUMBER_OF_BRUSH_DC_MOTORS - 1). 
00252      * @retval None.
00253      */
00254     virtual void hard_stop(unsigned int motorId)
00255     {
00256        STSpin240_250_HardStop(motorId);
00257     }
00258 
00259     /**
00260      * @brief  Running the motor.
00261      * @param  motorId from 0 to (MAX_NUMBER_OF_BRUSH_DC_MOTORS - 1).
00262      * @param  direction The direction of rotation.
00263      * @retval None.
00264      */
00265     virtual void run(unsigned int motorId, direction_t direction) 
00266     {
00267        STSpin240_250_Run(motorId, (motorDir_t) direction);
00268     }
00269     
00270     /**
00271      * @brief  Setting the PWM frequency of the specified bridge.
00272      * @param  bridgeId from 0 for bridge A to 1 for bridge B.
00273      * @param  frequency of the PWM in Hz
00274      * @retval None.
00275      */
00276     virtual void set_bridge_input_pwm_freq(unsigned int bridgeId, unsigned int frequency)
00277     {
00278         STSpin240_250_SetBridgeInputPwmFreq(bridgeId, frequency);
00279     }
00280         
00281     /**
00282      * @brief  Setting the dual bridge configuration mode.
00283      * @param  configuration. The bridge configuration.
00284      * @retval None.
00285      */
00286     virtual void set_dual_full_bridge_config(unsigned int configuration)
00287     {
00288         STSpin240_250_SetDualFullBridgeconfig(configuration);
00289     }
00290 
00291     /**
00292      * @brief  Setting the speed in %.
00293      * @param  motorId from 0 to (MAX_NUMBER_OF_BRUSH_DC_MOTORS - 1).
00294      * @param  speed The new speed in %.
00295      * @retval "true" in case of success, "false" otherwise.
00296      */
00297     virtual bool set_speed(unsigned int motorId, unsigned int speed)
00298     {
00299         return (bool) STSpin240_250_SetMaxSpeed(motorId, speed);
00300     }
00301 
00302     /**
00303      * @brief Public functions NOT inherited
00304      */
00305      
00306     /**
00307      * @brief  Attaching an error handler.
00308      * @param  fptr An error handler.
00309      * @retval None.
00310      */
00311     virtual void attach_error_handler(void (*fptr)(uint16_t error))
00312     {
00313         STSpin240_250_AttachErrorHandler((void (*)(uint16_t error)) fptr);
00314     }
00315     
00316     /**
00317      * @brief  Getting the motor current direction.
00318      * @param  motorId from 0 to (MAX_NUMBER_OF_BRUSH_DC_MOTORS - 1).
00319      * @retval direction The direction of rotation.
00320      */
00321     virtual direction_t get_direction(unsigned int motorId)
00322     {
00323         return (direction_t) STSpin240_250_GetDirection(motorId);
00324     }
00325 
00326     /**
00327      * @brief  Getting the version of the firmware.
00328      * @param  None.
00329      * @retval The version of the firmware.
00330      */
00331     virtual unsigned int get_fw_version(void)
00332     {
00333         return (unsigned int) STSpin240_250_GetFwVersion();
00334     }
00335 
00336     /**
00337      * @brief  Getting the duty cycle of the PWM used for REF.
00338      * @param  refId Id of the reference PWM signal.
00339      * @retval duty cycle in % (from 0 to 100)
00340      */
00341     virtual unsigned int get_ref_pwm_dc(unsigned int refId)
00342     {
00343         return (unsigned int) STSpin240_250_GetRefPwmDc(refId);
00344     }
00345     
00346     /**
00347      * @brief  Getting the frequency of the PWM used for REF.
00348      * @param  refId Id of the reference PWM signal.
00349      * @retval frequency in Hz.
00350      */
00351     virtual unsigned int get_ref_pwm_freq(unsigned int refId)
00352     {
00353         return (unsigned int) STSpin240_250_GetRefPwmFreq(refId);
00354     }
00355     
00356     /**
00357      * @brief  Releasing the reset (exiting standby mode).
00358      * @param  None.
00359      * @retval None.
00360      */
00361     virtual void release_reset(void)
00362     {
00363        STSpin240_250_ReleaseReset();
00364     }
00365     
00366     /**
00367      * @brief  Reseting (entering standby mode).
00368      * @param  None.
00369      * @retval None.
00370      */
00371     virtual void reset(void)
00372     {
00373        STSpin240_250_Reset();
00374     }
00375         
00376     /**
00377      * @brief  Setting the direction of rotation of the firmware.
00378      * @param  motorId from 0 to (MAX_NUMBER_OF_BRUSH_DC_MOTORS - 1).
00379      * @param direction The direction of rotation.
00380      * @retval None
00381      */
00382     virtual void set_direction(unsigned int motorId, direction_t direction)
00383     {
00384        STSpin240_250_SetDirection(motorId, (motorDir_t) direction);
00385     }
00386 
00387     /**
00388      * @brief  Setting the duty cycle of the PWM used for REF.
00389      * @param  refId Id of the reference PWM signal.
00390      * @param  newDc new duty cycle from 0 to 100
00391      * @retval None.
00392      */
00393     virtual void set_ref_pwm_dc(unsigned int refId, unsigned int newDc)
00394     {
00395         STSpin240_250_SetRefPwmDc(refId, newDc);
00396     }
00397     
00398     /**
00399      * @brief  Setting the frequency of the PWM used for REF.
00400      * @param  refId Id of the reference PWM signal.
00401      * @param  frequency in Hz.
00402      * @retval None.
00403      */
00404     virtual void set_ref_pwm_freq(unsigned int refId, unsigned int frequency)
00405     {
00406         STSpin240_250_SetRefPwmFreq(refId, frequency);
00407     }
00408 
00409     /**
00410      * @brief Public static functions
00411      */    
00412     static uint8_t get_nb_devices(void)
00413     {
00414         return numberOfDevices;
00415     }
00416 
00417     /*** Public Interrupt Related Methods ***/
00418 
00419     /* ACTION 6 --------------------------------------------------------------*
00420      * Implement here interrupt related methods, if any.                      *
00421      * Note that interrupt handling is platform dependent, e.g.:              *
00422      *   + mbed:                                                              *
00423      *     InterruptIn feature_irq(pin); //Interrupt object.                  *
00424      *     feature_irq.rise(callback);   //Attach a callback.                 *
00425      *     feature_irq.mode(PullNone);   //Set interrupt mode.                *
00426      *     feature_irq.enable_irq();     //Enable interrupt.                  *
00427      *     feature_irq.disable_irq();    //Disable interrupt.                 *
00428      *   + Arduino:                                                           *
00429      *     attachInterrupt(pin, callback, RISING); //Attach a callback.       *
00430      *     detachInterrupt(pin);                   //Detach a callback.       *
00431      *                                                                        *
00432      * Example (mbed):                                                        *
00433      *   void attach_feature_irq(void (*fptr) (void))                         *
00434      *   {                                                                    *
00435      *     feature_irq.rise(fptr);                                            *
00436      *   }                                                                    *
00437      *                                                                        *
00438      *   void enable_feature_irq(void)                                        *
00439      *   {                                                                    *
00440      *     feature_irq.enable_irq();                                          *
00441      *   }                                                                    *
00442      *                                                                        *
00443      *   void disable_feature_irq(void)                                       *
00444      *   {                                                                    *
00445      *     feature_irq.disable_irq();                                         *
00446      *   }                                                                    *
00447      *------------------------------------------------------------------------*/
00448     /**
00449      * @brief  Attaching an interrupt handler to the FLAG interrupt.
00450      * @param  fptr An interrupt handler.
00451      * @retval None.
00452      */
00453     void attach_flag_irq(void (*fptr)(void))
00454     {
00455         flag_and_enable.mode(PullDown);
00456         flag_and_enable.fall(fptr);
00457     }
00458     
00459     /**
00460      * @brief  Enabling the FLAG interrupt handling.
00461      * @param  None.
00462      * @retval None.
00463      */
00464     void enable_flag_irq(void)
00465     {
00466         flag_and_enable.enable_irq();
00467     }
00468     
00469     /**
00470      * @brief  Disabling the FLAG interrupt handling.
00471      * @param  None.
00472      * @retval None.
00473      */
00474     void disable_flag_irq(void)
00475     {
00476         flag_and_enable.disable_irq();
00477     }
00478     
00479 protected:
00480 
00481     /*** Protected Component Related Methods ***/
00482 
00483     /* ACTION 7 --------------------------------------------------------------*
00484      * Declare here the component's specific methods.                         *
00485      * They should be:                                                        *
00486      *   + Methods with the same name of the C component's virtual table's    *
00487      *     functions (1);                                                     *
00488      *   + Methods with the same name of the C component's extended virtual   *
00489      *     table's functions, if any (2);                                     *
00490      *   + Helper methods, if any, like functions declared in the component's *
00491      *     source files but not pointed by the component's virtual table (3). *
00492      *                                                                        *
00493      * Example:                                                               *
00494      *   status_t COMPONENT_get_value(float *f);   //(1)                      *
00495      *   status_t COMPONENT_enable_feature(void);  //(2)                      *
00496      *   status_t COMPONENT_compute_average(void); //(3)                      *
00497      *------------------------------------------------------------------------*/
00498     
00499     status_t STSpin240_250_Init(void *init);
00500     status_t STSpin240_250_ReadId(uint8_t *id);
00501     void STSpin240_250_AttachErrorHandler(void (*callback)(uint16_t error));
00502     void STSpin240_250_DisableBridge(uint8_t bridgeId);
00503     void STSpin240_250_EnableBridge(uint8_t bridgeId);
00504     void STSpin240_250_ErrorHandler(uint16_t error);
00505     uint32_t STSpin240_250_GetBridgeInputPwmFreq(uint8_t bridgeId);
00506     uint16_t STSpin240_250_GetBridgeStatus(void);
00507     uint16_t STSpin240_250_GetCurrentSpeed(uint8_t motorId);
00508     motorState_t STSpin240_250_GetDeviceState(uint8_t motorId); 
00509     motorDir_t STSpin240_250_GetDirection(uint8_t motorId); 
00510     uint32_t STSpin240_250_GetFwVersion(void);  
00511     uint8_t STSpin240_250_GetRefPwmDc(uint8_t refId);    
00512     uint32_t STSpin240_250_GetRefPwmFreq(uint8_t refId);
00513     void STSpin240_250_HardHiz(uint8_t motorId); 
00514     void STSpin240_250_HardStop(uint8_t motorId); 
00515     void STSpin240_250_ReleaseReset(void);  
00516     void STSpin240_250_Reset(void);
00517     void STSpin240_250_Run(uint8_t motorId, motorDir_t direction); 
00518     void STSpin240_250_SetBridgeInputPwmFreq(uint8_t bridgeId, uint32_t newFreq); 
00519     void STSpin240_250_SetDirection(uint8_t motorId, motorDir_t dir); 
00520     void STSpin240_250_SetDualFullBridgeconfig(uint8_t enable);         
00521     bool STSpin240_250_SetMaxSpeed(uint8_t motorId,uint16_t newMaxSpeed);
00522     void STSpin240_250_SetRefPwmDc(uint8_t refId, uint8_t newDc);   
00523     void STSpin240_250_SetRefPwmFreq(uint8_t refId, uint32_t newFreq);  
00524 
00525     /**
00526      * @brief Functions to initialize the registers
00527      */
00528     void STSpin240_250_SetDeviceParamsToGivenValues(STSpin240_250_init_t *pInitPrm);
00529     void STSpin240_250_SetDeviceParamsToPredefinedValues(void);
00530     
00531     /**
00532      * @brief  Get the state of the standby/reset pin
00533      */
00534     uint8_t STSpin240_250_GetResetState(void);
00535    
00536     /*** Component's I/O Methods ***/
00537 
00538     /* ACTION 8 --------------------------------------------------------------*
00539      * Implement here other I/O methods beyond those already implemented      *
00540      * above, which are declared extern within the component's header file.   *
00541      *------------------------------------------------------------------------*/
00542     /**
00543      * @brief  Making the CPU wait.
00544      * @param  None.
00545      * @retval None.
00546      */
00547     void STSpin240_250_Board_Delay(uint32_t delay)
00548     {
00549         wait_ms(delay);
00550     }
00551 
00552     /**
00553      * @brief  Disable bridge.
00554      * @param  None.
00555      * @retval None.
00556      */  
00557     void STSpin240_250_Board_DisableBridge(void) 
00558     {
00559         flag_and_enable.disable_irq();
00560         flag_and_enable.mode(PullDown);        
00561     }
00562 
00563     /**
00564      * @brief  Enable bridge.
00565      * @param  addDelay if different from 0, a delay is added after bridge activation..
00566      * @retval None.
00567      */  
00568     void STSpin240_250_Board_EnableBridge(uint8_t addDelay) 
00569     {
00570         flag_and_enable.mode(PullUp);
00571         if (addDelay)
00572         {
00573             STSpin240_250_Board_Delay(BRIDGE_TURN_ON_DELAY);
00574         }
00575         flag_and_enable.enable_irq();       
00576     }  
00577 
00578     /** 
00579      * @brief  Get the status of the reset Pin.
00580      * @param  None.
00581      * @retval None.
00582      */  
00583     uint16_t STSpin240_250_Board_GetResetPinState(void) 
00584     {
00585         return((uint16_t)flag_and_enable.read());
00586     }
00587 
00588     /**
00589      * @brief  Get the status of the flag and enable Pin.
00590      * @param  None.
00591      * @retval None.
00592      */  
00593     uint16_t STSpin240_250_Board_GetFaultPinState(void) 
00594     {
00595         return((uint16_t)flag_and_enable.read());
00596     }
00597     
00598      /**
00599      * @brief  Deinitialising the PWM.
00600      * @param  pwmId 0 for bridge A PWM, 1 for bridge B PWM, 2 for REF PWM.
00601      * @retval None.
00602      */
00603      void STSpin240_250_Board_PwmDeInit(uint8_t pwmId)
00604      {
00605         
00606      }
00607         
00608      /**
00609      * @brief  Initialising the PWM.
00610      * @param  pwmId 0 for bridge A PWM, 1 for bridge B PWM, 2 for REF PWM.
00611      * @param  onlyChannel.
00612      * @retval None.
00613      */
00614     void STSpin240_250_Board_PwmInit(uint8_t pwmId, uint8_t onlyChannel) 
00615     {
00616         
00617     }
00618 
00619     /**
00620      * @brief  Setting the frequency of PWM.
00621      *         The frequency of bridge A and B controls directly the speed of the device.
00622      * @param  pwmId 0 for bridge A PWM, 1 for bridge B PWM, 2 for REF PWM.
00623      * @param  newFreq frequency to apply in Hz.
00624      * @param  duty Duty cycle to use from 0 to 100.
00625      * @retval None.
00626      */
00627     void STSpin240_250_Board_PwmSetFreq(int8_t pwmId, uint32_t newFreq, uint8_t duty)
00628     {
00629         /* Computing the period of PWM. */
00630         double period = 1.0f / newFreq;
00631         
00632         switch (pwmId)
00633         {
00634             case 0:
00635             default:
00636                 /* Setting the period and the duty-cycle of PWM A. */
00637                 pwmA.period(period);
00638                 pwmA.write((float)(duty / 100.0f));
00639             break;
00640             case 1:
00641                 /* Setting the period and the duty-cycle of PWM B. */
00642                 pwmB.period(period);
00643                 pwmB.write((float)(duty / 100.0f));
00644             break;
00645             case 2:
00646                 /* Setting the period and the duty-cycle of PWM Ref. */
00647                 pwmRef.period(period);    
00648                 pwmRef.write((float)(duty / 100.0f));
00649             break;           
00650         }
00651     }
00652 
00653     /**
00654      * @brief  Stopping the PWM.
00655      * @param  pwmId 0 for bridge A PWM, 1 for bridge B PWM, 2 for REF PWM.
00656      * @retval None.
00657      */
00658     void STSpin240_250_Board_PwmStop(uint8_t pwmId)
00659     {
00660         switch (pwmId)
00661         {
00662             case 0:
00663             default:
00664                 pwmA.write(0.0f);
00665             break;
00666             case 1:
00667                 pwmB.write(0.0f);
00668             break;
00669             case 2:
00670                 pwmRef.write(0.0f);
00671             break;
00672         }
00673     }
00674 
00675     /**
00676      * @brief  Putting the device in standby mode.
00677      * @param  None.
00678      * @retval None.
00679      */
00680     void STSpin240_250_Board_ReleaseReset(void)
00681     {
00682         standby_reset = 1;
00683         STSpin240_250_Board_Delay(EXIT_STANDBY_MODE_DELAY);
00684     }
00685 
00686     /**
00687      * @brief  Putting the device in reset mode.
00688      * @param  None.
00689      * @retval None.
00690      */
00691     void STSpin240_250_Board_Reset(void)
00692     {
00693         standby_reset = 0;
00694     }
00695 
00696     /**
00697      * @brief  Setting the direction of rotation.
00698      * @param  bridgeId 0 for bridge A, 1 for bridge B.
00699      * @param  gpioState direction of rotation: "1" for forward, "0" for backward.
00700      * @retval None.
00701      */
00702     void STSpin240_250_Board_SetDirectionGpio(uint8_t bridgeId, uint8_t gpioState)
00703     {
00704       if (bridgeId == 0)
00705       {
00706         dirA = gpioState;
00707       }
00708       else
00709       {
00710         dirB = gpioState;
00711       }
00712     }
00713 
00714     /*** Component's Instance Variables ***/
00715 
00716     /* ACTION 9 --------------------------------------------------------------*
00717      * Declare here interrupt related variables, if needed.                   *
00718      * Note that interrupt handling is platform dependent, see                *
00719      * "Interrupt Related Methods" above.                                     *
00720      *                                                                        *
00721      * Example:                                                               *
00722      *   + mbed:                                                              *
00723      *     InterruptIn feature_irq;                                           *
00724      *------------------------------------------------------------------------*/
00725     /* Flag Interrupt. */
00726     InterruptIn flag_and_enable;
00727 
00728     /* ACTION 10 -------------------------------------------------------------*
00729      * Declare here other pin related variables, if needed.                   *
00730      *                                                                        *
00731      * Example:                                                               *
00732      *   + mbed:                                                              *
00733      *     DigitalOut standby_reset;                                          *
00734      *------------------------------------------------------------------------*/
00735     /* Standby/reset pin. */
00736     DigitalOut standby_reset;
00737 
00738     /* Direction pin of bridge A. */
00739     DigitalOut dirA;
00740 
00741     /* Direction pin of bridge B. */
00742     DigitalOut dirB;
00743 
00744     /* Pulse Width Modulation pin for bridge A input. */
00745     PwmOut pwmA;
00746     
00747     /* Pulse Width Modulation pin for bridge A input. */
00748     PwmOut pwmB;
00749 
00750     /* Pulse Width Modulation pin for Ref signal. */
00751     PwmOut pwmRef;
00752     
00753     /* ACTION 11 -------------------------------------------------------------*
00754      * Declare here communication related variables, if needed.               *
00755      *                                                                        *
00756      * Example:                                                               *
00757      *   + mbed:                                                              *
00758      *     DigitalOut ssel;                                                   *
00759      *     DevSPI &dev_spi;                                                   *
00760      *------------------------------------------------------------------------*/
00761 
00762     /* ACTION 12 -------------------------------------------------------------*
00763      * Declare here identity related variables, if needed.                    *
00764      * Note that there should be only a unique identifier for each component, *
00765      * which should be the "who_am_i" parameter.                              *
00766      *------------------------------------------------------------------------*/
00767     /* Identity */
00768     uint8_t who_am_i;
00769 
00770     /* ACTION 13 -------------------------------------------------------------*
00771      * Declare here the component's static and non-static data, one variable  *
00772      * per line.                                                              *
00773      *                                                                        *
00774      * Example:                                                               *
00775      *   float measure;                                                       *
00776      *   int instance_id;                                                     *
00777      *   static int number_of_instances;                                      *
00778      *------------------------------------------------------------------------*/
00779     /* Data. */
00780     void (*errorHandlerCallback)(uint16_t error);
00781     deviceParams_t device_prm;
00782     uint8_t deviceInstance;
00783 
00784     
00785     /* Static data. */
00786     static uint8_t numberOfDevices;
00787     static uint8_t arrayNbMaxMotorsByConfig[2];
00788     
00789 public:
00790 
00791     /* Static data. */
00792     
00793 };
00794 
00795 #endif // __STSPIN240_250_CLASS_H
00796 
00797 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/