Library to handle the X_NUCLEO_IHM02A1 Motor Control Expansion Board based on the L6470 component.
Dependencies: X_NUCLEO_COMMON ST_INTERFACES
Dependents: HelloWorld_IHM02A1 ConcorsoFinal HelloWorld_IHM02A1_mbedOS HelloWorld_IHM02A1-Serialinterpreter ... more
Fork of X_NUCLEO_IHM02A1 by
microstepping_motor_def.h
00001 /** 00002 ****************************************************************************** 00003 * @file microstepping_motor_def.h 00004 * @author IPD SYSTEM LAB & TECH MKTG 00005 * @version V0.0.1 00006 * @date 04-June-2015 00007 * @brief This file contains all the functions prototypes for the microstepping 00008 * motor driver with motion engine. 00009 ****************************************************************************** 00010 * @attention 00011 * 00012 * <h2><center>© COPYRIGHT(c) 2014 STMicroelectronics</center></h2> 00013 * 00014 * Redistribution and use in source and binary forms, with or without modification, 00015 * are permitted provided that the following conditions are met: 00016 * 1. Redistributions of source code must retain the above copyright notice, 00017 * this list of conditions and the following disclaimer. 00018 * 2. Redistributions in binary form must reproduce the above copyright notice, 00019 * this list of conditions and the following disclaimer in the documentation 00020 * and/or other materials provided with the distribution. 00021 * 3. Neither the name of STMicroelectronics nor the names of its contributors 00022 * may be used to endorse or promote products derived from this software 00023 * without specific prior written permission. 00024 * 00025 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00026 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00027 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00028 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 00029 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00030 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 00031 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00032 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 00033 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00034 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00035 * 00036 ****************************************************************************** 00037 */ 00038 00039 00040 /* Define to prevent recursive inclusion -------------------------------------*/ 00041 00042 #ifndef __MICROSTEPPINGMOTOR_H 00043 #define __MICROSTEPPINGMOTOR_H 00044 00045 #ifdef __cplusplus 00046 extern "C" { 00047 #endif 00048 00049 00050 /* Includes ------------------------------------------------------------------*/ 00051 00052 #include <stdint.h> 00053 #include "component_def.h" 00054 00055 00056 /* Types ---------------------------------------------------------------------*/ 00057 00058 /** @addtogroup BSP 00059 * @{ 00060 */ 00061 00062 /** @addtogroup Components 00063 * @{ 00064 */ 00065 00066 /** @defgroup MicrosteppingMotorDriver 00067 * @{ 00068 */ 00069 00070 /** @defgroup StepperMotorExportedTypes 00071 * @{ 00072 */ 00073 00074 /** 00075 * @brief The L6470 Registers Identifiers. 00076 */ 00077 typedef enum { 00078 L6470_ABS_POS_ID = 0, //!< Current position 00079 L6470_EL_POS_ID, //!< Electrical position 00080 L6470_MARK_ID, //!< Mark position 00081 L6470_SPEED_ID, //!< Current speed 00082 L6470_ACC_ID, //!< Acceleration 00083 L6470_DEC_ID, //!< Deceleration 00084 L6470_MAX_SPEED_ID, //!< Maximum speed 00085 L6470_MIN_SPEED_ID, //!< Minimum speed 00086 L6470_FS_SPD_ID, //!< Full-step speed 00087 L6470_KVAL_HOLD_ID, //!< Holding KVAL 00088 L6470_KVAL_RUN_ID, //!< Constant speed KVAL 00089 L6470_KVAL_ACC_ID, //!< Acceleration starting KVAL 00090 L6470_KVAL_DEC_ID, //!< Deceleration starting KVAL 00091 L6470_INT_SPEED_ID, //!< Intersect speed 00092 L6470_ST_SLP_ID, //!< Start slope 00093 L6470_FN_SLP_ACC_ID, //!< Acceleration final slope 00094 L6470_FN_SLP_DEC_ID, //!< Deceleration final slope 00095 L6470_K_THERM_ID, //!< Thermal compensation factor 00096 L6470_ADC_OUT_ID, //!< ADC output, (the reset value is according to startup conditions) 00097 L6470_OCD_TH_ID, //!< OCD threshold 00098 L6470_STALL_TH_ID, //!< STALL threshold 00099 L6470_STEP_MODE_ID, //!< Step mode 00100 L6470_ALARM_EN_ID, //!< Alarm enable 00101 L6470_CONFIG_ID, //!< IC configuration 00102 L6470_STATUS_ID //!< Status, (the reset value is according to startup conditions) 00103 } eL6470_RegId_t; 00104 00105 /** 00106 * @brief The L6470 Application Commands Identifiers. 00107 */ 00108 typedef enum { 00109 L6470_NOP_ID = 0, //!< Nothing 00110 L6470_SETPARAM_ID, //!< Writes VALUE in PARAM register 00111 L6470_GETPARAM_ID, //!< Returns the stored value in PARAM register 00112 L6470_RUN_ID, //!< Sets the target speed and the motor direction 00113 L6470_STEPCLOCK_ID, //!< Puts the device into Step-clock mode and imposes DIR direction 00114 L6470_MOVE_ID, //!< Makes N_STEP (micro)steps in DIR direction (Not performable when motor is running) 00115 L6470_GOTO_ID, //!< Brings motor into ABS_POS position (minimum path) 00116 L6470_GOTODIR_ID, //!< Brings motor into ABS_POS position forcing DIR direction 00117 L6470_GOUNTIL_ID, //!< Performs a motion in DIR direction with speed SPD until SW is closed, the ACT action is executed then a SoftStop takes place 00118 L6470_RELEASESW_ID, //!< Performs a motion in DIR direction at minimum speed until the SW is released (open), the ACT action is executed then a HardStop takes place 00119 L6470_GOHOME_ID, //!< Brings the motor into HOME position 00120 L6470_GOMARK_ID, //!< Brings the motor into MARK position 00121 L6470_RESETPOS_ID, //!< Resets the ABS_POS register (set HOME position) 00122 L6470_RESETDEVICE_ID, //!< Device is reset to power-up conditions 00123 L6470_SOFTSTOP_ID, //!< Stops motor with a deceleration phase 00124 L6470_HARDSTOP_ID, //!< Stops motor immediately 00125 L6470_SOFTHIZ_ID, //!< Puts the bridges into high impedance status after a deceleration phase 00126 L6470_HARDHIZ_ID, //!< Puts the bridges into high impedance status immediately 00127 L6470_GETSTATUS_ID //!< Returns the STATUS register value 00128 } eL6470_AppCmdId_t; 00129 00130 /** 00131 * @brief The L6470 Status Register Flag identifiers. 00132 */ 00133 typedef enum { 00134 HiZ_ID = 0, //!< HiZ flag identifier inside the L6470 Status Register 00135 BUSY_ID, //!< BUSY flag identifier inside the L6470 Status Register 00136 SW_F_ID, //!< SW_F flag identifier inside the L6470 Status Register 00137 SW_EVN_ID, //!< SW_EVN flag identifier inside the L6470 Status Register 00138 DIR_ID, //!< DIR flag identifier inside the L6470 Status Register 00139 MOT_STATUS_ID, //!< MOT_STATUS flag identifier inside the L6470 Status Register 00140 NOTPERF_CMD_ID, //!< NOTPERF_CMD flag identifier inside the L6470 Status Register 00141 WRONG_CMD_ID, //!< WRONG_CMD flag identifier inside the L6470 Status Register 00142 UVLO_ID, //!< UVLO flag identifier inside the L6470 Status Register 00143 TH_WRN_ID, //!< TH_WRN flag identifier inside the L6470 Status Register 00144 TH_SD_ID, //!< TH_SD flag identifier inside the L6470 Status Register 00145 OCD_ID, //!< OCD flag identifier inside the L6470 Status Register 00146 STEP_LOSS_A_ID, //!< STEP_LOSS_A flag identifier inside the L6470 Status Register 00147 STEP_LOSS_B_ID, //!< STEP_LOSS_B flag identifier inside the L6470 Status Register 00148 SCK_MOD_ID //!< SCK_MOD flag identifier inside the L6470 Status Register 00149 } eL6470_StatusRegisterFlagId_t; 00150 00151 /** 00152 * @brief The L6470 Direction identifiers. 00153 */ 00154 typedef enum { 00155 L6470_DIR_REV_ID = 0, //!< Reverse direction 00156 L6470_DIR_FWD_ID //!< Forward direction 00157 } eL6470_DirId_t; 00158 00159 /** 00160 * @brief The L6470 Action identifiers about ABS_POS register. 00161 */ 00162 typedef enum { 00163 L6470_ACT_RST_ID = 0, //!< ABS_POS register is reset 00164 L6470_ACT_CPY_ID //!< ABS_POS register value is copied into the MARK register 00165 } eL6470_ActId_t; 00166 00167 /** 00168 * @brief The L6470 Status Register Flag states. 00169 */ 00170 typedef enum { 00171 ZERO_F = 0, //!< The flag is '0' 00172 ONE_F = !ZERO_F //!< The flag is '1' 00173 } eFlagStatus_t; 00174 00175 /** 00176 * @brief The L6470 Motor Directions. 00177 */ 00178 typedef enum { 00179 REVERSE_F = 0, //!< Reverse motor direction 00180 FORWARD_F = !REVERSE_F //!< Forward motor direction 00181 } eMotorDirection_t; 00182 00183 /** 00184 * @brief The L6470 Motor Status. 00185 */ 00186 typedef enum { 00187 STOPPED_F = 0, //!< Stopped 00188 ACCELERATION_F = 1, //!< Acceleration 00189 DECELERATION_F = 2, //!< Deceleration 00190 CONSTANTSPEED_F = 3 //!< Constant speed 00191 } eMotorStatus_t; 00192 00193 /** 00194 * @brief The possible stepping modes for L6470. 00195 */ 00196 typedef enum 00197 { 00198 FULL_STEP = 0x00, //!< Full-step 00199 HALF_STEP = 0x01, //!< Half-step 00200 MICROSTEP_1_4 = 0x02, //!< 1/4 microstep 00201 MICROSTEP_1_8 = 0x03, //!< 1/8 microstep 00202 MICROSTEP_1_16 = 0x04, //!< 1/16 microstep 00203 MICROSTEP_1_32 = 0x05, //!< 1/32 microstep 00204 MICROSTEP_1_64 = 0x06, //!< 1/64 microstep 00205 MICROSTEP_1_128 = 0x07 //!< 1/128 microstep 00206 } eMotorStepMode_t; 00207 00208 /** 00209 * @brief The identifiers for the possible L6470 alarm conditions. 00210 */ 00211 typedef enum 00212 { 00213 L6470_OVERCURRENT = 0x01, //!< Overcurrent 00214 L6470_THERMAL_SHUTDOWN = 0x02, //!< Thermal shutdown 00215 L6470_THERMAL_WARNING = 0x04, //!< Thermal warning 00216 L6470_UNDERVOLTAGE = 0x08, //!< Undervoltage 00217 L6470_STALL_DETECTION_A = 0x10, //!< Stall detection (Bridge A) 00218 L6470_STALL_DETECTION_B = 0x20, //!< Stall detection (Bridge B) 00219 L6470_SWITCH_TURN_ON_EVENT = 0x40, //!< Switch turn-on event 00220 L6470_WRONG_OR_NON_PERFORMABLE_COMMAND = 0x80 //!< Wrong or non-performable command 00221 } eL6470_AlarmCondition_t; 00222 00223 /** 00224 * @brief The L6470 STEP_MODE Register (see L6470 DataSheet for more details). 00225 */ 00226 typedef struct { 00227 uint8_t STEP_SEL: 3; //!< Step mode 00228 uint8_t WRT: 1; //!< When the register is written, this bit should be set to 0. 00229 uint8_t SYNC_SEL: 3; //!< Synchronization selection 00230 uint8_t SYNC_EN: 1; //!< Synchronization enable 00231 } sL6470_StepModeRegister_t; 00232 00233 /** 00234 * @brief The L6470 ALARM_EN Register (see L6470 DataSheet for more details). 00235 */ 00236 typedef struct { 00237 uint8_t OCD_EN: 1; //!< Overcurrent 00238 uint8_t TH_SD_EN: 1; //!< Thermal shutdown 00239 uint8_t TH_WRN_EN: 1; //!< Thermal warning 00240 uint8_t UVLO_EN: 1; //!< Undervoltage 00241 uint8_t STEP_LOSS_A_EN: 1; //!< Stall detection (Bridge A) 00242 uint8_t STEP_LOSS_B_EN: 1; //!< Stall detection (Bridge B) 00243 uint8_t SW_EVN_EN: 1; //!< Switch turn-on event 00244 uint8_t WRONG_NOTPERF_CMD_EN: 1; //!< Wrong or non-performable command 00245 } sL6470_AlarmEnRegister_t; 00246 00247 /** 00248 * @brief The L6470 CONFIG Register (see L6470 DataSheet for more details). 00249 */ 00250 typedef struct { 00251 uint8_t OSC_SEL: 3; //!< Oscillator Selection 00252 uint8_t EXT_CLK: 1; //!< External Clock 00253 uint8_t SW_MODE: 1; //!< Switch mode 00254 uint8_t EN_VSCOMP: 1; //!< Motor supply voltage compensation 00255 uint8_t RESERVED: 1; //!< RESERVED 00256 uint8_t OC_SD: 1; //!< Overcurrent event 00257 uint8_t POW_SR: 2; //!< Output slew rate 00258 uint8_t F_PWM_DEC: 3; //!< Multiplication factor 00259 uint8_t F_PWM_INT: 3; //!< Integer division factor 00260 } sL6470_ConfigRegister_t; 00261 00262 /** 00263 * @brief The L6470 STATUS Register (see L6470 DataSheet for more details). 00264 */ 00265 typedef struct { 00266 uint8_t HiZ: 1; //!< The bridges are in high impedance state (the flag is active high) 00267 uint8_t BUSY: 1; //!< BUSY pin status (the flag is active low) 00268 uint8_t SW_F: 1; //!< SW input status (the flag is low for open and high for closed) 00269 uint8_t SW_EVN: 1; //!< Switch turn-on event (the flag is active high) 00270 uint8_t DIR: 1; //!< The current motor direction (1 as forward, 0 as reverse) 00271 uint8_t MOT_STATUS: 2; //!< The current motor status (0 as stopped, 1 as acceleration, 2 as deceleration, 3 as constant speed) 00272 uint8_t NOTPERF_CMD: 1; //!< The command received by SPI cannot be performed (the flag is active high) 00273 uint8_t WRONG_CMD: 1; //!< The command received by SPI does not exist at all (the flag is active high) 00274 uint8_t UVLO: 1; //!< Undervoltage lockout or reset events (the flag is active low) 00275 uint8_t TH_WRN: 1; //!< Thermal warning event (the flag is active low) 00276 uint8_t TH_SD: 1; //!< Thermal shutdown event (the flag is active low) 00277 uint8_t OCD: 1; //!< Overcurrent detection event (the flag is active low) 00278 uint8_t STEP_LOSS_A: 1; //!< Stall detection on bridge A (the flag is active low) 00279 uint8_t STEP_LOSS_B: 1; //!< Stall detection on bridge B (the flag is active low) 00280 uint8_t SCK_MOD: 1; //!< Step-clock mode (the flag is active high) 00281 } sL6470_StatusRegister_t; 00282 00283 /** 00284 * @brief Stepper Motor Registers 00285 */ 00286 typedef struct 00287 { 00288 uint32_t ABS_POS; //!< CurrentPosition Register 00289 uint16_t EL_POS; //!< ElectricalPosition Register 00290 uint32_t MARK; //!< MarkPosition Register 00291 uint32_t SPEED; //!< CurrentSpeed Register 00292 uint16_t ACC; //!< Acceleration Register 00293 uint16_t DEC; //!< Deceleration Register 00294 uint16_t MAX_SPEED; //!< MaximumSpeed Register 00295 uint16_t MIN_SPEED; //!< MinimumSpeed Register 00296 uint16_t FS_SPD; //!< FullStepSpeed Register 00297 uint8_t KVAL_HOLD; //!< HoldingKval Register 00298 uint8_t KVAL_RUN; //!< ConstantSpeedKval Register 00299 uint8_t KVAL_ACC; //!< AccelerationStartingKval Register 00300 uint8_t KVAL_DEC; //!< DecelerationStartingKval Register 00301 uint16_t INT_SPEED; //!< IntersectSpeed Register 00302 uint8_t ST_SLP; //!< StartSlope Register 00303 uint8_t FN_SLP_ACC; //!< AccelerationFinalSlope Register 00304 uint8_t FN_SLP_DEC; //!< DecelerationFinalSlope Register 00305 uint8_t K_THERM; //!< ThermalCompensationFactor Register 00306 uint8_t ADC_OUT; //!< AdcOutput Register 00307 uint8_t OCD_TH; //!< OcdThreshold Register 00308 uint8_t STALL_TH; //!< StallThreshold Register 00309 uint8_t STEP_MODE; //!< StepMode Register 00310 uint8_t ALARM_EN; //!< AlarmEnable Register 00311 uint16_t CONFIG; //!< Config Register 00312 uint16_t STATUS; //!< Status Register 00313 } StepperMotorRegister_t; 00314 00315 /** 00316 * @brief MICROSTEPPING_MOTOR driver virtual table structure definition. 00317 */ 00318 typedef struct 00319 { 00320 /* ACTION ----------------------------------------------------------------* 00321 * Declare here the component's generic functions. * 00322 * Tag this group of functions with the " Generic " C-style comment. * 00323 * A component's interface has to define at least the two generic * 00324 * functions provided here below within the "Example" section, as the * 00325 * first and second functions of its Virtual Table. They have to be * 00326 * specified exactly in the given way. * 00327 * * 00328 * Example: * 00329 * status_t (*Init) (void *handle, void *init); * 00330 * status_t (*ReadID) (void *handle, uint8_t *id); * 00331 *------------------------------------------------------------------------*/ 00332 /* Generic */ 00333 status_t (*Init)(void *handle, void *init); 00334 status_t (*ReadID)(void *handle, uint8_t *id); 00335 00336 /* ACTION ----------------------------------------------------------------* 00337 * Declare here the component's specific functions. * 00338 * Tag this group of functions with the " Specific " C-style comment. * 00339 * Do not specify any function if not required. * 00340 * * 00341 * Example: * 00342 * status_t (*GetValue) (void *handle, float *f); * 00343 *------------------------------------------------------------------------*/ 00344 /* Specific */ 00345 void (*SetParam)(void *handle, eL6470_RegId_t L6470_RegId, uint32_t Value); 00346 uint32_t (*GetParam)(void *handle, eL6470_RegId_t L6470_RegId); 00347 void (*Run)(void *handle, eL6470_DirId_t L6470_DirId, uint32_t Speed); 00348 void (*StepClock)(void *handle, eL6470_DirId_t L6470_DirId); 00349 void (*Move)(void *handle, eL6470_DirId_t L6470_DirId, uint32_t N_Step); 00350 void (*GoTo)(void *handle, uint32_t AbsPos); 00351 void (*GoToDir)(void *handle, eL6470_DirId_t L6470_DirId, uint32_t AbsPos); 00352 void (*GoUntil)(void *handle, eL6470_ActId_t L6470_ActId, eL6470_DirId_t L6470_DirId, uint32_t Speed); 00353 void (*ReleaseSW)(void *handle, eL6470_ActId_t L6470_ActId, eL6470_DirId_t L6470_DirId); 00354 void (*GoHome)(void *handle); 00355 void (*GoMark)(void *handle); 00356 void (*ResetPos)(void *handle); 00357 void (*ResetDevice)(void *handle); 00358 void (*SoftStop)(void *handle); 00359 void (*HardStop)(void *handle); 00360 void (*SoftHiZ)(void *handle); 00361 void (*HardHiZ)(void *handle); 00362 uint16_t (*GetStatus)(void *handle); 00363 void (*PrepareSetParam)(void *handle, eL6470_RegId_t L6470_RegId, uint32_t Value); 00364 void (*PrepareGetParam)(void *handle, eL6470_RegId_t L6470_RegId); 00365 void (*PrepareRun)(void *handle, eL6470_DirId_t L6470_DirId, uint32_t Speed); 00366 void (*PrepareStepClock)(void *handle, eL6470_DirId_t L6470_DirId); 00367 void (*PrepareMove)(void *handle, eL6470_DirId_t L6470_DirId, uint32_t N_Step); 00368 void (*PrepareGoTo)(void *handle, uint32_t AbsPos); 00369 void (*PrepareGoToDir)(void *handle, eL6470_DirId_t L6470_DirId, uint32_t AbsPos); 00370 void (*PrepareGoUntil)(void *handle, eL6470_ActId_t L6470_ActId, eL6470_DirId_t L6470_DirId, uint32_t Speed); 00371 void (*PrepareReleaseSW)(void *handle, eL6470_ActId_t L6470_ActId, eL6470_DirId_t L6470_DirId); 00372 void (*PrepareGoHome)(void *handle); 00373 void (*PrepareGoMark)(void *handle); 00374 void (*PrepareResetPos)(void *handle); 00375 void (*PrepareResetDevice)(void *handle); 00376 void (*PrepareSoftStop)(void *handle); 00377 void (*PrepareHardStop)(void *handle); 00378 void (*PrepareSoftHiZ)(void *handle); 00379 void (*PrepareHardHiZ)(void *handle); 00380 void (*PrepareGetStatus)(void *handle); 00381 uint8_t (*CheckStatusRegisterFlag)(void *handle, uint8_t L6470_StatusRegisterFlagId); 00382 uint8_t* (*PerformPreparedApplicationCommand)(void *handle); 00383 uint8_t* (*GetRegisterName)(void *handle, uint8_t id); 00384 int32_t (*AbsPos_2_Position)(void *handle, uint32_t AbsPos); 00385 uint32_t (*Position_2_AbsPos)(void *handle, int32_t Position); 00386 float (*Speed_2_Step_s)(void *handle, uint32_t Speed); 00387 uint32_t (*Step_s_2_Speed)(void *handle, float Step_s); 00388 float (*Acc_2_Step_s2)(void *handle, uint16_t Acc); 00389 uint16_t (*Step_s2_2_Acc)(void *handle, float Step_s2); 00390 float (*Dec_2_Step_s2)(void *handle, uint16_t Dec); 00391 uint16_t (*Step_s2_2_Dec)(void *handle, float Step_s2); 00392 float (*MaxSpeed_2_Step_s)(void *handle, uint16_t MaxSpeed); 00393 uint16_t (*Step_s_2_MaxSpeed)(void *handle, float Step_s); 00394 float (*MinSpeed_2_Step_s)(void *handle, uint16_t MinSpeed); 00395 uint16_t (*Step_s_2_MinSpeed)(void *handle, float Step_s); 00396 float (*FsSpd_2_Step_s)(void *handle, uint16_t FsSpd); 00397 uint16_t (*Step_s_2_FsSpd)(void *handle, float Step_s); 00398 float (*IntSpeed_2_Step_s)(void *handle, uint16_t IntSpeed); 00399 uint16_t (*Step_s_2_IntSpeed)(void *handle, float Step_s); 00400 float (*StSlp_2_s_Step)(void *handle, uint8_t StSlp); 00401 uint8_t (*s_Step_2_StSlp)(void *handle, float s_Step); 00402 float (*FnSlpAcc_2_s_Step)(void *handle, uint8_t FnSlpAcc); 00403 uint8_t (*s_Step_2_FnSlpAcc)(void *handle, float s_Step); 00404 float (*FnSlpDec_2_s_Step)(void *handle, uint8_t FnSlpDec); 00405 uint8_t (*s_Step_2_FnSlpDec)(void *handle, float s_Step); 00406 float (*OcdTh_2_mA)(void *handle, uint8_t OcdTh); 00407 uint8_t (*mA_2_OcdTh)(void *handle, float mA); 00408 float (*StallTh_2_mA)(void *handle, uint8_t StallTh); 00409 uint8_t (*mA_2_StallTh)(void *handle, float mA); 00410 uint32_t (*ExtractReturnedData)(void *handle, uint8_t* pL6470_DaisyChainSpiRxStruct, uint8_t LengthByte); 00411 } MICROSTEPPING_MOTOR_VTable_t; 00412 00413 /** 00414 * @brief Stepper Motor Board Driver Structure 00415 */ 00416 typedef struct 00417 { 00418 void (*SetParam)(uint8_t, uint8_t, eL6470_RegId_t, uint32_t); 00419 uint32_t (*GetParam)(uint8_t, uint8_t, eL6470_RegId_t); 00420 void (*Run)(uint8_t, uint8_t, eL6470_DirId_t, uint32_t); 00421 void (*StepClock)(uint8_t, uint8_t, eL6470_DirId_t); 00422 void (*Move)(uint8_t, uint8_t, eL6470_DirId_t, uint32_t); 00423 void (*GoTo)(uint8_t, uint8_t L6470_Id, uint32_t AbsPos); 00424 void (*GoToDir)(uint8_t, uint8_t, eL6470_DirId_t, uint32_t); 00425 void (*GoUntil)(uint8_t, uint8_t, eL6470_ActId_t, eL6470_DirId_t, uint32_t); 00426 void (*ReleaseSW)(uint8_t, uint8_t, eL6470_ActId_t, eL6470_DirId_t); 00427 void (*GoHome)(uint8_t, uint8_t); 00428 void (*GoMark)(uint8_t, uint8_t); 00429 void (*ResetPos)(uint8_t, uint8_t); 00430 void (*ResetDevice)(uint8_t, uint8_t); 00431 void (*SoftStop)(uint8_t, uint8_t); 00432 void (*HardStop)(uint8_t, uint8_t); 00433 void (*SoftHiZ)(uint8_t, uint8_t); 00434 void (*HardHiZ)(uint8_t, uint8_t); 00435 uint16_t (*GetStatus)(uint8_t, uint8_t); 00436 uint8_t (*CheckStatusRegisterFlag)(uint8_t, uint8_t, uint8_t); 00437 uint8_t* (*PerformPreparedApplicationCommand)(uint8_t); 00438 } MICROSTEPPING_MOTOR_EB_VTable_t; 00439 00440 /** 00441 * @brief Stepper Motor Handle Structure 00442 */ 00443 typedef struct __StepperMotorDriver_HandleTypeDef 00444 { 00445 uint8_t DaisyChainPosition; 00446 void (*Config)(void*); 00447 MICROSTEPPING_MOTOR_VTable_t *Command; 00448 } StepperMotorDriverHandle_t; 00449 00450 /** 00451 * @brief Stepper Motor Handle Structure 00452 */ 00453 typedef struct __StepperMotorBoard_HandleTypeDef 00454 { 00455 uint8_t StackedPosition; 00456 void (*Config)(void*); 00457 MICROSTEPPING_MOTOR_EB_VTable_t *Command; 00458 StepperMotorDriverHandle_t *StepperMotorDriverHandle[2]; 00459 uint8_t (*Select)(uint8_t); 00460 } StepperMotorBoardHandle_t; 00461 00462 /** 00463 * @} 00464 */ /* StepperMotorExportedTypes */ 00465 00466 /** 00467 * @} 00468 */ /* MicrosteppingMotorDriver */ 00469 00470 /** 00471 * @} 00472 */ /* Components */ 00473 00474 /** 00475 * @} 00476 */ /* BSP */ 00477 00478 #ifdef __cplusplus 00479 } 00480 #endif 00481 00482 #endif /* __MICROSTEPPINGMOTOR_H */ 00483 00484 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
Generated on Tue Dec 18 2018 08:19:50 by
