ST Expansion SW Team / X_NUCLEO_IHM14A1

Dependencies:   ST_INTERFACES

Dependents:   HelloWorld_IHM14A1

Fork of X_NUCLEO_IHM14A1 by Davide Aliprandi

Revision:
1:bc265521eb00
Child:
2:4fd08b67958c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Components/STSPIN820/STSPIN820_def.h	Fri Apr 27 17:02:08 2018 +0000
@@ -0,0 +1,402 @@
+/******************************************************//**
+  * @file    STSPIN820_def.h 
+  * @author  STM
+  * @version V1.0.0
+  * @date    August 7th, 2017
+  * @brief   Header for STSPIN820 driver (fully integrated microstepping motor driver)
+  * @note    (C) COPYRIGHT 2017 STMicroelectronics
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
+  *
+  * Redistribution and use in source and binary forms, with or without modification,
+  * are permitted provided that the following conditions are met:
+  *   1. Redistributions of source code must retain the above copyright notice,
+  *      this list of conditions and the following disclaimer.
+  *   2. Redistributions in binary form must reproduce the above copyright notice,
+  *      this list of conditions and the following disclaimer in the documentation
+  *      and/or other materials provided with the distribution.
+  *   3. Neither the name of STMicroelectronics nor the names of its contributors
+  *      may be used to endorse or promote products derived from this software
+  *      without specific prior written permission.
+  *
+  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+  *
+  ******************************************************************************
+  */
+
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+
+#ifndef __STSPIN820_H
+#define __STSPIN820_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif 
+
+
+/* Includes ------------------------------------------------------------------*/
+
+#include "STSPIN820_config.h"
+#include "motor_def.h"
+   
+/** @addtogroup BSP
+  * @{
+  */   
+   
+/** @addtogroup STSPIN820
+  * @{
+  */   
+   
+
+/* Definitions ---------------------------------------------------------------*/
+
+/** @defgroup STSPIN820_Exported_Constants STSPIN820 Exported Constants
+  * @{
+  */   
+/// Current FW major version
+#define STSPIN820_FW_MAJOR_VERSION (uint8_t)(1)
+/// Current FW minor version
+#define STSPIN820_FW_MINOR_VERSION (uint8_t)(0)
+/// Current FW patch version
+#define STSPIN820_FW_PATCH_VERSION (uint8_t)(0)
+/// Current FW version
+#define STSPIN820_FW_VERSION       (uint32_t)((STSPIN820_FW_MAJOR_VERSION<<16)|\
+                                              (STSPIN820_FW_MINOR_VERSION<<8)|\
+                                              (STSPIN820_FW_PATCH_VERSION))
+
+/// Max position
+#define STSPIN820_MAX_POSITION           (0x7FFFFFFF)
+
+/// Min position
+#define STSPIN820_MIN_POSITION           (0x80000000)
+
+/// Position range
+#define STSPIN820_POSITION_RANGE         ((uint32_t)(STSPIN820_MAX_POSITION -\
+                                                        STSPIN820_MIN_POSITION))
+/// STSPIN820 error base number
+#define STSPIN820_ERROR_BASE             (0xA000)
+
+/// run bit mask
+#define STSPIN820_RUN_BIT_MASK           (0x01)
+
+/// move bit mask
+#define STSPIN820_MOVE_BIT_MASK          (0x02)
+
+/// soft stop bit mask
+#define STSPIN820_SOFT_STOP_BIT_MASK     (0x04)
+   
+/// direction change bit mask
+#define STSPIN820_DIR_CHANGE_BIT_MASK    (0x08)
+
+/// Maximum frequency of the step clock frequency in Hz
+#define STSPIN820_MAX_STCK_FREQ          (10000)
+
+/// Minimum frequency of the step clock frequency in Hz
+#define STSPIN820_MIN_STCK_FREQ          (8)
+
+/// Minimum duration of standby 
+#define STANDBY_MIN_DURATION             (1)
+    
+/// Dead time after standby exit
+#define AFTER_STANDBY_EXIT_DEAD_TIME     (1)
+
+/// Reset delay to select step mode
+#define SELECT_STEP_MODE_DELAY           (1)
+
+/// PWM REF and bridges disable delay
+#define DISABLE_DELAY                    (1)
+
+/// Microstepping sequencer maximum value
+#define SEQUENCER_MAX_VALUE              (uint16_t)(0x3FF)
+
+
+/* Types ---------------------------------------------------------------------*/
+
+/** @defgroup STSPIN820_Exported_Types STSPIN820 Exported Types
+  * @{
+  */
+    
+/** @defgroup Error_Types Error Types
+  * @{
+  */
+/// Errors
+typedef enum
+{
+  STSPIN820_ERROR_SET_HOME         = STSPIN820_ERROR_BASE,      /// Error while setting home position
+  STSPIN820_ERROR_SET_MAX_SPEED    = STSPIN820_ERROR_BASE + 1,  /// Error while setting max speed
+  STSPIN820_ERROR_SET_MIN_SPEED    = STSPIN820_ERROR_BASE + 2,  /// Error while setting min speed
+  STSPIN820_ERROR_SET_ACCELERATION = STSPIN820_ERROR_BASE + 3,  /// Error while setting acceleration
+  STSPIN820_ERROR_SET_DECELERATION = STSPIN820_ERROR_BASE + 4,  /// Error while setting decelaration
+  STSPIN820_ERROR_MCU_OSC_CONFIG   = STSPIN820_ERROR_BASE + 5,  /// Error while configuring mcu oscillator
+  STSPIN820_ERROR_MCU_CLOCK_CONFIG = STSPIN820_ERROR_BASE + 6,  /// Error while configuring mcu clock
+  STSPIN820_ERROR_POSITION         = STSPIN820_ERROR_BASE + 7,  /// Unexpected current position (wrong number of steps)
+  STSPIN820_ERROR_SPEED            = STSPIN820_ERROR_BASE + 8,  /// Unexpected current speed
+  STSPIN820_ERROR_INIT             = STSPIN820_ERROR_BASE + 9,  /// Unexpected number of devices or unexpected value for predefined parameter
+  STSPIN820_ERROR_SET_DIRECTION    = STSPIN820_ERROR_BASE + 10, /// Error while setting direction
+  STSPIN820_ERROR_SET_STEP_MODE    = STSPIN820_ERROR_BASE + 11, /// Attempt to set an unsupported step mode
+  STSPIN820_ERROR_APPLY_SPEED      = STSPIN820_ERROR_BASE + 12, /// Error while applying speed
+  STSPIN820_ERROR_SET_TORQUE       = STSPIN820_ERROR_BASE + 13, /// Error while setting torque
+  STSPIN820_ERROR_STEP_CLOCK       = STSPIN820_ERROR_BASE + 14  /// Error related to step clock
+} error_types_t;
+/**
+  * @}
+  */
+
+/** @defgroup Device_Commands Device Commands
+  * @{
+  */
+/// Device commands 
+typedef enum
+{
+  NO_CMD              = 0x00, 
+  RUN_CMD             = (STSPIN820_RUN_BIT_MASK),
+  MOVE_CMD            = (STSPIN820_MOVE_BIT_MASK),
+} device_command_t;
+/**
+  * @}
+  */
+
+
+/** @defgroup Device_Parameters Device Parameters
+  * @{
+  */
+
+/// Device Parameters Structure Type
+typedef struct
+{
+    /// accumulator used to store speed increase smaller than 1 pps
+    volatile uint32_t accu;           
+    /// Position in microstep according to current step mode
+    volatile int32_t currentPosition;
+    /// Position of sequencer
+    volatile int16_t sequencerPosition;
+    /// mark position in microstep (motor position control mode)
+    volatile int32_t markPosition;
+    /// position in microstep at the end of the accelerating phase
+    volatile uint32_t endAccPos;      
+    /// nb of in microstep performed from the beggining of the goto or the move command 
+    volatile uint32_t relativePos;    
+    /// position in microstep step at the start of the decelerating phase
+    volatile uint32_t startDecPos;    
+    /// nb of microstep steps to perform for the goto or move commands
+    uint32_t stepsToTake;
+    
+    /// constant speed phase torque value (%)
+    volatile uint8_t runTorque;
+    /// acceleration phase torque value (%)
+    volatile uint8_t accelTorque;
+    /// deceleration phase torque value (%)
+    volatile uint8_t decelTorque;
+    /// holding phase torque value (%)
+    volatile uint8_t holdTorque;
+    /// current selected torque value
+    volatile uint8_t currentTorque;
+    /// torque update
+    volatile bool updateTorque;
+    /// PWM frequency used to generate REF voltage
+    volatile uint32_t refPwmFreq;
+    /// torque boost enable
+    volatile bool torqueBoostEnable;
+    /// torque boost speed threshold
+    volatile uint16_t torqueBoostSpeedThreshold;
+    
+    /// acceleration in pps^2 
+    volatile uint16_t acceleration;
+    /// deceleration in pps^2
+    volatile uint16_t deceleration;
+    /// max speed in pps (speed use for goto or move command)
+    volatile uint16_t maxSpeed;
+    /// min speed in pps
+    volatile uint16_t minSpeed;
+    /// current speed in pps
+    volatile uint16_t speed;
+    
+    /// command under execution
+    volatile device_command_t commandExecuted; 
+    /// FORWARD or BACKWARD direction
+    volatile motor_direction_t direction;                 
+    /// current state of the device
+    volatile motor_state_t motionState;
+    /// current step mode
+    volatile motor_step_mode_t stepMode;
+    /// latched step mode
+    motor_step_mode_t stepModeLatched;
+    /// current stop mode
+    motor_stop_mode_t stopMode;
+    
+} device_params_t; 
+
+/* ACTION --------------------------------------------------------------------*
+ * Declare here the component's initialization structure, if any, one         *
+ * variable per line without initialization.                                  *
+ *                                                                            *
+ * Example:                                                                   *
+ *   typedef struct                                                           *
+ *   {                                                                        *
+ *     int frequency;                                                         *
+ *     int update_mode;                                                       *
+ *   } COMPONENT_init_t;                                                      *
+ *----------------------------------------------------------------------------*/
+/// Motor driver initialization structure definition  
+typedef struct
+{
+  /// acceleration in pps^2
+  uint16_t acceleration;
+  /// deceleration in pps^2
+  uint16_t deceleration;
+  /// max speed in pps (speed use for goto or move command)
+  uint16_t maxSpeed;
+  /// min speed in pps
+  uint16_t minSpeed;
+  /// acceleration phase torque value (%)
+  uint8_t accelTorque;
+  /// deceleration phase torque value (%)
+  uint8_t decelTorque;
+  /// constant speed phase torque value (%)
+  uint8_t runTorque;
+  /// holding phase torque value (%)
+  uint8_t holdTorque;
+  /// torque boost enable
+  bool torqueBoostEnable;
+  /// torque boost speed threshold
+  uint16_t torqueBoostSpeedThreshold;
+  /// step mode
+  motor_step_mode_t stepMode;
+  /// stop mode
+  motor_stop_mode_t stopMode;
+  /// PWM frequency used to generate REF voltage
+  uint32_t vrefPwmFreq;
+} STSPIN820_init_t;
+
+/** 
+ * @brief  STSPIN820 driver data structure definition.
+ */ 
+/* ACTION --------------------------------------------------------------------*
+ * Declare here the structure of component's data, if any, one variable per   *
+ * line without initialization.                                               *
+ *                                                                            *
+ * Example:                                                                   *
+ *   typedef struct                                                           *
+ *   {                                                                        *
+ *       int T0_out;                                                          *
+ *       int T1_out;                                                          *
+ *       float T0_degC;                                                       *
+ *       float T1_degC;                                                       *
+ *   } COMPONENT_data_t;                                                      *
+ *----------------------------------------------------------------------------*/
+typedef struct
+{
+  /// Function pointer to flag interrupt call back
+  void (*flag_interrupt_callback)(void);
+  /// Function pointer to error handler call back
+  void (*error_handler_callback)(uint16_t error);
+  uint8_t toggle_odd;
+
+  /// STSPIN820 Device Paramaters structure
+  device_params_t device_prm;
+  uint8_t number_of_devices;
+  uint8_t device_instance;
+} STSPIN820_data_t;
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+
+/** @defgroup MotorControl_Board_Linked_Functions MotorControl Board Linked Functions
+  * @{
+  */
+/* ACTION --------------------------------------------------------------------*
+ * Declare here extern I/O and interrupt related functions you might need,    *
+ * and implemented then in a glue logic file on the target environment, for   *
+ * example within the "x_nucleo_board.c" file., e.g.:                         *
+ *   extern status_t COMPONENT_IO_Init (void *handle);                        *
+ *   extern status_t COMPONENT_IO_Read (handle, buf, regadd, bytes);          *
+ *   extern status_t COMPONENT_IO_Write(handle, buf, regadd, bytes);          *
+ *   extern void     COMPONENT_IO_ITConfig(void);                             *
+ *----------------------------------------------------------------------------*/
+///Delay of the requested number of milliseconds
+extern void STSPIN820_Board_Delay(void *handle, uint32_t delay);
+///Disable the power bridges (leave the output bridges HiZ)    
+extern void STSPIN820_Board_Disable(void *handle);
+///Disable Irq
+extern void STSPIN820_Board_DisableIrq(void *handle);
+//Get the EN FAULT pin state
+extern uint32_t STSPIN820_Board_EN_AND_FAULT_PIN_GetState(void *handle);
+///Enable the power bridges (leave the output bridges HiZ)
+extern void STSPIN820_Board_Enable(void *handle); 
+///Enable Irq
+extern void STSPIN820_Board_EnableIrq(void *handle);
+///Initialise GPIOs used for STSPIN820
+extern void STSPIN820_Board_GpioInit(void *handle);
+///Init the reference voltage pwm
+extern void STSPIN820_Board_PwmRefInit(void *handle); 
+///Set the frequency and duty cycle of PWM used for the reference voltage generation
+extern void STSPIN820_Board_PwmRefSetFreqAndDutyCycle(void *handle, uint32_t newFreq, uint8_t dutyCycle);
+///Start the reference voltage pwm
+extern void STSPIN820_Board_PwmRefStart(void *handle);
+///Stop the reference voltage pwm
+extern void STSPIN820_Board_PwmRefStop(void *handle);
+///Reset the STSPIN820 reset pin
+extern void STSPIN820_Board_ReleaseReset(void *handle);
+///Set the STSPIN820 reset pin 
+extern void STSPIN820_Board_Reset(void *handle);
+///Set decay GPIO
+extern void STSPIN820_Board_SetDecayGpio(void *handle, uint8_t gpioState);
+///Get decay GPIO
+extern uint8_t STSPIN820_Board_GetDecayGpio(void *handle);
+///Set direction GPIO
+extern void STSPIN820_Board_SetDirectionGpio(void *handle, uint8_t gpioState);
+///Select Full Step mode
+extern void STSPIN820_Board_SetFullStep(void *handle);
+///Select the STSPIN820 mode1, mode2, and mode3 pins levels
+extern bool STSPIN820_Board_SetModePins(void *handle, uint8_t modePin1Level, uint8_t modePin2Level, uint8_t modePin3Level);
+///Step clock compare value initialization
+extern void STSPIN820_Board_TimStckCompareInit(void *handle);
+///DeInit the timer
+extern void STSPIN820_Board_TimStckDeInit(void *handle);
+///Init the timer
+extern void STSPIN820_Board_TimStckInit(void *handle);
+///Set step clock frequency
+extern void STSPIN820_Board_TimStckSetFreq(void *handle, uint16_t newFreq);
+///Start step clock
+extern void STSPIN820_Board_TimStckStart(void *handle);
+///Stop the timer
+extern uint8_t STSPIN820_Board_TimStckStop(void *handle, uint8_t *pToggleOdd);
+///Unselect Full Step mode
+extern void STSPIN820_Board_UnsetFullStep(void *handle);
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+#ifdef __cplusplus
+  }
+#endif
+
+#endif /* #ifndef __STSPIN820_H */
+
+/******************* (C) COPYRIGHT 2017 STMicroelectronics *****END OF FILE****/