【电机控制】42步进电机+arduino:WHEELTEC_MS42DDC

轮趣科技

42步进电机+arduino:WHEELTEC_MS42DDC

接线方式:

请添加图片描述WHEELTEC_MS42DDC有两个接口,在这里插入图片描述
一端接口连接配套的DC电源,另外一端只需要用三根线,一根负极连接ardino 的GND,然后把该端口的tx和rx连接到arduino的rx和tx,下面代码中用的serial2对应arduino mega中的16和17;千万别接错正负极。

代码如下

#include <Arduino.h>

// 定义串口通信的波特率,根据 MS42DC 电机的 USB 串口控制协议,波特率为 115200
const long baudRate = 115200;

// 帧头,为固定值 0x7B
const byte START_BYTE = 0x7B;
// 控制 ID,现在为 0x02
const byte CONTROL_ID = 0x01;

void setup() {
  // 初始化调试串口
  Serial.begin(115200);
  while (!Serial) delay(1);

  // 初始化与电机通信的串口
  Serial2.begin(baudRate);
  Serial.println("Serial communication initialized");
}

// 发送控制信息到电机的函数
void sendMotorCommand(byte controlMode, byte direction, byte microstepping, int value1, int value2) {
  byte command[11];
  // 帧头
  command[0] = START_BYTE;
  // 控制 ID
  command[1] = CONTROL_ID;
  // 控制模式
  command[2] = controlMode;
  // 转向
  command[3] = direction;
  // 细分值
  command[4] = microstepping;
  // 数据字节 1
  command[5] = highByte(value1);
  // 数据字节 2
  command[6] = lowByte(value1);
  // 数据字节 3
  command[7] = highByte(value2);
  // 数据字节 4
  command[8] = lowByte(value2);
  // 计算 BCC 校验位,为前面九个字节的异或和
  byte bcc = command[0] ^ command[1] ^ command[2] ^ command[3] ^ command[4] ^ command[5] ^ command[6] ^ command[7] ^ command[8];
  command[9] = bcc;
  // 帧尾
  command[10] = 0x7D;
  
  Serial2.write(command, 11);
  Serial.print("Sent command to motor: ");
  for (int i = 0; i < 11; i++) {
    Serial.print(command[i], HEX);
    Serial.print(" ");
  }
  Serial.println();
}

void loop() {
  // // 速度控制模式示例
  // sendMotorCommand(0x01, 1, 0x20, 0, 0x0064); // 顺时针,32 细分,速度为 10 Rad/s
  // delay(1000);
  
  // // 位置控制模式示例
  // sendMotorCommand(0x02, 0, 0x20, 0x2710, 0x0064); // 逆时针,32 细分,位置为 1000 度,速度为 10 Rad/s
  // delay(1000);
  
  // // 力矩控制模式示例
  // sendMotorCommand(0x03, 1, 0x20, 0x03E8, 0x0064); // 顺时针,32 细分,电流为 1000 mA,速度为 10 Rad/s
  // delay(1000);
  
  // 单圈绝对角度控制模式示例
  sendMotorCommand(0x04, 0, 0x20, 0x04B0, 0x0064); // 逆时针,32 细分,目标角度为 100 度,速度为 10 Rad/s
  delay(1000);
  sendMotorCommand(0x04, 0, 0x20, 0x03E8, 0x0064); // 逆时针,32 细分,目标角度为 100 度,速度为 10 Rad/s
  delay(1000);
  sendMotorCommand(0x04, 0, 0x20, 0x0320, 0x0064); // 逆时针,32 细分,目标角度为 100 度,速度为 10 Rad/s
  delay(1000);
  sendMotorCommand(0x04, 0, 0x20, 0x0258, 0x0064); // 逆时针,32 细分,目标角度为 100 度,速度为 10 Rad/s
  delay(1000);
  // 接收电机的状态反馈(如果有)
  if (Serial2.available() > 0) {
    byte buffer[32];
    int bytesRead = Serial2.readBytes(buffer, Serial2.available());
    Serial.print("Received ");
    Serial.print(bytesRead);
    Serial.println(" bytes from motor:");
    for (int i = 0; i < bytesRead; i++) {
      Serial.print(buffer[i], HEX);
      Serial.print(" ");
    }
    Serial.println();
  }
}
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值