嵌入之梦-圆梦小车开发 May 1st, 2011
今天看到一台嵌入之梦的小车,但是上电之后发了疯似的乱跑,所以刷之。但新车间却没有网络,没办法,自己一点一点试。。结果如下
CT1 接受pwm,控制速度 CT2 前进控制信号,高电位转动 CT3 后退控制信号,高电位转动
但是由于小车上的UNO与我的Ubuntu连接有问题,貌似只有Windows是好的,Mac OS有时也会出问题。所以最后车上改用了Mega 1280。
但是又发现一个问题,就是Arduino使用USB供电的时候很正常,然而,使用车上接出来的5V电源时,程序就会混乱,完全没有一点规律。猜测可能是由于电机转动导致整个系统的电压下降,无法提供足够的电压给Arduino的板子上。这大概也是之前uno不会发疯的原因。没办法,在小车上再接一块9V层叠式电池,作为Arduino的电源。最后终于行了。
后面程序的作用是往前走,遇到前方有物体是后退,打弯,然后继续往前,一个简单的壁障程序。没有用到速度控制。下面就是这个小车最后的样子,手机拍的,将就看吧
左侧照
右侧照
再来一张
http://v.youku.com/v_show/id_XMjYzMzY0NzA0.html用到的程序就是下面的
//Author: HE Qichen //Email: heqichen(a)gaishi.vicp.net //Website: http://gaishi.vicp.net //Date: 2011-5-1 int status; #define LEFT_SPEED 6 #define LEFT_FORWARD 7 #define LEFT_BACKWARD 8 #define RIGHT_SPEED 10 #define RIGHT_FORWARD 11 #define RIGHT_BACKWARD 12 #define ULTRASONIC_ECHO 3 #define ULTRASONIC_TRIG 4 #define NORMAL_SPEED 100 #define STOP_SPEED 0 void setup() { Serial.begin(9600); setupMove(); setupUltrasonic(); } void loop() { unsigned int d; moveForward(); d = readDistance(); Serial.println(d, DEC); if (d < 700) { moveBackward(); delay(500); turnLeft(); delay(200); } } void moveForward() { analogWrite(LEFT_SPEED, NORMAL_SPEED); digitalWrite(LEFT_BACKWARD, LOW); digitalWrite(LEFT_FORWARD, HIGH); analogWrite(RIGHT_SPEED, NORMAL_SPEED); digitalWrite(RIGHT_BACKWARD, LOW); digitalWrite(RIGHT_FORWARD, HIGH); } void moveBackward() { analogWrite(LEFT_SPEED, NORMAL_SPEED); digitalWrite(LEFT_BACKWARD, HIGH); digitalWrite(LEFT_FORWARD, LOW); analogWrite(RIGHT_SPEED, NORMAL_SPEED); digitalWrite(RIGHT_BACKWARD, HIGH); digitalWrite(RIGHT_FORWARD, LOW); } void turnLeft() { analogWrite(LEFT_SPEED, NORMAL_SPEED); digitalWrite(LEFT_BACKWARD, HIGH); digitalWrite(LEFT_FORWARD, LOW); analogWrite(RIGHT_SPEED, NORMAL_SPEED); digitalWrite(RIGHT_BACKWARD, LOW); digitalWrite(RIGHT_FORWARD, HIGH); } void turnRight() { analogWrite(LEFT_SPEED, NORMAL_SPEED); digitalWrite(LEFT_BACKWARD, LOW); digitalWrite(LEFT_FORWARD, HIGH); analogWrite(RIGHT_SPEED, NORMAL_SPEED); digitalWrite(RIGHT_BACKWARD, HIGH); digitalWrite(RIGHT_FORWARD, LOW); } void moveStop() { analogWrite(LEFT_SPEED, STOP_SPEED); digitalWrite(LEFT_BACKWARD, LOW); digitalWrite(LEFT_FORWARD, LOW); analogWrite(RIGHT_SPEED, STOP_SPEED); digitalWrite(RIGHT_BACKWARD, LOW); digitalWrite(RIGHT_FORWARD, LOW); } void setupMove() { pinMode(LEFT_SPEED, OUTPUT); pinMode(LEFT_FORWARD, OUTPUT); pinMode(LEFT_BACKWARD, OUTPUT); pinMode(RIGHT_SPEED, OUTPUT); pinMode(RIGHT_FORWARD, OUTPUT); pinMode(RIGHT_BACKWARD, OUTPUT); analogWrite(LEFT_SPEED, STOP_SPEED); digitalWrite(LEFT_FORWARD, LOW); digitalWrite(LEFT_BACKWARD, LOW); analogWrite(RIGHT_SPEED, STOP_SPEED); digitalWrite(RIGHT_FORWARD, LOW); digitalWrite(RIGHT_BACKWARD, LOW); } unsigned int readDistance() { int duration; digitalWrite(ULTRASONIC_TRIG, LOW); delayMicroseconds(2); digitalWrite(ULTRASONIC_TRIG, HIGH); delayMicroseconds(5); digitalWrite(ULTRASONIC_TRIG, LOW); // The same pin is used to read the signal from the PING))): a HIGH // pulse whose duration is the time (in microseconds) from the sending // of the ping to the reception of its echo off of an object. duration = pulseIn(ULTRASONIC_ECHO, HIGH); return duration; } void setupUltrasonic() { pinMode(ULTRASONIC_TRIG, OUTPUT); pinMode(ULTRASONIC_ECHO, INPUT); digitalWrite(ULTRASONIC_TRIG, LOW); }]]>
Leave a Reply