Controlling Wheeled Vehicles
Controlling Wheeled Vehicles

Overview

A common type of robot is the two wheeled vehicle with independently controlled motors. This design uses differential steering and can turn in place. There are other possible mechanical designs which controlled by other classes. The classes that control vehicles work at several levels of abstraction. At bottom, there are the motors that turn the wheels, controlled by the NXTRegulatedMotor class. The DifferentialPilot class uses the motors to control elementary moves: rotate in place, travel in a straight line, or travel in an arc. At the next level, the Navigator uses a DifferentialPilot to move the robot through a complicated path in a plane. To do navigation, the navigator needs the robot location and the direction it is heading. It uses a OdometeryPoseProvider to keep this information up to date. The relationships among these classes is shown in the in the table.

Class Uses
Navigator DifferentialPilot
OdometryPoseProvider
OdometryPoseProvider DifferentialPilot
DifferntialPilot RegulatedMotor

The flow of control is from the top down: the navigator controls the pilot which controls the motors. But the flow of information is from bottom up. The pilot uses information from the motors to control them. The pose provider uses odometry information from the pilot to update its current estimate of the robot pose. The pose consists of the robot's coordinates (x and y) and its heading angle (the direction it is facing ). The navigator uses this data to calculate the distance and direction to its destination.

The flow of information uses the listener and event model. The pilot registers as a listener to with motors, which inform it when a motor rotation is started or completed. The pose provider registers as a listener with the pilot, which informs it of the start and completion of every movement. This event driven information flow is automatic. In addition to this event driven flow, the navigator can also requests a pose estimate from the pose provider at any time, even while the robot is moving. This chain of listeners is established as the DifferentialPilot and Navigator are constructed.

DifferentialPilot

The DifferentialPilot class controls a vehicle that has two driving wheels, each with its own motor. It steers the vehicle by controlling the speed and direction of rotation of its motors. It is one of several Move Controllers that are based on different mechanical designs, but the differential steering design is the simplest.
The pilot object needs to know the wiring diagram of the robot, i.e. which ports the motors are connected to and whether driving the motors forward makes the robot move forward or backward (reverse). It also needs to know the diameter of the wheels and the width of the track, i.e. the distance between the centres of the tracks of the two wheels. DifferentialPilot uses the wheel diameter to calculate the distance it has traveled. It uses the track width to calculate how far it has rotated. Obviously, both parameters must be in the same units, but they can be anything you wish. With proper adjustment of these parameters, errors in distance traveled and angle of rotation can be held do 2% or perhaps less. This information is passed to the pilot constructor. DifferentialPilot is in the lejos.robotics.navigation package. The documentation for this class is here.

Constructors:
  • DifferentialPilot(float wheelDiameter, float trackWidth, Motor leftMotor, Motor rightMotor)
  • DifferentialPilot(float wheelDiameter, float trackWidth, Motor leftMotor, Motor rightMotor, boolean reverse)
    If the motors are mounted on your robot such that the robot moves backwards when motors rotate forward, the use this constructor with the the reverse boolean to true. Then the pilot.forward() method
    will cause the robot to move forward.
  • DifferentialPilot(float leftWheelDiameter, float rightWheelDiameter(),float trackWidth, Motor leftMotor, Motor rightMotor, boolean reverse)
    If your robot will not run in a straight line on a smooth surface, there may be a small difference in the diameters of the two wheels. You can use this constructor to compensate for this manufacturing variabibility.
    All these constructors will register the DifferntialPilot as a motor listener with both motors.
Straight line movement

To control the robot moving in a straight line, use:

  • void setTravelSpeed(double travelSpeed)
    sets the speed of the motors in distance (wheel diameter)units per second
  • void forward()
    starts the robot moving forward
  • void backward()
  • void stop()

To control the distance the robot moves, use:

  • void travel(double distance)
  • void travel(double distance, boolean immediateReturn)
    distance is in the same units as wheel diameter; a negative distance means travel backwards.
  • getMovement().getDistanceTraveled()

    returns the distance the vehicle traveled since the last call of resetTachoCount()

