机器谱 发表于 2023-5-10 08:29:09

四福来轮全向底盘实现写字功能

本帖最后由 机器谱 于 2023-5-10 08:29 编辑

1. 功能说明
      本文示例将实现R310b样机四福来轮全向底盘绘制“探索者”空心字的功能。

https://28846868.s21i.faiusr.com/3/ABUIABADGAAgrL-joQYoy5XNtwEwsAQ4uwI.gif.webp
2.电子硬件
      本实验中采用了以下硬件:


主控板Basra主控板(兼容Arduino Uno)‍

扩展板Bigfish2.1扩展板‍

SH-ST步进电机扩展板
电池11.1v动力电池
其它
步进电机、标准舵机、笔架


电路连接:
       舵机连接在Bigfish扩展板的D11针脚上;4个步进电机与SH-ST扩展板的连接位置见下图:

https://28846868.s21i.faiusr.com/4/ABUIABAEGAAg3pLjoQYo3JDTywYw6Ak46Ak!600x600.png.webp
3. 功能实现
       在这里我们采用了一种算法,该算法的思路是:先建立一个平面坐标系,将我们所需要画的图形放置在该坐标系中,这样就可以确定该图形每个顶点的坐标,两个相邻的顶点之间确定一条直线,直线上各点坐标通过插补计算得到,然后画笔依次沿着这些坐标进行移动,完成绘制。所以在这个过程中,我们需要知道如何建立一个图形的坐标系,以及什么是插补计算。插补计算方法可参考 【R311】双轴XY平台-绘制斜向多边形 【https://www.robotway.com/h-col-201.html】 。
      本实验将基于四福来轮全向底盘利用processing软件处理gcode文件后,进行绘制文字“探索者”。gcode文件的生成可参考【R312】三轴XYZ平台-生成gcode文件【https://www.robotway.com/h-col-202.html】 。

3.1示例程序
编程环境:Arduino 1.8.19
下面给大家提供一个写字-探索者的参考例程(stepper_car_write.ino),将参考例程下载到主控板中:
/*------------------------------------------------------------------------------------

版权说明:Copyright 2023 Robottime(Beijing) Technology Co., Ltd. All Rights Reserved.

         Distributed under MIT license.See file LICENSE for detail or copy at

         https://opensource.org/licenses/MIT

         by 机器谱 2023-03-09 https://www.robotway.com/

------------------------------*/

#include <Servo.h>


/*

* en:定义步进电机使能引脚

* servo_pin:定义舵机引脚

* stepper_count:定义步进电机数量

* stepperPulse_delay:定义步进电机脉冲生成间隔

* LINE_BUFFER_LENGTH:定义串口接收数据长度

*/

#define en 8

#define servo_pin 11

#define stepper_count 4

#define stepperPulse_delay 850

#define LINE_BUFFER_LENGTH 512


/*

* positive_x:定义正向 X 轴

* positive_y:定义正向 Y 轴

* negative_x:定义负向 X 轴

* negative_y:定义负向 Y 轴

*/

#define positive_x 0

#define positive_y 1

#define negative_x 2

#define negative_y 3


/*

* stepperDir_pin:定义步进电机方向引脚数组

* stepperStp_pin:定义步进电机步进引脚数组

* dir: x: 5, y: 6, z: 7, a: 13

* stp: x: 2, y: 3, z: 4, a: 12

*/

int stepperDir_pin = {5, 6, 7, 13};

int stepperStp_pin = {2, 3, 4, 12};


Servo myServo;


const int stepsPerRevolution = 3200;   //定义步进电机每圈转动的步数,此处为16细分,每圈 3200 步

int penZup = 145;                      //定义舵机抬起角度

int penZdown = 150;                  //定义舵机放下角度


float LEAD = sqrt(2) * 58 * PI;      //定义步进电机转动 1 圈,小车前进的距离,单位 mm


struct point {

float x;

float y;

};


struct point actuatorPos;             // Current position of plothead


float Xmin = -60;                     //定义绘图范围,长120mm , 宽120mm

float Xmax = 60;

float Ymin = -60;

float Ymax = 60;


float Xpos = 0;                     

float Ypos = 0;


boolean verbose = true;


void setup() {

Serial.begin(9600);               //开启串口通信,波特率为 9600

myServo.attach(servo_pin);

myServo.write(penZup);

for(int i=0;i<stepper_count;i++)

{

    pinMode(stepperDir_pin, OUTPUT);

    pinMode(stepperStp_pin, OUTPUT);

}

pinMode(en, OUTPUT);

digitalWrite(en, LOW);

delay(1000);

}


