|
着急先看测试视频
要写舵机内部控制程序,必须了解构成舵机的器件
电位计,测量轴转动的角度 (一般3K-5K)
(图片涉及外部联系方式予以删除版主留)
减速齿轮, 把小直流电机的转动力量转化为大力矩
电机驱动 4个三级管/mos管构成的H桥,控制电机正反转
控制芯片:读取pwm值,电位计的值,比较差异,驱动H桥使电机转动
舵机 = 减速直流电机 + H桥+电位计+程序 + PWM读取
在arduino nano/pro_mini 实现的程序如下
- /* by Payne.Pan 2017.2 */
- /* only for study */
- #define A 5
- #define B 6
- #define Delta 5
- long prev_time=0;
- long pwm=0;
- void rising() {
- prev_time = micros();
- attachInterrupt(0, falling, FALLING);
- }
- void falling() {
- pwm = micros()-prev_time;
- attachInterrupt(0,rising, RISING);
- }
- void runMotor(int dir) {
- if (dir == 0) {
- digitalWrite(A,LOW);
- digitalWrite(B,LOW);
- }else if (dir > 0) {
- digitalWrite(A,HIGH);
- digitalWrite(B,LOW);
- } else {
- digitalWrite(A,LOW);
- digitalWrite(B,HIGH);
- }
- }
- void setup() {
- pinMode(2,INPUT);
- pinMode(A,OUTPUT);
- pinMode(B,OUTPUT);
- pinMode(A0,INPUT);
- attachInterrupt(0,rising, RISING);
- }
- void loop() {
- int a = analogRead(A0);
- a = map(a,0,1023,500,2500);
- if (pwm-a > Delta) {
- runMotor(1);
- } else if (pwm-a < -Delta) {
- runMotor(-1);
- } else {
- runMotor(0);
- }
- }
复制代码
更完整的内容参见:http://bbs.5imx.com/forum.php?mod=viewthread&tid=1253266&page=1&extra=#pid19306380
|
欢迎继续阅读楼主其他信息
|