Overview

The Cat and Mouse Car Project

RC Cat
Figure 1. RC "Cat" Car

This was the final project for ENGR3390: Robotics for Eric Gallimore, Gui Cavalcanti,and Jon Tse. Originally, projects for ENGR3390 were supposed to be done only in simulation, but after much frustration with various simulation packages, we settled on the best simulation package available: real-world physics.

Our intent for the project was to take existing hardware, in this case a TRAXXAS E-Maxx RC truck and an off-the-shelf RC car from a local toy store, and write software enabling the truck to chase the car without direct human intervention. Our very first project idea had something to do with a cat, so we decided that calling the truck a "cat" and the target RC car a "mouse" would be a good idea.

Why is this interesting?

RC Cat Front
Figure 2. "Cat" Car Front

Well, if we had chosen an RC tank that could turn on a dime instead of the E-Maxx RC truck, it probably wouldn’t be very interesting at all. The control algorithm for a tank would be rather simplistic: If the target is to your left or right, rotate in place then travel towards the target. The problem we chose was more difficult because the E-Maxx RC truck has front-wheel steering and can’t turn without moving forward or backward, unlike a tank which can turn in place.

I can drive a car, what’s so hard about steering?

It’s not incredibly hard, but it does have its difficulties. When the target car is far away, getting to it is relatively simple. The algorithm runs something like this: Drive forward and turn towards the target. Turn sharper if the target is very far to the left or right, and drive faster if the target is farther away. This sort of control is known as proportional control.

Proportional control is a very simple way to solve this problem. So we’re done, right? Not quite. What if you’re too close to the target and you can’t turn sharply enough even at your lowest speed to drive towards it? Herein lies the difficulty of controlling steered vehicles. In fact, this is an entire class of problems known as the control of non-holonomic vehicles.

Tip
Holo-what?

Holonomic! To be holonomic means that all of your Degrees of Freedom (DoF)s are controlled. DoFs are essentially independent variables that describe a system. Your elbow, for example, is a one DoF joint. You can only bend it in one plane of motion (if you can do more, your arm is broken, go see a doctor!), and the variable tied to that is some angle describing the amount of bending your elbow is doing.

Non-holonomic vehicles are ones where all of their DoFs are not directly controlled. For example, if you have a toy car, you can move it forward/backward, left/right, and turn it in place left/right (we’re ignoring up and down and the other types of turning for now). That’s three DoFs. In that case, your car is holonomic. All of its DoFs are controlled (by you).

In a real car, there’s no way you can actually move the car in a line to the left of the way it’s facing without some serious equipment. If you want to go directly left from where you are, you’ll probably have to do a three-point-turn or some other crazy maneuver. Essentially, if you have to actuate more than one DoF to move in only one DoF, you have a non-holonomic system.

Note It’s a common misconception that tanks are holonomic vehicles. They’re not. For example, if you wanted to travel perpendicular to your heading in a tank, you’d have to stop driving forward, turn 90 degrees, then start traveling again.

Okay, how do we deal with this?

Driving towards the target isn’t really a problem, we can just naively apply proportional control to get us close to the target. However, once the distance to the target begins to approach the turning radius of the truck, then we start to have problems. At this point there isn’t any good way to continue driving forward while turning towards the target, because you can never turn in a short enough distance. As a result, we had to develop some scripted routines to control the truck. For example, backing up with the wheels turned away from the target would eventually put the truck’s heading in line with the target, at the expense of added distance to the target.

But wait, how does the "cat" know where the "mouse" is?

A large part of the project was getting some sort of location information for the "mouse" in real time to the "brain" on the "cat." In order to do this, we used IR LEDs mounted on the "mouse" as a so-called lighthouse beacon. To pick up the beacon, we used the same type of IR sensors in your TV to triangulate the location of the "mouse." By mounting the sensors on hobby servos, we can pivot them independently of the current heading of the truck.

Accomplishments

By the end of the semester, we successfully wrote both a simulation of the "cat" truck and "mouse" car that behaved as desired, as well as getting the real thing (the E-Maxx RC truck and the RC car) to work.

In order to accomplish this, we wrote a number of algorithms to triangulate the location of the RC car using the IR sensors. Using this location data, we were able to do proportional control to steer the E-Maxx RC truck towards the target car. If the truck ever got too close to the car, we had several naive non-holonomic control routines, like the routine described earlier, to get the truck back on track.

We originally did not start with this "cat and mouse" idea for our project; in fact, we switched almost halfway through the semester. All told, we are happy with the amount of systems we got functioning given the short time frame.

