极客工坊

 找回密码
 注册

QQ登录

只需一步,快速开始

查看: 2372|回复: 0

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

[复制链接]
发表于 2023-5-10 08:29:09 | 显示全部楼层 |阅读模式
本帖最后由 机器谱 于 2023-5-10 08:29 编辑

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


2.  电子硬件
      本实验中采用了以下硬件:

主控板
Basra主控板(兼容Arduino Uno)
扩展板
Bigfish2.1扩展板
SH-ST步进电机扩展板
电池
11.1v动力电池
其它
步进电机、标准舵机、笔架

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


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),将参考例程下载到主控板中:
  1. /*------------------------------------------------------------------------------------

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

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

  4.            https://opensource.org/licenses/MIT

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

  6.   ------------------------------*/

  7. #include <Servo.h>


  8. /*

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

  10. * servo_pin:定义舵机引脚

  11. * stepper_count:定义步进电机数量

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

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

  14. */

  15. #define en 8

  16. #define servo_pin 11

  17. #define stepper_count 4

  18. #define stepperPulse_delay 850

  19. #define LINE_BUFFER_LENGTH 512


  20. /*

  21. * positive_x:定义正向 X 轴

  22. * positive_y:定义正向 Y 轴

  23. * negative_x:定义负向 X 轴

  24. * negative_y:定义负向 Y 轴

  25. */

  26. #define positive_x 0

  27. #define positive_y 1

  28. #define negative_x 2

  29. #define negative_y 3


  30. /*

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

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

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

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

  35. */

  36. int stepperDir_pin[4] = {5, 6, 7, 13};

  37. int stepperStp_pin[4] = {2, 3, 4, 12};


  38. Servo myServo;


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

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

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


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


  43. struct point {

  44.   float x;

  45.   float y;  

  46. };


  47. struct point actuatorPos;             // Current position of plothead


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

  49. float Xmax = 60;

  50. float Ymin = -60;

  51. float Ymax = 60;


  52. float Xpos = 0;                       

  53. float Ypos = 0;


  54. boolean verbose = true;


  55. void setup() {

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

  57.   myServo.attach(servo_pin);

  58.   myServo.write(penZup);

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

  60.   {

  61.     pinMode(stepperDir_pin[i], OUTPUT);

  62.     pinMode(stepperStp_pin[i], OUTPUT);  

  63.   }

  64.   pinMode(en, OUTPUT);

  65.   digitalWrite(en, LOW);

  66.   delay(1000);

  67. }


  68. void loop()

  69. {

  70.   delay(200);

  71.   char line[ LINE_BUFFER_LENGTH ];

  72.   char c;

  73.   int lineIndex;

  74.   bool lineIsComment, lineSemiColon;


  75.   lineIndex = 0;

  76.   lineSemiColon = false;

  77.   lineIsComment = false;


  78.   while (1) {


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

  80.     while ( Serial.available()>0 ) {

  81.       c = Serial.read();

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

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

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

  85.           if (verbose) {

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

  87.             Serial.println( line );

  88.           }

  89.           processIncomingLine( line, lineIndex );

  90.           lineIndex = 0;

  91.         }

  92.         else {

  93.           // Empty or comment line. Skip block.

  94.         }

  95.         lineIsComment = false;

  96.         lineSemiColon = false;

  97.         Serial.println("ok");   

  98.       }

  99.       else {

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

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

  102.         }

  103.         else {

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

  105.           }

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

  107.           }

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

  109.             lineIsComment = true;

  110.           }

  111.           else if ( c == ';' ) {

  112.             lineSemiColon = true;

  113.           }

  114.           else if ( lineIndex >= LINE_BUFFER_LENGTH-1 ) {

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

  116.             lineIsComment = false;

  117.             lineSemiColon = false;

  118.           }

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

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

  121.           }

  122.           else {

  123.             line[ lineIndex++ ] = c;

  124.           }

  125.         }

  126.       }

  127.     }

  128.   }



  129. }


  130. //串口数据处理函数

  131. void processIncomingLine( char* line, int charNB ) {

  132.   int currentIndex = 0;

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

  134.   struct point newPos;


  135.   newPos.x = 0.0;

  136.   newPos.y = 0.0;


  137.   //   Needs to interpret

  138.   //   G1 for moving

  139.   //   G4 P300 (wait 150ms)

  140.   //   G1 X60 Y30

  141.   //   G1 X30 Y50

  142.   //   M300 S30 (pen down)

  143.   //   M300 S50 (pen up)

  144.   //   Discard anything with a (

  145.   //   Discard any other command!


  146.   while( currentIndex < charNB ) {

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

  148.     case 'U':

  149.       penUp();

  150.       break;

  151.     case 'D':

  152.       penDown();

  153.       break;

  154.     case 'G':

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

  156.       //      buffer[1] = line[ currentIndex++ ];

  157.       //      buffer[2] = '\0';

  158.       buffer[1] = '\0';


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

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

  161.       case 1:

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

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

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

  165.         if ( indexY <= 0 ) {

  166.           newPos.x = atof( indexX + 1);

  167.           newPos.y = actuatorPos.y;

  168.         }

  169.         else if ( indexX <= 0 ) {

  170.           newPos.y = atof( indexY + 1);

  171.           newPos.x = actuatorPos.x;

  172.         }

  173.         else {

  174.           newPos.y = atof( indexY + 1);

  175.           indexY = '\0';

  176.           newPos.x = atof( indexX + 1);

  177.         }

  178.         drawLine(newPos.x, newPos.y );

  179.         //        Serial.println("ok");

  180.         actuatorPos.x = newPos.x;

  181.         actuatorPos.y = newPos.y;

  182.         break;

  183.       }

  184.       break;

  185.     case 'M':

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

  187.       buffer[1] = line[ currentIndex++ ];

  188.       buffer[2] = line[ currentIndex++ ];

  189.       buffer[3] = '\0';

  190.       switch ( atoi( buffer ) ){

  191.       case 300:

  192.         {

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

  194.           float Spos = atof( indexS + 1);

  195.           //          Serial.println("ok");

  196.           if (Spos == 30) {

  197.             penDown();

  198.           }

  199.           if (Spos == 50) {

  200.             penUp();

  201.           }

  202.           break;

  203.         }

  204.       case 114:                                // M114 - Repport position

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

  206.         Serial.print( actuatorPos.x );

  207.         Serial.print( "   -   Y = " );

  208.         Serial.println( actuatorPos.y );

  209.         break;

  210.       default:

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

  212.         Serial.println( buffer );

  213.       }

  214.     }

  215.   }

  216.    

  217. }


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

  219. void drawLine(float x1, float y1)

  220. {

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



  222.   if (x1 >= Xmax) {

  223.     x1 = Xmax;

  224.   }

  225.   if (x1 <= Xmin) {

  226.     x1 = Xmin;

  227.   }

  228.   if (y1 >= Ymax) {

  229.     y1 = Ymax;

  230.   }

  231.   if (y1 <= Ymin) {

  232.     y1 = Ymin;

  233.   }



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

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

  236.   float x0 = Xpos;

  237.   float y0 = Ypos;


  238.   Serial.print("X = ");

  239.   Serial.println(Xpos);

  240.   Serial.print("Y = ");

  241.   Serial.println(Ypos);



  242.   dx = abs(x1-x0);

  243.   dy = abs(y1-y0);

  244.   n = abs(dx+dy);


  245.   if(x1 >= x0)

  246.   {

  247.     k = y1 >= y0 ? 1:4;

  248.   }

  249.   else

  250.   {

  251.     k = y1 >= y0 ? 2:3;

  252.   }



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

  254.   {

  255.     if(f>=0)

  256.     {

  257.       switch(k)

  258.       {

  259.          case 1:

  260.          stepper_move(positive_x, 1);

  261.          f = f - dy;

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

  263.          break;

  264.          case 2:

  265.          stepper_move(negative_x, 1);

  266.          f = f - dy;

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

  268.          break;

  269.          case 3:

  270.          stepper_move(negative_x, 1);

  271.          f = f - dy;

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

  273.          break;

  274.          case 4:

  275.          stepper_move(positive_x, 1);

  276.          f = f - dy;

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

  278.          break;

  279.          default:break;

  280.       }

  281.     }

  282.     else

  283.     {

  284.       switch(k)

  285.       {

  286.         case 1:

  287.         stepper_move(positive_y, 1);

  288.         f = f + dx;

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

  290.         break;

  291.         case 2:

  292.         stepper_move(positive_y, 1);

  293.         f = f + dx;

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

  295.         break;

  296.         case 3:

  297.         stepper_move(negative_y, 1);

  298.         f = f + dx;

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

  300.         break;

  301.         case 4:

  302.         stepper_move(negative_y, 1);

  303.         f = f +dx;

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

  305.         break;

  306.         default:break;

  307.       }

  308.     }

  309.   }


  310.   Xpos = x1;

  311.   Ypos = y1;

  312. }


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

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

  315. {

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



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

  318.   {

  319.     //Serial.print(dir_value[i]);

  320.     //Serial.print(",");

  321.     digitalWrite(stepperDir_pin[i], dir_value[i]);

  322.   }

  323.   //Serial.println();



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

  325.   {

  326.     digitalWrite(stepperStp_pin[j], HIGH);

  327.   }  

  328.   delayMicroseconds(stepperPulse_delay);

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

  330.   {

  331.     digitalWrite(stepperStp_pin[j], LOW);

  332.   }

  333.   delayMicroseconds(stepperPulse_delay);

  334. }


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

  336. void stepper_move(int dir_xy, int steps)

  337. {

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

  339.   {

  340.     switch(dir_xy)

  341.     {

  342.       case 0:

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

  344.       break;

  345.       case 1:

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

  347.       break;

  348.       case 2:

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

  350.       break;

  351.       case 3:

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

  353.       break;

  354.       default:break;  

  355.     }  

  356.   }

  357. }


  358. //舵机抬笔函数

  359. void penUp()

  360. {

  361.   myServo.write(penZup);

  362. }


  363. //舵机落笔函数

  364. void penDown()

  365. {

  366.   myServo.write(penZdown);

  367. }
复制代码
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

回复

使用道具 举报

您需要登录后才可以回帖 登录 | 注册

本版积分规则 需要先绑定手机号

Archiver|联系我们|极客工坊

GMT+8, 2024-4-26 13:59 , Processed in 0.040134 second(s), 17 queries .

Powered by Discuz! X3.4 Licensed

Copyright © 2001-2021, Tencent Cloud.

快速回复 返回顶部 返回列表