ST3215 Servo教程

资料

3D模型

2D图纸

文档

程序

软件

开源结构

说明

前言

本产品是一款大扭矩的可编程串行总线舵机,采用了360°高精度的磁编码器,可以在360°范围内进行角度控制。能够通过程序控制,将任意角度设置为舵机中位,也可以切换为连续转动的电机/步进电机模式,内置加速度启停功能,使动作更加柔和。每个舵机上面有两个接口,可以将舵机串联起来使用,理论上可以同时控制253个总线舵机并且每个舵机都能够获取自己当前的角度、负载、电压、模式等信息。适用于机械手臂,六足机器人,人形机器人,轮式机器人等需要闭环控制的机器人项目。
同时我们为该型号舵机提供了开源的12自由度机器狗模型,你可以在最下面的资料-开源结构中下载该开源结构的模型和工程文件。

产品规格

  • 输入电压VIN:6-12.6V
  • 机构极限角度:无限制
  • 转动角度:360°(舵机模式角度控制)/电机模式可连续转动
  • 通信波特率:1Mbps
  • 齿轮形式:高精度金属齿轮
  • 空载速度:0.222sec/60°(45RPM)@12V
  • 位置传感器分辨率:360°/4096
  • ID范围:0-253
  • 反馈信息:位置(Position);负载(Load);速度(Speed);输入电压(Input Voltage)
  • 空载电流:180 mA
  • 堵转电流:2.7 A
  • 产品尺寸:45.22mm x 35mm x 24.72mm

产品特性

  • 可串联使用,同时控制多达 253 个舵机(前提是供电充分)并获取每个舵机的反馈信息
  • 360°磁编码器,角度控制范围更大
  • 高精度,角度控制精度达到360°/4096
  • 可将任意角度设置为舵机中位,方便组装
  • 加速度启停功能,运动效果更加柔和
  • 紧凑的结构设计,产品外观更加美观
  • 宽电压输入 6-12.6V,可以与2s或3s锂电池直接供电
  • 大扭矩,可达到30kg.cm@12V
  • 可通过程序设置工作模式:舵机模式角度控制/电机模式可连续转动

硬件使用方法

  • 你可以使用我们的总线舵机驱动板来控制总线舵机。
  • 如果你希望在自己的项目中使用总线舵机,可以参考下面的这个原理图:

总线舵机驱动电路原理图

软件使用方法

安装Arduino IDE

  • 选择适用于你的系统的Arduino IDE。

  • 运行安装包。

  • 点击I Agree。

  • 勾选Install USB driver和Associate.ino files,然后点击Next。

  • 选择Arduino IDE的安装路径,然后点击Install。

  • 等待安装完成。

  • 安装需要的驱动。
  • 点击安装。

  • 点击安装。

  • 点击安装。

  • Arduino IDE安装完成。

安装Arduino core for the ESP32

  • 运行Arduino IDE,点击File。

  • 点击Preferences。

  • 在Additional Boards Manager URLs内填写https://dl.espressif.com/dl/package_esp32_index.json 然后点击OK。

  • 重启IDE,点击Tools > Board > Boards Manager, 打开Boards Manager。
  • 填写ESP32,点击Install。【注意:这里要安装1.0.6版本的ESP32】

  • 等待安装完成。

  • 安装完成后即可使用Arduino IDE来开发ESP32。

下载产品程序并安装依赖库

  • 通过库管理器安装的库有:
  • Adafruit SSD1306
  • Adafruit NeoPixel
  • 点击Tools > Manage Libraries,打开库管理器。

  • 依次在搜索框中输入需要通过库管理器安装的库的名称,并安装这些库。
  • Adafruit SSD1306
  • Adafruit NeoPixel
  • 鼠标放上去有Update的点Update,没有Update的选择最新的版本后点击Install。

 

  • 下载总线舵机的库和用于舵机驱动板的Arduino程序:
  • ServoDriverST开源程序(Arduino)
  • 下载后解压即可活得产品程序。
  • 将解压缩后将SCServo文件夹复制到\Documents\Arduino\libraries,来安装控制舵机的库 。

上传程序到机器人

  • 双击运行SERVO DRIVER WITH ESP32 ST/ServoDriverST/ServoDriverST.ino。

  • 点击Tools > Port 记住已有的COM Port,不用点击它。
  • 不同电脑这里显示的COM是不一样的,记住现在已有COM。

  • 连接驱动板和电脑。
  • 点击Tools > Port,点击这个新的COM。
  • 不同电脑这里新出现的COM是不一样的,点击新出现的COM。

  • 点击 Tools > Boards: > ESP32 Arduino > ESP32 Dev Module ,选择ESP32 Dev Module。

  • 其它设置如下:
