The robot navigates without knowing a detailed map of the surroundings. If an obstacle is detected in its path, the robot adapts its velocity in order to avoid the collision. If the surrounding environment is free of obstructions, the robot simply moves forward until an obstacle is detected in the range of the sensors.
List of main components:
- 1 X 2WD Robot Chassis Kit [Amazon]
- 1 X L298N Motor Driver [Amazon]
- 1 X Arduino UNO [Amazon]
- 3 X HC-SR04 Ultrasonic Sensor [Amazon]
- 1 X 5V Battery Bank [Amazon]
- 1 X Battery Holder for 4 x AA-Cell [Amazon]
First, we need to define the inputs to know from where the robot takes the information into its system. This detection and avoidance robot will have two types of inputs.
1. The most straightforward input is the switch button that will turn ON and OFF the motor driver and a power on/off button for the battery bank to power the Arduino board and the sensors.
2. The robot sees the world through sensors and is the way of taking information into the control system. The sensors are the second input of the robot. The sensors let the robot to detect and respond to the surrounding environment around it. The sensors enable the robot to operate safely, automatically detecting obstacles, and dynamically change its route.
The robot uses sensors to measure the distance between the robot and the obstacle. As you may know, inside a home are different objects with different sizes and build from many types of materials. The robot can detect objects from different materials like a wooden chair or a sofa bed.
Once the robot detects an obstacle, the algorithm calculates an alternative path based on the last outputs of the sensors. If the object is on the left side of the platform, the robot dynamically moves its direction to the right until the sensors no longer detect the obstacle. The same behavior when the sensor detects a barrier on the right side.
If the sensor detects an obstacle in the middle of the robot’s path, then the algorithm randomly changes its direction to the left or right until the sensors no longer detect an obstacle.
We finished defining the types of input for the autonomous robot. Inputs are essential, so are the outputs.
The obstacle detection and avoidance robot have one type of output.
3. The mobile robot uses two DC motors, one for each side of the platform. Each motor is programmed individually and can move the robot in any direction for turning and pivoting.
To have complete control over the DC motors, we have to control the speed and the direction of rotation. This can be achieved by combining the PWM method for controlling the speed, and the H-bridge electronic circuit for controlling the rotation of direction.
Once we finish defining the inputs and output, we go further and break up the obstacle detection and avoidance robot into simple pieces and work on them one by one.
For this robot, I use a flexible architecture, meaning that the user is allowed to:
- Add multiple sensors and components.
- Possibility to replace actual sensors with other sensors.
- Write with easy your own software.
Table of Contents
TogglePart 1: The Detection System
This part is about translating the raw data output from sensors into accurate measurements that are used in Navigation.
Part 2: Navigation
In this part we build the algorithm to calculate the steering in order to find a collision-free path in the surrounded environment of the mobile robot.
Part 3: Drive System
In this part, we are using the data from the Navigation to steer the robot.
Once we know what we have to do, we go further to make things simple and easy-to-understand. We will start by explaining how to do it, build the circuits, and write the program.
Part 1: The Detection System
At this step, we have to give to the robot sensing capabilities. We have to create a detection system with the ability to see the surrounding environment. The ultrasonic sensors are very efficient for sensing the surrounding environment in both the inside and the outside world.
Instead of using a single ultrasonic sensor to solve the sensing problem, we made use of three sensors to guide the robot in a complex environment. We will use all the sensors in a close-range observation task. This is because the robot will work inside, and the maneuver space is limited. For example, an HC-SR04 provides 2 cm to 400 cm of non-contact measurement function. Make use of the maximum range of the sensors, the robot will always detect an object in its path inside a room and will not move at all.
1.1 Setup Arduino and HC-SR04 Ultrasonic Sensors
According to specifications, the HC-SR04 has an operating voltage of 5V. Arduino has an interface pin that provides 5V output.
The operating current for one ultrasonic sensor is 15mA. Three sensors will consume 45mA, which can be supported by Arduino even if it is connected to a USB port of a 5V battery bank. The 5V output pin of Arduino UNO is suitable for ~400 mA on USB, and more than double (~900 mA) when it is used with an external power adapter.
For connections between sensors and Arduino, I use jumper wires.
Powering the sensors from one 5V pin is a challenge and requires cutting and soldering the wires. As a workaround, you can use a breadboard to connect the 5V and ground pins from Arduino to the 5V and ground pins of the sensors.
This is my final setup to power the sensors. The red/orange wires are the 5V, and black/blue wires are for ground.
After connecting the power wires, we go further and use female-to-male jumper wires to connect the trigger and echo pins.
Sensor left:
Echo -> pin 2 Arduino
Trig -> pin 3 Arduino
Sensor center:
Echo -> pin 4 Arduino
Trig -> pin 5 Arduino
Sensor right:
Echo -> pin 6 Arduino
Trig -> pin 7 Arduino
The final setup for the sensors and Arduino:
Once we have all the sensors connected to Arduino, it’s time to read the output signal from these and transform the output signal into centimeters.
C++
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
|
void sensorCycle() {
  for (uint8_t i = 0; i < SONAR_NUM; i++) {
    if (millis() >= pingTimer[i]) {
      pingTimer[i] += PING_INTERVAL * SONAR_NUM;
      if (i == 0 && currentSensor == SONAR_NUM – 1) oneSensorCycle();
      sonar[currentSensor].timer_stop();
      currentSensor = i;
      cm[currentSensor] = 0;
      sonar[currentSensor].ping_timer(echoCheck);
    }
  }
}
// If ping received, set the sensor distance to array.
void echoCheck() {
  if (sonar[currentSensor].check_timer())
    cm[currentSensor] = sonar[currentSensor].ping_result / US_ROUNDTRIP_CM;
}
|
Lines 100 to 109: We’re using the NewPing library. Looping through each sensor and when the sensor ping cycle is complete, return the readings;
Lines 114 to 115: if the ping is received, add to array the distance measured;
1.2 Apply filters to remove noisy, jumpy or erratic readings
Our task in filtering the output of the sensor includes several steps. We apply a filter to remove some of the unwanted readings and leave a smoother result. Then use a Kalman Filter to remove jumpy or erratic sensor’s readings.
C++
126
127
128
129
130
131
132
133
134
135
136
137
138
139
|
int returnLastValidRead(uint8_t sensorArray, uint8_t cm) {
  if (cm != 0) {
    return oldSensorReading[sensorArray] = cm;
  } else {
    return oldSensorReading[sensorArray];
  }
}
//Apply Kalman Filter to sensor reading.
void applyKF() {
  isObstacleLeft = obstacleDetection(KF_Left.updateEstimate(leftSensor));
  isObstacleCenter = obstacleDetection(KF_Center.updateEstimate(centerSensor));
  isObstacleRight = obstacleDetection(KF_Right.updateEstimate(rightSensor));
}
|
Lines 127 to 131: Check the output of sensors, and if the value is 0, return the last stored value different than 0. The previous value different than 0 is stored in an array.
Lines 136 to 138: Apply Kalman Filters to all the three sensors. In this way, we remove jumpy or erratic sensor’s readings;
1.3 Install the sensors
The 2WD robot chassis that I used is approximately 16 centimeters width. This means that the sensors should detect obstacles for at least 16 centimeters in front of the robot. To be clear, let’s check the sketch below.
Detecting obstacles inside the area that is covered by the width of the robot is not the best approach. We increase the area of interest with one centimeter left and right of the chassis – which means 18 centimeters width in front of the robot. This means that each sensor should cover a width of at least 6 centimeters in front of the robot.
A few weeks ago, I wrote a tutorial about HC-SR04 and Arduino. In the tutorial, you can find the operating detection range for an HC-SR04 in the range of 5 to 100cm. At 100cm, the sensor has an operating detection range of 8 centimeters, which is more than we need for this example. Doing some math, we discover that a maximum range of 75 centimeters is what we need to detect all the obstacles in front of our robot.
We also have a blind zone between 0 and 5 centimeters in front of the robot. A bumper along the lower front part of the robot could be a solution to help protect it. But this part is not the subject of this tutorial, and will not be covered.
This is a 3D printed triple sensor holder for the HC-SR04 ultrasonic sensor. It has a simple design, and it is practical to assemble and disassemble. The sensors are very stable and don’t need any screws or glue them. Also, the holder will protect the sensors and give the robot a better look.
The sensor holder is fixed on the chassis using M3 screws and M3 nuts.
We finish the detection system. We connect the sensors to Arduino and design the 3D printed triple sensor holder. We are ready to use the sensors for detecting and avoiding obstacles.
Part 2: Navigation
Our robot would be much useful if it could move the obstacles out of the way. Well, since it’s impossible for a small robot, we have to program the robot to find collision-free paths.
The real world contains objects, doors, furniture that should be detected and avoided by the robot. The algorithm that controls the movements of the robot should decide which course to follow and steer it there.
2.1 The algorithm
1. First, we have to define the minimum and maximum range of the sensors. We have to write the algorithm capable of identifying the obstacle and its position between the blind zone and the maximum range acceptable for this project.
2. If none of the sensors detects an obstacle, go forward at maximum speed.
3. If at least one sensor detects an obstacle, decrease the speed.
4. Check again if the sensors detect obstacles.
5. If at least one sensor is still detecting an obstacle, go to the sensor’s state.
6. If the left sensor detects an obstacle, move to the right until the sensor doesn’t detect the obstacle.
7. If the center sensor detects an obstacle, move randomly to the left or right until the center and left/right sensors do not detect the obstacle.
8. If the right sensor detects an obstacle, move to the left until the sensor doesn’t detect the obstacles.
9. If all the sensors detect obstacles, move back and turn left or right until a free obstacle path is detected.
This simple obstacle avoidance algorithm includes nine states. It is a solution that doesn’t demand a heavy computational load and is easy to implement.
C++
54
55
56
57
58
59
60
61
62
63
64
|
enum NavigationStates {
  CHECK_ALL,
  MAX_SPEED,
  SPEED_DECREASE,
  CHECK_OBSTACLE_POSITION,
  LEFT,
  CENTER,
  RIGHT,
  BACK
};
NavigationStates _navState = CHECK_ALL;
|
Lines 54 to 64: define the set of values through which the robot passes depending on its condition;
C++
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
|
bool obstacleDetection(int sensorRange) {
  if ((MIN_RANGE_OBSTACLE <= sensorRange) && (sensorRange <= MAX_RANGE_OBSTACLE)) return true; else return false;
}
//Obstacle avoidance algorithm.
void obstacleAvoidance()
{
  switch (_navState) {
    case CHECK_ALL: { //if no obstacle, go forward at maximum speed
        if (isObstacleLeft == 0 && isObstacleCenter == 0 && isObstacleRight == 0) {
          _navState = MAX_SPEED;
        } else {
          startTimerReady();
          _navState = SPEED_DECREASE;
        }
      } break;
    case MAX_SPEED: {
        moveForward(maximumSpeed);
        _navState = CHECK_ALL;
      } break;
    case SPEED_DECREASE: {
        moveForward(minSpeed);
        //Wait for few more readings at low speed and then go to check the obstacle position
        if (isTimerReady(DECREESE_SPEED_LOOP)) _navState = CHECK_OBSTACLE_POSITION;
      } break;
    case CHECK_OBSTACLE_POSITION: {
        //If the path is free, go again to MAX_SPEED else check the obstacle position
        if (isObstacleLeft == 0 && isObstacleCenter == 0 && isObstacleRight == 0) {
          _navState = MAX_SPEED;
        }
        else if (isObstacleLeft == 1 && isObstacleCenter == 0 && isObstacleRight == 0) {
          startTimerPosition();
          _navState = LEFT;
        }
        else if (isObstacleLeft == 0 && isObstacleCenter == 1 && isObstacleRight == 0) {
          startTimerPosition();
          _navState = CENTER;
        }
        else if (isObstacleLeft == 0 && isObstacleCenter == 0 && isObstacleRight  == 1) {
          startTimerPosition();
          _navState = RIGHT;
        }
        else if (isObstacleLeft == 1 && isObstacleCenter == 1 && isObstacleRight == 1) {
          startTimerPosition();
          _navState = BACK;
        }
      } break;
 Â
    case LEFT: { //Move left and check obstacle. If obstacle exists, go again to left, else exit
        moveLeft(minSpeed);
        if (isTimerPosition(MOVE_TO_NEW_POSITION)) {
          if (isObstacleLeft == 1) _navState = LEFT;
          else _navState = CHECK_ALL;
        }
      } break;
    case CENTER: { //If obstacle exists, go left or right
        if (randomMove() == 1)  _navState = LEFT; else  _navState = RIGHT;
      } break;
    case RIGHT: {
        moveRight(minSpeed);
        if (isTimerPosition(MOVE_TO_NEW_POSITION)) {
          if (isObstacleRight == 1) _navState = RIGHT;
          else _navState = CHECK_ALL;
        }
      } break;
    case BACK: {
        moveBackward(minSpeed);
        if (isTimerPosition(MOVE_TO_NEW_POSITION)) {
          if (randomMove() == 1)  _navState = LEFT; else  _navState = RIGHT;
        }
      } break;
  }
}
|
Line 143: Define the minimum and maximum range of the sensors, and return true if an obstacle is in range.
Lines 150 to 157: We are in the CHECK_ALL case where we check if an obstacle is in the range of the sensors. If none of the sensors detect an obstacle, then go forward with maximum speed. If at least one of the sensor detects an obstacle, we start to count the milliseconds used to decrease the speed of the robot and then move to the SPEED_DECREASE case;
Lines 160 and 161: We are moving forward at maximum speed and check if all the sensors are free of obstacles;
Lines 165 to 167: The robot is moving forward with a lower speed for a certain amount of time. When the time is passed, enter in the CHECK_OBSTACLE_POSITION.
Lines 172 to 191: If the path is free, this means that the sensor(s) has a false reading, and we can go back to navigate with maximum speed.
If one of the sensors still detects an obstacle, then we check all the sensors to determine the position of the obstacle relative to the robot. If the sensor from the left side of the robot detects the obstacle, then we are to the LEFT case. If the sensor located in the center of the robot is detecting the obstacle, then we are in the CENTER case. If the right sensor detects an obstacle, we are in the RIGHT case. If all the sensors detect the obstacle, then the robot cannot move forward and enter in case BACK.
Lines 194 to 198: The robot is moving to the left at minimum speed for a particular amount of time. When time passed, we recheck the left sensor. If the sensor returns the obstacle, then we stay in the LEFT case and move again to the left. If the sensor is free of obstacle, then we go to the CHECK_ALL stage.
Line 202: Randomly select one of the next cases in which the robot enters. It could be left or right.
Lines 206 to 210: The robot is moving to the right at minimum speed for a particular amount of time. When time passed, we recheck the right sensor. If the sensor returns the obstacle, then we stay in the RIGHT case and move again to the right. If the sensor is free of obstacle, then we go to the CHECK_ALL stage.
Lines 214 to 217: All the sensors return an obstacle. In this case, the robot is moving backward at a lower speed for a certain amount of time and then randomly is moving to left or right.
Part 3: Drive System
The drive system should be capable of moving the robot with maximum power generated by the DC motors. The two DC motors are generally suited to driving the robot in all directions.
Since this is a 2WD platform, turning via skid steering is easier than a 4WD robot. Using the differential drive (two wheels plus a caster), we are allowed to program the robot to turn in place, left or right by turning the motors in opposite directions.
The DC motors have gears mechanisms that adjust the speed of electric motors, leading them to rotate the wheels at a maximum of 100 rpm. The electric motors have an operating voltage range between 3 to 6V. The 6V is the nominal voltage for which the DC motors are supposed to operate optimally.
The two wheels measure 65 mm in diameter and press-fit onto the 3mm D shafts on the DC motors. The black tires are made of soft rubber for increased traction.
The two DC motors are controlled with an L298N driver. It is a dual full-bridge driver that controls the speed and direction of the DC motors. The electric motors can be driven at the same time or one by one. We take this advantage to drive the robot in any direction with minimum effort for the drive system.
The L298N can drive DC motors at nominal voltages between 5 and 35V with peak current up to 2A.
The output of the motor driver is the PWM signal (pulse width modulation), which switches the output power on and off fast to reduce the average voltage supplied to the motor to precisely control the rotations of the motors.
3.1 Connect the motor drive to motors and Arduino
The driver board has two screw terminal blocks for motor A and B. We will use these two terminals to connect the DC motors. Also, we will use another screw terminal block for the Ground pin and the VMS as the power source for motors. GND and VMS terminals should be connected to the 6V battery pack.
Use female-to-male jumper wires to connect the driver pins to Arduino pins.
ENA -> pin 9
IN1 -> pin 8
IN2 -> pin 11
IN3 -> pin 12
IN4 -> pin 13
ENB -> pin 10
Ground screw terminal block -> pin Gnd Arduino (we use two power supply sources, and we have to share the ground between them)
3.2 Steering the Robot
Once the DC motors are connected to the motor driver, and the motor driver to Arduino, let’s start writing the sketch to control the steering of the robot.
According to the algorithm that controls the robot, we need to decrease the speed of the motors, move the robot forward, backward, left, and right. In our program, is a function for each of these actions.
Download source code
C++
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
|
/*
  :Version 2.0
  :Author: Dragos Calin
  :Email: dragos@intorobotics.com
  :License: BSD
  :Date: 20/04/2020
  :Last update: dd/mm/YYYY
*/
#include <NewPing.h>
#include <SimpleKalmanFilter.h>
#define SONAR_NUM 3Â Â Â Â Â Â Â Â Â Â //The number of sensors.
#define MAX_DISTANCE 200Â Â Â Â //Mad distance to detect obstacles.
#define PING_INTERVAL 33Â Â Â Â //Looping the pings after 33 microseconds.
int LOOPINGÂ Â Â Â Â Â Â Â Â Â Â Â Â Â = 10; //Loop for every 10 milliseconds.
int DECREESE_SPEED_LOOPÂ Â = 400;//Give some time to sensors for few more readings.
int MOVE_TO_NEW_POSITION = 500;//Wait for the new position.
unsigned long _timerStart        = 0;
unsigned long _timerStartReady    = 0;
unsigned long _timerStartPosition = 0;
uint8_t MIN_RANGE_OBSTACLE = 5; //Between 0 and 5 cm is the blind zone of the sensor.
uint8_t MAX_RANGE_OBSTACLE = 75; //The maximum range to check if obstacle exists.
uint8_t oldSensorReading[3];Â Â Â Â //Store last valid value of the sensors.
uint8_t leftSensor;Â Â Â Â Â Â Â Â Â Â Â Â //Store the sensor’s value.
uint8_t centerSensor;
uint8_t rightSensor;
bool isObstacleLeft;Â Â Â Â Â Â Â Â Â Â //If obstacle detected or not.
bool isObstacleCenter;
bool isObstacleRight;
uint8_t maximumSpeed = 255; //PWM value for maximum speed.
uint8_t minSpeed = 100; //PWM value for minimum speed.
unsigned long pingTimer[SONAR_NUM]; // Holds the times when the next ping should happen for each sensor.
unsigned int cm[SONAR_NUM];Â Â Â Â Â Â Â Â // Where the ping distances are stored.
uint8_t currentSensor = 0;Â Â Â Â Â Â Â Â Â Â // Keeps track of which sensor is active.
NewPing sonar[SONAR_NUM] = {
  NewPing(3, 2, MAX_DISTANCE), // Trigger pin, echo pin, and max distance to ping.
  NewPing(5, 4, MAX_DISTANCE),
  NewPing(7, 6, MAX_DISTANCE)
};
SimpleKalmanFilter KF_Left(2, 2, 0.01);
SimpleKalmanFilter KF_Center(2, 2, 0.01);
SimpleKalmanFilter KF_Right(2, 2, 0.01);
enum NavigationStates {
  CHECK_ALL,
  MAX_SPEED,
  SPEED_DECREASE,
  CHECK_OBSTACLE_POSITION,
  LEFT,
  CENTER,
  RIGHT,
  BACK
};
NavigationStates _navState = CHECK_ALL;
//L298N motor driver pins
byte enA = 9;
byte in1 = 8;
byte in2 = 11;
byte enB = 10;
byte in3 = 12;
byte in4 = 13;
void startTimer() {
  _timerStart = millis();
}
void startTimerReady() {
  _timerStartReady = millis();
}
void startTimerPosition() {
  _timerStartPosition = millis();
}
bool isTimeForLoop(int _mSec) {
  return (millis() – _timerStart) > _mSec;
}
bool isTimerReady(int _mSec) {
  return (millis() – _timerStartReady) > _mSec;
}
bool isTimerPosition(int _mSec) {
  return (millis() – _timerStartPosition) > _mSec;
}
//looping the sensors
void sensorCycle() {
  for (uint8_t i = 0; i < SONAR_NUM; i++) {
    if (millis() >= pingTimer[i]) {
      pingTimer[i] += PING_INTERVAL * SONAR_NUM;
      if (i == 0 && currentSensor == SONAR_NUM – 1) oneSensorCycle();
      sonar[currentSensor].timer_stop();
      currentSensor = i;
      cm[currentSensor] = 0;
      sonar[currentSensor].ping_timer(echoCheck);
    }
  }
}
// If ping received, set the sensor distance to array.
void echoCheck() {
  if (sonar[currentSensor].check_timer())
    cm[currentSensor] = sonar[currentSensor].ping_result / US_ROUNDTRIP_CM;
}
//Return the last valid value from the sensor.
void oneSensorCycle() {
  leftSensor  = returnLastValidRead(0, cm[0]);
  centerSensor = returnLastValidRead(1, cm[1]);
  rightSensor  = returnLastValidRead(2, cm[2]);
}
//If sensor value is 0, then return the last stored value different than 0.
int returnLastValidRead(uint8_t sensorArray, uint8_t cm) {
  if (cm != 0) {
    return oldSensorReading[sensorArray] = cm;
  } else {
    return oldSensorReading[sensorArray];
  }
}
//Apply Kalman Filter to sensor reading.
void applyKF() {
  isObstacleLeft = obstacleDetection(KF_Left.updateEstimate(leftSensor));
  isObstacleCenter = obstacleDetection(KF_Center.updateEstimate(centerSensor));
  isObstacleRight = obstacleDetection(KF_Right.updateEstimate(rightSensor));
}
//Define the minimum and maximum range of the sensors, and return true if an obstacle is in range.
bool obstacleDetection(int sensorRange) {
  if ((MIN_RANGE_OBSTACLE <= sensorRange) && (sensorRange <= MAX_RANGE_OBSTACLE)) return true; else return false;
}
//Obstacle avoidance algorithm.
void obstacleAvoidance()
{
  switch (_navState) {
    case CHECK_ALL: { //if no obstacle, go forward at maximum speed
        if (isObstacleLeft == 0 && isObstacleCenter == 0 && isObstacleRight == 0) {
          _navState = MAX_SPEED;
        } else {
          startTimerReady();
          _navState = SPEED_DECREASE;
        }
      } break;
    case MAX_SPEED: {
        moveForward(maximumSpeed);
        _navState = CHECK_ALL;
      } break;
    case SPEED_DECREASE: {
        moveForward(minSpeed);
        //Wait for few more readings at low speed and then go to check the obstacle position
        if (isTimerReady(DECREESE_SPEED_LOOP)) _navState = CHECK_OBSTACLE_POSITION;
      } break;
    case CHECK_OBSTACLE_POSITION: {
        //If the path is free, go again to MAX_SPEED else check the obstacle position
        if (isObstacleLeft == 0 && isObstacleCenter == 0 && isObstacleRight == 0) {
          _navState = MAX_SPEED;
        }
        else if (isObstacleLeft == 1 && isObstacleCenter == 0 && isObstacleRight == 0) {
          startTimerPosition();
          _navState = LEFT;
        }
        else if (isObstacleLeft == 0 && isObstacleCenter == 1 && isObstacleRight == 0) {
          startTimerPosition();
          _navState = CENTER;
        }
        else if (isObstacleLeft == 0 && isObstacleCenter == 0 && isObstacleRight  == 1) {
          startTimerPosition();
          _navState = RIGHT;
        }
        else if (isObstacleLeft == 1 && isObstacleCenter == 1 && isObstacleRight == 1) {
          startTimerPosition();
          _navState = BACK;
        }
      } break;
 Â
    case LEFT: { //Move left and check obstacle. If obstacle exists, go again to left, else exit
        moveLeft(minSpeed);
        if (isTimerPosition(MOVE_TO_NEW_POSITION)) {
          if (isObstacleLeft == 1) _navState = LEFT;
          else _navState = CHECK_ALL;
        }
      } break;
    case CENTER: { //If obstacle exists, go left or right
        if (randomMove() == 1)  _navState = LEFT; else  _navState = RIGHT;
      } break;
    case RIGHT: {
        moveRight(minSpeed);
        if (isTimerPosition(MOVE_TO_NEW_POSITION)) {
          if (isObstacleRight == 1) _navState = RIGHT;
          else _navState = CHECK_ALL;
        }
      } break;
    case BACK: {
        moveBackward(minSpeed);
        if (isTimerPosition(MOVE_TO_NEW_POSITION)) {
          if (randomMove() == 1)  _navState = LEFT; else  _navState = RIGHT;
        }
      } break;
  }
}
//L298N Motor Driver.
void stopMotors() {
  digitalWrite(in1, LOW);
  digitalWrite(in2, LOW);
  digitalWrite(in3, LOW);
  digitalWrite(in4, LOW);
}
void moveForward(uint8_t pwmValue) {
  digitalWrite(in1, HIGH);
  digitalWrite(in2, LOW);
  digitalWrite(in3, HIGH);
  digitalWrite(in4, LOW);
  analogWrite(enA, pwmValue);
  analogWrite(enB, pwmValue);
}
void moveBackward(uint8_t pwmValue) {
  digitalWrite(in1, LOW);
  digitalWrite(in2, HIGH);
  digitalWrite(in3, LOW);
  digitalWrite(in4, HIGH);
  analogWrite(enA, pwmValue);
  analogWrite(enB, pwmValue);
}
void moveLeft(uint8_t pwmValue) {
  digitalWrite(in1, LOW); //Left wheel backward.
  digitalWrite(in2, HIGH);
  digitalWrite(in3, HIGH);//Right wheel forward.
  digitalWrite(in4, LOW);
  analogWrite(enA, pwmValue);
  analogWrite(enB, pwmValue);
}
void moveRight(uint8_t pwmValue) {
  digitalWrite(in1, HIGH); //Left wheel forward.
  digitalWrite(in2, LOW);
  digitalWrite(in3, LOW);//Right wheel backward.
  digitalWrite(in4, HIGH);
  analogWrite(enA, pwmValue);
  analogWrite(enB, pwmValue);
}
//Return 1 or 0 from a random number.
int randomMove() {
  uint8_t rnd_number = random(1, 100);
  return rnd_number % 2;
}
/*SETUP & LOOP*/
void setup() {
  Serial.begin(115200);
  pingTimer[0] = millis() + 75;
  for (uint8_t i = 1; i < SONAR_NUM; i++)
    pingTimer[i] = pingTimer[i – 1] + PING_INTERVAL;
  pinMode(enA, OUTPUT);
  pinMode(in1, OUTPUT);
  pinMode(in2, OUTPUT);
  pinMode(enB, OUTPUT);
  pinMode(in3, OUTPUT);
  pinMode(in4, OUTPUT);
  stopMotors();
}
void loop() {
  if (isTimeForLoop(LOOPING)) {
    sensorCycle();
    applyKF();
    obstacleAvoidance();
    startTimer();
  }
}
|
Summary
We finished a very long tutorial. In this tutorial, you learned how to define the inputs and outputs of the robot, how to write an algorithm that controls the actions and the steering of the robot.
In the first part of the tutorial, we covered the functional specifications of the robot. We define the two inputs and the output of the robot. Then we give to the robot sensing capabilities by installing the sensors and transforming the readings in centimeters. Applying filters, we managed to stabilize and remove jumpy or erratic sensor readings.
Then we go further, and in the second part, we write the algorithm that controls how the robot responds to obstacles in the environment.
In the third part, we implement the steering of the robot by reducing the motor speed and moving the robot in a certain direction according to the decision of the algorithm.