void loop()

{

delay(200);

char line[ LINE_BUFFER_LENGTH ];

char c;

int lineIndex;

bool lineIsComment, lineSemiColon;


lineIndex = 0;

lineSemiColon = false;

lineIsComment = false;


while (1) {


    // 接受来自Grbl的串口数据

    while ( Serial.available()>0 ) {

      c = Serial.read();

      if (( c == '\n') || (c == '\r') ) {             // End of line reached

      if ( lineIndex > 0 ) {                        // Line is complete. Then execute!

          line[ lineIndex ] = '\0';                   // Terminate string

          if (verbose) {

            //Serial.print( "Received : ");

            Serial.println( line );

          }

          processIncomingLine( line, lineIndex );

          lineIndex = 0;

      }

      else {

          // Empty or comment line. Skip block.

      }

      lineIsComment = false;

      lineSemiColon = false;

      Serial.println("ok");   

      }

      else {

      if ( (lineIsComment) || (lineSemiColon) ) {   // Throw away all comment characters

          if ( c == ')' )   lineIsComment = false;   // End of comment. Resume line.

      }

      else {

          if ( c <= ' ' ) {                           // Throw away whitepace and control characters

          }

          else if ( c == '/' ) {                  // Block delete not supported. Ignore character.

          }

          else if ( c == '(' ) {                  // Enable comments flag and ignore all characters until ')' or EOL.

            lineIsComment = true;

          }

          else if ( c == ';' ) {

            lineSemiColon = true;

          }

          else if ( lineIndex >= LINE_BUFFER_LENGTH-1 ) {

            Serial.println( "ERROR - lineBuffer overflow" );

            lineIsComment = false;

            lineSemiColon = false;

          }

          else if ( c >= 'a' && c <= 'z' ) {      // Upcase lowercase

            line[ lineIndex++ ] = c-'a'+'A';

          }

          else {

            line[ lineIndex++ ] = c;

          }

      }

      }

    }

}



}


//串口数据处理函数

void processIncomingLine( char* line, int charNB ) {

int currentIndex = 0;

char buffer[ 64 ];                                 // Hope that 64 is enough for 1 parameter

struct point newPos;


newPos.x = 0.0;

newPos.y = 0.0;


//   Needs to interpret

//   G1 for moving

//   G4 P300 (wait 150ms)

//   G1 X60 Y30

//   G1 X30 Y50

//   M300 S30 (pen down)

//   M300 S50 (pen up)

//   Discard anything with a (

//   Discard any other command!


while( currentIndex < charNB ) {

    switch ( line[ currentIndex++ ] ) {            // Select command, if any

    case 'U':

      penUp();

      break;

    case 'D':

      penDown();

      break;

    case 'G':

      buffer = line[ currentIndex++ ];          // /!\ Dirty - Only works with 2 digit commands

      //      buffer = line[ currentIndex++ ];

      //      buffer = '\0';

      buffer = '\0';


      switch ( atoi( buffer ) ){                   // Select G command

      case 0:                                 // G00 & G01 - Movement or fast movement. Same here

      case 1:

      // /!\ Dirty - Suppose that X is before Y

      char* indexX = strchr( line+currentIndex, 'X' );   // Get X/Y position in the string (if any)

      char* indexY = strchr( line+currentIndex, 'Y' );

      if ( indexY <= 0 ) {

          newPos.x = atof( indexX + 1);

          newPos.y = actuatorPos.y;

      }

      else if ( indexX <= 0 ) {

          newPos.y = atof( indexY + 1);

          newPos.x = actuatorPos.x;

      }

      else {

          newPos.y = atof( indexY + 1);

          indexY = '\0';

          newPos.x = atof( indexX + 1);

      }

      drawLine(newPos.x, newPos.y );

      //      Serial.println("ok");

      actuatorPos.x = newPos.x;

      actuatorPos.y = newPos.y;

      break;

      }

      break;

    case 'M':

      buffer = line[ currentIndex++ ];      // /!\ Dirty - Only works with 3 digit commands

      buffer = line[ currentIndex++ ];

      buffer = line[ currentIndex++ ];

      buffer = '\0';

      switch ( atoi( buffer ) ){

      case 300:

      {

          char* indexS = strchr( line+currentIndex, 'S' );

          float Spos = atof( indexS + 1);

          //          Serial.println("ok");

          if (Spos == 30) {

            penDown();

          }

          if (Spos == 50) {

            penUp();

          }

          break;

      }

      case 114:                              // M114 - Repport position

      Serial.print( "Absolute position : X = " );

      Serial.print( actuatorPos.x );

      Serial.print( "   -   Y = " );

      Serial.println( actuatorPos.y );

      break;

      default:

      Serial.print( "Command not recognized : M");

      Serial.println( buffer );

      }

    }

}

   

}


