High-Level Design
Our vehicle uses reflective phototransistors to follow a line on the ground beneath it. The state of the phototransistors is captured, and the car is controlled accordingly by an Atmel 8515 microcontroller. If the car detects a small deviation from the line, it will correct its path by steering in the appropriate direction. If it detects a large deviation, it will take more "drastic" measures to correct its path: it will back up while steering itself back towards the line until it re-centers itself. It then continues on its path.
The original objective for this project was to optimize the car for the speed with which it navigated the line. To do this, we would have increased the speed when little compensation was needed, and decreased the speed as more was needed. This optimization, however, did not require much more effort on our part than the heuristic outlined above. This is because the speed is mechanically regulated by the gradual acceleration of the car in balance with the direction reversal for large corrections. |
Hardware
The hardware for this project was the bulk of the work. Because we were making a moving vehicle, we decided that it would be best not to have any of the circuitry on breadboards. Breadboards are also expensive, so we probably would have had to disassemble the car after its demonstration. We therefore chose to wire-wrap all of the circuitry. This required a fair amount of labor, but it was well worth it in the end.
The car we selected is fairly simple to operate. It has a rear wheel drive, complete with a differential, which is powered by a DC motor. The steering is not controlled by a servo, but rather by a solenoid. This results in an "all or nothing" control over the steering, but we did not find this to be overly constraining. We built two H-bridges using TIP-31, TIP3055, and TIP-42 BJTs to deliver power to the steering and the drive motor. Because of the current requirements (the drive motor and steering solenoid could draw several amps), we used 20-gauge wire for the high-current areas of the H-bridges rather than the 30-gauge wire used for the rest of the circuit. Schematics of the H-bridges and supporting CMOS logic appear below.
To detect the line, we use an array of five reflective photo-sensor pairs manufactured by Fairchild Semiconductor. We mounted them just ahead of the front wheels on a threaded rod to allow us to reposition them as necessary. The current through the photo-transistor depends on the intensity it detects, but what we really need is a logic level output. We therefore used an open-loop-gain amplifier made from an LMC7111 op-amp. A trim-pot allowed us to set a threshold level, and LEDs were used to aid in calibration. A schematic of the circuit used for the photo-sensors appears below.
Because of the high current draw from the motor and steering, we decided to use a separate power supply for the logic. The logic runs on 6V while the car's motors run on 12V. This initially resulted in some careless bugs, but we seem to have avoided problems with any inductive "kick" from the motor and solenoid. |
|
Software
The software for the autonomous car was not overly complicated, but it provides most of the functionality we could have hoped for. The drive motor is controlled by the 8515's pulse width modulator to give us good control over the speed of the vehicle. The drive direction, steering control, and photo-sensors use I/O ports. The heuristic described in the "high level design" section above is implemented using a single state machine design style.
There is one state in the machine for each of the photo-sensors. We tried to assume as little as possible about the width of the line relative to the spacing of the photo-sensors, though ideally the width of the line will be smaller than the minimum spacing between photo-sensors (about 2.5cm, but configurable). The machine polls the inputs for a potential state change every 10ms. We determined (by experiment) that this time base was necessary to ensure that none of the photo-sensors would cross the line without the car "noticing." The state machine itself follows quite directly from the heuristic described above, and we will leave a more thorough description of it to our code
In order to avoid the need for switches, our car starts and stops itself based on the status of the photo-sensors. The car will not start moving until the middle photo-sensor (and only the middle photo-sensor) is on the line. If no photo-sensor detects the line for 1.5 seconds, the car stops; it assumes that the line has ended, or that it is hopelessly lost. If all of the photo-sensors detect darkness, then the car stops since it has probably been picked up. We can take advantage of this feature when designing courses by placing a thick cross bar at the end of the course (like a T) to stop the car at the end. |
|
|
Results
We had very favorable results. Our car has successfully navigated a number of courses of varying length and complexity, all containing turns drastically sharper than the turning radius of the car. The ability of the car to distinguish line from floor was about what we expected. A line in electrical tape on the floor of Phillips Hall works quite effectively. Our design is not entirely bug-free, nor is the car fail-proof. Given more time, we could add features like the ability to navigate courses which cross themselves (like a figure-8), or track down that pesky bug which infrequently surfaces (we suspect a power-supply isolation problem). All-in-all, the functionality of this vehicle is quite robust so long as we don't crash it into anything. |
|
Appendix A: Code Listing
#include <90s8515.h>
/* speed and direction output pins */
#define speed OCR1B //use PWM for speed control
#define drivedir PORTA.0
#define turndir PORTA.1
#define turn PORTA.2
/* direction signal values */
#define fwd 1
#define rev 0
#define dirleft 1
#define dirright 0
/* state definitions */
#define center 0
#define left 1
#define farleft 2
#define right 3
#define farright 4
#define start 5
/* photosensor values */
#define LEDS ~PINC //inverted since "on" is for a black line
#define LLL (0x01 & LEDS) == 0x01 //far left sensor
#define LL (0x02 & LEDS) == 0x02 //slightly left sensor
#define CC (0x04 & LEDS) == 0x04 //center sensor
#define RR (0x08 & LEDS) == 0x08 //slightly right sensor
#define RRR (0x10 & LEDS) == 0x10 //far right sensor
/* other definitions */
#define t0reload 256-62 //1 ms timebase @ 4MHz
#define deltaT 10 //state change time
unsigned char state;
unsigned int watchdog; //stops car if no line is found after time
unsigned int farcount; //after backing up, car steers and waits before going forward
unsigned int t_statemachine; //task timer
void initialize(void);
void steer_off(void);
void steer_left(void);
void steer_right(void);
void reset(void);
void statemachine(void);
void steer_off(void)
{
turn = 0;
}
void steer_left(void)
{
turndir = dirleft;
turn = 1;
}
void steer_right(void)
{
turndir = dirright;
turn = 1;
}
void reset(void) //turn off steering and stop car; return to start state
{
steer_off();
speed = 0;
state = start;
}
void statemachine(void)
{
t_statemachine = deltaT; //reset machine timer
if(LEDS == 0x1f) //all LEDS off (car has been picked up in the air)
{
reset();
}
/* We want to reset the watchdog timer to 0 as long as
* at least one sensor is on the line. */
if(LEDS != 0)
{
watchdog = 0;
}
/* If the watchdog counter reaches 1.5 seconds, the car should be stopped. However,
* if we're backing up to find the line again, let it go until 3 seconds have passed. */
if((watchdog++ == 1500/deltaT) && (drivedir != rev))
{
reset();
}
else if(watchdog == 3000/deltaT)
{
reset();
}
switch(state)
{
case start: //initial state
if(LEDS == 0x04) //do nothing until only center sensor is on
{
drivedir = fwd;
speed = 200;
state = center;
}
break;
case center: //center of car is on the line
if(LL) //near left sensor on, steer left to correct
{
steer_left();
state = left;
}
else if(RR) //near right sensor on, steer right to correct
{
steer_right();
state = right;
}
break;
case left:
if(CC)
{
steer_off(); //we're back on track, go straight
state = center;
}
else if(LLL) //we're way off track, back up and turn the
{ //wheels in the opposite direction to correct
drivedir = rev;
speed = 255;
steer_right();
state = farleft;
}
break;
case right:
if(CC)
{
steer_off();
state = center;
}
if(RRR)
{
drivedir = rev;
speed = 255;
steer_left();
state = farright;
}
break;
case farleft: //we're currently backing up to find the line
if(LL) //the inner left sensor is back on the line, so
{ //go forward again & flip the steering
steer_left();
drivedir = fwd;
state = left;
}
break; //otherwise, continue backing up
case farright:
if(RR)
{
steer_right();
drivedir = fwd;
state = right;
}
break;
}
}
interrupt [TIM0_OVF] void t0(void) //establishes 1msec time base
{
TCNT0 = t0reload;
if(t_statemachine > 0) t_statemachine--;
}
void main(void)
{
initialize();
while(1)
{
if(t_statemachine == 0) statemachine(); //fire off state machine if it's time
}
}
void initialize(void)
{
DDRA = 0xff; //PORTA is an output
DDRC = 0x00; //PORTC is an input
PORTC = 0xe0; //internal pullups off, except for the top 3 unused bits
/* set up PWM to cycle every ~32 msec */
TCCR1A = 0x20 + 0x01; //non-inverted, 8-bit PWM
TCCR1B = 0x04; //prescale to 256
/* set up timer 0 to interrupt every 1 msec */
TIMSK = 0x02; //timer 0 overflow interrupt
TCCR0 = 0x03; //prescale to 64
TCNT0 = t0reload;
watchdog = 0;
t_statemachine = deltaT; //initialize task timer
state = start; //initialize state variable
#asm("sei") //fire up the interrupts
}
Appendix B: Schematics
Figure 1: H-bridge connected to drive motor
Figure 2: H-bridge used for the steering control
Figure 3: Circuit used for each photosensor
|
0 comments:
Post a Comment