Upload Speed: "921600"
CPU Frequency: "240MHz(WiFi/BT)"
Flash Frequency: "80MHz"
Flash Mode: "QIO"
Flash Size: "4MB(32Mb)"
'''Partition Scheme: "Huge APP(3MB No OTA/1MB SPIFFS)"
PSRAM: "Disabled"'''
  • 点击左上角的```Upload```上传程序。
  • 这里注意当WAVEGO使用串口与树莓派连接时自动下载电路会失效,需要断开与树莓派的串口连接后再上传程序到WAVEGO。

  • 等待程序上传完成。
  • 显示Leaving... Hard resetting via RTS pin...后表示已经上传成功。

产品使用教程

  • 以下教程默认以使用总线舵机驱动板的情况来解释舵机的使用方法,如果你需要在自己的项目中使用总线舵机,可以参考示例程序和总线舵机驱动电路原理图来进行二次开发。
  • 舵机的出厂默认ID为1,与同一块舵机驱动板连接的舵机中,同一个ID只能对应一个舵机,不可以有一个以上ID相同的舵机在同一控制链路中。当你为舵机设置ID时,尽量保证只有一个要更改ID的舵机与驱动板连接,ID更改后会被永久保存在舵机中即使断电也不会丢失。
  • 首先你需要为每个舵机设置一个独立的ID,当为一个舵机设置ID时,驱动板不要连接其它舵机。
  • 如果你使用ST3215舵机,当舵机与舵机驱动板连接后,你需要通过舵机驱动板的5.5*2.1mmDC接口为其供电6-12.6V(推荐使用12V供电),该供电接口会直接为舵机供电,如果你使用的舵机数量较多,需要保证这个接口有足够大的电流为其供电。
  • 驱动板上电后,默认会建立一个WiFi热点,默认热点名称为ESP32_DEV,默认热点密码为12345678。用手机连接这一热点。
  • 连接舵机驱动板发出的热点后,建议使用谷歌浏览器,访问地址192.168.4.1,需要注意的事,由于连接该WiFi后手机不能Ping通用来验证网络连接的服务器,所以可能会自动切换到其它已知WiFi,如果发生这种情况只要再重新连接ESP32_DEV即可,第二次连接成功后手机就不会自动切换了。
  • 驱动板在开机时会自动扫描ID:0-20的舵机(为了缩短开机时间),如果你使用了超过这一ID的舵机,需要更改ServoDriverST.ino内的MAX_ID数值再重新上传程序到舵机驱动板。

  • 如果舵机是在驱动板上电后才连接的,需要按一下手机浏览器页面上的Start Searching来重新扫描。
  • Active ID为现在所选择的舵机ID号,ID to Set为要设置的新ID号,通过ID to Set+ID to Set-来调整ID to Set的数值,调整后按Set New ID键来将当前ID为的Active ID的舵机的ID设置为ID to Set
  • 当全部舵机的ID都设置完成后,就可以将它们全部连接起来了。如果不重启设备,则需要按一下Start Searching来扫描所有舵机。
  • ID:后面显示的是当前所有与舵机驱动板相连接的舵机ID号。
  • Active ID当前所选择的舵机ID号,后续的操作都是在控制这个Active ID舵机。
  • 你可以通过ID Select+ID Select-这两个按键来选择Active ID舵机。
  • Middle键,可以让舵机转动到中间位置,舵机的位置范围为0-4095,中间位置为2047。
  • Stop键,默认程序中不会让舵机一直动作下去,如果对程序进行了二次开发导致舵机转动停不下来,可以通过按Stop键停下舵机运动。
  • Release键,按下后舵机会关闭扭矩锁(Torque Off),此时可以用手转动舵机。
  • Torque键,按下后舵机会开启扭矩锁(Torque On),此时舵机会用力保持在指定位置。
  • Position+键,按下后舵机会开始顺时针转动,当舵机处于舵机模式时,转动到4095的位置后就不会继续转动。
  • Position-键,按下后舵机会开始逆时针转动,当舵机处于舵机模式时,转动到0的位置后就不会继续转动。
  • Speed+Speed-用来设置舵机转速,ST系列舵机最高可设置为3073左右,速度为每秒钟转动转动的步数,50步/秒≈0.732RPM。
  • Set Middle Position键,无论当前舵机处于什么位置,当按下该按键后,舵机会将当前的位置设置为中间位置(2047)。
  • Set Servo Mode键,将舵机设置为舵机模式,舵机模式下可进行360°的绝对角度控制,该设置会永久保存即使掉电也不会丢失。
  • Set Motor Mode键,将舵机设置为步进电机模式,舵机可连续转动30000步,连续按下即可一直转动下去,该模式可进行±7圈内的相对角度控制,圈数掉电不保存,步进电机模式设置会永久保存即使掉电也不会丢失。
  • Start Serial Forwarding键,将舵机驱动板设置为串口转发模式,你可以用舵机驱动板上面的typeC接口直接控制舵机和获得舵机反馈,该功能用于调试舵机。
  • Normal键,将舵机驱动板设置为普通模式,该模式下,既不会通过ESP-NOW发送信息也不会接收信息。
  • Leader键,将舵机驱动板设置为主机端,该模式下,驱动板通过ESP-NOW协议连续发送当前Active ID舵机的ID,位置和速度发送给被控制从动端的驱动板中。舵机驱动板开机后,屏幕上第一行的MAC:是此开发板的MAC地址,该地址是独一无二的,例如MAC:08 3A F2 93 5F A8。ESP-NOW通信的前提是要知道从动端的MAC地址,记下那个地址,填写到ServoDriverST.ino的broadcastAddress[] = {0x08, 0x3A, 0xF2, 0x93, 0x5F, 0xA8};再上传到主机端的驱动板后就可以使用这个功能了。
  • Follower键,将舵机驱动板设置为从动端,当主机端的程序中改好从动端的MAC地址后就可以在主机端的遥控下进行动作。
  • RainbowONRainbowOFF键用于开机和关闭RGB灯的彩虹变换效果。