Mechanical Design

Equipment

RC Cat CAD
Figure 3. E-Maxx RC Truck CAD Model

In order to convert the E-Maxx RC truck into a embedded-computing platform, we need to add components such as microcontrollers, power supplies, hobby servos, motor controllers, and sensors. Since the E-Maxx RC truck was never intended to carry a load, and had no flat surface to mount components to. As a result, mounting the equipment on the truck required the fabrication of a mounting plate.

Fortunately, another project team at Olin had used the E-Maxx truck before in a navigation project, so we had access to detailed CAD drawings of the E-Maxx truck. Before long, we had developed a suitable mounting plate for the components that fastened to the posts for the stock E-Maxx truck’s shell.

Mounting Plate

Mounting Plate
Figure 4. Mounting Plate CAD Model

Since we needed to mate the the mounting plate with the posts in the truck’s superstructure, the dimensions of the holes had to be very precise. Additionally, because of the truck’s suspension, the posts do not stay the same distance from each other at all times, so the material we chose for the plate had to be flexible.

In the end, we went with a clear polycarbonate resin thermoplastic, Lexan, which is flexible enough to deal with the posts moving, as well as being machinable on an abrasive waterjet cutter. An abrasive waterjet cutter uses high-pressure water as well as an abrasive grit to cut plastics and metals, and has a a sufficient accuracy for the mounting plate post holes.

Electrical Design

E-Maxx RC Truck Circuitry

Power System

Control Boards
Figure 5. RC Truck Control Boards

The E-Maxx RC truck’s stock power supply is a pair of 7.2V batteries in series for a total of 14.4V. The only components on the truck that run at 14.4V were the main drive motors. Seeing as we had to run a PIC for logic and control, as well as some hobby servos, we added some additional batteries.

For the PIC, we put in a 9V battery and installed a voltage regulator to bring the voltage down to 5V. To power the hobby servos, we attached 4 AA cells in series for a 6V battery pack.

As a safety feature, we used a 30A circuit breaker on the main drive motor circuit, and added a servo to trip it on release of a radio "deadman’s switch".

Tip
Deadman’s Switch

A "deadman’s switch" is usually used for safety. The default state of the switch is depressed. When the switch is released, the saftey routines kick in, and the system turns off.

Colloquially, this sort of thing was used to protect oneself. If one was holding a deadman’s switch when killed, presumably one would release the switch and something unfortunate would befall the killer, most likely something to do with lots of explosives.

Motor Controller

The stock TRAXXAS motor controller on the E-Maxx RC truck proved to be inadequate for our uses. During intended use, the stock controller is more than sufficent, because all you’re trying to do is drive the truck around with a radio controller. We wanted the truck to move as slowly as possible, but the stock speed controller cut off the bottom 10% of the input command range and kept the minimum speed of the truck to about jogging speed. However, because the top speed of the E-Maxx truck is 25mph, we needed to be able to go as slow as possible. The stock controller has a deadzone of about 10%, so we installed a Victor 885 from IFI Robotics, which has a deadzone of 3% and a a current capacity of 120A, which exceeded our needs.

Tip
Deadzone

A deadzone, in this context, is essentially the range of input values that are ignored. So the stock TRAXXAS controller ignores the first 10% of the input range in both the positive and negative directions from its set zero point, and the Victor 885 only ignores the first 3%.

Sensors

Servo Head
Figure 6. Sensor Platforms

We used the TSOP22xx series IR sensors from Vishay Semiconductors, which are typically designed for use in something like a TV set or other IR remote-controllable devices.

TV’s and other remote controlled devices are often around sunlight or other sources of ambient IR radiation. In order to help reduce interference from these outside sources, remote control signals are modulated on a carrier frequency of 38kHz (typically). The TSOP22xx series IR sensors do exactly that, by band-passing a frequency range near 38kHz and demodulating the sent signal.

The TSOP22x series are digital, meaning we cannot determine distance to the IR source by measuring the signal’s intensity. Also, the sensors have a limited cone of "vision." To address both of these issues, we mounted two angularly offset sensors on a custom PCB in order to obtain directional data. That is, if the left sensor on the PCB is on but not the right one, we know that the target is somewhere to the left of the centerline of the PCB.

Logic/Control System

PIC
Figure 7. PIC Board

For the logic and control components of the truck, we used the PIC18F2455 microcontroller from Microchip and the SSC-32 servo controller from Lynxmotion. The SSC-32’s logic and the PIC18F2455 were both run off of the 9V battery, although the PIC was run off of a 5V voltage regulator. The SSC-32 servo power buses were run off of the 4 AA cell 6V battery pack.