//直线插补函数,参数为点坐标值

void drawLine(float x1, float y1)

{

int dx, dy, n, k, i, f, stepInc;



if (x1 >= Xmax) {

    x1 = Xmax;

}

if (x1 <= Xmin) {

    x1 = Xmin;

}

if (y1 >= Ymax) {

    y1 = Ymax;

}

if (y1 <= Ymin) {

    y1 = Ymin;

}



x1 = (int)(x1/LEAD*stepsPerRevolution);

y1 = (int)(y1/LEAD*stepsPerRevolution);

float x0 = Xpos;

float y0 = Ypos;


Serial.print("X = ");

Serial.println(Xpos);

Serial.print("Y = ");

Serial.println(Ypos);



dx = abs(x1-x0);

dy = abs(y1-y0);

n = abs(dx+dy);


if(x1 >= x0)

{

    k = y1 >= y0 ? 1:4;

}

else

{

    k = y1 >= y0 ? 2:3;

}



for(i=0,f=0;i<n;i+=1)

{

    if(f>=0)

    {

      switch(k)

      {

         case 1:

         stepper_move(positive_x, 1);

         f = f - dy;

         //Serial.println("+x");

         break;

         case 2:

         stepper_move(negative_x, 1);

         f = f - dy;

         //Serial.println("-x");

         break;

         case 3:

         stepper_move(negative_x, 1);

         f = f - dy;

         //Serial.println("-x");

         break;

         case 4:

         stepper_move(positive_x, 1);

         f = f - dy;

         //Serial.println("+x");

         break;

         default:break;

      }

    }

    else

    {

      switch(k)

      {

      case 1:

      stepper_move(positive_y, 1);

      f = f + dx;

      //Serial.println("+y");

      break;

      case 2:

      stepper_move(positive_y, 1);

      f = f + dx;

      //Serial.println("+y");

      break;

      case 3:

      stepper_move(negative_y, 1);

      f = f + dx;

      //Serial.println("-y");

      break;

      case 4:

      stepper_move(negative_y, 1);

      f = f +dx;

      //Serial.println("-y");

      break;

      default:break;

      }

    }

}


Xpos = x1;

Ypos = y1;

}


//小车行进方向控制函数

void stepper_dir(int positiveDir_x, int positiveDir_y, int negativeDir_x, int negativeDir_y)

{

int dir_value[] = {positiveDir_x, positiveDir_y, negativeDir_x, negativeDir_y};



for(int i=0;i<stepper_count;i++)

{

    //Serial.print(dir_value);

    //Serial.print(",");

    digitalWrite(stepperDir_pin, dir_value);

}

//Serial.println();



for(int j=0;j<stepper_count;j++)

{

    digitalWrite(stepperStp_pin, HIGH);

}

delayMicroseconds(stepperPulse_delay);

for(int j=0;j<stepper_count;j++)

{

    digitalWrite(stepperStp_pin, LOW);

}

delayMicroseconds(stepperPulse_delay);

}


//步进电机转动函数,参数 dir_xy:步进电机转动方向,steps:步进电机转动步数

void stepper_move(int dir_xy, int steps)

{

for(int i=0;i<abs(steps);i++)

{

    switch(dir_xy)

    {

      case 0:

      stepper_dir(1, 1, 0, 0);   // X 正方向

      break;

      case 1:

      stepper_dir(1, 0, 1, 0);   // Y 正方向

      break;

      case 2:

      stepper_dir(0, 0, 1, 1);   // X 负方向

      break;

      case 3:

      stepper_dir(0, 1, 0, 1);   // Y 负方向

      break;

      default:break;

    }

}

}


//舵机抬笔函数

void penUp()

{

myServo.write(penZup);

}


//舵机落笔函数

void penDown()

{

myServo.write(penZdown);

}3.2 图形绘制
       接下来我们将通过上位机的processing软件发送生成文字“探索者”的 gcode文件给四福来轮全向底盘进行图形绘制。具体操作步骤可参考【R312】三轴XYZ平台-绘制空心字【https://www.robotway.com/h-col-202.html】 。

4. 资料下载
资料内容:
​①写字-例程源代码
​②软件资料包
​资料下载地址:https://www.robotway.com/h-col-198.html

想了解更多机器人开源项目资料请关注 机器谱网站 https://www.robotway.com
页: [1]
查看完整版本: 四福来轮全向底盘实现写字功能