Davide Aliprandi / X_NUCLEO_IHM14A1

Dependencies:   ST_INTERFACES

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers STSPIN820_def.h Source File

STSPIN820_def.h

Go to the documentation of this file.
00001 /******************************************************//**
00002   * @file    STSPIN820_def.h 
00003   * @author  STM
00004   * @version V1.0.0
00005   * @date    August 7th, 2017
00006   * @brief   Header for STSPIN820 driver (fully integrated microstepping motor driver)
00007   * @note    (C) COPYRIGHT 2017 STMicroelectronics
00008   ******************************************************************************
00009   * @attention
00010   *
00011   * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
00012   *
00013   * Redistribution and use in source and binary forms, with or without modification,
00014   * are permitted provided that the following conditions are met:
00015   *   1. Redistributions of source code must retain the above copyright notice,
00016   *      this list of conditions and the following disclaimer.
00017   *   2. Redistributions in binary form must reproduce the above copyright notice,
00018   *      this list of conditions and the following disclaimer in the documentation
00019   *      and/or other materials provided with the distribution.
00020   *   3. Neither the name of STMicroelectronics nor the names of its contributors
00021   *      may be used to endorse or promote products derived from this software
00022   *      without specific prior written permission.
00023   *
00024   * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00025   * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00026   * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00027   * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00028   * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00029   * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00030   * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031   * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00032   * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00033   * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00034   *
00035   ******************************************************************************
00036   */
00037 
00038 
00039 /* Define to prevent recursive inclusion -------------------------------------*/
00040 
00041 #ifndef __STSPIN820_H
00042 #define __STSPIN820_H
00043 
00044 #ifdef __cplusplus
00045  extern "C" {
00046 #endif 
00047 
00048 
00049 /* Includes ------------------------------------------------------------------*/
00050 
00051 #include "STSPIN820_config.h"
00052 #include "motor_def.h"
00053    
00054 /** @addtogroup BSP
00055   * @{
00056   */   
00057    
00058 /** @addtogroup STSPIN820
00059   * @{
00060   */   
00061    
00062 
00063 /* Definitions ---------------------------------------------------------------*/
00064 
00065 /** @defgroup STSPIN820_Exported_Constants STSPIN820 Exported Constants
00066   * @{
00067   */   
00068 /// Current FW major version
00069 #define STSPIN820_FW_MAJOR_VERSION (uint8_t)(1)
00070 /// Current FW minor version
00071 #define STSPIN820_FW_MINOR_VERSION (uint8_t)(0)
00072 /// Current FW patch version
00073 #define STSPIN820_FW_PATCH_VERSION (uint8_t)(0)
00074 /// Current FW version
00075 #define STSPIN820_FW_VERSION       (uint32_t)((STSPIN820_FW_MAJOR_VERSION<<16)|\
00076                                               (STSPIN820_FW_MINOR_VERSION<<8)|\
00077                                               (STSPIN820_FW_PATCH_VERSION))
00078 
00079 /// Max position
00080 #define STSPIN820_MAX_POSITION           (0x7FFFFFFF)
00081 
00082 /// Min position
00083 #define STSPIN820_MIN_POSITION           (0x80000000)
00084 
00085 /// Position range
00086 #define STSPIN820_POSITION_RANGE         ((uint32_t)(STSPIN820_MAX_POSITION -\
00087                                                         STSPIN820_MIN_POSITION))
00088 /// STSPIN820 error base number
00089 #define STSPIN820_ERROR_BASE             (0xA000)
00090 
00091 /// run bit mask
00092 #define STSPIN820_RUN_BIT_MASK           (0x01)
00093 
00094 /// move bit mask
00095 #define STSPIN820_MOVE_BIT_MASK          (0x02)
00096 
00097 /// soft stop bit mask
00098 #define STSPIN820_SOFT_STOP_BIT_MASK     (0x04)
00099    
00100 /// direction change bit mask
00101 #define STSPIN820_DIR_CHANGE_BIT_MASK    (0x08)
00102 
00103 /// Maximum frequency of the step clock frequency in Hz
00104 #define STSPIN820_MAX_STCK_FREQ          (10000)
00105 
00106 /// Minimum frequency of the step clock frequency in Hz
00107 #define STSPIN820_MIN_STCK_FREQ          (8)
00108 
00109 /// Minimum duration of standby 
00110 #define STANDBY_MIN_DURATION             (1)
00111     
00112 /// Dead time after standby exit
00113 #define AFTER_STANDBY_EXIT_DEAD_TIME     (1)
00114 
00115 /// Reset delay to select step mode
00116 #define SELECT_STEP_MODE_DELAY           (1)
00117 
00118 /// PWM REF and bridges disable delay
00119 #define DISABLE_DELAY                    (1)
00120 
00121 /// Microstepping sequencer maximum value
00122 #define SEQUENCER_MAX_VALUE              (uint16_t)(0x3FF)
00123 
00124 
00125 /* Types ---------------------------------------------------------------------*/
00126 
00127 /** @defgroup STSPIN820_Exported_Types STSPIN820 Exported Types
00128   * @{
00129   */
00130     
00131 /** @defgroup Error_Types Error Types
00132   * @{
00133   */
00134 /// Errors
00135 typedef enum
00136 {
00137   STSPIN820_ERROR_SET_HOME         = STSPIN820_ERROR_BASE,      /// Error while setting home position
00138   STSPIN820_ERROR_SET_MAX_SPEED    = STSPIN820_ERROR_BASE + 1,  /// Error while setting max speed
00139   STSPIN820_ERROR_SET_MIN_SPEED    = STSPIN820_ERROR_BASE + 2,  /// Error while setting min speed
00140   STSPIN820_ERROR_SET_ACCELERATION = STSPIN820_ERROR_BASE + 3,  /// Error while setting acceleration
00141   STSPIN820_ERROR_SET_DECELERATION = STSPIN820_ERROR_BASE + 4,  /// Error while setting decelaration
00142   STSPIN820_ERROR_MCU_OSC_CONFIG   = STSPIN820_ERROR_BASE + 5,  /// Error while configuring mcu oscillator
00143   STSPIN820_ERROR_MCU_CLOCK_CONFIG = STSPIN820_ERROR_BASE + 6,  /// Error while configuring mcu clock
00144   STSPIN820_ERROR_POSITION         = STSPIN820_ERROR_BASE + 7,  /// Unexpected current position (wrong number of steps)
00145   STSPIN820_ERROR_SPEED            = STSPIN820_ERROR_BASE + 8,  /// Unexpected current speed
00146   STSPIN820_ERROR_INIT             = STSPIN820_ERROR_BASE + 9,  /// Unexpected number of devices or unexpected value for predefined parameter
00147   STSPIN820_ERROR_SET_DIRECTION    = STSPIN820_ERROR_BASE + 10, /// Error while setting direction
00148   STSPIN820_ERROR_SET_STEP_MODE    = STSPIN820_ERROR_BASE + 11, /// Attempt to set an unsupported step mode
00149   STSPIN820_ERROR_APPLY_SPEED      = STSPIN820_ERROR_BASE + 12, /// Error while applying speed
00150   STSPIN820_ERROR_SET_TORQUE       = STSPIN820_ERROR_BASE + 13, /// Error while setting torque
00151   STSPIN820_ERROR_STEP_CLOCK       = STSPIN820_ERROR_BASE + 14  /// Error related to step clock
00152 } error_types_t;
00153 /**
00154   * @}
00155   */
00156 
00157 /** @defgroup Device_Commands Device Commands
00158   * @{
00159   */
00160 /// Device commands 
00161 typedef enum
00162 {
00163   NO_CMD              = 0x00, 
00164   RUN_CMD             = (STSPIN820_RUN_BIT_MASK),
00165   MOVE_CMD            = (STSPIN820_MOVE_BIT_MASK),
00166 } device_command_t;
00167 /**
00168   * @}
00169   */
00170 
00171 
00172 /** @defgroup Device_Parameters Device Parameters
00173   * @{
00174   */
00175 
00176 /// Device Parameters Structure Type
00177 typedef struct
00178 {
00179     /// accumulator used to store speed increase smaller than 1 pps
00180     volatile uint32_t accu;           
00181     /// Position in microstep according to current step mode
00182     volatile int32_t currentPosition;
00183     /// Position of sequencer
00184     volatile int16_t sequencerPosition;
00185     /// mark position in microstep (motor position control mode)
00186     volatile int32_t markPosition;
00187     /// position in microstep at the end of the accelerating phase
00188     volatile uint32_t endAccPos;      
00189     /// nb of in microstep performed from the beggining of the goto or the move command 
00190     volatile uint32_t relativePos;    
00191     /// position in microstep step at the start of the decelerating phase
00192     volatile uint32_t startDecPos;    
00193     /// nb of microstep steps to perform for the goto or move commands
00194     uint32_t stepsToTake;
00195     
00196     /// constant speed phase torque value (%)
00197     volatile uint8_t runTorque;
00198     /// acceleration phase torque value (%)
00199     volatile uint8_t accelTorque;
00200     /// deceleration phase torque value (%)
00201     volatile uint8_t decelTorque;
00202     /// holding phase torque value (%)
00203     volatile uint8_t holdTorque;
00204     /// current selected torque value
00205     volatile uint8_t currentTorque;
00206     /// torque update
00207     volatile bool updateTorque;
00208     /// PWM frequency used to generate REF voltage
00209     volatile uint32_t refPwmFreq;
00210     /// torque boost enable
00211     volatile bool torqueBoostEnable;
00212     /// torque boost speed threshold
00213     volatile uint16_t torqueBoostSpeedThreshold;
00214     
00215     /// acceleration in pps^2 
00216     volatile uint16_t acceleration;
00217     /// deceleration in pps^2
00218     volatile uint16_t deceleration;
00219     /// max speed in pps (speed use for goto or move command)
00220     volatile uint16_t maxSpeed;
00221     /// min speed in pps
00222     volatile uint16_t minSpeed;
00223     /// current speed in pps
00224     volatile uint16_t speed;
00225     
00226     /// command under execution
00227     volatile device_command_t commandExecuted; 
00228     /// FORWARD or BACKWARD direction
00229     volatile motor_direction_t direction;                 
00230     /// current state of the device
00231     volatile motor_state_t motionState;
00232     /// current step mode
00233     volatile motor_step_mode_t stepMode;
00234     /// latched step mode
00235     motor_step_mode_t stepModeLatched;
00236     /// current stop mode
00237     motor_stop_mode_t stopMode;
00238     
00239 } device_params_t; 
00240 
00241 /* ACTION --------------------------------------------------------------------*
00242  * Declare here the component's initialization structure, if any, one         *
00243  * variable per line without initialization.                                  *
00244  *                                                                            *
00245  * Example:                                                                   *
00246  *   typedef struct                                                           *
00247  *   {                                                                        *
00248  *     int frequency;                                                         *
00249  *     int update_mode;                                                       *
00250  *   } COMPONENT_init_t;                                                      *
00251  *----------------------------------------------------------------------------*/
00252 /// Motor driver initialization structure definition  
00253 typedef struct
00254 {
00255   /// acceleration in pps^2
00256   uint16_t acceleration;
00257   /// deceleration in pps^2
00258   uint16_t deceleration;
00259   /// max speed in pps (speed use for goto or move command)
00260   uint16_t maxSpeed;
00261   /// min speed in pps
00262   uint16_t minSpeed;
00263   /// acceleration phase torque value (%)
00264   uint8_t accelTorque;
00265   /// deceleration phase torque value (%)
00266   uint8_t decelTorque;
00267   /// constant speed phase torque value (%)
00268   uint8_t runTorque;
00269   /// holding phase torque value (%)
00270   uint8_t holdTorque;
00271   /// torque boost enable
00272   bool torqueBoostEnable;
00273   /// torque boost speed threshold
00274   uint16_t torqueBoostSpeedThreshold;
00275   /// step mode
00276   motor_step_mode_t stepMode;
00277   /// stop mode
00278   motor_stop_mode_t stopMode;
00279   /// PWM frequency used to generate REF voltage
00280   uint32_t vrefPwmFreq;
00281 } STSPIN820_init_t;
00282 
00283 /** 
00284  * @brief  STSPIN820 driver data structure definition.
00285  */ 
00286 /* ACTION --------------------------------------------------------------------*
00287  * Declare here the structure of component's data, if any, one variable per   *
00288  * line without initialization.                                               *
00289  *                                                                            *
00290  * Example:                                                                   *
00291  *   typedef struct                                                           *
00292  *   {                                                                        *
00293  *       int T0_out;                                                          *
00294  *       int T1_out;                                                          *
00295  *       float T0_degC;                                                       *
00296  *       float T1_degC;                                                       *
00297  *   } COMPONENT_data_t;                                                      *
00298  *----------------------------------------------------------------------------*/
00299 typedef struct
00300 {
00301   /// Function pointer to flag interrupt call back
00302   void (*flag_interrupt_callback)(void);
00303   /// Function pointer to error handler call back
00304   void (*error_handler_callback)(uint16_t error);
00305   uint8_t toggle_odd;
00306 
00307   /// STSPIN820 Device Paramaters structure
00308   device_params_t device_prm;
00309   uint8_t number_of_devices;
00310   uint8_t device_instance;
00311 } STSPIN820_data_t;
00312 
00313 /**
00314   * @}
00315   */
00316 
00317 /**
00318   * @}
00319   */
00320 
00321 
00322 /** @defgroup MotorControl_Board_Linked_Functions MotorControl Board Linked Functions
00323   * @{
00324   */
00325 /* ACTION --------------------------------------------------------------------*
00326  * Declare here extern I/O and interrupt related functions you might need,    *
00327  * and implemented then in a glue logic file on the target environment, for   *
00328  * example within the "x_nucleo_board.c" file., e.g.:                         *
00329  *   extern status_t COMPONENT_IO_Init (void *handle);                        *
00330  *   extern status_t COMPONENT_IO_Read (handle, buf, regadd, bytes);          *
00331  *   extern status_t COMPONENT_IO_Write(handle, buf, regadd, bytes);          *
00332  *   extern void     COMPONENT_IO_ITConfig(void);                             *
00333  *----------------------------------------------------------------------------*/
00334 ///Delay of the requested number of milliseconds
00335 extern void STSPIN820_Board_Delay(void *handle, uint32_t delay);
00336 ///Disable the power bridges (leave the output bridges HiZ)    
00337 extern void STSPIN820_Board_Disable(void *handle);
00338 ///Disable Irq
00339 extern void STSPIN820_Board_DisableIrq(void *handle);
00340 //Get the EN FAULT pin state
00341 extern uint32_t STSPIN820_Board_EN_AND_FAULT_PIN_GetState(void *handle);
00342 ///Enable the power bridges (leave the output bridges HiZ)
00343 extern void STSPIN820_Board_Enable(void *handle); 
00344 ///Enable Irq
00345 extern void STSPIN820_Board_EnableIrq(void *handle);
00346 ///Initialise GPIOs used for STSPIN820
00347 extern void STSPIN820_Board_GpioInit(void *handle);
00348 ///Init the reference voltage pwm
00349 extern void STSPIN820_Board_PwmRefInit(void *handle); 
00350 ///Set the frequency and duty cycle of PWM used for the reference voltage generation
00351 extern void STSPIN820_Board_PwmRefSetFreqAndDutyCycle(void *handle, uint32_t newFreq, uint8_t dutyCycle);
00352 ///Start the reference voltage pwm
00353 extern void STSPIN820_Board_PwmRefStart(void *handle);
00354 ///Stop the reference voltage pwm
00355 extern void STSPIN820_Board_PwmRefStop(void *handle);
00356 ///Reset the STSPIN820 reset pin
00357 extern void STSPIN820_Board_ReleaseReset(void *handle);
00358 ///Set the STSPIN820 reset pin 
00359 extern void STSPIN820_Board_Reset(void *handle);
00360 ///Set decay GPIO
00361 extern void STSPIN820_Board_SetDecayGpio(void *handle, uint8_t gpioState);
00362 ///Get decay GPIO
00363 extern uint8_t STSPIN820_Board_GetDecayGpio(void *handle);
00364 ///Set direction GPIO
00365 extern void STSPIN820_Board_SetDirectionGpio(void *handle, uint8_t gpioState);
00366 ///Select Full Step mode
00367 extern void STSPIN820_Board_SetFullStep(void *handle);
00368 ///Select the STSPIN820 mode1, mode2, and mode3 pins levels
00369 extern bool STSPIN820_Board_SetModePins(void *handle, uint8_t modePin1Level, uint8_t modePin2Level, uint8_t modePin3Level);
00370 ///Step clock compare value initialization
00371 extern void STSPIN820_Board_TimStckCompareInit(void *handle);
00372 ///DeInit the timer
00373 extern void STSPIN820_Board_TimStckDeInit(void *handle);
00374 ///Init the timer
00375 extern void STSPIN820_Board_TimStckInit(void *handle);
00376 ///Set step clock frequency
00377 extern void STSPIN820_Board_TimStckSetFreq(void *handle, uint16_t newFreq);
00378 ///Start step clock
00379 extern void STSPIN820_Board_TimStckStart(void *handle);
00380 ///Stop the timer
00381 extern uint8_t STSPIN820_Board_TimStckStop(void *handle, uint8_t *pToggleOdd);
00382 ///Unselect Full Step mode
00383 extern void STSPIN820_Board_UnsetFullStep(void *handle);
00384 /**
00385   * @}
00386   */
00387 
00388 /**
00389   * @}
00390   */
00391 
00392 /**
00393   * @}
00394   */
00395 
00396 #ifdef __cplusplus
00397   }
00398 #endif
00399 
00400 #endif /* #ifndef __STSPIN820_H */
00401 
00402 /******************* (C) COPYRIGHT 2017 STMicroelectronics *****END OF FILE****/