The IR sensors were connected directly to the PIC and powered off the same 5V source from the voltage regulator, and all of the servos as well as the Victor 885 controller were all connected to the Lynxmotion SSC-32 board. All of the decision making is done on the PIC after the sensors are polled, and the output is sent over RS-232 serial to the SSC-32 which controls the servos and speed controller appropriately.

RC Car Circuitry

Power System

Mouse
Figure 8. RC "Mouse" Car

We started with 4 AA cells to power the beacon, but since each of the 12 LEDs pull 0.1A by themselves, this proved to drain the AA cells extremely quickly. We decided it might be a good idea to invest in some recharagable NiMH AA cells. Unfortunately, due to the large current draw and the slight differences in voltage across the NiMH AA cells, one of the four was drained disproportionately quickly and became reverse-biased, resulting in irreparable damage. In the end, we switched to using an external power supply that was more than capable of providing the required power.

The drive train of the RC car was powered by 4 AA cells. In this case, the AA cells were sufficient, even though they were not the factory-approved power solution for the car.

Beacon

Beacon
Figure 9. IR Beacon

The most important part of the target RC car is the IR beacon. Since the IR sensors bandpass a frequency range around 38kHz, we needed a way to generate a 38kHz square wave.

In the end, we used a 555 timer tuned to 38kHz with a precision capacitor and a potentiometer. After several prototypes, we managed to get the 555 timer working. However, because of the relatively high 0.1A current draw from the IR LEDs, we needed to use a MOSFET to drive them.

One thing we neglected to do was add an pull-up transistor to our circuit, so the resultant wave was not a perfectly formed square wave. As a result of this, the IR sensors, which typically have a range on the order of the length of a large room, only were able to detect the beacon within about five feet.

Algorithms

There were two main sets of algorithms used to control the E-Maxx truck. The first set of algorithms control the sensors and triangulates the position of the target. The second set of algorithms control the drive train.

Sensor Algorithms

Sensor Algorithms
Figure 10. Sensor Algorithm Visualization

The E-Maxx truck has two "eyes", with two binary sensors each. Each sensor reports if it sees the target or not, and as a whole each eye reports if it sees the target with both sensors, just one sensor, or neither. We used hobby servos to position each eye, and we know the angle command we’re sending to each hobby servo; therefore, we can integrate the result of an eye seeing a target with one, both or no sensors with its angle to the car. The two binary sensors see the target within a certain cone (roughly a 45 degree angle) centered around the direction they are pointing, and the eyes are designed to maintain an angle of approximately 5 degrees between sensors. The truck has no sensor that can detect exactly where the target is, so the four algorithms that we have implemented are state machines that attempt to guess the position of the target as best they can under certain circumstances.

Parameter Controller

The parameter controller was the first and simplest of all four state estimators developed. Both eyes are always focused on a single point, which the controller returns as the guess of the target position. This intersection of servo angles moves based on what each eye reports that it sees.

The parameter control works by only changing either the radius of the guess or the angle of the guess. If each eye sees the target with both sensors, the guess does not move. If only the left eye or only the right eye sees the target, the angle of the guess changes to follow the targets' new move. If the target enters one of the crossed zones where three sensors see the target, the guess changes radius to follow the target.

The parameter controller relies a damping effect on its changes of radius and angle. Every time it changes state, it analyzes how long it has been in the previous state and the current radius and continues the change in angle or radius for a proportional amount of time. This minimizes the hysteresis inherent in a multi-state system, and assumes the target and the car have some inertia which will not allow for instantaneous changes in position.

Static Averager

The static averager was created in order to find as exact a position as possible when the E-Maxx is stationary and the target is moving relatively slowly. The static averager sweeps both eyes from left to right and records changes in eye state and the angle at which those changes occurred. When each eye has changed state twice, the static averager decides on a servo angle that is the average of the two state change events, and focuses both servos on the intersection of the two angles.

Wiggle Controller

The wiggle controller was created as an addition to the parameter controller when it was found that the parameter controller lost ranging information too easily for targets moving radially towards or away from the the cat. The wiggle controller kicked in after a certain amount of time had elapsed, and purposefully moved the focused eyes through a change in angle in order to observe a state change event. Once the event had been observed, the parameter controller kicked in and generated a position guess.

Brute Force Controller