二次开发教程

  • 舵机初始化

每个控制舵机的程序,都需要对舵机进行初始化,初始化后才可以使用。

#include <SCServo.h>
SMS_STS st;
void setup(){
	Serial1.begin(1000000);  //串口初始化,如果使用ESP32等设备也可以选择自定义串口
	// Serial1.begin(1000000, SERIAL_8N1, RX, TX);  // 自定义串口
	st.pSerial = &Serial1;
	while(!Serial1) {}
}
  • 更改舵机ID

串联起来的舵机中,每个ID只能对应一个舵机,否则不能正常获取舵机反馈的信息。 当更改舵机ID时,尽量保证驱动板只与一个舵机相连接,ID会被永久保存在舵机中。

#include <SCServo.h>
SMS_STS st;
int ID_ChangeFrom = 1;   // 要更改ID的舵机原本ID,出厂默认为1
int ID_Changeto      = 2;   // 新的ID
void setup(){
  Serial1.begin(1000000);
  st.pSerial = &Serial1;
  while(!Serial1) {}

  st.unLockEprom(ID_ChangeFrom); //解锁EPROM-SAFE
  st.writeByte(ID_ChangeFrom, SMS_STS_ID, ID_Changeto);//更改ID
  st.LockEprom(ID_Changeto); // EPROM-SAFE上锁
}

void loop(){
}
  • Ping

用于测试某一舵机是否正常连接。

#include <SCServo.h>
SMS_STS st;
int TEST_ID = 3;  // 要测试的舵机ID
void setup()
{
  Serial.begin(115200);
  Serial1.begin(1000000, SERIAL_8N1, RX, TX); // 自定义串口
  st.pSerial = &Serial1;
  while(!Serial1) {}
}

void loop()
{
  int ID = st.Ping(TEST_ID);  //ping该ID的舵机,ping不通返回-1
  if(ID!=-1){
    Serial.print("Servo ID:");
    Serial.println(ID, DEC);
    delay(100);
  }else{
    Serial.println("Ping servo ID error!");
    delay(2000);
  }
}
  • 写位置

可用于控制单独舵机转动。

#include <SCServo.h>
SMS_STS st;
void setup()
{
  Serial1.begin(1000000); 
  st.pSerial = &Serial1;
  while(!Serial1) {}
}

void loop()
{
  st.WritePos(1, 1000, 1500, 50); // 控制ID为1的舵机以1500的速度转动到1000的位置,启停加速度50。
  delay(754);//[(P1-P0)/V]*1000+100

  st.WritePos(1, 20, 1500, 50); // 控制ID为1的舵机以1500的速度转动到20的位置,启停加速度50。
  delay(754);//[(P1-P0)/V]*1000+100
}
  • 同步写

可用于同时控制多个舵机(转动到不同的位置和不同的速度)。

#include <SCServo.h>
SMS_STS st;

// the uart used to control servos.
// GPIO 18 - S_RXD, GPIO 19 - S_TXD, as default.
#define S_RXD 18    //自定义串口的IO,如果不使用自定义串口下面的Serial1.begin(1000000, SERIAL_8N1, S_RXD, S_TXD);需要改为Serial1.begin(1000000);
#define S_TXD 19

byte ID[2];
s16 Position[2];
u16 Speed[2];
byte ACC[2];

