树莓派舵机控制程序占用树莓派资源,软件生成的pwm不稳定,舵机间歇性抖动。为避免这一情况,使用专门的舵机控制板比较好,淘宝上有卖16路舵机控制板,也是I2c通信控制的。因疫情不能发货,故使用Arduio Nano设计一款自用的树莓派外设——舵机控制板。

1.接口选择

Arduino Nano pins

从图中可以看出舵机连接口可为3,5,6,9,10,11

A4,A5为I2c通信接口,将舵机控制与控制主机相连。

2.arduino I2c 六路舵机控制板程序

// I2c 舵机控制板,使用arduino nano主控,I2c从机模式,地址为#8
// 舵机连接口为3,5,6,9,10,11
// 接收7字节数据,第一位0xFF为标志位,其余对应上述舵机口想要达到的角度。
#include <Wire.h>
#include <Servo.h>

Servo myservo[6];  // create servo object to control a servo
int pos[6]; //= {90, 90, 90, 90, 90, 90};
int targetPos[6]; //= {60, 70, 80, 90, 100, 110};
int flag = 0;
int num = 0;
void setup() {
  myservo[0].attach(3);  // attaches the servo on pin 3 to the servo object
  myservo[1].attach(5);
  myservo[2].attach(6);
  myservo[3].attach(9);
  myservo[4].attach(10);
  myservo[5].attach(11);
  Wire.begin(8);                // join i2c bus with address #8
  Wire.onReceive(receiveEvent); // register event
  //  Serial.begin(9600);
}

void loop() {
  while (pos[0] != targetPos[0] || pos[1] != targetPos[1] || pos[2] != targetPos[2] || pos[3] != targetPos[3] || pos[4] != targetPos[4] || pos[5] != targetPos[5])
  {
    for (int i = 0; i < 6; i++) {
      mv(i, targetPos[i]);
      //Serial.print(targetPos[i]);  
    }
  }
}

void mv(int o, int p) {//o是端口号,p是需要到达的角度
  if (p > pos[o])  {
    myservo[o].write(pos[o] + 1);
    pos[o] += 1;
    delay(1);
  }
  if (p < pos[o]) {
    myservo[o].write(pos[o] - 1);
    pos[o] -= 1;
    delay(1);
  }
}

void receiveEvent(int howMany) {
  int x = Wire.read();    // receive byte as an integer
  //  Serial.print(x); 
  if (flag == 1 && x <=180) {
    targetPos[num] = x;
    num ++;
    if (num == 7 )
      flag = 0;
  }
  else if (x == 255) {
    flag = 1;
    num = 0;
  }
}

3.Arduino 测试主机程序。

#include <Wire.h>
unsigned int pos[7] = {255, 30, 30, 30, 30, 30, 50};
int flag = 1;
void setup() {
  Wire.begin(); // join i2c bus (address optional for master)
}
void loop() {
  if (flag == 1) {
    pos[0] = 255;
    pos[1] = 10;
    pos[2] = 20;
    pos[3] = 30;
    pos[4] = 40;
    pos[5] = 50;
    pos[6] = 60;
  }
  if (flag == -1) {
    pos[0] = 255;
    pos[1] = 50;
    pos[2] = 50;
    pos[3] = 50;
    pos[4] = 50;
    pos[5] = 90;
    pos[6] = 80;
  }
  flag = -flag;
  
  sendmessage();
  
  delay(1000);
}

void sendmessage() {
  int i =0;
  for (int i=0; i<7;i++)  {
  Wire.beginTransmission(8); // transmit to device #8
  Wire.write(pos[i]);
  Wire.endTransmission();    // stop transmitting
  delay(10);
  }
}

4.树莓派程序实现

import smbus
import time

bus = smbus.SMBus(1)
pos = [255,90,90,90,90,90,90]

def servo270(port,angle):
    pos[port] = int(angle*180/270)

def runservo():
    for x in pos:
        bus.write_byte(0x08, x)  # 向地址8发送数据
        time.sleep(0.01)

while 1:
    # servo270(120,120,90,90,90,90)
    servo270(1,170)
    servo270(2,170)
    runservo()
    time.sleep(2)  # 延时
    # servo270(90, 90, 90, 90, 90, 90)
    servo270(1,90)
    servo270(2,90)
    runservo()
    time.sleep(2)  # 延时

发表评论