ADI Trinamic Blog

We transform digital information into physical motion.

 
  • Newsletter
  • Blog Ethics
  • Legal/Impressum
  • Main Website
Menu
  • Newsletter
  • Blog Ethics
  • Legal/Impressum
  • Main Website
  • Driving a linear stage with the TMC4671 – Firmware Adaptation

    Application Setup

    In our last blog post, we were able to determine stable P-I-parameters for our cascaded controller loop. With that knowledge in mind I want to show you how I created a small example program which I will include in the firmware of the Landungsbrücke. 

    What this code basically does is initializing the TMC4671 for stepper motor control. This is done in init_Basics(…) by writing several configuration-registers whereas reset_Basics(…) resets all registers used in this work to a defined state of 0. This replaces the first steps in the configuration wizard of our IDE where we used the default buttons. 

    The configure_ABN(…)-function will set the ABN-count to 0 after PHI_E aligned the rotor to 0. For this to happen we need to apply a voltage to the flux as well. 

    init_PosMode(…) sets the correct registers for the TMC4671 to enter position mode.  

    Using tmc4671_setAbsolutTargetPosition(…) sets the target position of the controller to the desired value, making the motor turn until the target position is reached. Here the absolute position will always refer to our zero position configured in the configure_ABN(…) function.  

    Side note: If you want movement relative to your actual position you can use the function tmc4671_setRelativeTargetPosition(…). 

    In order to find the minimum and maximum positions of my setup, I select two target positions in  find_targetPositions(…) that are impossible to reach. For me, these are 500000 and –500000. The controller waits a certain amount of time to be sure that it reached an end position. Then it will save the actual position with the function tmc4671_getActualPosition(…).  We do that for the other direction as well. The values of both endings can now be used for new target positions which can be set by using tmc4671_setAbsolutTargetPosition(…) again.  

    I can also use linear ramping for acceleration and deceleration while driving. I use the function tmc_ramp_linear_compute(…) and a struct of type TMC_LinearRamp for this (you can find more information in the API in the files LinearRamp1.h and LinearRamp1.c). This creates a ramp with the information of our track in software. I also set some of the parameters of the struct using the corresponding functions from the aforementioned files. I can set the target position for my ramp using tmc_ramp_linear_set_targetPosition(…) in the struct. After that, I use the calculated ramp position in tmc4671_setAbsolutTargetPosition(calculated_Ramp). This will be looped until the actual target position is reached. 

    What does ramping do? Instead of setting an absolute target position to be reached with one instruction, we divide our track in multiple sub-target positions. In each iteration of the loop, we increase the target position and the controller will adjust to the new target. However, the velocity of the Landungsbrücke increasing the target position is higher than the adaption of our controller, thus increasing the difference between target position and actual motor position over time.  This leads to the motor accelerating as the offset between actual and target position increases. 

    Decelerating works the other way around. The Landungsbrücke will decrease the velocity in which the target position is set and the controller will slowly catch up to it until it reaches the end position. 

    In order to increase the speed of the motor, I multiply the actual ramp position by a factor of 1024. This must be compensated by dividing the target position of the software ramp by 1024. With this we scale the ramp to our application and increase the acceleration and velocity of the motor. 

    Why do I want to use a (software) ramp? Basically, it gives us a more stable way to reach our target position as we have a determined way of accelerating and decelerating and it reduces the possibility of overshooting the target significantly. 

    The Landungsbrücke alternates these target positions in the TMC4671 register so the motor will be alternating the position of the slide. 

    With the finished code I generate a hex-file for the bootloader of the Landungsbrücke and update it using the TMCL-IDE.  

    I hope you can utilize some of the shown examples in order for you to transform digital information into physical motion for your projects! Thank you for keeping up with these blog posts and keep your eyes open for more to come! 

    Figure 1: Flashing the firmware

    Code and explanation

    #include "boards/Board.h"
    #include "hal/derivative.h"
    #include "hal/HAL.h"
    #include "tmc/IdDetection.h"
    #include "tmc/TMCL.h"
    #include "tmc/VitalSignsMonitor.h"
    #include "tmc/BoardAssignment.h"
    #include "tmc/ramp/LinearRamp1.h"
    #include "TMC-API/tmc/ic/TMC4671/TMC4671.h"
    #include "TMC-API/tmc/ic/TMC4671/TMC4671_Register.h" //As I use the names of its registers this needs to be included
    
    //mydefines
    #define STATE_START_INIT       1
    #define STATE_RUN_1			   2
    #define STATE_RUN_2			   3
    
    #define UD_EXT				   3202
    
    //Torque-Flux Limits 15000
    #define TORQUE_FLUX_LIMIT	   10000
    //Velocity Limit 10000
    #define VELOCITY_LIMIT		   10000
    //P-I-defines
    #define TORQUE_FLUX_P			4952
    #define TORQUE_FLUX_I		   10939
    #define VELOCITY_P				2200
    #define VELOCITY_I				2000
    #define POSITION_P				  45
    #define POSITION_I				   0
    
    //for checking motor supply voltage
    #define VM_FACTOR              713
    #define ADC_VM_RES 			   65535 //Landungsbruecke define -- change for Startrampe
    
    //Software-Ramp defines
    #define STEPDIR_FREQUENCY         (1 << 17)
    #define STEPDIR_MAX_VELOCITY      (1 << 20)
    #define STEPDIR_MAX_ACCELERATION  2147418111
    #define STEPDIR_DEFAULT_ACCELERATION 100000
    #define STEPDIR_DEFAULT_VELOCITY STEPDIR_MAX_VELOCITY
    #define RAMP_SPEED_FACTOR			1024
    //end mydefines
    
    
    void init_PosMode(uint8_t motor)
    {	//Set registers needed for position mode
    	//tmc4671_writeInt(motor, TMC4671_VELOCITY_SELECTION, TMC4671_VELOCITY_PHI_M_ABN);
    	tmc4671_writeInt(motor, TMC4671_PID_TORQUE_FLUX_TARGET_DDT_LIMITS, 32767);  //max
    	tmc4671_writeInt(motor, TMC4671_PIDOUT_UQ_UD_LIMITS, 32767); 			    //max
    	tmc4671_writeInt(motor, TMC4671_PID_TORQUE_FLUX_LIMITS, TORQUE_FLUX_LIMIT);
    	tmc4671_writeInt(motor, TMC4671_PID_ACCELERATION_LIMIT, 2147483647);
    	tmc4671_writeInt(motor, TMC4671_PID_VELOCITY_LIMIT, VELOCITY_LIMIT);
    	tmc4671_writeInt(motor, TMC4671_PID_POSITION_LIMIT_LOW, 0x80000001);
    	tmc4671_writeInt(motor, TMC4671_PID_POSITION_LIMIT_HIGH, 0x7FFFFFFF);
    	tmc4671_writeInt(motor, TMC4671_PHI_E_SELECTION, 0x00000003);			  			//phi_e_abn
    	tmc4671_writeInt(motor, TMC4671_VELOCITY_SELECTION, TMC4671_VELOCITY_PHI_M_ABN);
    	tmc4671_writeInt(motor, TMC4671_POSITION_SELECTION, TMC4671_POSITION_PHI_M_ABN);	//phi_m_abn
    	tmc4671_writeInt(motor, TMC4671_MODE_RAMP_MODE_MOTION, 0x00000003);		  			//position mode
    
    	//The following gain-values were determined using the USB-2-RTMI and following the PI-tuning guide
    	tmc4671_setTorqueFluxPI(motor, TORQUE_FLUX_P, TORQUE_FLUX_I); //(motor, P, I)
    	tmc4671_setVelocityPI(motor, VELOCITY_P, VELOCITY_I);
    	tmc4671_setPositionPI(motor, POSITION_P, POSITION_I);
    }
    
    //Check VM
    uint32_t current_VM()
    {
    	uint32_t VM;
    
    	VM = *HAL.ADCs->VM;              // read ADC value for motor supply VM
    	VM = (VM*VM_FACTOR)/ADC_VM_RES;  // calculate voltage from ADC value
    
    	return VM;
    }
    //End Check VM
    
    void init_Basics(uint8_t motor)
    {
    	//Configure basic registers like motor type, adc-offset
    
    	tmc4671_writeInt(motor, TMC4671_MOTOR_TYPE_N_POLE_PAIRS, 0x00020032); //x0002 - Stepper, x0032 = 50 polepairs
    	tmc4671_writeInt(motor, TMC4671_PWM_POLARITIES, 0x00000000);
    	tmc4671_writeInt(motor, TMC4671_PWM_MAXCNT, 0x00000F9F); 			  //Maxcount of PWM-counter
    	tmc4671_writeInt(motor, TMC4671_PWM_BBM_H_BBM_L, 0x00001919); 		  //Break before make times
    	tmc4671_writeInt(motor, TMC4671_PWM_SV_CHOP, 0x00000007);			  //turn on PWM
    
    	//Configure ADC -- Values were taken from the ide after the set offset option was used
    	tmc4671_writeInt(motor, TMC4671_ADC_I_SELECT, 0x18000100); 			  // configure ADC-Inputs
    	tmc4671_writeInt(motor, TMC4671_dsADC_MCFG_B_MCFG_A, 0x00100010);	  // configure ADCs
    	tmc4671_writeInt(motor, TMC4671_dsADC_MCLK_A, 0x20000000);			  // turn on  clock-signal for group-A ADCs
    	tmc4671_writeInt(motor, TMC4671_dsADC_MCLK_B, 0x00000000);			  // turn off clock-signal for group-B ADCs
    	tmc4671_writeInt(motor, TMC4671_dsADC_MDEC_B_MDEC_A, 0x014E014E);	  // Constants for filter
    	tmc4671_writeInt(motor, TMC4671_ADC_I0_SCALE_OFFSET, 0x01005D80); 	  // Fill in the offsets determined in the IDE
    	tmc4671_writeInt(motor, TMC4671_ADC_I1_SCALE_OFFSET, 0x01005CEF); 	  // Fill in the offsets determined in the IDE
    
    	// Open loop settings
    	tmc4671_writeInt(motor, TMC4671_OPENLOOP_MODE, 0x00000000);
    	tmc4671_writeInt(motor, TMC4671_OPENLOOP_ACCELERATION, 0x0000003C);
    	tmc4671_writeInt(motor, TMC4671_OPENLOOP_VELOCITY_TARGET, 0x00000000);
    	tmc4671_writeInt(motor, TMC4671_OPENLOOP_PHI, 0x00000000);
    
    	// Feedback selection
    	tmc4671_writeInt(motor, TMC4671_PHI_E_SELECTION, 0x00000000);
    	tmc4671_writeInt(motor, TMC4671_MODE_RAMP_MODE_MOTION, 0x00000008);
    	//tmc4671_writeInt(motor, TMC4671_UQ_UD_EXT, 0x00000F9F);
    	tmc4671_writeInt(motor, TMC4671_ABN_DECODER_PPR, 0x00009C40);
    
    	//Set Limits
    	tmc4671_writeInt(motor, TMC4671_PID_TORQUE_FLUX_TARGET_DDT_LIMITS, 0x7FFF); //max
    	tmc4671_writeInt(motor, TMC4671_PIDOUT_UQ_UD_LIMITS, 32767); 			    //max
    	tmc4671_writeInt(motor, TMC4671_PID_TORQUE_FLUX_LIMITS, TORQUE_FLUX_LIMIT);
    	tmc4671_writeInt(motor, TMC4671_PID_ACCELERATION_LIMIT, 2147483647);
    	tmc4671_writeInt(motor, TMC4671_PID_VELOCITY_LIMIT, VELOCITY_LIMIT);
    	tmc4671_writeInt(motor, TMC4671_PID_POSITION_LIMIT_LOW, 0x80000001);
    	tmc4671_writeInt(motor, TMC4671_PID_POSITION_LIMIT_HIGH, 0x7FFFFFFF);
    
    }
    
    void reset_Basics(uint8_t motor)
    {
    	//reset registers of TMC4671 that will later be used to 0
    	wait(1500);
    	tmc4671_writeInt(motor, TMC4671_PWM_SV_CHOP, 0);
    	tmc4671_writeInt(motor, TMC4671_MOTOR_TYPE_N_POLE_PAIRS, 0);
    	tmc4671_writeInt(motor, TMC4671_PWM_POLARITIES, 0);
    	tmc4671_writeInt(motor, TMC4671_PWM_MAXCNT, 0);
    	tmc4671_writeInt(motor, TMC4671_PWM_BBM_H_BBM_L, 0);
    
    	tmc4671_writeInt(motor, TMC4671_ADC_I_SELECT, 0);
    	tmc4671_writeInt(motor, TMC4671_dsADC_MCFG_B_MCFG_A, 0);
    	tmc4671_writeInt(motor, TMC4671_dsADC_MCLK_A, 0);
    	tmc4671_writeInt(motor, TMC4671_dsADC_MCLK_B, 0);
    	tmc4671_writeInt(motor, TMC4671_dsADC_MDEC_B_MDEC_A, 0);
    	tmc4671_writeInt(motor, TMC4671_ADC_I0_SCALE_OFFSET, 0);
    	tmc4671_writeInt(motor, TMC4671_ADC_I1_SCALE_OFFSET, 0);
    
    	tmc4671_writeInt(motor, TMC4671_OPENLOOP_MODE, 0);
    	tmc4671_writeInt(motor, TMC4671_OPENLOOP_ACCELERATION, 0);
    	tmc4671_writeInt(motor, TMC4671_OPENLOOP_VELOCITY_TARGET, 0);
    
    	tmc4671_writeInt(motor, TMC4671_PHI_E_SELECTION, 0);
    	tmc4671_writeInt(motor, TMC4671_MODE_RAMP_MODE_MOTION, 0);
    	tmc4671_writeInt(motor, TMC4671_UQ_UD_EXT, 0);
    	tmc4671_writeInt(motor, TMC4671_ABN_DECODER_PPR, 0);
    
    	tmc4671_writeInt(motor, TMC4671_PID_TORQUE_FLUX_TARGET_DDT_LIMITS, 0);
    	tmc4671_writeInt(motor, TMC4671_PIDOUT_UQ_UD_LIMITS, 0);
    	tmc4671_writeInt(motor, TMC4671_PID_TORQUE_FLUX_LIMITS, 0);
    	tmc4671_writeInt(motor, TMC4671_PID_ACCELERATION_LIMIT, 0);
    	tmc4671_writeInt(motor, TMC4671_PID_VELOCITY_LIMIT, 0);
    	tmc4671_writeInt(motor, TMC4671_PID_POSITION_LIMIT_LOW, 0);
    	tmc4671_writeInt(motor, TMC4671_PID_POSITION_LIMIT_HIGH, 0);
    	tmc4671_writeInt(motor, TMC4671_PHI_E_SELECTION, 0);
    	tmc4671_writeInt(motor, TMC4671_VELOCITY_SELECTION, 0);
    	tmc4671_writeInt(motor, TMC4671_POSITION_SELECTION, 0);
    	tmc4671_writeInt(motor, TMC4671_MODE_RAMP_MODE_MOTION, 0);
    	tmc4671_writeInt(motor, TMC4671_PID_POSITION_TARGET, 0);
    	tmc4671_writeInt(motor, TMC4671_PID_POSITION_ACTUAL, 0);
    	tmc4671_setTorqueFluxPI(motor, 0, 0); //(motor, P, I)
    	tmc4671_setVelocityPI(motor, 0, 0); // (motor, P, I)
    	tmc4671_setPositionPI(motor, 0, 0); // (motor, P, I)
    
    }
    
    void init_softwareRamp(TMC_LinearRamp *linearRamp)
    {
    	tmc_ramp_linear_init(linearRamp);
    	tmc_ramp_linear_set_mode(linearRamp, TMC_RAMP_LINEAR_MODE_POSITION);
    	tmc_ramp_linear_set_maxVelocity(linearRamp, STEPDIR_DEFAULT_VELOCITY);
    	tmc_ramp_linear_set_acceleration(linearRamp, STEPDIR_DEFAULT_ACCELERATION);
    
    }
    
    void find_targetPositions(uint8_t motor, int32_t *lower_End, int32_t*upper_End)
    {
    	tmc4671_setAbsolutTargetPosition(motor, 500000); // ~ 7.5 motor turns
    	wait(1500);
    	/* After slide reached one end of the setup the absolute position is stored in memory
    		For convenience I reduce the value of the target position to be saved a little,
    	 *  as driving into the endposition with full force is annoyingly loud :)
    	 *  if this is your goal just remove the +/- 1000 */
    	*lower_End = (tmc4671_getActualPosition(motor)-1000);
    	tmc4671_setAbsolutTargetPosition(motor, 0); //return to the starting position
    	wait(1000);
    
    	// Assumed an unreachable position so the slide reaches the other side of the setup
    	tmc4671_setAbsolutTargetPosition(motor, -500000); // ~ -7.5 motor turns
    	wait(1500);
    	// After slide reached the other end of the setup the absolute position is stored in memory
    	*upper_End = (tmc4671_getActualPosition(motor)+1000);
    	tmc4671_setAbsolutTargetPosition(motor, 0);
    	wait(1500);
    }
    
    void configure_ABN(uint8_t motor, uint16_t startVoltage)
    {
    	// set ABN_DECODER_PHI_E_OFFSET to zero
    	tmc4671_writeRegister16BitValue(motor, TMC4671_ABN_DECODER_PHI_E_PHI_M_OFFSET, BIT_16_TO_31, 0);
    	// select phi_e_ext
    	tmc4671_writeRegister16BitValue(motor, TMC4671_PHI_E_SELECTION, BIT_0_TO_15, 1);
    	// set an initialization voltage on UD_EXT (to the flux, not the torque!)
    	tmc4671_writeRegister16BitValue(motor, TMC4671_UQ_UD_EXT, BIT_16_TO_31, 0);
    	tmc4671_writeRegister16BitValue(motor, TMC4671_UQ_UD_EXT, BIT_0_TO_15, startVoltage);
    	// set the "zero" angle
    	tmc4671_writeRegister16BitValue(motor, TMC4671_PHI_E_EXT, BIT_0_TO_15, 0);
    	tmc4671_writeInt(motor, TMC4671_ABN_DECODER_MODE, 0x00001000);
    	//Set PHI_E to 0° angle so the rotor alignes itself with it
    	tmc4671_writeInt(motor, TMC4671_PHI_E_SELECTION, 0x00000000);
    	wait(4000);
    	tmc4671_readRegister16BitValue(motor, TMC4671_ABN_DECODER_PHI_E_PHI_M, BIT_16_TO_31);
    	//After the rotor has aligned this will set the ABN_DECODER_COUNT to 0 so there is a defined 0-position
    	tmc4671_writeInt(motor, TMC4671_ABN_DECODER_COUNT, 0);
    }
    void tmc4671setPositionModeAndRun(uint8_t motor, uint8_t *initState, uint16_t startVoltage, int32_t *upper_End, int32_t *lower_End, TMC_LinearRamp *linearRamp)
    {
    	/*State Machine with state-pointer *initState and 3 states
    	 * STATE_START_INIT: Sets TMC4671-registers for my application and configures the ABN-Encoder
    	 * 					 Drives to the ends of the track to get the actual min/max position values
    	 * 					 Drives to the first end position
    	 *
    	 * STATE_RUN_1:		 Drives to one end and changes direction when the *lower_End is reached
    	 *
    	 * STATE_RUN_2:		 Drives to the other end and changes direction when *upper_End is reached
    	 */
    	switch (*initState)
    	{
    	case STATE_START_INIT:
    		//reset TMC4671 registers
    		reset_Basics(motor);
    		//set TMC4671 registers with basic data like motortype, number of polepairs and so on
    		init_Basics(motor);
    
    		//initialize the software ramp
    		init_softwareRamp(linearRamp);
    		//configure ABN
    		configure_ABN(motor, startVoltage);
    
    		//Enter position-Mode
    		init_PosMode(motor);
    
    		//configure the end positions and store them in *lower_End and *upper_End
    		find_targetPositions(motor, lower_End, upper_End);
    
    		*initState = STATE_RUN_1;
    		//set the first target position using the software ramp
    		tmc_ramp_linear_set_targetPosition(linearRamp, (*lower_End/RAMP_SPEED_FACTOR));
    		break;
    	case STATE_RUN_1:
    
    		//drive from one end to the other: positive direction
    		tmc_ramp_linear_compute(linearRamp);
    		tmc4671_setAbsolutTargetPosition(motor, (RAMP_SPEED_FACTOR*tmc_ramp_linear_get_rampPosition(linearRamp)));
    		//When the target position is reached we will change direction
    		if(tmc4671_getActualPosition(motor) >= (*lower_End-RAMP_SPEED_FACTOR))
    		{
    			wait(50);
    			*initState = STATE_RUN_2;
    			tmc_ramp_linear_set_targetPosition(linearRamp, (*upper_End/RAMP_SPEED_FACTOR));
    			break;
    		}
    		*initState = STATE_RUN_1;
    		break;
    	case STATE_RUN_2:
    		//drive from one end to the other: negative direction
    		tmc_ramp_linear_compute(linearRamp);
    		tmc4671_setAbsolutTargetPosition(motor, (RAMP_SPEED_FACTOR*tmc_ramp_linear_get_rampPosition(linearRamp)));
    		//When the target position is reached we will change direction
    		if(tmc4671_getActualPosition(motor) <= (*upper_End + RAMP_SPEED_FACTOR))
    		{
    			wait(50);
    			*initState = STATE_RUN_1;
    			tmc_ramp_linear_set_targetPosition(linearRamp, (*lower_End/RAMP_SPEED_FACTOR));
    			break;
    		}
    		*initState = STATE_RUN_2;
    		break;
    	default:
    		*initState = 0;
    		break;
    	}
    }
    
    const char *VersionString = MODULE_ID"V308"; // module id and version of the firmware shown in the TMCL-IDE
    
    /* Keep as is! These lines are important for the update functionality. */
    #if defined(Landungsbruecke)
    	const uint8_t Protection[] __attribute__ ((section(".cfmconfig")))=
    	{
    		0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,  //Backdoor key
    		0xFF, 0xFF, 0xFF, 0xFF,                          //Flash protection (FPPROT)
    		0x7E,                                            //Flash security   (FSEC)
    		0xF9,                                            //Flash option     (FOPT)
    		0xFF,                                            //reserved
    		0xFF                                             //reserved
    	};
    
    	struct BootloaderConfig {
    		uint32_t BLMagic;
    		uint32_t drvEnableResetValue;
    	};
    
    	// This struct gets placed at a specific address by the linker
    	struct BootloaderConfig __attribute__ ((section(".bldata"))) BLConfig;
    #endif
    
    
    /* Check if jumping into bootloader is forced                                           */
    /*                                                                                      */
    /* In order to jump to bootloader e.g. because of an accidental infinite loop           */
    /* in a modified firmware you may short ID_CLK and ID_CH0 pins on start up.             */
    /* This will force the entrance into bootloader mode and allow to replace bad firmware. */
    void shallForceBoot()
    {
    	// toggle each pin and see if you can read the state on the other
    	// leave if not, because this means that the pins are not tied together
    	HAL.IOs->config->toOutput(&HAL.IOs->pins->ID_CLK);
    	HAL.IOs->config->toInput(&HAL.IOs->pins->ID_CH0);
    
    	HAL.IOs->config->setHigh(&HAL.IOs->pins->ID_CLK);
    	if(!HAL.IOs->config->isHigh(&HAL.IOs->pins->ID_CH0))
    		return;
    
    	HAL.IOs->config->setLow(&HAL.IOs->pins->ID_CLK);
    	if(HAL.IOs->config->isHigh(&HAL.IOs->pins->ID_CH0))
    		return;
    
    	HAL.IOs->config->toOutput(&HAL.IOs->pins->ID_CH0);
    	HAL.IOs->config->toInput(&HAL.IOs->pins->ID_CLK);
    
    	HAL.IOs->config->setHigh(&HAL.IOs->pins->ID_CH0);
    	if(!HAL.IOs->config->isHigh(&HAL.IOs->pins->ID_CLK))
    		return;
    
    	HAL.IOs->config->setLow(&HAL.IOs->pins->ID_CH0);
    	if(HAL.IOs->config->isHigh(&HAL.IOs->pins->ID_CLK))
    		return;
    
    	// not returned, this means pins are tied together
    	tmcl_boot();
    }
    
    
    /* Call all standard initialization routines. */
    static void init()
    {
    #if defined(Landungsbruecke)
    	// Default value: Driver enable gets set high by the bootloader
    	BLConfig.drvEnableResetValue = 1;
    #endif
    
    	HAL.init();                  // Initialize Hardware Abstraction Layer
    	IDDetection_init();          // Initialize board detection
    	tmcl_init();                 // Initialize TMCL communication
    
    	tmcdriver_init();            // Initialize dummy driver board --> preset EvalBoards.ch2
    	tmcmotioncontroller_init();  // Initialize dummy motion controller board  --> preset EvalBoards.ch1
    
    	VitalSignsMonitor.busy = 1;  // Put state to busy
    	Evalboards.driverEnable = DRIVER_ENABLE;
    
    	Evalboards.ch1.id = 0;       // preset id for driver board to 0 --> error/not found
    	Evalboards.ch2.id = 0;       // preset id for driver board to 0 --> error/not found
    
    	// We disable the drivers before configurating anything
    	HAL.IOs->config->toOutput(&HAL.IOs->pins->DIO0);
    	HAL.IOs->config->setHigh(&HAL.IOs->pins->DIO0);
    
    	IdAssignmentTypeDef ids = { 0 };
    	IDDetection_initialScan(&ids);  // start initial board detection
    	IDDetection_initialScan(&ids);  // start second time, first time not 100% reliable, not sure why - too fast after startup?
    	if(!ids.ch1.id && !ids.ch2.id)
    	{
    		shallForceBoot();           // only checking to force jump into bootloader if there are no boards attached
    		HAL.IOs->config->toOutput(&HAL.IOs->pins->ID_CLK);
    		HAL.IOs->config->toInput(&HAL.IOs->pins->ID_CH0);
    	}
    	Board_assign(&ids);             // assign boards with detected id
    
    	VitalSignsMonitor.busy 	= 0;    // not busy any more!
    }
    
    /* main function */
    int main(void)
    {
    	//initialise some pointers
    	//state pointer for fsm
    	uint8_t   init_State = STATE_START_INIT;
    	uint8_t  *initState;
    	initState = &init_State;
    
    	//store one end of the track
    	int32_t   upper_end = 0;
    	int32_t  *upper_End;
    	upper_End= &upper_end;
    
    	//store the other end
    	int32_t   lower_end = 0;
    	int32_t  *lower_End;
    	lower_End= &lower_end;
    
    	//convenience
    	uint8_t motor = 0;
    
    	//"flipflop"
    	uint8_t block = 0;
    
    	//struct used for the software ramp - see \TMC-API\tmc\ramp\LinearRamp1.h for typedef etc.
    	TMC_LinearRamp adressRamp;
    	TMC_LinearRamp *aRamp;
    	aRamp = &adressRamp;
    
    	init();
    
    	// Main loop
    	while(1)
    	{
    		// Check all parameters and life signs and mark errors
    		vitalsignsmonitor_checkVitalSigns();
    		// Perodic jobs of Motion controller/Driver boards
    		Evalboards.ch1.periodicJob(systick_getTick());
    
    		Evalboards.ch2.periodicJob(systick_getTick());
    		// Process TMCL communication
    		tmcl_process();
    
    		if (Evalboards.ch1.id != ID_TMC4671)
    			continue;
    
    		if(current_VM()<20){
    			tmc4671_writeInt(motor, TMC4671_PWM_SV_CHOP, 0); // Turn off PWM after unexpected reset
    			reset_Basics(motor);							 // Set the registers needed in this example to a defined default state
    			continue;
    		}
    
    		if(block == 0)
    		{
    			tmc4671_writeInt(motor, TMC4671_PWM_SV_CHOP, 0);	//Turn of PWM-Register after SPI was initialized
    			reset_Basics(motor);
    			block = 1;
    		}
    		tmc4671setPositionModeAndRun(motor, initState, UD_EXT, lower_End, upper_End, aRamp);
    	}
    
    	return 0;
    }
    

    With this code my drive is initialized, the encoder initialization is performed and homing on both end stops is performed. Afterwards, a back and forth movement is implemented.

    I can upload the firmware to the Landungsbrücke with the TMCL-IDE and it starts automatically after power-up. I can monitor the system behavior over the RTMI.

    You can copy the code above, or get the main.c file here.

    That’s it for today. I hope you like the application example and stay tuned for my next TMC4671 blogpost.

    Share this:

    • Twitter
    • Facebook
    • LinkedIn
    • Pinterest
    • Print
    • Email

    Related

    February 28, 2020 / Klemens Konhäuser / 0

    Categories: Code Snippet, Products, Software, technology, Tutorial

    Tags: code, code snippet, drive, eval kit, evaluation kit, Field Oriented Control, firmware, FOC, GUI, guide, How-To, IC, linear stage, programming, rtmi, servo, servo controller IC, setup, TMC4671, TMCL-IDE, tuning

    Driving a Linear Stage With the TMC4671 – Controller Tuning TMC7300 Example Script

    Comments are currently closed.