The brute force controller was created to attempt to generate faster, more accurate guesses on target location by keeping the eyes in continuous motion. Each eye panned right and left, attempting to keep both sensors focused on the target by reversing the travel direction every time it observed a sensor state change. The controller stored the angle of state change in a buffer and compared it to the next angle update from the other eye to compute the next guess intersection. The oscillation of the two eyes was linked by a damping constant in order to ensure that the eyes were either moving towards each other or away from each other. This decreased the time between one eye registering a state change and the other registering a state change, which was critical for an accurate guess of current position.

Driving Algorithms

Proportional Control

What’s proportinal control? Typically you have some desired value, in this case, you want to be pointed directly at the target, so you take the direction heading from you to your target. You then take your current value: your current heading in this case, and take the difference of the two values.

The thing you control, the steering wheel, is then moved proportionally to the difference, which is typically referred to as the "error." As a result, you will turn the steering wheel more sharply if your target is far from your current direction of travel.

Another example is the gas pedal. If your target is far from where you are (the error is great) you will step harder on the gas pedal. If your target is close, you don’t step on the pedal quite as hard.

Main Driving Algorithm

The main driving algorithm essentially checks to see if the target is closer than 50 inches. If it is, then it will run the parallel_park() function. If it farther than 50 inches, we should run the proportional control driving algorithm.

function [car_self,car_world,sim_params] = ...
  car(car_self,car_world,L_Turret,R_Turret,Guess,Target,sim_params)

    if(abs(Guess.Y) > 50)
        sim_params.Car.Ctrl_Name = 'Parameter';
        [car_self,car_world,sim_params] = ...
          parameter_drive(car_self,car_world,L_Turret,...
            R_Turret,Guess,Target,sim_params);
    else
        sim_params.Car.Ctrl_Name = 'Parallel';
        [car_self,car_world,sim_params] = ...
          parallel_park(car_self,car_world,L_Turret,...
            R_Turret,Guess,Target,sim_params);
    end
end

parallel_park()

The parallel_park() algorithm essentially turns the truck’s wheels in the opposite direction of the target’s location, and backs the car up until the truck’s heading angle is within a certain error angle of the target. That is, the truck will execute a backup turn until it faces the target once again.

function [car_self,car_world,sim_params] = ...
  parallel_park(car_self,car_world,L_Turret,R_Turret,Guess,Target,sim_params)

    sim_params.timesteps = 1;
    ctrl_params.min_turn_r = 1;    %Ctrl_Params.Overshoot_Angle = 0.0625;
    ctrl_params.heading_threshold = 15/180*pi;
    Guess.Angle = atan(Guess.X/(Guess.Y + sim_params.Turret.Y));
    if (abs(Guess.Angle) >= ctrl_params.heading_threshold || abs(Guess.Y) > 50)
        sim_params.Car.Ctrl_Name = 'Parameter';
        [car_self,car_world,sim_params] = ...
          parameter_drive(car_self,car_world,L_Turret,...
            R_Turret,Guess,Target,sim_params);
        return
    elseif (Guess.Angle > 0)
        [car_self,car_world] =
          car_kinematics(-1,-ctrl_params.min_turn_r,car_self,...
            car_world,Guess,Target,sim_params);
    elseif (Guess.Angle < 0)
        [car_self,car_world] =
          car_kinematics(-1,ctrl_params.min_turn_r,car_self,...
            car_world,Guess,Target,sim_params);
    else
        disp('Something broke');
    end
end

parameter_drive()

The parameter_drive() algorithm uses proportional control to drive the truck. If the truck is far away from the target, the truck will drive faster. If the target is very far to the right or left, the truck will turn more sharply.

function [car_self,car_world,sim_params] = ...
  parameter_drive(car_self,car_world,L_Turret,R_Turret,Guess,Target,sim_params)
    sim_params.timesteps = 1;
    volts = max(Guess.Y/200,0);
    turn_radius = sign(Guess.X)*max(abs(10/Guess.X),0.5);
    [car_self,car_world] = ...
      car_kinematics(volts,turn_radius,car_self,car_world,Guess,Target,sim_params);
end

Simulation

Part of the requirement for the ENGR3390 final project was to write a simulation of the robot. Using MATLAB, we wrote a simple simulation of the E-Maxx truck that can drive around and chase a target.

The target’s path was generated using polar coordinates and parametric equations as follows:

function [Target] = MovingTarget(t)
    %[x,y] = pol2cart(t*scalingfactor,heightofpole*...
    %  sin_or_cos(numpoles*t*scalingfactor));
    % Time scaling factor
    k = 1;
    [Target.X Target.Y] = pol2cart(t*k,60*cos(3*t*k));
    Target.Y = Target.Y + 120;
    return
end

