SaintStefan
2/15/2020 - 6:15 PM

驱动器和步进电机控制


#ifndef __STEPPER_MOTOR_A4988_CONTROL_H__
#define __STEPPER_MOTOR_A4988_CONTROL_H__

#include <stdio.h>
#include <wiringPi.h>

#include "Keyboard_Control.h"

/*使用C语言GPIO库wiringPi约定的编号
 */
/************************************************
 * 17HM15-0904S步进电机正常模式是360度分400步走完,
 * 也就是A4988步进电机驱动器的2细分模式
 ************************************************
 * MS1   MS2   MS3
 *  L     L     L    整步(没有细分)   1.8度/步
 *  H     L     L    1/2(2细分)      0.9度/步
 *  L     H     L    1/4(4细分)      0.45度/步
 *  H     H     L    1/8(8细分)      0.225度/步
 *  H     H     H    1/16(16细分)    0.1125度/步
 ************************************************/
#define MS1	4
#define MS2 5
#define MS3 6

#define RST_SLP 21							// RST(RESET):复位引脚,一般接高电平。
											// SLP(SLEEP):睡眠引脚,一般接高电平。
#define Left_EN 23							// 步进驱动使能端,一般接低电平。
#define Left_DIR 24							// DIR(Direction):用高低电平控制点击旋转方向。
#define Left_STEP 25						// 用高低电平驱动电机转动
											// STEP脉冲输入,往这个脚输入一个方波,电机转动一步,也就是(1.8/2)°(0.9°电机,2细分),
											// 往这个脚持续输入方波,则电机持续转动。
#define Right_EN 27							
#define Right_DIR 28						
#define Right_STEP 29						

void IO_A4988Init()
{
	printf("A4988 Init begin\n");
	pinMode(MS1, OUTPUT);
	pinMode(MS2, OUTPUT);
	pinMode(MS3, OUTPUT);

	pinMode(RST_SLP, OUTPUT);

	pinMode(Left_EN, OUTPUT);				// Enable:使能端控制启停,低电平启动。可不接
	pinMode(Left_DIR, OUTPUT);				// Dir:高低电平控制转动方向
	pinMode(Left_STEP, OUTPUT);				// Step:高低电平控制电机转动

	pinMode(Right_EN, OUTPUT);
	pinMode(Right_DIR, OUTPUT);	
	pinMode(Right_STEP, OUTPUT);
	printf("A4988 Init end\n");				
}

/*
 * dir低电平,电机逆时针转
 * dir高电平,电机顺时针转
 */
void forward(int t, int steps)
{
	int i;
	digitalWrite(Left_DIR, LOW);			// 设置dir低电平,左电机逆时针转,但对于小车左轮前进方向是前进!!!
	digitalWrite(Right_DIR, HIGH);			// 设置dir高电平,右电机顺时针转,但对于小车右轮前进方向是前进!!! 
	for(i = 0; i < steps; i++)				// for循环,如果设置steps=2048,则步进0-2048步
	{
		digitalWrite(RST_SLP, HIGH);		// 复位引脚,睡眠引脚,一般设置为高电平			
		
		digitalWrite(MS1, HIGH);			// 选择步进精度,初始化步进精度是1/2步
		digitalWrite(MS2, LOW);
		digitalWrite(MS3, LOW);

		digitalWrite(Left_EN, LOW);			// 设置en低电平
		digitalWrite(Right_EN, LOW);

		digitalWrite(Left_STEP, HIGH);		// 设置左step为高电平 
		digitalWrite(Right_STEP, HIGH);		// 控制速度其实就是控制脉冲频率,也就是控制拉高拉低之间的延迟时间。
		delayMicroseconds(t);				// delayMicroseconds的单位是微秒,一秒等于1000000微秒。
		digitalWrite(Left_STEP, LOW);		// 设置step为低电平 
		digitalWrite(Right_STEP, LOW);
		delayMicroseconds(t);
	}
}