void setup()
{
  Serial1.begin(1000000, SERIAL_8N1, S_RXD, S_TXD);
  st.pSerial = &Serial1;
  delay(1000);
  ID[0] = 1;   // 将需要控制的舵机ID保存到ID[]中。
  ID[1] = 2;   // 将需要控制的舵机ID保存到ID[]中。
  Speed[0] = 3400;  // 设置舵机速度,Speed[0]与上面的ID[0]的舵机对应。
  Speed[1] = 3400;  // 设置舵机速度,Speed[1]与上面的ID[1]的舵机对应。
  ACC[0] = 50;   // 设置启停加速度,数值越小加速度越小,最大可设置为150.
  ACC[1] = 50;
}

void loop()
{
  Position[0] = 3000;  // 设置ID[0](这里是ID为1的)舵机的目标位置,范围为0-4095
  Position[1] = 3000;  // 设置ID[1](这里是ID为2的)舵机的目标位置,范围为0-4095
  st.SyncWritePosEx(ID, 2, Position, Speed, ACC);//servo(ID1/ID2) speed=3400,acc=50,move to position=3000.
  delay(2000);

  Position[0] = 100;
  Position[1] = 100;
  st.SyncWritePosEx(ID, 2, Position, Speed, ACC);//servo(ID1/ID2) speed=3400,acc=50,move to position=100.
  delay(2000);
}
  • 获得舵机信息反馈
#define S_RXD 18
#define S_TXD 19
#include <SCServo.h>

SMS_STS sms_sts;

void setup()
{
  Serial1.begin(1000000, SERIAL_8N1, S_RXD, S_TXD);
  Serial.begin(115200);
  sms_sts.pSerial = &Serial1;
  delay(1000);
}

void loop()
{
  int Pos;
  int Speed;
  int Load;
  int Voltage;
  int Temper;
  int Move;
  int Current;
  if(sms_sts.FeedBack(1)!=-1){
    Pos = sms_sts.ReadPos(-1);
    Speed = sms_sts.ReadSpeed(-1);
    Load = sms_sts.ReadLoad(-1);
    Voltage = sms_sts.ReadVoltage(-1);
    Temper = sms_sts.ReadTemper(-1);
    Move = sms_sts.ReadMove(-1);
    Current = sms_sts.ReadCurrent(-1);
    Serial.print("Position:");
    Serial.println(Pos);
    Serial.print("Speed:");
    Serial.println(Speed);
    Serial.print("Load:");
    Serial.println(Load);
    Serial.print("Voltage:");
    Serial.println(Voltage);
    Serial.print("Temper:");
    Serial.println(Temper);
    Serial.print("Move:");
    Serial.println(Move);
    Serial.print("Current:");
    Serial.println(Current);
    delay(10);
  }else{
    Serial.println("FeedBack err");
    delay(500);
  }
  
  Pos = sms_sts.ReadPos(1);  // 获得位置反馈
  if(Pos!=-1){
    Serial.print("Servo position:");
    Serial.println(Pos, DEC);
    delay(10);
  }else{
    Serial.println("read position err");
    delay(500);
  }
  
  Voltage = sms_sts.ReadVoltage(1);   // 获得电压反馈
  if(Voltage!=-1){
	Serial.print("Servo Voltage:");
    Serial.println(Voltage, DEC);
    delay(10);
  }else{
    Serial.println("read Voltage err");
    delay(500);
  }
  
  Temper = sms_sts.ReadTemper(1);   // 获得温度反馈
  if(Temper!=-1){
    Serial.print("Servo temperature:");
    Serial.println(Temper, DEC);
    delay(10);
  }else{
    Serial.println("read temperature err");
    delay(500);    
  }

  Speed = sms_sts.ReadSpeed(1);   // 获得速度反馈
  if(Speed!=-1){
    Serial.print("Servo Speed:");
    Serial.println(Speed, DEC);
    delay(10);
  }else{
    Serial.println("read Speed err");
    delay(500);    
  }
  
  Load = sms_sts.ReadLoad(1);   // 获得负载反馈
  if(Load!=-1){
    Serial.print("Servo Load:");
    Serial.println(Load, DEC);
    delay(10);
  }else{
    Serial.println("read Load err");
    delay(500);    
  }
  
  Current = sms_sts.ReadCurrent(1);   // 获得电流反馈
  if(Current!=-1){
    Serial.print("Servo Current:");
    Serial.println(Current, DEC);
    delay(10);
  }else{
    Serial.println("read Current err");
    delay(500);    
  }

  Move = sms_sts.ReadMove(1);   // 获得运动状态反馈
  if(Move!=-1){
    Serial.print("Servo Move:");
    Serial.println(Move, DEC);
    delay(10);
  }else{
    Serial.println("read Move err");
    delay(500);    
  }
  Serial.println();
}