Library used to control ST Nucleo Evaluation board IHM04A1, based on L6206 motor control driver.

Dependencies:   ST_INTERFACES

Dependents:   HelloWorld_IHM04A1 RoboCane_Motore arm_dcmotor_can arm_linear_can_2 ... more

Fork of X_NUCLEO_IHM04A1 by ST Expansion SW Team

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers L6206.h Source File

L6206.h

Go to the documentation of this file.
00001 /**
00002   ******************************************************************************
00003   * @file    L6206.h
00004   * @author  IPC Rennes
00005   * @version V1.1.0
00006   * @date    March 02, 2016
00007   * @brief   L6206 driver (dual full bridge driver)
00008   * @note     (C) COPYRIGHT 2015 STMicroelectronics
00009   ******************************************************************************
00010   * @attention
00011   *
00012   * <h2><center>&copy; COPYRIGHT(c) 2015 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 /* Generated with STM32CubeTOO -----------------------------------------------*/
00041 
00042 
00043 /* Revision ------------------------------------------------------------------*/
00044 /*
00045     Repository:       http://svn.x-nucleodev.codex.cro.st.com/svnroot/X-NucleoDev
00046     Branch/Trunk/Tag: trunk
00047     Based on:         X-CUBE-SPN4/trunk/Drivers/BSP/Components/L6206/L6206.h
00048     Revision:         0
00049 */
00050 
00051 
00052 /* Define to prevent recursive inclusion -------------------------------------*/
00053 
00054 #ifndef __L6206_CLASS_H
00055 #define __L6206_CLASS_H
00056 
00057 
00058 /* Includes ------------------------------------------------------------------*/
00059 
00060 /* ACTION 1 ------------------------------------------------------------------*
00061  * Include here platform specific header files.                               *
00062  *----------------------------------------------------------------------------*/        
00063 #include "mbed.h"
00064 /* ACTION 2 ------------------------------------------------------------------*
00065  * Include here component specific header files.                              *
00066  *----------------------------------------------------------------------------*/        
00067 #include "L6206_def.h"
00068 /* ACTION 3 ------------------------------------------------------------------*
00069  * Include here interface specific header files.                              *
00070  *                                                                            *
00071  * Example:                                                                   *
00072  *   #include "HumiditySensor.h"                                              *
00073  *   #include "TemperatureSensor.h"                                           *
00074  *----------------------------------------------------------------------------*/
00075 #include "BDCMotor.h"
00076 
00077 
00078 
00079 /* Private constants ---------------------------------------------------------*/
00080 
00081 /** @defgroup L6206_Private_Constants L6206 Private Constants
00082   * @{
00083   */
00084 
00085 /// The Number of L6206 devices required for initialisation is not supported
00086 #define L6206_ERROR_0   (0x8000)
00087 /// Error: Access a motor index greater than the one of the current brigde configuration
00088 #define L6206_ERROR_1   (0x8001)
00089 /// Error: Access a motor index which is not bidirectionnal
00090 #define L6206_ERROR_2   (0x8002)
00091 
00092 /// Maximum frequency of the PWMs in Hz
00093 #define L6206_MAX_PWM_FREQ   (100000)
00094 
00095 /// Minimum frequency of the PWMs in Hz
00096 #define L6206_MIN_PWM_FREQ   (2)
00097 
00098 /// Bridge Input 1A
00099 #define INPUT_1A         (0)
00100 /// Bridge Input 2A
00101 #define INPUT_2A         (1)
00102 /// Bridge Input 1B
00103 #define INPUT_1B         (2)
00104 /// Bridge Input 2B
00105 #define INPUT_2B         (3)
00106 
00107 /// Bridge A
00108 #define BRIDGE_A         (0)
00109 /// Bridge B
00110 #define BRIDGE_B         (1)
00111 
00112 
00113 
00114 
00115 
00116 /* Classes -------------------------------------------------------------------*/
00117 
00118 /**
00119  * @brief Class representing a L6206 component.
00120  */
00121 class L6206 : public BDCMotor
00122 {
00123 public:
00124 
00125     /*** Constructor and Destructor Methods ***/
00126 
00127     /**
00128      * @brief Constructor.
00129      */
00130     L6206(PinName EN_flag_A, PinName EN_flag_B, PinName pwm_1A, PinName pwm_2A, PinName pwm_1B, PinName pwm_2B) : BDCMotor(), flag_A_irq(EN_flag_A), flag_B_irq(EN_flag_B), EN_flag_A(EN_flag_A), EN_flag_B(EN_flag_B), pwm_1A(pwm_1A), pwm_2A(pwm_2A), pwm_1B(pwm_1B), pwm_2B(pwm_2B)
00131     {
00132         /* ACTION 4 ----------------------------------------------------------*
00133          * Initialize here the component's member variables, one variable per *
00134          * line.                                                              *
00135          *                                                                    *
00136          * Example:                                                           *
00137          *   measure = 0;                                                     *
00138          *   instance_id = number_of_instances++;                             *
00139          *--------------------------------------------------------------------*/
00140          
00141         flagInterruptCallback = 0;
00142         errorHandlerCallback = 0;
00143         numberOfDevices = 0;
00144         deviceInstance = 0;
00145     }
00146     
00147     /**
00148      * @brief Destructor.
00149      */
00150     virtual ~L6206(void) {}
00151     
00152 
00153     /*** Public Component Related Methods ***/
00154 
00155     /* ACTION 5 --------------------------------------------------------------*
00156      * Implement here the component's public methods, as wrappers of the C    *
00157      * component's functions.                                                 *
00158      * They should be:                                                        *
00159      *   + Methods with the same name of the C component's virtual table's    *
00160      *     functions (1);                                                     *
00161      *   + Methods with the same name of the C component's extended virtual   *
00162      *     table's functions, if any (2).                                     *
00163      *                                                                        *
00164      * Example:                                                               *
00165      *   virtual int get_value(float *f)  //(1)                               *
00166      *   {                                                                    *
00167      *     return COMPONENT_get_value(float *f);                              *
00168      *   }                                                                    *
00169      *                                                                        *
00170      *   virtual int enable_feature(void) //(2)                               *
00171      *   {                                                                    *
00172      *     return COMPONENT_enable_feature();                                 *
00173      *   }                                                                    *
00174      *------------------------------------------------------------------------*/
00175      
00176     /**
00177      * @brief  Initializing the component.
00178      * @param  init Pointer to device specific initalization structure.
00179      * @retval "0" in case of success, an error code otherwise.
00180      */
00181     virtual int init(void *init = NULL)
00182     {
00183         return (int) L6206_Init((void *) init);
00184     }
00185     
00186     /**
00187      * @brief  Getting the ID of the component.
00188      * @param  id Pointer to an allocated variable to store the ID into.
00189      * @retval "0" in case of success, an error code otherwise.
00190      */
00191     virtual int read_id(uint8_t *id = NULL)
00192     {
00193         return (int) L6206_ReadId((uint8_t *) id);
00194     }
00195 
00196 
00197     /**
00198     * @brief  Attaches a user callback to the error Handler.
00199     * The call back will be then called each time the library detects an error
00200     * @param[in] callback Name of the callback to attach to the error Hanlder
00201     * @retval None
00202     */
00203     virtual void attach_error_handler(void (*callback)(uint16_t error))
00204     {
00205         L6206_AttachErrorHandler((void (*)(uint16_t error)) callback);
00206     }
00207 
00208 
00209     /**
00210     * @brief  Attaches a user callback to the flag Interrupt
00211     * The call back will be then called each time the status 
00212     * flag pin will be pulled down due to the occurrence of 
00213     * a programmed alarms ( OCD, thermal alert)
00214     * @param[in] callback Name of the callback to attach 
00215     * to the Flag Interrupt
00216     * @retval None
00217     */
00218     virtual void attach_flag_interrupt(void (*callback)(void))
00219     {
00220         L6206_attach_flag_interrupt((void (*)(void)) callback);
00221     }
00222 
00223     /**
00224     * @brief  Returns the current speed of the specified motor
00225     * @param[in] motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS 
00226     * @retval current speed in % from 0 to 100
00227     */
00228     virtual unsigned int get_speed(unsigned int motorId)
00229     {
00230         return (unsigned int) L6206_GetCurrentSpeed((uint8_t) motorId);
00231     }
00232 
00233     /**
00234     * @brief Returns the device state
00235     * @param[in] motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS 
00236     * @retval State (STEADY or INACTIVE)
00237     */
00238     virtual unsigned int get_device_state(unsigned int motorId)
00239     {
00240         return (motorState_t) L6206_get_device_state((uint8_t) motorId);
00241     }
00242 
00243     /**
00244     * @brief Returns the FW version of the library
00245     * @retval L6206_FW_VERSION
00246     */
00247     virtual uint8_t get_fw_version(void)
00248     {
00249         return (uint8_t) L6206_GetFwVersion();
00250     }
00251 
00252     /**
00253     * @brief  Returns the max  speed of the specified motor
00254     * @param[in] motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS 
00255     * @retval maxSpeed in % from 0 to 100
00256     */
00257     virtual uint16_t get_max_speed(unsigned int motorId)
00258     {
00259         return (uint16_t) L6206_GetMaxSpeed((uint8_t) motorId);
00260     }
00261 
00262     /**
00263     * @brief  Stops the motor without disabling the bridge
00264     * @param[in] motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS 
00265     * @retval none
00266     */
00267     virtual void hard_stop(unsigned int motorId)
00268     {
00269         L6206_HardStop((uint8_t) motorId);
00270     }
00271 
00272     /**
00273     * @brief  Runs the motor
00274     * @param[in] motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS 
00275     * @param[in] direction FORWARD or BACKWARD
00276     * @retval None
00277     * @note  For unidirectionnal motor, direction parameter has no effect
00278     */
00279     virtual void run(unsigned int motorId, direction_t direction)
00280     {
00281         L6206_Run((uint8_t) motorId, (motorDir_t) direction);
00282     }
00283 
00284     /**
00285     * @brief  Changes the max speed of the specified device
00286     * @param[in] motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS 
00287     * @param[in] newMaxSpeed in % from 0 to 100
00288     * @retval true if the command is successfully executed, else false
00289     */
00290     virtual bool set_speed(unsigned int motorId, unsigned int newMaxSpeed)
00291     {
00292         return (bool) L6206_SetMaxSpeed((uint8_t) motorId, (uint16_t) newMaxSpeed);
00293     }
00294 
00295     /**
00296     * @brief Disable the specified bridge
00297     * @param[in] bridgeId (from 0 for bridge A to 1 for bridge B)
00298     * @retval None
00299     * @note  When input of different brigdes are parallelized 
00300     * together, the disabling of one bridge leads to the disabling
00301     * of the second one
00302     */
00303     virtual void disable_bridge(unsigned int bridgeId)
00304     {
00305         L6206_DisableBridge((uint8_t) bridgeId);
00306     }
00307 
00308     /**
00309     * @brief Enable the specified bridge
00310     * @param[in] bridgeId (from 0 for bridge A to 1 for bridge B)
00311     * @retval None
00312     * @note  When input of different brigdes are parallelized 
00313     * together, the enabling of one bridge leads to the enabling
00314     * of the second one
00315     */
00316     virtual void enable_bridge(unsigned int bridgeId)
00317     {
00318         L6206_EnableBridge((uint8_t) bridgeId);
00319     }
00320 
00321     /**
00322     * @brief  Get the status of the bridge enabling of the corresponding bridge
00323     * @param[in] bridgeId from 0 for bridge A to 1 for bridge B
00324     * @retval State of the Enable&Flag pin of the corresponding bridge (1 set, 0 for reset)
00325     */
00326     virtual unsigned int get_bridge_status(unsigned int bridgeId)
00327     {
00328         return (unsigned int) L6206_GetBridgeStatus((uint8_t) bridgeId);
00329     }
00330 
00331     /**
00332     * @brief  Immediatly stops the motor and disable the power bridge
00333     * @param[in] motorId from 0 to MAX_NUMBER_OF_BRUSH_DC_MOTORS 
00334     * @retval None
00335     * @note  if two motors uses the same power bridge, the 
00336     * power bridge will be disable only if the two motors are stopped
00337     */
00338     virtual void hard_hiz(unsigned int motorId)
00339     {
00340         L6206_HardHiz((uint8_t) motorId);
00341     }
00342     
00343     /**
00344     * @brief Error handler which calls the user callback (if defined)
00345     * @param[in] error Number of the error
00346     * @retval None
00347     */
00348     virtual void error_handler(uint16_t error)
00349     {
00350         L6206_ErrorHandler((uint16_t) error);
00351     }
00352 
00353     /**
00354     * @brief Set dual full bridge parallelling configuration
00355     * @param[in] newConfig bridge configuration to apply from 
00356     * dualFullBridgeConfig_t enum
00357     * @retval None
00358     */
00359     virtual void set_dual_full_bridge_config(unsigned int newConfig)
00360     {
00361         L6206_SetDualFullBridgeConfig((uint8_t) newConfig);
00362     }
00363 
00364     /**
00365     * @brief  Get the PWM frequency of the specified bridge 
00366     * @param[in] bridgeId 0 for bridge A, 1 for bridge B
00367     * @retval Freq in Hz
00368     */
00369     virtual unsigned int  get_bridge_input_pwm_freq(unsigned int bridgeId)
00370     {
00371         return (unsigned int) L6206_GetBridgeInputPwmFreq((uint8_t) bridgeId);
00372     }
00373 
00374     /**
00375     * @brief  Changes the PWM frequency of the bridge input
00376     * @param[in] bridgeId 0 for bridge A, 1 for bridge B
00377     * @param[in] newFreq in Hz
00378     * @retval None
00379     */
00380     virtual void set_bridge_input_pwm_freq(unsigned int bridgeId, unsigned int newFreq)
00381     {
00382         L6206_SetBridgeInputPwmFreq((uint8_t) bridgeId, (uint32_t) newFreq);
00383     }
00384 
00385     /**
00386     * @brief  Sets the number of devices to be used
00387     * @param[in] nbDevices (from 1 to MAX_NUMBER_OF_DEVICES)
00388     * @retval TRUE if successfull, FALSE if failure, attempt to set a number of
00389     * devices greater than MAX_NUMBER_OF_DEVICES
00390     */
00391     virtual bool set_nb_devices(uint8_t nbDevices)
00392     {
00393         return (bool) L6206_SetNbDevices((uint8_t) nbDevices);
00394     }
00395 
00396 
00397     /*** Public Interrupt Related Methods ***/
00398 
00399     /* ACTION 6 --------------------------------------------------------------*
00400      * Implement here interrupt related methods, if any.                      *
00401      * Note that interrupt handling is platform dependent, e.g.:              *
00402      *   + mbed:                                                              *
00403      *     InterruptIn feature_irq(pin);           //Interrupt object.        *
00404      *     feature_irq.fall(callback);             //Attach a callback.       *
00405      *     feature_irq.mode(PullNone);             //Set interrupt mode.      *
00406      *     feature_irq.enable_irq();               //Enable interrupt.        *
00407      *     feature_irq.disable_irq();              //Disable interrupt.       *
00408      *   + Arduino:                                                           *
00409      *     attachInterrupt(pin, callback, RISING); //Attach a callback.       *
00410      *     detachInterrupt(pin);                   //Detach a callback.       *
00411      *                                                                        *
00412      * Example (mbed):                                                        *
00413      *   void attach_feature_irq(void (*fptr) (void))                         *
00414      *   {                                                                    *
00415      *     feature_irq.fall(fptr);                                            *
00416      *   }                                                                    *
00417      *                                                                        *
00418      *   void enable_feature_irq(void)                                        *
00419      *   {                                                                    *
00420      *     feature_irq.enable_irq();                                          *
00421      *   }                                                                    *
00422      *                                                                        *
00423      *   void disable_feature_irq(void)                                       *
00424      *   {                                                                    *
00425      *     feature_irq.disable_irq();                                         *
00426      *   }                                                                    *
00427      *------------------------------------------------------------------------*/
00428 
00429 
00430     /**
00431      * @brief  Enabling the FLAG interrupt handling.
00432      * @param[in]  bridgeId 0 for bridge A, 1 for bridge B
00433      * @retval None.
00434      */
00435     virtual void enable_flag_irq(uint8_t bridgeId)
00436     {
00437         if (bridgeId == BRIDGE_A)
00438         {
00439             flag_A_irq.mode(PullUp);
00440             flag_A_irq.fall(this, &L6206::L6206_FlagInterruptHandler);
00441         }
00442         else
00443         {
00444             flag_B_irq.mode(PullUp);
00445             flag_B_irq.fall(this, &L6206::L6206_FlagInterruptHandler);
00446         }
00447     }
00448 
00449     /**
00450      * @brief  Disabling the FLAG interrupt handling.
00451      * @param[in]  bridgeId 0 for bridge A, 1 for bridge B
00452      * @retval None.
00453      */
00454     virtual void disable_flag_irq(uint8_t bridgeId)
00455     {
00456         if (bridgeId == BRIDGE_A)
00457         {
00458             flag_A_irq.fall(NULL);
00459         }
00460         else
00461         {
00462             flag_B_irq.fall(NULL);
00463         }
00464     }
00465 
00466 
00467     /*** Public In/Out Related Methods ***/
00468 
00469 
00470 
00471 protected:
00472 
00473     /*** Protected Component Related Methods ***/
00474 
00475     /* ACTION 7 --------------------------------------------------------------*
00476      * Declare here the component's specific methods.                         *
00477      * They should be:                                                        *
00478      *   + Methods with the same name of the C component's virtual table's    *
00479      *     functions (1);                                                     *
00480      *   + Methods with the same name of the C component's extended virtual   *
00481      *     table's functions, if any (2);                                     *
00482      *   + Helper methods, if any, like functions declared in the component's *
00483      *     source files but not pointed by the component's virtual table (3). *
00484      *                                                                        *
00485      * Example:                                                               *
00486      *   status_t COMPONENT_get_value(float *f);   //(1)                      *
00487      *   status_t COMPONENT_enable_feature(void);  //(2)                      *
00488      *   status_t COMPONENT_compute_average(void); //(3)                      *
00489      *------------------------------------------------------------------------*/
00490     status_t L6206_Init(void *init);
00491     status_t L6206_ReadId(uint8_t *id);
00492     void L6206_TickHandler(uint8_t deviceId);                                    //Handle the device state machine at each tick timer pulse end
00493     void L6206_AttachErrorHandler(void (*callback)(uint16_t error));  //Attach a user callback to the error handler
00494     void L6206_attach_flag_interrupt(void (*callback)(void));                  //Attach a user callback to the flag Interrupt
00495     void L6206_DisableBridge(uint8_t bridgeId);                              //Disable the specified bridge
00496     void L6206_EnableBridge(uint8_t bridgeId);                               //Enable the specified bridge
00497     uint16_t L6206_GetBridgeStatus(uint8_t deviceId);                        //Get bridge status
00498     uint16_t L6206_GetCurrentSpeed(uint8_t motorId);                         //Return the current speed in pps
00499     motorState_t L6206_get_device_state(uint8_t motorId);                      //Return the device state
00500     uint8_t L6206_GetFwVersion(void);                                        //Return the FW version
00501     uint16_t L6206_GetMaxSpeed(uint8_t motorId);                             //Return the max speed in pps
00502     void L6206_HardHiz(uint8_t motorId);                                     //Stop the motor and disable the power bridge
00503     void L6206_HardStop(uint8_t motorId);                                    //Stop the motor without disabling the power bridge
00504     void L6206_Run(uint8_t motorId, motorDir_t direction);                   //run the motor
00505     uint32_t L6206_GetBridgeInputPwmFreq(uint8_t bridgeId);                  // Get the PWM frequency of the bridge input
00506     void L6206_SetBridgeInputPwmFreq(uint8_t bridgeId, uint32_t newFreq);    // Set the PWM frequency of the bridge input
00507     void L6206_SetDualFullBridgeConfig(uint8_t newConfig);                   // Set dual full bridge configuration
00508     bool L6206_SetMaxSpeed(uint8_t motorId,uint16_t newMaxSpeed);            //Set the max speed in pps
00509     bool L6206_SetNbDevices(uint8_t nbDevices);                              //Set the number of driver devices
00510     void L6206_ErrorHandler(uint16_t error);
00511     void L6206_FlagInterruptHandler(void);
00512     uint8_t L6206_GetBridgeIdUsedByMotorId(uint8_t motorId);
00513     uint8_t L6206_GetBridgeInputUsedByMotorId(uint8_t motorId);
00514     uint8_t L6206_GetMotorIdUsingbridgeInput(uint8_t bridgeInput);
00515     uint8_t L6206_GetSecondBridgeInputUsedByMotorId(uint8_t motorId);
00516     bool L6206_IsBidirectionnalMotor(uint8_t motorId);
00517     void L6206_SetDeviceParamsToPredefinedValues(void);
00518     void L6206_SetDeviceParamsToGivenValues(L6206_init_t* initDevicePrm);
00519 
00520     /*** Component's I/O Methods ***/
00521 
00522     /* ACTION 8 --------------------------------------------------------------*
00523      * Implement here other I/O methods beyond those already implemented      *
00524      * above, which are declared extern within the component's header file.   *
00525      *------------------------------------------------------------------------*/
00526      
00527     /**
00528      * @brief      Utility function to set or unset EN pin for Bridge A or Bridge B.
00529      * @param[out] none
00530      * @param[in]  bridgeId 0 for bridge A, 1 for bridge B
00531      * @retval     none
00532      */
00533     void L6206_OutVal( uint8_t bridgeId, uint8_t val)
00534     {
00535         if( bridgeId == BRIDGE_A)
00536         {
00537             EN_flag_A.output();
00538             EN_flag_A.mode(PullNone);
00539             EN_flag_A.write(val);
00540         }
00541         else
00542         {
00543             EN_flag_B.output();
00544             EN_flag_B.mode(PullNone);
00545             EN_flag_B.write(val);
00546         }
00547     }
00548      
00549     /**
00550      * @brief  Making the CPU wait.
00551      * @param  None.
00552      * @retval None.
00553      */
00554     void L6206_Board_Delay(uint32_t delay)
00555     {
00556         wait_ms(delay);
00557     }
00558 
00559     /**
00560     * @brief Disable the specified bridge
00561     * @param[in] bridgeId (from 0 for bridge A to 1 for bridge B)
00562     * @retval None
00563     * @note  When input of different brigdes are parallelized 
00564     * together, the disabling of one bridge leads to the disabling
00565     * of the second one
00566     */
00567     void L6206_Board_DisableBridge(uint8_t bridgeId)
00568     {
00569         disable_flag_irq(BRIDGE_A);
00570         disable_flag_irq(BRIDGE_B);
00571 
00572         __disable_irq();
00573         L6206_OutVal( bridgeId, 0);
00574         __enable_irq();
00575     }
00576 
00577     /**
00578     * @brief Enable the specified bridge
00579     * @param[in] bridgeId (from 0 for bridge A to 1 for bridge B)
00580     * @retval None
00581     * @note  When input of different brigdes are parallelized 
00582     * together, the enabling of one bridge leads to the enabling
00583     * of the second one
00584     */
00585     void L6206_Board_EnableBridge(uint8_t bridgeId, uint8_t addDelay)
00586     {
00587         L6206_OutVal( bridgeId, 1);
00588 
00589         if (addDelay != 0)
00590         {
00591             wait_ms(BSP_MOTOR_CONTROL_BOARD_BRIDGE_TURN_ON_DELAY);
00592         }
00593 
00594         enable_flag_irq( bridgeId);
00595     }
00596     
00597     /**
00598     * @brief  Returns the FLAG pin state.
00599     * @param[in]  bridgeId (from 0 for bridge A to 1 for bridge B)
00600     * @retval The FLAG pin value.
00601     */
00602     uint32_t L6206_Board_GetFlagPinState(uint8_t bridgeId)
00603     {
00604         if (bridgeId == 0)
00605         {
00606             EN_flag_A.input();
00607             return EN_flag_A.read();
00608         }
00609         else
00610         {
00611             EN_flag_B.input();
00612             return EN_flag_B.read(); 
00613         }
00614     }
00615 
00616     /**
00617     * @brief  Initiliases the GPIOs used by the L6206s
00618     * @retval None
00619     */
00620     void L6206_Board_GpioInit(void)
00621     {
00622         /* init bridge Enable */
00623         EN_flag_A.output();
00624         EN_flag_A.write(0);
00625         EN_flag_A.input();
00626 
00627         EN_flag_B.output();
00628         EN_flag_B.write(0);
00629         EN_flag_B.input();
00630         
00631 
00632         /* init flag Irq */
00633         disable_flag_irq(BRIDGE_A);
00634         disable_flag_irq(BRIDGE_B);
00635 
00636     }
00637 
00638     /**
00639     * @brief  Sets the frequency of PWM used for bridges inputs
00640     * @param[in] bridgeInput 0 for input 1A, 1 for input 2A,
00641     * 2 for input 1B,  3 for input 2B
00642     * @param[in] newFreq in Hz
00643     * @param[in] duty Duty cycle
00644     * @retval None
00645     * @note The frequency is directly the current speed of the device
00646     */
00647     void L6206_Board_PwmSetFreq(uint8_t bridgeInput, uint32_t newFreq, uint8_t duty)
00648     {
00649         /* Computing the period of PWM. */
00650         float period = 1.0f / newFreq;
00651         float duty_cycle;
00652         int period_us = (int)(period * 1000000);
00653 
00654         if (duty > 100)
00655         {
00656             duty = 100;
00657         }
00658         duty_cycle = (float)duty / 100.0f;
00659 
00660         switch (bridgeInput)
00661         {
00662             case 0:
00663             default:
00664                 /* Setting the period and the duty-cycle of PWM. */
00665                 pwm_1A.period_us(period_us);
00666                 pwm_1A.write(duty_cycle);
00667                 break;
00668 
00669             case  1:
00670                 /* Setting the period and the duty-cycle of PWM. */
00671                 pwm_2A.period_us(period_us);
00672                 pwm_2A.write(duty_cycle);
00673                 break;
00674 
00675             case 2:
00676                 /* Setting the period and the duty-cycle of PWM. */
00677                 pwm_1B.period_us(period_us);
00678                 pwm_1B.write(duty_cycle);
00679                 break;
00680 
00681             case 3:
00682                 /* Setting the period and the duty-cycle of PWM. */
00683                 pwm_2B.period_us(period_us);
00684                 pwm_2B.write(duty_cycle);
00685                 break;    
00686         }
00687     }
00688 
00689     /**
00690     * @brief  Reset the PWM for the specified brigde input
00691     * @param[in] bridgeInput 0 for input 1A, 1 for input 2A,
00692     * 2 for input 1B, 3 for input 2B
00693     * @retval None
00694     */
00695     void L6206_Board_PwmDeInit(uint8_t bridgeInput)
00696     {
00697           switch (bridgeInput)
00698           {
00699             case 0:
00700             default:
00701                 //timer_pwm_1A.detach();
00702                 break;
00703 
00704             case  1:
00705                 //timer_pwm_2A.detach();
00706                 break;
00707 
00708             case 2:
00709                 //timer_pwm_1B.detach();
00710                 break;
00711 
00712             case 3:
00713                 //timer_pwm_2B.detach();
00714                 break;
00715           }
00716     }
00717 
00718     /**
00719     * @brief  Set the PWM frequency the for the specified bridge input
00720     * @param[in] bridgeInput 0 for input 1A, 1 for input 2A,
00721     * 2 for input 1B, 3 for input 2B
00722     * @retval None
00723     */
00724     void L6206_Board_PwmInit(uint8_t bridgeInput)
00725     {
00726     }
00727 
00728     /**
00729     * @brief  Stops the PWM uses for the specified brige input
00730     * @param[in] bridgeInput 0 for input 1A, 1 for input 2A,
00731     * 2 for input 1B, 3 for input 2B
00732     * @retval None
00733     */
00734     void L6206_Board_PwmStop(uint8_t bridgeInput)
00735     {
00736           switch (bridgeInput)
00737           {
00738             case 0:
00739             default:
00740                 pwm_1A.write(0.0);
00741                 break;
00742 
00743             case  1:
00744                 pwm_2A.write(0.0);
00745                 break;
00746 
00747             case 2:
00748                 pwm_1B.write(0.0);
00749                 break;
00750 
00751             case 3:
00752                 pwm_2B.write(0.0);
00753                 break;
00754           }
00755     }
00756 
00757 
00758     /*** Component's Instance Variables ***/
00759 
00760     /* ACTION 9 --------------------------------------------------------------*
00761      * Declare here interrupt related variables, if needed.                   *
00762      * Note that interrupt handling is platform dependent, see                *
00763      * "Interrupt Related Methods" above.                                     *
00764      *                                                                        *
00765      * Example:                                                               *
00766      *   + mbed:                                                              *
00767      *     InterruptIn feature_irq;                                           *
00768      *------------------------------------------------------------------------*/
00769 
00770     /* Flag Interrupt. */
00771     InterruptIn flag_A_irq;
00772     InterruptIn flag_B_irq;
00773 
00774     /* ACTION 10 -------------------------------------------------------------*
00775      * Declare here other pin related variables, if needed.                   *
00776      *                                                                        *
00777      * Example:                                                               *
00778      *   + mbed:                                                              *
00779      *     DigitalOut standby_reset;                                          *
00780      *------------------------------------------------------------------------*/
00781 
00782     /* Digital In/Out for Flag EN pin */
00783     DigitalInOut EN_flag_A;
00784     DigitalInOut EN_flag_B;
00785     
00786     /* PWM Out  pin */
00787     PwmOut pwm_1A;
00788     PwmOut pwm_2A;
00789     PwmOut pwm_1B;
00790     PwmOut pwm_2B;
00791 
00792     /* ACTION 11 -------------------------------------------------------------*
00793      * Declare here communication related variables, if needed.               *
00794      *                                                                        *
00795      * Example:                                                               *
00796      *   + mbed:                                                              *
00797      *     DigitalOut address;                                                *
00798      *     DevI2C &dev_i2c;                                                   *
00799      *------------------------------------------------------------------------*/
00800 
00801     /* ACTION 12 -------------------------------------------------------------*
00802      * Declare here identity related variables, if needed.                    *
00803      * Note that there should be only a unique identifier for each component, *
00804      * which should be the "who_am_i" parameter.                              *
00805      *------------------------------------------------------------------------*/
00806     /* Identity */
00807     uint8_t who_am_i;
00808 
00809     /* ACTION 13 -------------------------------------------------------------*
00810      * Declare here the component's static and non-static data, one variable  *
00811      * per line.                                                              *
00812      *                                                                        *
00813      * Example:                                                               *
00814      *   float measure;                                                       *
00815      *   int instance_id;                                                     *
00816      *   static int number_of_instances;                                      *
00817      *------------------------------------------------------------------------*/
00818     void (*flagInterruptCallback)(void);
00819     
00820     void (*errorHandlerCallback)(uint16_t error);
00821     
00822     uint8_t numberOfDevices;
00823     
00824     uint8_t deviceInstance;
00825     
00826     deviceParams_t devicePrm;
00827 
00828 
00829     /** PWM timer variables */
00830 
00831     bool pwm_1A_activated;
00832     bool pwm_2A_activated;
00833     bool pwm_1B_activated;
00834     bool pwm_2B_activated;
00835 };
00836 
00837 #endif /* __L6206_CLASS_H */
00838 
00839 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
00840 
00841 
00842