void backward(int t, int steps)
{
	int i;
	digitalWrite(Left_DIR, HIGH);			// 设置dir高电平,左电机顺时针转 
	digitalWrite(Right_DIR, LOW);			// 设置dir低电平,右电机逆时针转
	for(i = 0; i < steps; i++)
	{
		digitalWrite(RST_SLP, HIGH);		// 复位引脚,睡眠引脚,一般设置为高电平

		digitalWrite(MS1, HIGH);			// 选择步进精度,初始化步进精度是1/2步
		digitalWrite(MS2, LOW);
		digitalWrite(MS3, LOW);

		digitalWrite(Left_EN, LOW);			// 设置en低电平
		digitalWrite(Right_EN, LOW);

		digitalWrite(Left_STEP, HIGH);		// 设置左step为高电平 
		digitalWrite(Right_STEP, HIGH);
		delayMicroseconds(t);				
		digitalWrite(Left_STEP, LOW);		// 设置step为低电平 
		digitalWrite(Right_STEP, LOW);
		delayMicroseconds(t);
	}
}

void turnleft(int t, int steps)
{
	int i;
	digitalWrite(Left_DIR, HIGH);			// 设置dir高电平,左电机顺时针转 
	digitalWrite(Right_DIR, HIGH);			// 设置dir高电平,左电机顺时针转
	for(i = 0; i < steps; i++)
	{
		digitalWrite(RST_SLP, HIGH);		// 复位引脚,睡眠引脚,一般设置为高电平

		digitalWrite(MS1, HIGH);			// 选择步进精度,初始化步进精度是1/2步
		digitalWrite(MS2, LOW);
		digitalWrite(MS3, LOW);

		digitalWrite(Left_EN, LOW);			// 设置en低电平
		digitalWrite(Right_EN, LOW);

		digitalWrite(Left_STEP, HIGH);		// 设置左step为高电平 
		digitalWrite(Right_STEP, HIGH);
		delayMicroseconds(t);				
		digitalWrite(Left_STEP, LOW);		// 设置step为低电平 
		digitalWrite(Right_STEP, LOW);
		delayMicroseconds(t);
	}
}

void turnright(int t, int steps)
{
	int i;
	digitalWrite(Left_DIR, LOW);			// 设置dir低电平,左电机逆时针转
	digitalWrite(Right_DIR, LOW);			// 设置dir低电平,左电机逆时针转
	for(i = 0; i < steps; i++)
	{
		digitalWrite(RST_SLP, HIGH);		// 复位引脚,睡眠引脚,一般设置为高电平

		digitalWrite(MS1, HIGH);			// 选择步进精度,初始化步进精度是1/2步
		digitalWrite(MS2, LOW);
		digitalWrite(MS3, LOW);

		digitalWrite(Left_EN, LOW);			// 设置en低电平
		digitalWrite(Right_EN, LOW);

		digitalWrite(Left_STEP, HIGH);		// 设置左step为高电平 
		digitalWrite(Right_STEP, HIGH);
		delayMicroseconds(t);				
		digitalWrite(Left_STEP, LOW);		// 设置step为低电平 
		digitalWrite(Right_STEP, LOW);
		delayMicroseconds(t);
	}
}

void stepstop()								
{
	digitalWrite(RST_SLP, HIGH);
	
	digitalWrite(MS1, HIGH);			// 选择步进精度,初始化步进精度是1/2步
	digitalWrite(MS2, LOW);
	digitalWrite(MS3, LOW);
	
	digitalWrite(Left_EN, HIGH);
	digitalWrite(Right_EN, HIGH);

	digitalWrite(Left_STEP, LOW);		
	digitalWrite(Right_STEP, LOW);
}

/*int main(void)
{
	wiringPiSetup();
	if (-1 == wiringPiSetup()) 
	{
		printf("Setup wiringPi failed!");
		return 1;
	}

	IO_A4988Init();
	stepstop();

	while (1)
	{
		printf("forward...\n");
		forward(150, 2048);					// 延时150微秒。
		delay(2000);						// 整体延时2秒,一秒等于1000000微秒。
		printf("turnleft...\n");
		turnleft(150, 2048);
		delay(2000);						// delay的单位是毫秒,一秒等于1000毫秒。
		printf("turnright...\n");
		turnright(150, 2048);
		delay(2000);
		printf("backward...\n");
		backward(150, 2048);
		delay(2000);
	}
}*/

#endif