小R科技-WIFI机器人网·机器人创意工作室

 找回密码
 立即注册
查看: 8444|回复: 3

我的arduino两轮小车下位机

[复制链接]
发表于 2013-7-21 16:38:06 | 显示全部楼层 |阅读模式
本帖最后由 u70253a 于 2013-8-8 22:06 编辑

云台两个舵机挂上去了,但是安卓1.05的云台控制总怪怪的,估计是上位机发送太快超过我的程序处理速度,先放在1 2号控制条就没事了下行协议差速度档位,上行协议就再等等吧,没模组没得玩,买的底座也小了塞不下

  1. /*
  2. * 云台伺服电机设定
  3. * 现有两个伺服电机做为云台
  4. * 因应云台两侧及后面有东西会卡到,所以有预设转动极限角度
  5. */
  6. #include <Servo.h>
  7. Servo horiServo; // 云台水平伺服电机
  8. const static int HORIZONTAL_SERVO_PIN = 9; // 接到PIN 9
  9. const static int MAX_HORIZONTAL_ANGLE = 120; // 最大旋转角度 120
  10. const static int MIN_HORIZONTAL_ANGLE = 40;  // 最小旋转角度 40
  11. const static int CENTER_HORIZONTAL_ANGLE = 80; // 初始角度 80

  12. Servo vertServo; // Vertical camera servo
  13. const static int VERTICAL_SERVO_PIN = 10; // 接到PIN 10
  14. const static int MAX_VERTICAL_ANGLE = 130; // 最大仰角 130
  15. const static int MIN_VERTICAL_ANGLE = 40; // 最小俯角 40
  16. const static int CENTER_VERTICAL_ANGLE = 85; // 初始角度 85

  17. /*
  18. * 车轮直流电机设定
  19. * 一般L298模块一个电机有三个输入,ENA、IN1、IN2,这模块只用EN与IN2,IN2直接反转進IN1
  20. */
  21. const static int RIGHT_DIRECT_PIN = 7;
  22. const static int RIGHT_POWER_PIN = 6; // Pin 5 PWM
  23. const static int LEFT_DIRECT_PIN = 4;
  24. const static int LEFT_POWER_PIN = 5; // Pin 6 PWM

  25. /*
  26. * 车灯设定
  27. */
  28. const static int HEADLIGHT_PIN = 13; // 车灯接到PIN 13

  29. /*
  30. * 小车控制程序
  31. * 输入0时电机不转,正负值控制电机正反转.
  32. */
  33. static void carMove(int leftPower = 0, int rightPower = 0){
  34.   boolean leftDirect = HIGH,rightDirect = HIGH;
  35.   
  36.   if(leftPower < 0) { // 左轮负值,取正值并反转电机方向
  37.     leftPower *= -1;
  38.     leftDirect = LOW;
  39.   }
  40.   if(rightPower < 0) { // 右轮负值,取正值并反转右轮电机方向
  41.     rightPower *= -1;
  42.     rightDirect = LOW;
  43.   }
  44.   
  45.   digitalWrite(RIGHT_DIRECT_PIN, rightDirect);
  46.   digitalWrite(LEFT_DIRECT_PIN, leftDirect);
  47.   analogWrite(RIGHT_POWER_PIN, rightPower);
  48.   analogWrite(LEFT_POWER_PIN, leftPower);
  49. }

  50. /*
  51. * 解译通讯协议
  52. * 格式: FFxxxxxxFF,已定义内容见论坛
  53. * http://www.wifi-robots.com/forum.php?mod=viewthread&tid=3546
  54. */
  55. void decodeCommand(int *buffer){

  56.   Serial.print("Command: ");
  57.   Serial.print(buffer[0],HEX);
  58.   Serial.print(buffer[1],HEX);
  59.   Serial.println(buffer[2],HEX);

  60.   /*
  61.    * FF00xxxxFF 控制小车移动
  62.    * 输入1: 移动方向 2:未使用
  63.    */
  64.   if(buffer[0] == 0x00){
  65.     switch(buffer[1]){
  66.       case 0x00: // FF0000xxFF: 停车
  67.         carMove(0,0); return;
  68.       case 0x01: // FF0001xxFF: 前进
  69.         carMove(200,200); return;
  70.       case 0x02: // FF0002xxFF: 后退
  71.         carMove(-150,-150); return;
  72.       case 0x03: // FF0003xxFF: 左旋转
  73.         carMove(-150,150); return;
  74.       case 0x04: // FF0004xxFF: 右旋转
  75.         carMove(150,-150); return;
  76.       case 0x05: // FF0005xxFF: 左前
  77.         carMove(150,200); return;
  78.       case 0x06: // FF0006xxFF: 左后
  79.         carMove(-100,-150); return;
  80.       case 0x07: // FF0007xxFF: 右前
  81.         carMove(200,150); return;
  82.       case 0x08: // FF0008xxFF: 右后
  83.         carMove(-150,-100); return;
  84.       }
  85.   }
  86.   
  87.   /*
  88.    * FF01xxxxFF 控制伺服电机
  89.    * 传入1:电机编号 2:转动角度
  90.    * 上位机预设角度0至180,在此处直接转换为限制角度
  91.    */
  92.   else if(buffer[0] == 0x01){
  93.     switch(buffer[1]){
  94.       case 0x01: // FF0101xxFF: 一号电机: 云台水平
  95.         if(buffer[2] <= 90)
  96.           horiServo.write(map(buffer[2],0,90,MIN_HORIZONTAL_ANGLE,CENTER_HORIZONTAL_ANGLE));
  97.         else
  98.           horiServo.write(map(buffer[2],90,180,CENTER_HORIZONTAL_ANGLE,MAX_HORIZONTAL_ANGLE));
  99.         break;
  100.       case 0x02: // FF0102xxFF: 八号电机: 云台垂直
  101.         if(buffer[2] <= 90)
  102.           vertServo.write(map(buffer[2],0,90,MIN_VERTICAL_ANGLE,CENTER_VERTICAL_ANGLE));
  103.         else
  104.           vertServo.write(map(buffer[2],90,180,CENTER_VERTICAL_ANGLE,MAX_VERTICAL_ANGLE));
  105.         break;
  106.     }
  107.   }
  108.   
  109.   /*
  110.    * FF04xxxxFF 控制车灯
  111.    */
  112.   else if(buffer[0] == 0x04){
  113.     switch(buffer[1]){
  114.       case 0x00: // FF0400xxFF: 关灯
  115.         digitalWrite(HEADLIGHT_PIN,LOW); break;
  116.       case 0x01: // FF0401xxFF: 开灯
  117.         digitalWrite(HEADLIGHT_PIN,HIGH); break;
  118.     }
  119.   }
  120. }

  121. /*
  122. * 初始设定
  123. */
  124. void setup(){
  125.   Serial.begin(9600); // 不可删除,用于读取外部指令
  126.   
  127.   pinMode(RIGHT_DIRECT_PIN,OUTPUT);
  128.   pinMode(RIGHT_POWER_PIN,OUTPUT);
  129.   pinMode(LEFT_DIRECT_PIN,OUTPUT);
  130.   pinMode(LEFT_POWER_PIN,OUTPUT);
  131.   
  132.   pinMode(HEADLIGHT_PIN,OUTPUT);
  133.   digitalWrite(HEADLIGHT_PIN,LOW); // 先关灯
  134.   
  135.   vertServo.attach(VERTICAL_SERVO_PIN);
  136.   vertServo.write(CENTER_VERTICAL_ANGLE); // 云台垂直定位
  137.   horiServo.attach(HORIZONTAL_SERVO_PIN);
  138.   horiServo.write(CENTER_HORIZONTAL_ANGLE); // 云台水平定位

  139. }

  140. /*
  141. * 读取指令
  142. */
  143. void loop()
  144. {
  145.   timer.run();
  146.   
  147.   int readValue;
  148.   boolean waitCommandHead = true;  
  149.   int commandIndex=0; // 快取位置指标
  150.   int buffer[3]; // 输入协议快取,扣除包头包尾仅3字节

  151.   while(true) {
  152.     readValue = Serial.read(); // 读输入
  153.     if(readValue != -1) { // -1表示无输入
  154.       if(waitCommandHead){ // 等待协议包头
  155.         if(readValue == 0xff) waitCommandHead = false; // 读取协议包头
  156.       }
  157.       else { // 读取协议中
  158.         if(readValue == 0xff){ // 读取到协议包尾
  159.           waitCommandHead = true; // 结束读取协议,回到等待协议包头
  160.           decodeCommand(buffer); // 解码协议
  161.           commandIndex = 0; //  清除快取位置指标
  162.         }
  163.         else if(commandIndex < 3) buffer[commandIndex++] = readValue; // 推入快取,位置加一
  164.       }
  165.     }
  166.   }
  167. }
复制代码





回复

使用道具 举报

发表于 2013-7-30 20:13:59 | 显示全部楼层
呵呵,很多车友让我把详细的注释写上去,你帮我完成了。注释写的很清楚,赞一个。
回复 支持 反对

使用道具 举报

发表于 2013-9-12 14:32:50 | 显示全部楼层
参考你的代码,改进了下,,成功运行,,,,赞一个啊。。。
回复 支持 反对

使用道具 举报

发表于 2013-12-10 15:15:18 | 显示全部楼层
  timer.run();
请问这一句的作用是?
回复 支持 反对

使用道具 举报

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

本版积分规则

关闭

新品特惠推荐上一条 /2 下一条

QQ|QQ技术咨询1|QQ技术咨询2|商务合作微信1:xiaorgeek001|商务合作微信2:XiaoRGEEK|诚聘英才|Archiver|手机版|小R科技-WIFI机器人网·机器人创意工作室 ( 粤ICP备15000788号-6 )

GMT+8, 2024-11-22 23:49 , Processed in 1.210115 second(s), 18 queries .

Powered by XiaoR GEEK X3.4

© 2014-2021 XiaoR GEEK

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