Example:

import lejos.nxt.Button;
import lejos.nxt.Motor;
import lejos.nxt.SensorPort;
import lejos.nxt.TouchSensor;
import lejos.robotics.navigation.DifferentialPilot;

/**
 * Robot that stops if it hits something before it completes its travel.
 */
public class TravelTest {
  DifferentialPilot pilot;
  TouchSensor bump = new TouchSensor(SensorPort.S1);

  public void go() {
    pilot.travel(20, true);
    while (pilot.isMoving()) {
      if (bump.isPressed()) pilot.stop();
    }
    System.out.println(" "+pilot.getMovement().getDistanceTraveled());
    Button.waitForAnyPress();
  }

  public static void main(String[] args) {
    TravelTest traveler = new TravelTest();
    traveler.pilot = new DifferentialPilot(2.25f, 5.5f, Motor.A, Motor.C);
    traveler.go();
  }
}

You can cause the robot to begin rotating in place by using

  • void rotateLeft() or
  • void rotateRight()
If you want the rotation to stop after a certain angle, use:
  • void rotate(double angle) or
  • void rotate(double angle, boolean immediateReturn )

If angle is positive, the robot turns to the left. The immediateReturn parameter works as in the Motor methods –allowing the calling thread to do other work while the rotation task in progress. If another method is called on the pilot while the rotation is in progress, the rotation will be terminated.
You must have accurate values for wheelDiameter and trackWidth for this method to produce accurate results.

Program SquareTracer

Write a program that uses a DifferentialPilot to trace out a square, using the travel and void rotate(double degrees) methods.

Solution

Program SquareTracer2

Write a program that traces 2 squares with increasing angle at the corners, then retraces the same path in the opposite direction.. Modify the traceSquare method of program DifferentialPilot 1 so it can trace a square in either direction, and use it in this program. This is stringent test of the accuracy of the wheel diameter and track width constants you use in you pilot.

Solution

Traveling in a circular path.

DifferentialPilot can also control the robot to move in a circular path using these methods:

  • void steer(double turnRate) – follows a circular path until another method is executed
  • void steer(double turnRate, int angle)
  • void steer(double turnRate, int angle, boolean immediateReturn)

The turnRate parameter determines the radius of the path. A positive value means that center of the circle is to the left of the robot (so the left motor drives the inside wheel). A negative value means the left motor drives the outside wheel. The absolute value is between 0 and 200, and this determines the ratio of inside to outside motor speed. The outside motor runs at the set speed of the robot; the inner motor is slowed down to make the robot turn. At turn rate 0, the speed ratio is 1.0 and the robot travels in a straight line. At turn rate 200, the speed ratio is -1 and the robot turns in place. Turn rate 100 gives speed ratio 0, so the inside motor stops. The formula is: speed ratio = 100 - abs(turnRate).

The angle parameter determines the rotation angle at which the robot stops. If the angle is negative, the robot follows the circular path with the center defined by the turn rate, but it moves backwards.

Program SteerTester

Write a program that uses the ButtonCounter to enter the turn rate and angle variables, and then calls the steer() method. It does this in a loop so you can try different values of these parameters to control the robot path.

Solution

Methods that start the robot moving in a circular arc path:
  • void arc backwards(double radius) - the robot backs up
  • void arc forwards(double radius)

If the radius is positive, center of rotation is on left side of the robot. Methods that complete a circular arc:

  • void arc(double radius, double angle )
  • void arc(double radius, double angle , boolean immediate return )
Communicating with OdometryPoseProvider

The OdometryPoseProvider keeps track of the robot position and heading. To do this, it needs to know about every move made by the DifferetnialPilot. So the pose provider needs to register as a listener with the pilot by calling the addListener method. After the pilot adds pose provider as a listener, it will automatically call the moveStarted method on the pose provider every time a movement starts, and moveStopped when the move is complete. If the pose provider needs to know the status of a movement that is in progress, it calls the getMovement() method on the pilot.