As time increments, the position of the particle follows a the path described by the equation in polar coordinates.

Driving Simulation

In order to drive the truck around, we used a simplied version of Ackerman steering. Assuming that the friction that the wheels are capable of exerting is infinite, we can use the forward velocity of the truck as well as a desired turning radius to calculate the centripetal acceleration. We also know the tangential acceleration of the truck, because we can specify how much torque the motors are exerting. Using both of these acceleration vectors, we run a simple forward Euler solver to calculate the kinematics of the car, thus obtaining a velocity vector and a displacement.

Tip
Ackerman Steering

Ackerman steering is a model for front wheel steering and is commonly found in most cars today. The idea is that when a car turns, it turns about a point colinear with the rear axle.

The front wheels of the car circumscribe concentric circles about this turning point during the turn, which means they are tangent to the circles. However, since the front wheels are not on the same radial ray from the turning point, they must turn different amounts to be tangent to the concentric circles of the turn.

Using the difference in displacement between timesteps, along with the velocity vector, we can determine the heading of the truck at all times. In turn, this enables us to use a translation matrix to find the location of the target in the coordinate system of the truck, where the truck’s heading is the y-axis, and the center of the rear axle of the car is the origin of the origin system.

Having this information is vital for the sensor simulation, which has no concept of world space, and assumes that the truck is completely stationary and that only the target is moving. For more information on the driving control algorithms, please look at the Algorithms section.

Sensor Simulation

The sensors were simulated as simplified versions of the real thing. The real physical sensors have a teardrop shaped field of view, but we chose to model that as a cone with a specified angle. Also, on the actual robot, the sensors are offset horizontally by the width of the PCB, but because that distance is negligible, we consider them to be colocated in the simulation.

We know how fast the hobby servos that the sensors are mounted on can move, so we can use forward Euler to calculate how far the servos travel in a given timestep, assuming instantaneous acceleration. All of these calculations allow us to sweep the sensors and search for the target.

To determine if the sensors could see the target, we simply looked at the target’s position in the truck’s frame of reference. If the target was within a sensor’s cone, that sensor was said to "see" the target. This digital behavior mimics the actual behavior of the physical sensor, albeit without the range limitations. Knowing which sensors could see the target as well as where the sensors were facing allows us to run a number of different triangulation algorithms to guess where the target is. For a detailed look at the different sensor algorithms, please look at the Algorithms section.

Implementation

Sensors

Below is a snippet of the sensor code as implemented for the PIC. It doesn’t implement all of the algorithms, but it does implement a variant of the Brute Force Controller.

// Move the eyes...
if (LeL & !LeR) {
        // It's to the left.  Move unless we're already at a limit.
        if (eyeLeft > 1000) {
                eyeLeft -= 20;
                leftDir = -30;
        }
}
if (LeR & !LeL) {
        // It's to the right.  Move unless we're already at a limit.
        if (eyeLeft < 2000) {
                eyeLeft += 20;
                leftDir = 30;
        }
}
if (!LeL & !LeR) {
        // We don't see it.  Go in whatever direction we last saw it.
        if ((eyeLeft < 2000) & (eyeLeft > 1000)) {
                eyeLeft += leftDir;
        }
}
if (ReL & ~ReR) {
        // It's to the left.  Move unless we're already at a limit.
        if (eyeRight > 1000) {
                eyeRight -= 20;
                rightDir = -30;
        }
}
if (ReR & !ReL) {
        // It's to the right.  Move unless we're already at a limit.
        if (eyeRight < 2000) {
                eyeRight += 20;
                rightDir = 30;
        }
}
if (!ReL & !ReR) {
        // We don't see it.  Go right anyway.
        if ((eyeRight < 2000) & (eyeRight > 1000)) {
                eyeRight += rightDir;
        }
}

Driving

Below is a simple implementation of the proportional control algorithm for driving the car.

// Determine steering

// find average direction and recenter about zero
curvature = (eyeLeft + eyeRight) / 2 - 1500;
//scale the value appropriately to send it to the servo board
steering = 1500 + (curvature);

// deal with the case where we don't see it.
if (~LeL & ~LeR & ~ReL & ~ReR) {
        steering = 2000;        // Drive hard right
}

// Determine speed
if (eyeLeft-eyeRight == 0){
        // this is a discontinuity
        speed = 1600;           // something that looks good
} else {
        // the more cross-eyed, the closer.  Scaled to send to the servo board.
        speed = 1/(eyeLeft - eyeRight) + 1500;
        // NOTE: the above line has a possible error condition,
        // where the sensors are pointed away from one another
}