Arduino三轮全向小车(一):编码马达的使用

Arduino三轮全向小车(一):编码马达的使用## 标题

近期准备做一个arduino作为下位机的底盘,看了很多,还是不知所以然,干脆直接开始动手,变搞边学习。然而查阅网上各种资料高深莫测,看得我云里雾里,初学很是艰辛。所以就写几篇博客记录一下自己的学习过程。作为菜鸡,欢迎大家指正。

马达的选用
​  如果是要做小车的,选用什么样的马达是很重要的,需要考虑的一个方面。之前用Arduino做小车一般直接用减速直流电机,就是那种小黄马达。说实在的效果不是很好,所谓便宜没好货,拿去比赛各种问题接踵而至,但若不考虑其控制的精确性,只是用来实现移动,还算可以接受。现在不参加比赛,帮老老板完成科研任务即可,所以主要重点在逻辑控制上。
​  其实这算是一个开环控制系统,信号单向流通,由驱动板传向马达,马达没有反馈,因此其控制精度不会很高。就算它转速的控制很精准,但如果电池供电忽大忽小,或是地面阻力时强时弱,这些外界输入依旧会给小车的运动带来极大的不确定性。这种方案在要求稍微高一点的情况下,就是应当舍弃的。
​  为了解决开环控制的问题,人们自然而然地就想到了在马达上加一个传感器,让它可以返回它的各种运动参数。而我们一般用编码器来做这样的传感器。

马达接线
马达的接线比较粗糙,白色A、黄色B、蓝色VCC、绿色GEN、红色电机+、黑色电机-;

图片后期上传
————————————————————分割线——————————————

编码器取值

这个部分需要对编码器的数据进行计数,参考了大佬的代码拿来改改试试

motor.h

/*
 * @Autor: Mond
 * @Date: 2021-04-13 22:32:13
 * @LastEditors: Mond
 * @LastEditTime: 2021-04-14 23:21:12
 * @Description: An library for motor and its encoder
 */
#ifndef motor_H
#define motor_H

#include "Arduino.h"
/**
 * @description: define a motor
 * @param {int} pA: Encoder A phase port number
 * @param {int} pB: Encoder B phase port number
 * @param {int} MOTOR_S: The port number that controls the motor speed
 * @param {int} MOTOR_D1: The port number that controls the direction of motor rotation -A
 * @param {int} MOTOR_D2: The port number that controls the direction of motor rotation -B
 * @param {int} *PPs: Variable address for storing the number of encoder pulses
 * @param {bool} FC: FALLING->0; CHANGE->1; 
 */
class motor
{
public:
	long m;
	float velocity;
	long *pps;
	motor(int pA, int pB, int MOTOR_S, int MOTOR_D1, int MOTOR_D2, long *PPs, bool FC);
	void Init();
	void MotorControl(int sp);
	void Count(int flag);
	void SpeedDetection(int sampletime, int resolution);

private:
	int pinA;
	int pinB;
	int MOTOR_SP;
	int MOTOR_PIN1;
	int MOTOR_PIN2;
	bool ForC;
	int adjust(int sp);
};
#endif

motor.c

#include "motor.h"
motor::motor(int pA, int pB, int MOTOR_S, int MOTOR_D1, int MOTOR_D2, long *PPs, bool FC)
{
	pinA = pA;
	pinB = pB;
	MOTOR_SP = MOTOR_S;
	MOTOR_PIN1 = MOTOR_D1;
	MOTOR_PIN2 = MOTOR_D2;
	pps = PPs;
	ForC = FC;
}
/**
 * @description: initial a motor
 * @param {*}
 * @return {*}
 */
void motor::Init()
{
	pinMode(pinA, INPUT);
	pinMode(pinB, INPUT);
	pinMode(MOTOR_SP, OUTPUT);
	pinMode(MOTOR_PIN1, OUTPUT);
	pinMode(MOTOR_PIN2, OUTPUT);
}

/**
 * @description: control motor speed
 * @param {int} sp: motor speed; -255 to 255
 * @return {*}
 */
void motor::MotorControl(int sp)
{
	if (sp > 255)
		sp = 255;
	else if (sp < -255)
		sp = -255;

	if (sp > 0)
	{
		digitalWrite(MOTOR_PIN1, LOW);
		digitalWrite(MOTOR_PIN2, HIGH);
		analogWrite(MOTOR_SP, sp);
	}
	else if (sp < 0)
	{
		digitalWrite(MOTOR_PIN1, HIGH);
		digitalWrite(MOTOR_PIN2, LOW);
		analogWrite(MOTOR_SP, -1 * sp);
	}
	else
	{
		digitalWrite(MOTOR_PIN1, LOW);
		digitalWrite(MOTOR_PIN2, LOW);
	}
}

/**
 * @description: count the encoder
 * usage: 
 * 	void Count()
 * 		myMotor.Count(1);
 * 	void setup()
 * 	...	  attachInterrupt(5, Count, CHANGE); ... // CHANGE -> FC=1; FALLING -> FC=0
 * @param {int} flag: adjust the direction of encoder
 * @return {*}
 */
void motor::Count(int flag)
{
	int now_pps = *pps;
	if (ForC)
	{
		if (digitalRead(pinA) == LOW)
		{
			if (digitalRead(pinB) == HIGH)
				*pps = now_pps - flag;
			else if (digitalRead(pinB) == LOW)
				*pps = now_pps + flag;
		}
		else
		{
			if (digitalRead(pinB) == HIGH)
				*pps = now_pps + flag;
			else if (digitalRead(pinB) == LOW)
				*pps = now_pps - flag;
		}
	}
	else
	{
		if (digitalRead(pinB) == HIGH)
			*pps = now_pps - flag;
		else if (digitalRead(pinB) == LOW)
			*pps = now_pps + flag;
	}
}

/**
 * @description: Calculate the motor speed and rotation angle
 * usage:
 * void SpeedDetection()
	{
	  detachInterrupt(5);
	  myMotor.SpeedDetection(t, 390);
	  attachInterrupt(5, Count, CHANGE);
	}
	void setup()
	... MsTimer2::set(t, SpeedDetection);
  	MsTimer2::start(); ...
 * @param {int} sampletime	
 * @param {int} resolution
 * @return {*}
 */
void motor::SpeedDetection(int sampletime, int resolution)
{
	if (ForC)
		resolution *= 2;
	int pps_val = *pps;
	velocity = (float)pps_val * (1000 / sampletime) / (float)(resolution);
	m += pps_val * 360.0 / (float)(resolution);
	*pps = 0;
}

实验完了分享怎么用

稍后更新

  • 1
    点赞
  • 7
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值