Other methods for DifferentialPilot

If you need very accurate pilot movement, you might need to use speed and acceleration values less than the defaults.

  • void setRotateSpeed(double speed )
    speed in degrees per second
  • void setTravelSpeed(double speed )
    speed in wheel diameter units per second
  • void setAcceleration(double acceleration)
  • void resetTachocount()
    Resets the count for both motors, and will likely cause errors in the OdometryPoseProvider calculations.
  • boolean isMoving()
    Returns true if either motor is moving. Useful if you have used the immediateReturn parameter and need to know if the task is still in progress.
  • boolean stalled()
    returns true if either motor actual speed is zero. Remember, the actual speed is calculated every 100ms, so stalled() will return true for the first 100ms after the robot begins its move.

Back to top

Compass Pilot

The CompassPilot is an extension of the DifferentialPilot class. It implements the same methods, but uses a Compass Sensor to ensure that the pilot does not deviate from the correct angle of robot heading.

It needs a HiTechnic or Mindsensors compass sensor plugged in to one of the sensor ports. Its constructors are similar those of DifferentialPilot, but with the additional information of the compass sensor port.

Constructors:
  • CompassPilot(SensorPort compassPort, float wheelDiameter, float trackWidth,Motor leftMotor, Motor rightMotor)
  • CompassPilot(SensorPort compassPort, float wheelDiameter, float trackWidth,Motor leftMotor, Motor rightMotor, boolean reverse)
Additional methods in CompassPilot:

  • void calibrate()
    calibrate the compass sensor; rotates the robot slowly through 360 degreees.
  • setHeading(int angle)
    set the desired robot heading, in degrees in Cartesian coordinates (a left turn increases the heading)
  • int getHeading()
    return the desired robot heading
  • int getAngle()
    return the compass Cartesian angle. Also the actual robot heading assuming the compass sensor points forward.
Additional methods in CompassPilot:

Write a program that does these steps:

  1. Calibrate the compass.
  2. Rotate the robot to a heading or 90 degrees
  3. Reset the Cartesian zero of the compass sensor to correspond the current heading.
  4. Move the robot a fixed distance forward.
  5. Rotate 90 degrees to the left.
  6. Move the robot the same distance backwards.
  7. Display the compass reading and the distance traveled at the end of each move.

Suggestion: while the robot is moving, nudge it off course and watch it steer back to the correct heading.

Solution

Back to top

OdometryPoseProvider

The responsibility of this class is to maintain a current estimate of the robot location and the direction in which it is heading. The robot heading uses Cartesian coordinates, with angles in degrees; 0 degrees is the direction of the positive x axis, 90 degrees is the positive y axis. The heading and x and y coordinates are stored in a Pose object. The API for Pose is here. For the OdometryPoseProvider documentation click here.
The only constructor for this class is:

  • OdometryPoseProvider(MoveProvider mp) )
    It registers the new pose provider object as a listener with the MoveProvider.

The only methods you are likely to need to use are:

  • void setPose(Pose aPose)
    used to set the initial Pose.
  • Pose getPose()
    If this method is called while the robot is moving, the pose provider will call getMovement() on the move provider. This guarantees that the pose is current.

If you want to know about the inner workings of this class, read on.
When a movement starts of ends, the information needed to update the estimated posse is provided automatically by the Move Controller by calling one these methods:

  • void moveStarted(Move move, MoveProvider mp)
  • void moveStopped(Move move, MoveProvider mp)

The odometry data is contained in a Move object. The API of this data carrier class is here.

Back to top

Navigator