Recent Posts

  • Guest Blog: UBC Thunderbots
  • Guest Blog: TURAG
  • Guest Blog: School of Engineering Telecom Physics University of Strasbourg
  • Guest Blog: STAR Dresden
  • Pushing the Limits of Stepper Motor Control in 3D Printing

Social

  • View trinamic.mc’s profile on Facebook
  • View Trinamic_MC’s profile on Twitter
  • View trinamic’s profile on GitHub
  • View UC4SHA5_GAw1Wbm2T2NWpWbA’s profile on YouTube

Meta

  • Log in
  • Entries feed
  • Comments feed
  • WordPress.org

Newsletter

 

Info

Waterloohain 5
22769 Hamburg
+49 40 514 806 40

Tags

3D printer 3d printing arduino BLDC cDriver code code snippet coolStep drive Driver ease of use ethercat eval kit evaluation kit Field Oriented Control FOC GUI guide heliostat How-To IC linear stage motion controller motor driver open source hardware programming rtmi servo servo controller IC setup silentstepstick stealthChop stepper stepper motor stepper motor driver stepper motor driver ic stepper motors technology TMC4671 tmc5130 TMCL TMCL-IDE TRINAMIC TRINAMIC Motion Control tuning

Tag Cloud

    3D printer 3d printing arduino BLDC cDriver code code snippet coolStep drive Driver ease of use ethercat eval kit evaluation kit Field Oriented Control FOC GUI guide heliostat How-To IC linear stage motion controller motor driver open source hardware programming rtmi servo servo controller IC setup silentstepstick stealthChop stepper stepper motor stepper motor driver stepper motor driver ic stepper motors technology TMC4671 tmc5130 TMCL TMCL-IDE TRINAMIC TRINAMIC Motion Control tuning

Pages

  • Blog Ethics
  • Newsletter
  • Player Embed
  • Search Videos
  • User Videos
  • Video Category
  • Video Tag

Categories

  • Competition
  • Guest blog
  • Industry News
  • Jobs
  • Myths about Motors
  • Open Source Hardware
  • Products
  • Projects
    • DIY
    • University Projects
  • Research
  • Social
  • Software
  • technology
  • Trade Shows
  • Tutorial
    • Code Snippet
  • Uncategorized

Copyright © 2015 TRINAMIC BlogTheme created by PWT. Powered by WordPress.org

loading Cancel
Post was not sent - check your email addresses!
Email check failed, please try again
Sorry, your blog cannot share posts by email.