3/7/14
Tuned Turns for line following:
----------------------------------------------------------
int sensorPin0 = A0; // Middle Sensor
int sensorVal0 = 0;
int sensorPin1 = A1; // Left Sensor
int sensorVal1 = 0;
int sensorPin2 = A2; // Right Sensor
int sensorVal2 = 0;
// Pin Assignments //
// Don't change these! These pins are statically defined by shield layout
const byte PWMA = 3; // PWM control (speed) for motor A
const byte PWMB = 11; // PWM control (speed) for motor B
const byte DIRA = 12; // Direction control for motor A
const byte DIRB = 13; // Direction control for motor B
const byte pinX = 1;
void setup() {
setupArdumoto(); // Set all pins as outputs
setupSensors(); // Sets all sensor analog pins as inputs
Serial.begin(9600); // Set up Serial Library at 9600 bps
}
void loop() {
sensorVal0=analogRead(sensorPin0);
sensorVal1=analogRead(sensorPin1);
sensorVal2=analogRead(sensorPin2);
Serial.println(sensorVal0);
if (sensorVal0 >= 400 && sensorVal0 <= 2000) {
//middle sensor you go straight
analogWrite(PWMA,50);
digitalWrite(DIRA,0);
analogWrite(PWMB,50);
digitalWrite(DIRB,0);
}
else if (sensorVal1 >= 400 && sensorVal1 <= 2000) {
//left sensor you go straight
//Motor B is to much
analogWrite(PWMA,0);
digitalWrite(DIRA,0);
analogWrite(PWMB,40);
digitalWrite(DIRB,0);
}
else if (sensorVal2 >= 400 && sensorVal2 <= 2000) {
//left sensor you go straight
//Motor A is to much to the right
analogWrite(PWMA,40);
digitalWrite(DIRA,0);
analogWrite(PWMB,0);
digitalWrite(DIRB,0);
}
else {
analogWrite(PWMA,0);
digitalWrite(DIRA,0);
analogWrite(PWMB,0);
digitalWrite(DIRB,0);
}
}
void setupArdumoto() {
pinMode(PWMA, OUTPUT);
pinMode(PWMB, OUTPUT);
pinMode(DIRA, OUTPUT);
pinMode(DIRB, OUTPUT);
digitalWrite(PWMA, LOW);
digitalWrite(PWMB, LOW);
digitalWrite(DIRA, LOW);
digitalWrite(DIRB, LOW);
}
void setupSensors() {
pinMode(sensorPin0,INPUT); // Sets sensor pin to input
pinMode(sensorPin1,INPUT); // Sets sensor pin to input
pinMode(sensorPin2,INPUT); // Sets sensor pin to input
}
-------------------------------------------------------------------------------------
3/7/14
PID Control
//Pin Assignments//
//Don't change these. These pins are statically defined by shield layout//
const byte PWMA = 3; //PWM control (speed) for motor A//
const byte PWMB = 11; //PWM control (speed) for motor B//
const byte DIRA = 12; //Direction control for motor A//
const byte DIRB = 13; //Direction control for motor B//
int sensorPin0 = A0; //Middle Sensor//
int sensorVal0 = 0;
int sensorPin1 = A1; //Left Sensor1//
int sensorVal1 = 0;
int sensorPin2 = A2; //Right Sensor1//
int sensorVal2 = 0;
int sensorPin3 = A3; //Left Sensor2//
int sensorVal3 = 0;
int sensorPin4 = A4; //Right Sensor2//
int sensorVal4 = 0;
int sensorVal = 0;
int e = 0; int ep = 0; int epp = 0;
int u = 0; int up = 0;
float Kd = 0; float Kp = 0.05; float Ki = 0; long T = 1;
int A[2] ={0, 0};
int offset = 3;
void setup()
{
setupArdumoto(); // Set all motor pins as outputs
setupSensors(); // Sets all sensor analog pins as inputs
Serial.begin(9600); // Set up Serial Library at 9600 bps
}
void loop() {
sensorVal0 = readSensor(sensorPin0);
sensorVal1 = readSensor(sensorPin1);
sensorVal2 = readSensor(sensorPin2);
sensorVal3 = readSensor(sensorPin3);
sensorVal4 = readSensor(sensorPin4);
//printSensors();
//digitilize sensors.//
if(sensorVal0>200) { sensorVal0 = 1000;}
else {sensorVal0 = 0;}
if(sensorVal1>200) { sensorVal1 = 1000;}
else {sensorVal1 = 0;}
if(sensorVal2>200) { sensorVal2 = 1000;}
else {sensorVal2 = 0;}
if(sensorVal3>200) { sensorVal3 = 1000;}
else {sensorVal3 = 0;}
if(sensorVal4>200) { sensorVal4 = 1000;}
else {sensorVal4 = 0;}
//printSensors();
//printVariables();
e = calcError( sensorVal1, sensorVal2, sensorVal3, sensorVal4 );
u = updateU(up, e, ep, epp, Kd, Kp, Ki, T);
up = u; epp = ep; ep = e;
//delay(T*1000);
if( u < -100 ) { u = -100; }
else if( u > 100 ) { u = 100; }
else { u = u; }
if(sensorVal0 = 0)
{
stopRobot();
if(u<0){turnRight2(u,A);}
else if(u>0){turnLeft2(u,A);}
else{}
}
else if(sensorVal0 = 1000)
{
if(u<-25 && u>-75){turnRight(u,A);}
else if(u<-75){turnRight1(u,A);}
else if(u>25 && u<75){turnLeft(u,A);}
else if(u>75){turnLeft1(u,A);}
else{driveStraight(offset,A);}
}
}
void setupArdumoto()
{
pinMode(PWMA, OUTPUT);
pinMode(PWMB, OUTPUT);
pinMode(DIRA, OUTPUT);
pinMode(DIRB, OUTPUT);
digitalWrite(PWMA, LOW);
digitalWrite(PWMB, LOW);
digitalWrite(DIRA, LOW);
digitalWrite(DIRB, LOW);
}
void setupSensors()
{
pinMode(sensorPin0,INPUT);
pinMode(sensorPin1,INPUT);
pinMode(sensorPin2,INPUT);
pinMode(sensorPin3,INPUT);
pinMode(sensorPin4,INPUT);
}
int readSensor ( int sensorPin )
{
sensorVal = analogRead(sensorPin);
return sensorVal;
}
void printSensors()
{
Serial.print("sensorVal0 \t\t");
Serial.println(sensorVal0);
Serial.print("sensorVal1 \t\t");
Serial.println(sensorVal1);
Serial.print("sensorVal2 \t\t");
Serial.println(sensorVal2);
Serial.print("sensorVal3 \t\t");
Serial.println(sensorVal3);
Serial.print("sensorVal4 \t\t");
Serial.println(sensorVal4);
}
void printVariables()
{
Serial.print("e \t\t\t");
Serial.println(e);
Serial.print("u \t\t\t");
Serial.println(u);
Serial.print("\n");
Serial.print("A \t\t\t");
Serial.println(A[0]);
Serial.print("\n");
Serial.print("B \t\t\t");
Serial.println(A[1]);
Serial.print("\n");
}
int calcError( int sensorVal1, int sensorVal2, int sensorVal3, int sensorVal4)
{
e = int(sensorVal1 + sensorVal2*(-1) + sensorVal3 + sensorVal4*(-1));
return e;
}
int updateU( int up, int e, int ep, int epp, float Kd, float Kp, float Ki, int T )
{
u = Kp*e;
//u = up + ((Kd/T) + (Kp) + (Ki*T))*e - (((2*Kd)/T) + (Kp))*ep + (Kd/T)*epp;
return u;
}
// a dark object relflect less light than a bright object.
// or a dark object absorbs more light than a bright object, this is the
// the fundamental logic behind a line sensing robot.
// we want to make a sensor that detects the
// diference between bright object and a dark object
// or say distingueshes a black line
// from a white surface.
void driveStraight(int offset,int A[2])
{
A[0] = 35+offset;
A[1] = 35-offset;
analogWrite(PWMA,35 + offset);
digitalWrite(DIRA,0);
analogWrite(PWMB,35 - offset);
digitalWrite(DIRB,0);
}
void turnRight(int u,int A[2])
{
A[0] = 35;
A[1] = 35 - 0.5*u;
analogWrite(PWMA,35);
digitalWrite(DIRA,0);
analogWrite(PWMB,35-0.5*u);
digitalWrite(DIRB,0);
delay(50);
// return A[];
}
void turnLeft(int u,int A[2])
{
A[0] = 35 + 0.5*u;
A[1] = 35;
analogWrite(PWMA,35+0.5*u);
digitalWrite(DIRA,0);
analogWrite(PWMB,35);
digitalWrite(DIRB,0);
delay(50);
}
void turnRight1(int u,int A[2])
{
A[0] = 35;
A[1] = 35 - 0.5*u;
analogWrite(PWMA,35);
digitalWrite(DIRA,0);
analogWrite(PWMB,35-0.5*u);
digitalWrite(DIRB,0);
delay(50);
// return A[];
}
void turnLeft1(int u,int A[2])
{
A[0] = 35 + 0.5*u;
A[1] = 35;
analogWrite(PWMA,35+0.5*u);
digitalWrite(DIRA,0);
analogWrite(PWMB,35);
digitalWrite(DIRB,0);
delay(30);
}
void turnRight2(int u,int A[2])
{
A[0] = 35;
A[1] = 35 - 0.75*u;
analogWrite(PWMA,35);
digitalWrite(DIRA,0);
analogWrite(PWMB,35-0.75*u);
digitalWrite(DIRB,0);
delay(50);
// return A[];
}
void turnLeft2(int u,int A[2])
{
A[0] = 35 + 0.75*u;
A[1] = 35;
analogWrite(PWMA,35+0.75*u);
digitalWrite(DIRA,0);
analogWrite(PWMB,40);
digitalWrite(DIRB,0);
delay(50);
}
void stopRobot()
{
analogWrite(PWMA,50);
digitalWrite(DIRA,1);
analogWrite(PWMB,50);
digitalWrite(DIRB,1);
delay(50);
}
-----------------------------------------------
http://robotix.in/tutorials/category/avr/pid
Content
“PID” is an acronym for Proportional Integral Derivative. As the name suggests, these terms describe three basic mathematical functions applied to the error (error = SetVal - SensorVal, where SetVal is the target value and SensorVal is the present input value obtained from the sensor ). Main task of the PID controller is to minimize the error of whatever we are controlling. It takes in input, calculates the deviation from the intended behaviour and accordingly adjusts the output so that deviation from the intended behaviour is minimized and greater accuracy obtained.
Line following seems to be accurate when carried out at lower speeds. As we start increasing the speed of the robot, it wobbles a lot and is often found getting off track.
Hence some kind of control on the robot is required that would enable us to make it follow the line efficiently at higher speeds. This is where PID controller shines.
In order to implement line following one can basically start with just three sensors which are so spaced on the robot that-
If the centre sensor detects the line the robot steers forward
If the left sensor detects the line the robot steers right
If the right sensor detects the line the robot steers left.
This algorithm would make the robot follow the line, however, we would need to compromise with its speed to follow the line efficiently.
We can increase the efficiency of line following by increasing the number of sensors, say 5.
Here the possible combinations represent exact position like-
00100
00001
10000
On the centre of the line
To the left of the line
To the right of the line
There will be other possible combinations such as 00110 and 00011 that can provide us data on how far to the right is the robot from the centre of the line(same follows for left). Further to implement better line following we need to keep track of how long is the robot not centered on the line and how fast does it change its position from the centre.This is exactly what we can achieve using “PID” control.The data obtained from the array of sensors would then be put into utmost use and line following process would be much more smoother, faster and efficient at greater speeds.
PID is all about improving our control on the robot.
The idea behind PID control is that we set a value that we want maintained, either speed of a motor or reading from a sensor. We then take the present readings as input and compare them to the setpoint. From this an error value can be calculated, i.e, (error = setpoint - actual reading). This error value is then used to calculate how much to alter the output by to make the actual reading closer to the setpoint.
Terminology:
The basic terminology that one would require to understand PID are:
Error - The error is the amount at which a device isn’t doing something right. For example, suppose the robot is located at x=5 but it should be at x=7, then the error is 2.
Proportional (P) - The proportional term is directly proportional to the error at present.
Integral (I) - The integral term depends on the cumulative error made over a period of time (t).
Derivative (D) - The derivative term depends rate of change of error.
Constant (factor)- Each term (P, I, D) will need to be tweaked in the code. Hence,they are included in the code by multiplying with respective constants.
P-Factor (Kp) - A constant value used to increase or decrease the impact of Proportional
I-Factor (Ki) - A constant value used to increase or decrease the impact of Integral
D-Factor (Kd) - A constant value used to increase or decrease the impact of Derivative
Error measurement: In order to measure the error from the set position, i.e. the centre we can use the weighted values method. Suppose we are using a 5 sensor array to take the position input of the robot. The input obtained can be weighted depending on the possible combinations of input. The weight values assigned would be such that the error in position is defined both exactly and relatively.
The full range of weighted values is shown below. We assign a numerical value to each one.
The range of possible values for the measured position is -5 to 5. We will measure the position of the robot over the line several times a second and use these value to determine Proportional, Integral and Derivative values.
PID formula:
So what do we do with the error value to calculate how much the output be altered by? We would need to simply add the error value to the output to adjust the robot’s motion. And this would work, and is known as proportional control (the P in PID). It is often necessary to scale the error value before adding it to the output by using the constant(Kp).
Proportional:
Difference = (Target Position) - (Measured Position)
Proportional = Kp*(Difference)
This approach would work, but it is found that if we want a quick response time, by using a large constant, or if the error is very large, the output may overshoot from the set value. Hence the change in output may turn out to be unpredictable and oscillating. In order to control this, derivative expression comes to limelight.
Derivative:
Derivative provides us the rate of change of error. This would help us know how quickly does the error change from time to time and accordingly we can set the output.
Rate of Change = ((Difference) – (Previous Difference))/time interval
Derivative= Kd *(Rate of Change)
The time interval can be obtained by using the timer of microcontroller.
The integral improves steady state performance, i.e. when the output is steady how far away is it from the setpoint. By adding together all previous errors it is possible to monitor if there are accumulating errors. For example- if the position is slightly to the right all the time, the error will always be positive so the sum of the errors will get bigger, the inverse is true if position is always to the left. This can be monitored and used to further improve the accuracy of line following.
Integral:
Integral = Integral + Difference
Integral = Ki*(Integral)
Summarizing “PID” control-
Therefore, Control value used to adjust the robot's motion=
(Proportional) + (Integral) + (Derivative)
Tuning:
PID implementation would prove to be useless rather more troublesome unless the constant values are tuned depending on the platform the robot is intended to run on. The physical environment in which the robot is being operated vary significantly and cannot be modelled mathematically. It includes ground friction, motor inductance, center of mass, etc. Hence, the constants are just guessed numbers obtained by trial and error. Their best fit value varies from robot to robot and also the circumstance in which it is being run. The aim is to set the constants such that the settling time is minimum and there is no overshoot.
There are some basic guidelines that will help reduce the tuning effort.
Start with Kp, Ki and Kd equalling 0 and work with Kp first. Try setting Kp to a value of 1 and observe the robot. The goal is to get the robot to follow the line even if it is very wobbly. If the robot overshoots and loses the line, reduce the Kp value. If the robot cannot navigate a turn or seems sluggish, increase the Kp value.
Once the robot is able to somewhat follow the line, assign a value of 1 to Kd (skip Ki for the moment). Try increasing this value until you see lesser amount of wobbling.
Once the robot is fairly stable at following the line, assign a value of 0.5 to 1.0 to Ki. If the Ki value is too high, the robot will jerk left and right quickly. If it is too low, you won't see any perceivable difference. Since Integral is cumulative, the Ki value has a significant impact. You may end up adjusting it by .01 increments.
Once the robot is following the line with good accuracy, you can increase the speed and see if it still is able to follow the line. Speed affects the PID controller and will require retuning as the speed changes.
Pseudo Code:Here is a simple loop that implements the PID control:
start:
error = (target_position) - (theoretical_position)
integral = integral + (error*dt)
derivative = ((error) - (previous_error))/dt
output = (Kp*error) + (Ki*integral) + (Kd*derivative)
previous_error = error
wait (dt)
goto start
Lastly, PID doesn’t guarantee effective results just by simple implementation of a code, it requires constant tweaking based on the circumstances, once correctly tweaked it yields exceptional results. The PID implementation also involves a settling time, hence effective results can be seen only after a certain time from the start of the run of the robot. Also to obtain a fairly accurate output it is not always necessary to implement all the three expressions of PID. If implementing just PI results yields a good result we can skip the derivative part.
PID control for arduino robot
PID Control:
---------------------------------------------------------------
int sensorPin0 = A0; // Middle Sensor
int sensorVal0 = 0;
int sensorPin1 = A1; // Left Sensor
int sensorVal1 = 0;
int sensorPin2 = A2; // Right Sensor
int sensorVal2 = 0;
int Kp = 1;
int Kd = 1;
int Ki = 1;
int position = 0;
int proportional = 0;
int integral = 0;
int derivative = 0;
int prev_proportional = 0;
int error = 0;
int max_speed = 255;
int set_point = 0;
int right_speed = 0;
int left_speed = 0;
int sensors_average = 0;
int sensors_sum = 0;
long sensors[] = { 0, 0, 0 }; // Store values read by sensors
// Pin Assignments //
// Don't change these! These pins are statically defined by shield layout
const byte PWMA = 3; // PWM control (speed) for motor A
const byte PWMB = 11; // PWM control (speed) for motor B
const byte DIRA = 12; // Direction control for motor A
const byte DIRB = 13; // Direction control for motor B
const byte pinX = 1;
void setup() {
setupArdumoto(); // Set all pins as outputs
setupSensors(); // Sets all sensor analog pins as inputs
Serial.begin(9600); // Set up Serial Library at 9600 bps
}
void loop() {
sensorRead();
PID_Calc();
calcTurn();
motorDrive(right_speed, left_speed);
}
void sensorRead() {
sensorVal0=analogRead(sensorPin0);
sensorVal1=analogRead(sensorPin1);
sensorVal2=analogRead(sensorPin2);
sensors[1] = sensorVal0;
sensors[2] = sensorVal1; // USE FOR LOOP LATER
sensors[3] = sensorVal2;
sensors_average = 0;
sensors_sum = 0;
for (int i = 0; i < 3; i++) {
sensors_average += sensors[i]*i*1000;
sensors_sum += int(sensors[i]);
}
}
void PID_Calc() {
position = int(sensors_average / sensors_sum);
proportional = position - set_point;
integral = integral + proportional;
derivative = proportional - prev_proportional;
prev_proportional = proportional;
error = int(proportional*Kp + integral*Ki + derivative*Kd);
}
void calcTurn() {
if (error < -256){ error = -256; }
if (error > 256){ error = 256; }
if (error < 0) {
right_speed = max_speed - error;
left_speed = max_speed;
}
else {
right_speed = max_speed;
left_speed = max_speed - error;
}
}
void motorDrive(int right_speed, int left_speed){
analogWrite(PWMA, right_speed);
digitalWrite(DIRA, 0);
analogWrite(PWMB, left_speed);
digitalWrite(DIRB, 0);
delay(50);
}
void setupArdumoto() {
pinMode(PWMA, OUTPUT);
pinMode(PWMB, OUTPUT);
pinMode(DIRA, OUTPUT);
pinMode(DIRB, OUTPUT);
digitalWrite(PWMA, LOW);
digitalWrite(PWMB, LOW);
digitalWrite(DIRA, LOW);
digitalWrite(DIRB, LOW);
}
void setupSensors() {
pinMode(sensorPin0,INPUT); // Sets sensor pin to input
pinMode(sensorPin1,INPUT); // Sets sensor pin to input
pinMode(sensorPin2,INPUT); // Sets sensor pin to input
}
Calibrate:
---------------------------------------------------------------
int sensorPin0 = A0; // Middle Sensor
int sensorVal0 = 0;
int sensorPin1 = A1; // Left Sensor
int sensorVal1 = 0;
int sensorPin2 = A2; // Right Sensor
int sensorVal2 = 0;
// Pin Assignments //
// Don't change these! These pins are statically defined by shield layout
const byte PWMA = 3; // PWM control (speed) for motor A
const byte PWMB = 11; // PWM control (speed) for motor B
const byte DIRA = 12; // Direction control for motor A
const byte DIRB = 13; // Direction control for motor B
const byte pinX = 1;
void setup() {
setupArdumoto(); // Set all pins as outputs
setupSensors(); // Sets all sensor analog pins as inputs
Serial.begin(9600); // Set up Serial Library at 9600 bps
}
void loop() {
sensorVal0=analogRead(sensorPin0);
sensorVal1=analogRead(sensorPin1);
sensorVal2=analogRead(sensorPin2);
Serial.print(sensorVal0);
Serial.print(' ');
Serial.print(sensorVal1);
Serial.print(' ');
Serial.print(sensorVal2);
Serial.print(' ');
delay(1500)
}
void setupArdumoto() {
pinMode(PWMA, OUTPUT);
pinMode(PWMB, OUTPUT);
pinMode(DIRA, OUTPUT);
pinMode(DIRB, OUTPUT);
digitalWrite(PWMA, LOW);
digitalWrite(PWMB, LOW);
digitalWrite(DIRA, LOW);
digitalWrite(DIRB, LOW);
}
void setupSensors() {
pinMode(sensorPin0,INPUT); // Sets sensor pin to input
pinMode(sensorPin1,INPUT); // Sets sensor pin to input
pinMode(sensorPin2,INPUT); // Sets sensor pin to input
}
---------------------------------------------------------------
Setpoint:
int sensorPin0 = A0; // Middle Sensor
int sensorVal0 = 0;
int sensorPin1 = A1; // Left Sensor
int sensorVal1 = 0;
int sensorPin2 = A2; // Right Sensor
int sensorVal2 = 0;
int sensors_average = 0;
int sensors_sum = 0;
int position = 0;
long sensors[] = { 0, 0, 0 }; // Store values read by sensors
// Pin Assignments //
// Don't change these! These pins are statically defined by shield layout
const byte PWMA = 3; // PWM control (speed) for motor A
const byte PWMB = 11; // PWM control (speed) for motor B
const byte DIRA = 12; // Direction control for motor A
const byte DIRB = 13; // Direction control for motor B
const byte pinX = 1;
void setup() {
setupArdumoto(); // Set all pins as outputs
setupSensors(); // Sets all sensor analog pins as inputs
Serial.begin(9600); // Set up Serial Library at 9600 bps
}
void loop() {
sensorVal0=analogRead(sensorPin0);
sensorVal1=analogRead(sensorPin1);
sensorVal2=analogRead(sensorPin2);
sensors[1] = sensorVal0;
sensors[2] = sensorVal1; // USE FOR LOOP LATER
sensors[3] = sensorVal2;
sensors_average = 0;
sensors_sum = 0;
for (int i = 0; i < 3; i++) {
sensors_average += sensors[i]*i*1000;
sensors_sum += int(sensors[i]);
}
position = int(sensors_average / sensors_sum);
// Change to columns
Serial.print(sensors_average);
Serial.print("\t");
Serial.print(sensors_sum);
Serial.print("\t");
Serial.print(position);
Serial.println();
delay(100);
}
void setupArdumoto() {
pinMode(PWMA, OUTPUT);
pinMode(PWMB, OUTPUT);
pinMode(DIRA, OUTPUT);
pinMode(DIRB, OUTPUT);
digitalWrite(PWMA, LOW);
digitalWrite(PWMB, LOW);
digitalWrite(DIRA, LOW);
digitalWrite(DIRB, LOW);
}
void setupSensors() {
pinMode(sensorPin0,INPUT); // Sets sensor pin to input
pinMode(sensorPin1,INPUT); // Sets sensor pin to input
pinMode(sensorPin2,INPUT); // Sets sensor pin to input
}
---------------------------------------------------------------
line following code 0.1 of many that works with spark fun motor shield
int sensorPin0 = A0; // Middle Sensor
int sensorVal0 = 0;
int sensorPin1 = A1; // Left Sensor
int sensorVal1 = 0;
int sensorPin2 = A2; // Right Sensor
int sensorVal2 = 0;
// Pin Assignments //
// Don't change these! These pins are statically defined by shield layout
const byte PWMA = 3; // PWM control (speed) for motor A
const byte PWMB = 11; // PWM control (speed) for motor B
const byte DIRA = 12; // Direction control for motor A
const byte DIRB = 13; // Direction control for motor B
const byte pinX = 1;
void setup() {
setupArdumoto(); // Set all pins as outputs
setupSensors(); // Sets all sensor analog pins as inputs
Serial.begin(9600); // Set up Serial Library at 9600 bps
}
void loop() {
sensorVal0=analogRead(sensorPin0);
sensorVal1=analogRead(sensorPin1);
sensorVal2=analogRead(sensorPin2);
Serial.println(sensorVal0);
if (sensorVal0 >= 400 && sensorVal0 <= 1000) {
analogWrite(PWMA,50);
digitalWrite(DIRA,0);
analogWrite(PWMB,50);
digitalWrite(DIRB,0);
}
else if (sensorVal1 >= 400 && sensorVal1 <= 1000) {
analogWrite(PWMA,50);
digitalWrite(DIRA,0);
analogWrite(PWMB,15);
digitalWrite(DIRB,0);
}
else if (sensorVal2 >= 400 && sensorVal2 <= 1000) {
analogWrite(PWMA,15);
digitalWrite(DIRA,0);
analogWrite(PWMB,50);
digitalWrite(DIRB,0);
}
else {
analogWrite(PWMA,0);
digitalWrite(DIRA,0);
analogWrite(PWMB,0);
digitalWrite(DIRB,0);
}
}
void setupArdumoto() {
pinMode(PWMA, OUTPUT);
pinMode(PWMB, OUTPUT);
pinMode(DIRA, OUTPUT);
pinMode(DIRB, OUTPUT);
digitalWrite(PWMA, LOW);
digitalWrite(PWMB, LOW);
digitalWrite(DIRA, LOW);
digitalWrite(DIRB, LOW);
}
void setupSensors() {
pinMode(sensorPin0,INPUT); // Sets sensor pin to input
pinMode(sensorPin1,INPUT); // Sets sensor pin to input
pinMode(sensorPin2,INPUT); // Sets sensor pin to input
}
Working code with wheels and Infrared sensor:
/*
This is a test sketch for the Adafruit assembled Motor Shield for Arduino v2
It won't work with v1.x motor shields! Only for the v2's with built in PWM
control
For use with the Adafruit Motor Shield v2
----> http://www.adafruit.com/products/1438
*/
#include <Wire.h>
#include <Adafruit_MotorShield.h>
#include "utility/Adafruit_PWMServoDriver.h"
//Variables for IR Senso
int sensorPin=A0;
int sensorVal=0;
// Create the motor shield object with the default I2C address
Adafruit_MotorShield AFMS = Adafruit_MotorShield();
// Or, create it with a different I2C address (say for stacking)
// Adafruit_MotorShield AFMS = Adafruit_MotorShield(0x61);
// Select which 'port' M1, M2, M3 or M4. In this case, M1
Adafruit_DCMotor *myMotor = AFMS.getMotor(1);
// You can also make another motor on port M2
Adafruit_DCMotor *myOtherMotor = AFMS.getMotor(2);
void setup() {
pinMode(sensorPin,INPUT); //Pin setup for the IR sensor
Serial.begin(9600); // set up Serial library at 9600 bps
Serial.println("Adafruit Motorshield v2 - DC Motor test!");
AFMS.begin(); // create with the default frequency 1.6KHz
//AFMS.begin(1000); // OR with a different frequency, say 1KHz
// Set the speed to start, from 0 (off) to 255 (max speed)
myMotor->setSpeed(150);
myOtherMotor->setSpeed(150);
}
void loop() {
sensorVal=analogRead(sensorPin);
Serial.println(sensorVal);
if (sensorVal <= 50)
{myMotor->run(FORWARD);
myOtherMotor->run(FORWARD);}
else
{myMotor->run(RELEASE);
myOtherMotor->run(RELEASE);
}
}
Line Following
https://learn.sparkfun.com/tutorials/getting-started-with-the-redbot/all?print=1#arduino-library
Goal of the project:
1. Speed of course
2. The number of gates you pass through
Need some Libraries: 3 of them!
1. Adafruit library
http://learn.adafruit.com/downloads/pdf/adafruit-motor-shield-v2-for-arduino.pdf
//putting a 0 means go in the forward direction and 1 means go in the reverse of that.
Motors working:
// Pin Assignments //
// Don't change these! These pins are statically defined by shield layout
const byte PWMA = 3; // PWM control (speed) for motor A
const byte PWMB = 11; // PWM control (speed) for motor B
const byte DIRA = 12; // Direction control for motor A
const byte DIRB = 13; // Direction control for motor B
const byte pinX = 1;
void setup()
{
setupArdumoto(); // Set all pins as outputs
}
void loop()
{
analogWrite(PWMA,127);
digitalWrite(DIRA,0);
analogWrite(PWMB,50);
digitalWrite(DIRB,0);
analogWrite(PWMA,0);
delay(1000);
}
void setupArdumoto()
{
pinMode(PWMA, OUTPUT);
pinMode(PWMB, OUTPUT);
pinMode(DIRA, OUTPUT);
pinMode(DIRB, OUTPUT);
digitalWrite(PWMA, LOW);
digitalWrite(PWMB, LOW);
digitalWrite(DIRA, LOW);
digitalWrite(DIRB, LOW);
}
Motor Shield Soldering layout
https://learn.sparkfun.com/tutorials/ardumoto-shield-hookup-guide/all
Pulse with Modulation:
http://arduino.cc/en/Tutorial/PWM
Bill of Materials/Cost Report:
Complete kit:
http://www.amazon.com/Arduino-Robot-Starter-Kit-Authentic/dp/B00FURQAKM/ref=sr_1_21?s=electronics&ie=UTF8&qid=1391016880&sr=1-21&keywords=arduino+uno+motor+shield
Line following sensors:
https://www.sparkfun.com/products/11769
https://www.sparkfun.com/products/9815
https://www.sparkfun.com/products/11864
https://www.sparkfun.com/products/8084
https://www.sparkfun.com/products/10007
http://www.amazon.com/gp/aw/d/B002Y2LJW0
Your order number is 892644.
This order was placed at 10:17:28 am.
Want to see all the products you've purchased in one place? Try My Products.
I just bought: 'Tenergy Li-Ion 18650 7.4V 2200mAh Rechargeable Battery module with PCB' by Tenergy
www.amazon.com
Features and Benefits * High quality 7.4 V Li-Ion rechargeable battery pack * Made of 2 2200mAh cylindrical 18650 cells with PCB for full protection * Light weight and higher energy density than any rechargeable battery * No memory effect and rechargeable * Longer storage life than NiMH battery * You can build 7.4V/4.4Ah Li-Ion battery pack by connecting two or three PCB ready battery module in parallel . *...
1 item will be shipped to Michael Thompson by Battery Superstore. Estimated delivery: Feb. 4, 2014 - Feb. 7, 2014
I just bought: 'Tenergy Li-Ion 18650 7.4V 2200mAh Rechargeabl...
www.amazon.com
Feature