Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: ST_INTERFACES
Dependents: HelloWorld_IHM14A1
Fork of X_NUCLEO_IHM14A1 by
Components/STSPIN820/STSPIN820.h
- Committer:
- Davidroid
- Date:
- 2018-04-27
- Revision:
- 1:bc265521eb00
- Child:
- 2:4fd08b67958c
File content as of revision 1:bc265521eb00:
/** ****************************************************************************** * @file STSPIN820.h * @author STM * @version V1.0.0 * @date August 7th, 2017 * @brief STSPIN820 driver (fully integrated microstepping motor driver) * @note (C) COPYRIGHT 2017 STMicroelectronics ****************************************************************************** * @attention * * <h2><center>© 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. * ****************************************************************************** */ /* Generated with STM32CubeTOO -----------------------------------------------*/ /* Revision ------------------------------------------------------------------*/ /* Repository: http://svn.x-nucleodev.codex.cro.st.com/svnroot/X-NucleoDev Branch/Trunk/Tag: trunk Based on: X-CUBE-SPN14/trunk/Drivers/BSP/Components/STSPIN820/STSPIN820.h Revision: 0 */ /* Define to prevent recursive inclusion -------------------------------------*/ #ifndef __STSPIN820_CLASS_H #define __STSPIN820_CLASS_H /* Includes ------------------------------------------------------------------*/ /* ACTION 1 ------------------------------------------------------------------* * Include here platform specific header files. * *----------------------------------------------------------------------------*/ #include "mbed.h" #include "DevSPI.h" /* ACTION 2 ------------------------------------------------------------------* * Include here component specific header files. * *----------------------------------------------------------------------------*/ #include "STSPIN820_def.h" /* ACTION 3 ------------------------------------------------------------------* * Include here interface specific header files. * * * * Example: * * #include "../Interfaces/Humidity.h" * * #include "../Interfaces/Temperature.h" * *----------------------------------------------------------------------------*/ #include "../Interfaces/Motor.h" /* Classes -------------------------------------------------------------------*/ /** * @brief Class representing a STSPIN820 component. */ class STSPIN820 : public Motor { public: /*** Constructor and Destructor Methods ***/ /** * @brief Constructor. * @param ssel pin name of the SSEL pin of the SPI device to be used for communication. * @param spi SPI device to be used for communication. */ STSPIN820(PinName ssel, DevSPI &spi) : Motor(), ssel(ssel), dev_spi(spi) { /* ACTION 4 ----------------------------------------------------------* * Initialize here the component's member variables, one variable per * * line. * * * * Example: * * measure = 0; * * instance_id = number_of_instances++; * *--------------------------------------------------------------------*/ flag_interrupt_callback = 0; error_handler_callback = 0; toggle_odd = 0; device_prm = 0; number_of_devices = 0; device_instance = 0; } /** * @brief Destructor. */ virtual ~STSPIN820(void) {} /*** Public Component Related Methods ***/ /* ACTION 5 --------------------------------------------------------------* * Implement here the component's public methods, as wrappers of the C * * component's functions. * * They should be: * * + Methods with the same name of the C component's virtual table's * * functions (1); * * + Methods with the same name of the C component's extended virtual * * table's functions, if any (2). * * * * Example: * * virtual int get_value(float *p_data) //(1) * * { * * return COMPONENT_get_value(float *pf_data); * * } * * * * virtual int enable_feature(void) //(2) * * { * * return COMPONENT_enable_feature(); * * } * *------------------------------------------------------------------------*/ virtual int init(void *init = NULL) { return (int) STSPIN820_Init((void *) init); } virtual int read_id(uint8_t *id = NULL) { return (int) STSPIN820_ReadId((uint8_t *) id); } virtual void attach_error_handler(void (*callback)(uint16_t error)) { STSPIN820_AttachErrorHandler((void (*)(uint16_t error)) callback); } virtual void attach_flag_interrupt(void (*callback)(void)) { STSPIN820_AttachFlagInterrupt((void (*)(void)) callback); } virtual void flag_interrupt_handler(void) { STSPIN820_FlagInterruptHandler(); } virtual uint16_t get_acceleration(uint8_t deviceId) { return (uint16_t) STSPIN820_GetAcceleration((uint8_t) deviceId); } virtual uint16_t get_current_speed(uint8_t deviceId) { return (uint16_t) STSPIN820_GetCurrentSpeed((uint8_t) deviceId); } virtual uint16_t get_deceleration(uint8_t deviceId) { return (uint16_t) STSPIN820_GetDeceleration((uint8_t) deviceId); } virtual motor_state_t get_device_state(uint8_t deviceId) { return (motor_state_t) STSPIN820_GetDeviceState((uint8_t) deviceId); } virtual uint32_t get_fw_version(void) { return (uint32_t) STSPIN820_GetFwVersion(); } virtual int32_t get_mark(uint8_t deviceId) { return (int32_t) STSPIN820_GetMark((uint8_t) deviceId); } virtual uint16_t get_max_speed(uint8_t deviceId) { return (uint16_t) STSPIN820_GetMaxSpeed((uint8_t) deviceId); } virtual uint16_t get_min_speed(uint8_t deviceId) { return (uint16_t) STSPIN820_GetMinSpeed((uint8_t) deviceId); } virtual int32_t get_position(uint8_t deviceId) { return (int32_t) STSPIN820_GetPosition((uint8_t) deviceId); } virtual void go_home(uint8_t deviceId) { STSPIN820_GoHome((uint8_t) deviceId); } virtual void go_mark(uint8_t deviceId) { STSPIN820_GoMark((uint8_t) deviceId); } virtual void go_to(uint8_t deviceId, int32_t targetPosition) { STSPIN820_GoTo((uint8_t) deviceId, (int32_t) targetPosition); } virtual void hard_stop(uint8_t deviceId) { STSPIN820_HardStop((uint8_t) deviceId); } virtual void move(uint8_t deviceId, motor_direction_t direction, uint32_t stepCount) { STSPIN820_Move((uint8_t) deviceId, (motor_direction_t) direction, (uint32_t) stepCount); } virtual void run(uint8_t deviceId, motor_direction_t direction) { STSPIN820_Run((uint8_t) deviceId, (motor_direction_t) direction); } virtual bool set_acceleration(uint8_t deviceId, uint16_t newAcc) { return (bool) STSPIN820_SetAcceleration((uint8_t) deviceId, (uint16_t) newAcc); } virtual bool set_deceleration(uint8_t deviceId, uint16_t newDec) { return (bool) STSPIN820_SetDeceleration((uint8_t) deviceId, (uint16_t) newDec); } virtual void set_home(uint8_t deviceId) { STSPIN820_SetHome((uint8_t) deviceId); } virtual void set_mark(uint8_t deviceId) { STSPIN820_SetMark((uint8_t) deviceId); } virtual bool set_max_speed(uint8_t deviceId, uint16_t newMaxSpeed) { return (bool) STSPIN820_SetMaxSpeed((uint8_t) deviceId, (uint16_t) newMaxSpeed); } virtual bool set_min_speed(uint8_t deviceId, uint16_t newMinSpeed) { return (bool) STSPIN820_SetMinSpeed((uint8_t) deviceId, (uint16_t) newMinSpeed); } virtual bool soft_stop(uint8_t deviceId) { return (bool) STSPIN820_SoftStop((uint8_t) deviceId); } virtual void step_clock_handler(uint8_t deviceId) { STSPIN820_StepClockHandler((uint8_t) deviceId); } virtual void wait_while_active(uint8_t deviceId) { STSPIN820_WaitWhileActive((uint8_t) deviceId); } virtual void cmd_disable(uint8_t deviceId) { STSPIN820_Disable((uint8_t) deviceId); } virtual void cmd_enable(uint8_t deviceId) { STSPIN820_Enable((uint8_t) deviceId); } virtual bool select_step_mode(uint8_t deviceId, motor_step_mode_t stepMode) { return (bool) STSPIN820_SetStepMode((uint8_t) deviceId, (motor_step_mode_t) stepMode); } virtual void set_direction(uint8_t deviceId, motor_direction_t direction) { STSPIN820_SetDirection((uint8_t) deviceId, (motor_direction_t) direction); } virtual void cmd_go_to_dir(uint8_t deviceId, motor_direction_t direction, int32_t targetPosition) { STSPIN820_GoToDir((uint8_t) deviceId, (motor_direction_t) direction, (int32_t) targetPosition); } virtual uint8_t check_status_hw(void) { return (uint8_t) STSPIN820_CheckStatusHw(); } virtual void cmd_reset_device(uint8_t deviceId) { STSPIN820_PutDeviceInStandby((uint8_t) deviceId); } virtual uint8_t get_nb_devices(void) { return (uint8_t) STSPIN820_GetNbDevices(); } virtual void error_handler(uint16_t error) { STSPIN820_ErrorHandler((uint16_t) error); } virtual uint32_t get_bridge_input_pwm_freq(uint8_t deviceId) { return (uint32_t) STSPIN820_VrefPwmGetFreq((uint8_t) deviceId); } virtual void set_bridge_input_pwm_freq(uint8_t deviceId, uint32_t newFreq) { STSPIN820_VrefPwmSetFreq((uint8_t) deviceId, (uint32_t) newFreq); } virtual void set_stop_mode(uint8_t deviceId, motor_stop_mode_t stopMode) { STSPIN820_SetStopMode((uint8_t) deviceId, (motor_stop_mode_t) stopMode); } virtual motor_stop_mode_t get_stop_mode(uint8_t deviceId) { return (motor_stop_mode_t) STSPIN820_GetStopMode((uint8_t) deviceId); } virtual void set_decay_mode(uint8_t deviceId, motor_decay_mode_t decayMode) { STSPIN820_SetDecayMode((uint8_t) deviceId, (motor_decay_mode_t) decayMode); } virtual motor_decay_mode_t get_decay_mode(uint8_t deviceId) { return (motor_decay_mode_t) STSPIN820_GetDecayMode((uint8_t) deviceId); } virtual motor_step_mode_t get_step_mode(uint8_t deviceId) { return (motor_step_mode_t) STSPIN820_GetStepMode((uint8_t) deviceId); } virtual motor_direction_t get_direction(uint8_t deviceId) { return (motor_direction_t) STSPIN820_GetDirection((uint8_t) deviceId); } virtual void exit_device_from_reset(uint8_t deviceId) { STSPIN820_ExitDeviceFromStandby((uint8_t) deviceId); } virtual void set_torque(uint8_t deviceId, motor_torque_mode_t torqueMode, uint8_t torqueValue) { STSPIN820_SetTorque((uint8_t) deviceId, (motor_torque_mode_t) torqueMode, (uint8_t) torqueValue); } virtual uint8_t get_torque(uint8_t deviceId, motor_torque_mode_t torqueMode) { return (uint8_t) STSPIN820_GetTorque((uint8_t) deviceId, (motor_torque_mode_t) torqueMode); } virtual bool set_nb_devices(uint8_t deviceId) { return (bool) STSPIN820_SetNbDevices((uint8_t) deviceId); } virtual void set_torque_boost_enable(uint8_t deviceId, bool enable) { STSPIN820_SetTorqueBoostEnable((uint8_t) deviceId, (bool) enable); } virtual bool get_torque_boost_enable(uint8_t deviceId) { return (bool) STSPIN820_GetTorqueBoostEnable((uint8_t) deviceId); } virtual void set_torque_boost_threshold(uint8_t deviceId, uint16_t speedThreshold) { STSPIN820_SetTorqueBoostThreshold((uint8_t) deviceId, (uint16_t) speedThreshold); } virtual uint16_t get_torque_boost_threshold(uint8_t deviceId) { return (uint16_t) STSPIN820_GetTorqueBoostThreshold((uint8_t) deviceId); } /*** Public Interrupt Related Methods ***/ /* ACTION 6 --------------------------------------------------------------* * Implement here interrupt related methods, if any. * * Note that interrupt handling is platform dependent, e.g.: * * + mbed: * * InterruptIn feature_irq(pin); //Interrupt object. * * feature_irq.rise(callback); //Attach a callback. * * feature_irq.mode(PullNone); //Set interrupt mode. * * feature_irq.enable_irq(); //Enable interrupt. * * feature_irq.disable_irq(); //Disable interrupt. * * + Arduino: * * attachInterrupt(pin, callback, RISING); //Attach a callback. * * detachInterrupt(pin); //Detach a callback. * * * * Example (mbed): * * void attach_feature_irq(void (*fptr) (void)) * * { * * feature_irq.rise(fptr); * * } * * * * void enable_feature_irq(void) * * { * * feature_irq.enable_irq(); * * } * * * * void disable_feature_irq(void) * * { * * feature_irq.disable_irq(); * * } * *------------------------------------------------------------------------*/ protected: /*** Protected Component Related Methods ***/ /* ACTION 7 --------------------------------------------------------------* * Declare here the component's specific methods. * * They should be: * * + Methods with the same name of the C component's virtual table's * * functions (1); * * + Methods with the same name of the C component's extended virtual * * table's functions, if any (2); * * + Helper methods, if any, like functions declared in the component's * * source files but not pointed by the component's virtual table (3). * * * * Example: * * status_t COMPONENT_get_value(float *f); //(1) * * status_t COMPONENT_enable_feature(void); //(2) * * status_t COMPONENT_compute_average(void); //(3) * *------------------------------------------------------------------------*/ void STSPIN820_ApplySpeed(uint8_t pwmId, uint16_t newSpeed); void STSPIN820_ApplyTorque(uint8_t deviceId, motor_torque_mode_t torqueMode); void STSPIN820_ComputeSpeedProfile(uint8_t deviceId, uint32_t nbSteps); void STSPIN820_FlagInterruptHandler(void); void STSPIN820_SetDeviceParamsOtherValues(void); void STSPIN820_SetDeviceParamsToGivenValues(STSPIN820_init_t* initDevicePrm); void STSPIN820_SetDeviceParamsToPredefinedValues(void); void STSPIN820_StartMovement(uint8_t deviceId); void STSPIN820_StepClockHandler(uint8_t deviceId); MOTOR_vt_t* STSPIN820_GetMotorHandle(void); //Return handle of the motor driver handle void STSPIN820_Init(void* pInit); //Start the STSPIN820 library uint16_t STSPIN820_ReadId(void); //Read Id to get driver instance void STSPIN820_AttachErrorHandler(void (*callback)(uint16_t)); //Attach a user callback to the error handler void STSPIN820_AttachFlagInterrupt(void (*callback)(void)); //Attach a user callback to the flag Interrupt uint8_t STSPIN820_CheckStatusHw(void); //Check if STSPIN820 has a fault by reading EN pin position void STSPIN820_Disable(uint8_t deviceId); //Disable the power stage of the specified device void STSPIN820_Enable(uint8_t deviceId); //Enable the power stage of the specified device void STSPIN820_ErrorHandler(uint16_t error); //Error handler which calls the user callback void STSPIN820_ExitDeviceFromStandby(uint8_t deviceId); //Exit STSPIN820 device from standby uint16_t STSPIN820_GetAcceleration(uint8_t deviceId); //Return the acceleration in pps^2 uint16_t STSPIN820_GetCurrentSpeed(uint8_t deviceId); //Return the current speed in pps motor_decay_mode_t STSPIN820_GetDecayMode(uint8_t deviceId); //Return the device decay mode uint16_t STSPIN820_GetDeceleration(uint8_t deviceId); //Return the deceleration in pps^2 motor_state_t STSPIN820_GetDeviceState(uint8_t deviceId); //Return the device state motor_direction_t STSPIN820_GetDirection(uint8_t deviceId); //Get the motor current direction uint32_t STSPIN820_GetFwVersion(void); //Return the FW version int32_t STSPIN820_GetMark(uint8_t deviceId); //Return the mark position uint16_t STSPIN820_GetMaxSpeed(uint8_t deviceId); //Return the max speed in pps uint16_t STSPIN820_GetMinSpeed(uint8_t deviceId); //Return the min speed in pps uint8_t STSPIN820_GetNbDevices(void); //Return the nupber of devices int32_t STSPIN820_GetPosition(uint8_t deviceId); //Return the ABS_POSITION (32b signed) motor_step_mode_t STSPIN820_GetStepMode(uint8_t deviceId); //Get the motor step mode motor_stop_mode_t STSPIN820_GetStopMode(uint8_t deviceId); //Get the selected mode to stop the motor uint8_t STSPIN820_GetTorque(uint8_t deviceId, motor_torque_mode_t torqueMode); bool STSPIN820_GetTorqueBoostEnable(uint8_t deviceId); //Get the torque boost feature status uint16_t STSPIN820_GetTorqueBoostThreshold(uint8_t deviceId); //Get the torque boost threshold void STSPIN820_GoHome(uint8_t deviceId); //Move to the home position void STSPIN820_GoMark(uint8_t deviceId); //Move to the Mark position void STSPIN820_GoTo(uint8_t deviceId, int32_t targetPosition); //Go to the specified position void STSPIN820_GoToDir(uint8_t deviceId, motor_direction_t direction, int32_t targetPosition); //Go to the specified position using the specified direction void STSPIN820_HardStop(uint8_t deviceId); //Stop the motor and keep holding torque void STSPIN820_HardHiZ(uint8_t deviceId); //Stop the motor and disable the power bridge void STSPIN820_Move(uint8_t deviceId, motor_direction_t direction, uint32_t stepCount); //Move the motor of the specified number of steps void STSPIN820_PutDeviceInStandby(uint8_t deviceId); //Put STSPIN820 device in standby (low power consumption) void STSPIN820_Run(uint8_t deviceId, motor_direction_t direction); //Run the motor bool STSPIN820_SetAcceleration(uint8_t deviceId,uint16_t newAcc); //Set the acceleration in pps^2 bool STSPIN820_SetDeceleration(uint8_t deviceId,uint16_t newDec); //Set the deceleration in pps^2 void STSPIN820_SetDecayMode(uint8_t deviceId, motor_decay_mode_t decay); //Set the STSPIN820 decay mode pin void STSPIN820_SetDirection(uint8_t deviceId, motor_direction_t direction); //Set the STSPIN820 direction pin void STSPIN820_SetHome(uint8_t deviceId); //Set current position to be the home position void STSPIN820_SetMark(uint8_t deviceId); //Set current position to be the Markposition bool STSPIN820_SetMaxSpeed(uint8_t deviceId,uint16_t newMaxSpeed);//Set the max speed in pps bool STSPIN820_SetMinSpeed(uint8_t deviceId,uint16_t newMinSpeed);//Set the min speed in pps bool STSPIN820_SetNbDevices(uint8_t nbDevices); bool STSPIN820_SetStepMode(uint8_t deviceId, motor_step_mode_t stepMode); // Step mode selection void STSPIN820_SetStopMode(uint8_t deviceId, motor_stop_mode_t stopMode); //Select the mode to stop the motor void STSPIN820_SetTorque(uint8_t deviceId, motor_torque_mode_t torqueMode, uint8_t torqueValue); void STSPIN820_SetTorqueBoostEnable(uint8_t deviceId, bool enable); // Enable or disable the torque boost feature void STSPIN820_SetTorqueBoostThreshold(uint8_t deviceId, uint16_t speedThreshold); //Set the torque boost threshold bool STSPIN820_SoftStop(uint8_t deviceId); //Progressively stop the motor by using the device deceleration and set deceleration torque uint32_t STSPIN820_VrefPwmGetFreq(uint8_t deviceId); //Get the frequency of REF PWM of the specified device void STSPIN820_VrefPwmSetFreq(uint8_t deviceId, uint32_t newFreq);//Set the frequency of REF PWM of the specified device void STSPIN820_WaitWhileActive(uint8_t deviceId); //Wait for the device state becomes Inactive /*** Component's I/O Methods ***/ /** * @brief Utility function to read data from STSPIN820. * @param[out] pBuffer pointer to the buffer to read data into. * @param[in] NumBytesToRead number of bytes to read. * @retval COMPONENT_OK in case of success, COMPONENT_ERROR otherwise. */ status_t read(uint8_t* pBuffer, uint16_t NumBytesToRead) { if (dev_spi.spi_read(pBuffer, ssel, NumBytesToRead) != 0) return COMPONENT_ERROR; return COMPONENT_OK; } /** * @brief Utility function to write data to STSPIN820. * @param[in] pBuffer pointer to the buffer of data to send. * @param[in] NumBytesToWrite number of bytes to write. * @retval COMPONENT_OK in case of success, COMPONENT_ERROR otherwise. */ status_t write(uint8_t* pBuffer, uint16_t NumBytesToWrite) { if (dev_spi.spi_write(pBuffer, ssel, NumBytesToWrite) != 0) return COMPONENT_ERROR; return COMPONENT_OK; } /** * @brief Utility function to read and write data from/to STSPIN820 at the same time. * @param[out] pBufferToRead pointer to the buffer to read data into. * @param[in] pBufferToWrite pointer to the buffer of data to send. * @param[in] NumBytes number of bytes to read and write. * @retval COMPONENT_OK in case of success, COMPONENT_ERROR otherwise. */ status_t read_write(uint8_t* pBufferToRead, uint8_t* pBufferToWrite, uint16_t NumBytes) { if (dev_spi.spi_read_write(pBufferToRead, pBufferToWrite, ssel, NumBytes) != 0) return COMPONENT_ERROR; return COMPONENT_OK; } /* ACTION 8 --------------------------------------------------------------* * Implement here other I/O methods beyond those already implemented * * above, which are declared extern within the component's header file. * *------------------------------------------------------------------------*/ void STSPIN820_Board_Delay(uint32_t delay) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_Disable(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_DisableIrq(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } uint32_t STSPIN820_Board_EN_AND_FAULT_PIN_GetState(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ return (uint32_t) 0; } void STSPIN820_Board_Enable(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_EnableIrq(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_GpioInit(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_PwmRefInit(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_PwmRefSetFreqAndDutyCycle(uint32_t newFreq, uint8_t dutyCycle) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_PwmRefStart(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_PwmRefStop(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_ReleaseReset(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_Reset(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_SetDecayGpio(uint8_t gpioState) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } uint8_t STSPIN820_Board_GetDecayGpio(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ return (uint8_t) 0; } void STSPIN820_Board_SetDirectionGpio(uint8_t gpioState) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_SetFullStep(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } bool STSPIN820_Board_SetModePins(uint8_t modePin1Level, uint8_t modePin2Level, uint8_t modePin3Level) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ return (bool) 0; } void STSPIN820_Board_TimStckCompareInit(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_TimStckDeInit(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_TimStckInit(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_TimStckSetFreq(uint16_t newFreq) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } void STSPIN820_Board_TimStckStart(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } uint8_t STSPIN820_Board_TimStckStop(uint8_t *pToggleOdd) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ return (uint8_t) 0; } void STSPIN820_Board_UnsetFullStep(void) { /* TO BE IMPLEMENTED BY USING TARGET PLATFORM'S APIs. */ } /*** Component's Instance Variables ***/ /* ACTION 9 --------------------------------------------------------------* * Declare here interrupt related variables, if needed. * * Note that interrupt handling is platform dependent, see * * "Interrupt Related Methods" above. * * * * Example: * * + mbed: * * InterruptIn feature_irq; * *------------------------------------------------------------------------*/ /* ACTION 10 -------------------------------------------------------------* * Declare here other pin related variables, if needed. * * * * Example: * * + mbed: * * DigitalOut standby_reset; * *------------------------------------------------------------------------*/ /* ACTION 11 -------------------------------------------------------------* * Declare here communication related variables, if needed. * * * * Example: * * + mbed: * * DigitalOut ssel; * * DevSPI &dev_spi; * *------------------------------------------------------------------------*/ /* Configuration. */ DigitalOut ssel; /* IO Device. */ DevSPI &dev_spi; /* ACTION 12 -------------------------------------------------------------* * Declare here identity related variables, if needed. * * Note that there should be only a unique identifier for each component, * * which should be the "who_am_i" parameter. * *------------------------------------------------------------------------*/ /* Identity */ uint8_t who_am_i; /* ACTION 13 -------------------------------------------------------------* * Declare here the component's static and non-static data, one variable * * per line. * * * * Example: * * float measure; * * int instance_id; * * static int number_of_instances; * *------------------------------------------------------------------------*/ void (*flag_interrupt_callback)(void); void (*error_handler_callback)(uint16_t error); uint8_t toggle_odd; device_params_t device_prm; uint8_t number_of_devices; uint8_t device_instance; }; #endif /* __STSPIN820_CLASS_H */ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/