The Navigator class uses a pilot to control the robot movement, and a PoseProvider to keep track of the robot position. The navigator follows a route, a sequence of locations. Each location is an instance of the Waypoint class. The WayPoint API is here. The route is an instance of the Path class, and the Path API is here. The route behaves as a first-in-first-queue. When the a way point is reached, it is removed from the route and the robot goes to the next one. New way points can be added to the end of the route at any time. Documentation for the Navigator is here.
The Navigator can use any of the several pilot classes the implement the MoveController interface. There are two ways to construct an instance of this class:

Constructors:
  • Navigator(MoveController aPilot)
    To use this constructor, you must construct a pilot and use it as the parameter. The constuctor will create its own OdometryPoseProvider
  • Navigator(MoveController pilot, PoseProvider poseProvider
    Use this if you want to use another PoseProvider class

Both constructors will register the pose provider as a MoveListener with the pilot.

Navigation methods

All the methods (with one exception) in this class are non-blocking, i.e. they return immediatey.

  • void setPath(Path aPath)
    There are three variations of the method that adds a waypoint at the end of an existing path. They can be called at any time.
  • void addWaypoint(Waypoint aWaypoint)
  • void addWaypoint(float x, float y )

    Creates a new Waypoint and adds it
  • void addWaypoint(float x, float y , heading )
    Creates a new Waypoint and adds it ; use this to specify the heading of the robot when it gets to the waypoint.
  • void followRoute(Path aRoute )
    Start the robot following the route.
  • void followRoute()
    Starts the robot moving along an existing route. If the robot is already moving, this has no effect.
  • goTo(WayPoint destination)
    Adds destination to the end of the route and starts the robot moving.
  • void goTo(double x,double y)
    Just another way to specify the destination waypoint. Acts like the previous method.
  • void goTo(double x,double y , double heading)
    A third way to specify the destination. Acts like the previous method.
  • void stop()
    Stops the robot but preserves the route. To resume the route, call followRoute().
  • boolean isMoving()
    Returns true if the robot is moving toward a waypoint.
  • boolean pathCompleted()
    Returns true if the robot has reached the final waypoint.
  • void rotateTo(double direction)
    Rotate to the direction angle in the cartesian plane. The X axis is 0, the Y axis
    is 90 degrees.
  • void waitForStop()
    The only blocking method in this class. Returns when the robot is no longer moving.
  • void singleStep(boolean yes)
    If you want the robot to stop at each waypoint, call this method with a true parameter. You can start it moving to the next waypoint by calling followRoute()

Back to top

ShortestPathFinder

Suppose your robot is in a known location and needs to get to a destination. But there are obstacles in the way. These obstacles are shown on a map. So what route should it follow? This class can find the shortest path to the destination, and produce a route (a collection of WayPoints) that the NavPathController can use. The map this class needs is a LineMap which, as its name suggests, consists of straight lines.The complete documentation for this class is here. Using this class is very simple. The constructor is:

  • ShortestPathFinder(LineMap map)

After you constructed the path finder, you can get the route by using either of the route finding methods. They both use a Pose as the starting point, which might be returned returned by the a pose provider, and a WayPoint as the destination. The both will throw the DestinationUnreachableException if no route can be found.

  • Path findRoute(Pose start,WayPoint finish)
  • Path findRoute(Pose start, WayPoint finish, LineMap theMap)
    If you don't want to use the map specified in the constructor, you can use a different one in this method.

The shortest path, if not a direct line, will have way points at the ends of lines, such as the corners of obstacles on the map. But the physical robot is not a point, so if the center of the robot tries to pass through a corner, there will be a crash. One solution to this difficulty is to enlarge the map obstacles to allow clearance for the robot. However, this may be tedious to by hand, and complex to do with software. A simpler scheme is to extends all the lines on the original map so that a corner now is represented by two points, each some distance from the corner. To make this modification of the map,use the method :

  • void lengthenLines(float delta)

which adds a segment of length delta to each line on the map. The extension delta should probably be at least the track width of the robot, plus an allowance for uncertainties in the robot location.

There are several other path finding classes that use various map representations. See the links to the classes in the pathfinding package here.

Back to top