LIDAR Odometry with ICP

This post is the second in a series of tutorials on SLAM using scanning 2D LIDAR and wheel odometry. The other posts in the series can be found in the links below. The links will be updated as work on the series progresses.

In the previous post I introduced the Intel Research Center (IRC) Dataset and we used it in some basic visualizations. In particular, I used the robot’s odometry to get a rough estimate of its pose over time by simply concatenating the relative transformations between timesteps, T_i 0 \leq i \leq n:

    \begin{equation*} T_n = T_1 T_2 \dots T_n \end{equation*}

I then used the transform T_n to project the laser scan at each timestep into the global coordinate frame: p_g = T_n p_l where p_g is the set of homogeneous scan points in the global frame, p_l is the set of homogeneous points in the robot’s local frame, and T_n is the estimated transform between the global and local coordinate frames. This process is visualized in VisualizeMeasurements.py in my github repo:

Visualization of the odometry and lidar measurements together.

Watching this visualization even over a short time, it’s obvious that the robot’s odometry is very noisy and collects drift very quickly. With perfect odometry, the objects measured by the LIDAR would stay static as the robot moves past them. This is clearly not the case. Interestingly, the odometry seems to be fairly reliable for translational motion, but it drifts quickly in rotation. This will be significant later.

How Do We Fix The Drift Problem?

It’s clear to us the robot’s wheel odometry isn’t sufficient to estimate its motion. We know this because we can overlay the robot’s LIDAR scans in our minds and get a sense of how the robot’s estimated motion is deviating from its true motion. If we can do this in our minds, could we tell the robot how to do it? Can the robot use its LIDAR scans to estimate its own motion?

Hopefully you’ve guessed the answer is yes, through a process called scan matching. Basically the goal is to take a new scan from the robot’s LIDAR and find the transformation that best aligns the new scan with either previous scans or some sort of abstracted map. There are many ways to implement this idea and for this tutorial I’m going to demonstrate the simplest method: using the Iterative Closest Point (ICP) algorithm to align the newest LIDAR scan with the previous scan.

Iterative Closest Point In Pictures

The ICP algorithm involves 3 steps: association, transformation, and error evaluation. These are repeated until the scans are aligned satisfactorily. I’ll first demonstrate the process pictorially with an example from the IRL dataset and delve into the math below. Let’s first imagine we want to find the transformation that aligns the two scans pictured below. The previous scan, referred to as the target, is in cyan while the new scan, also called the source is in magenta. The goal is to find the rigid transformation (rotation and translation) that best aligns the source to the target.

Two scans we wish to align using ICP

Our first step in estimating this transformation is to decide which points in the source scan correspond to the same physical features as points in the target scan. The simplest way to do this is through a nearest neighbor search: points in the source scan are associated to the nearest point in the target scan. In the image below I’ve found the nearest neighbors of each point in the target scan. Associated points are connected with blue lines:

The association step

We can immediately see some mistakes in the nearest neighbor search, but in general the associations pictured will pull the source points in the right direction. The next step in the process is transformation. We find the transformation that, when applied to the source points, minimizes the mean-squared distance between the associated points: \tilde{T}=\underset{T}{\text{argmin}}\frac{1}{N}\sum_i^N \|t_i - Ts_i\|^2 where \tilde{T} is the final estimated transform and t_i and s_i are target points and source points, respectively. The result of this estimation is pictured below:

Result of the first transformation step

After this we evaluate the error in the alignment as e=\frac{1}{N}\sum_i^N \|t_i - Ts_i\|^2 and decide if we need to repeat the above process. In this case our scans still aren’t aligned very well, so we redo the associations with the transformed source points and repeat the process.

Nearest neighbor associations for the transformed source points

After five iterations our scans the algorithm finds a pretty good alignment:

Scan alignment after the fifth iteration

The Math Details

ICP is actually pretty straightforward, mathematically. The association step is pretty simple. It can just be a brute-force search for the nearest pairs of points between the source and target scans. If you’re working with large scans though, it’s a good idea to use KD Trees for this step.

The real trick to ICP is in the transformation step. Basically, we find the covariance between the two point sets, the matrix M.

    \begin{equation*} M = PQ^T  \end{equation*}

Where P is a matrix whose i^\text{th} column is s_i - \mu_s or the i^\text{th} source point expressed relative to the centroid of the source point set \mu_s. Similarly, Q is a matrix whose i^\text{th} column is t_i - \mu_t. Once we have the covariance matrix M, we find the rotation R between the two point clouds using singular value decomposition:

    \begin{align*} M &= UWV^T \\ R &= VU^T \end{align*}

If you’re wondering how you break the M matrix down into U, W, and V^T, know that most linear algebra packages (including matlab and numpy) have functions for SVD. That’s about as far as you need to get into it. If you’re interested though, the wikipedia page has some good details.

We’ve found the rotation R between the point sets, now we just need the translation t. Luckily it’s pretty simple, just the difference between the centroids of the point clouds t = \mu_t - \mu_s.

Once we have our translation and rotation we evaluate the alignment error as e=\frac{1}{N}\sum_i^N \|t_i - Rs_i + t\|^2. We use this to determine if we should quit or iterate again. Normally we stop the process if the error at the current step is below a threshold, if the difference between the error at the current step and the previous step’s error is below a threshold, or if we’ve reached a maximum number of iterations.

Below is a visualization of a simple ICP motion estimation algorithm. It simply aligns the newest scan to the previous scan to find the motion of the robot between scans:

Demonstration of motion estimation using ICP

Note that this method for motion estimation works pretty well sometimes. If the robot is near large sections of wall at different angles it can estimate its transformation between scans pretty reliably. This is because it has good environmental queues to its motion in all directions. On the other hand, if the robot is in a mostly straight hallway, there’s really nothing in its measurements that will tell it how it’s moving along the hallway. One alignment is as good as any other as long as the walls line up. In these cases the robot’s estimates of its translation are very poor. Similarly, if there just aren’t a lot of unique, persistent features in the scan, which happens sometimes when the robot approaches corners, there aren’t any good cues for the robot to estimate its rotation.

So, matching successive LIDAR scans via the iterative closest point algorithm can give our robot some information about its own movement. However, this on its own is not enough to provide a reliable motion estimate. Luckily, our robot has wheel odometry in addition to LIDAR. Even luckier, in fact, ICP is pretty reliable at estimating rotations but poor with translation in some cases. The wheel odometry, on the other hand, gives us very accurate translation but it is very unreliable with rotation. Next time, we’ll experiment with fusing information from these two sensors to create a more reliable motion estimate.

The Code

Below you can see an implementation of the ICP algorithm in python. You can find the full class, Align2D.py, in my github repo as well as a demonstration of its use in VisualizeICP.py.

# uses the iterative closest point algorithm to find the
# transformation between the source and target point clouds
# that minimizes the sum of squared errors between nearest 
# neighbors in the two point clouds
# params:
#   max_iter: int, max number of iterations
#   min_delta_err: float, minimum change in alignment error
def AlignICP(self, max_iter, min_delta_err):

	mean_sq_error = 1.0e6 # initialize error as large number
	delta_err = 1.0e6    # change in error (used in stopping condition)
	T = self.init_T
	num_iter = 0         # number of iterations
	tf_source = self.source

	while delta_err > min_delta_err and num_iter < max_iter:

		# find correspondences via nearest-neighbor search
		matched_trg_pts,matched_src_pts,indices = self.FindCorrespondences(tf_source)

		# find alingment between source and corresponding target points via SVD
		# note: svd step doesn't use homogeneous points
		new_T = self.AlignSVD(matched_src_pts, matched_trg_pts)

		# update transformation between point sets
		T = np.dot(T,new_T)

		# apply transformation to the source points
		tf_source = np.dot(self.source,T.T)

		# find mean squared error between transformed source points and target points
		new_err = 0
		for i in range(len(indices)):
			if indices[i] != -1:
				diff = tf_source[i,:2] - self.target[indices[i],:2]
				new_err += np.dot(diff,diff.T)

		new_err /= float(len(matched_trg_pts))

		# update error and calculate delta error
		delta_err = abs(mean_sq_error - new_err)
		mean_sq_error = new_err

		num_iter += 1

	return T

# uses singular value decomposition to find the 
# transformation from the target to the source point cloud
# assumes source and target point clounds are ordered such that 
# corresponding points are at the same indices in each array
#
# params:
#   source: numpy array representing source pointcloud
#   target: numpy array representing target pointcloud
# returns:
#   T: transformation between the two point clouds
def AlignSVD(self, source, target):

	# first find the centroids of both point clouds
	src_centroid = self.GetCentroid(source)
	trg_centroid = self.GetCentroid(target)

	# get the point clouds in reference to their centroids
	source_centered = source - src_centroid
	target_centered = target - trg_centroid

	# get cross covariance matrix M
	M = np.dot(source_centered.T,target_centered)

	# get singular value decomposition of the cross covariance matrix
	U,W,V_t = np.linalg.svd(M)

	# get rotation between the two point clouds
	R = np.dot(V_t.T,U.T)

	# get the translation (simply the difference between the point clound centroids)
	t = trg_centroid - src_centroid

	# assemble translation and rotation into a transformation matrix
	T = np.identity(3)
	T[:2,2] = np.squeeze(t)
	T[:2,:2] = R

	return T

def GetCentroid(self, points):
	point_sum = np.sum(points,axis=0)
	return point_sum / float(len(points))

Obstacle Avoidance

 

At long last I’ve gotten around to doing a post on obstacle avoidance! Thanks to everyone for your patience.

When I started writing this post it had been months since I had last thought about obstacle avoidance. I opened my obstacle avoidance sketch for Colin intending to use it for this post unchanged but it looked terrible. It was a kludgy mess of nested if/else statements. So I took a few hours to totally rewrite my code and make it more efficient and readable. Revisiting old programs can be a great opportunity to reevaluate previous work.

Anyway, the basic idea behind obstacle avoidance is pretty simple. Colin, my mobile robot, can sense objects around himself. If he gets too close to an object he turns away and goes off in another direction. Easy, right?

Wiring Diagram
Program Design
Example Sketch
Video


Preliminaries

We’ll be using HC-SR04 ultrasonic sensors for this tutorial. If you’ve never used ultrasonic sensors before you should take a look at my tutorial. This tutorial also uses DC motors. If you’ve never used DC motors with an Arduino before, take a look at my motor control tutorial.

There is one problem to address right away: the configuration of our sensors. HC-SR04 sensors have a roughly 30° field of view, so with just one sensor Colin won’t be able to see anything to his sides.

Others have solved this problem by mounting a sensor on a servo so the sensor rotates and sweeps out a larger field of view. This instructable is a good example of the technique.

For my purposes it was easier to use an array of three sensors, however. With sensors facing forward, left and right Colin gets a pretty good picture of what’s around him. He still has blind spots at +45° and -45° though, so I’m planning on adding two more sensors.

top


Wiring Diagram

Wiring up the sensors and motors is pretty simple. We really just have to combine the wiring diagrams from the motor control tutorial and the ultrasonic sensor tutorial. Wire the components per the diagram below and you’ll be in good shape.

Wiring diagram for obstacle avoidanceIt’s come to my attention that, on some displays, the color of the TRIG and ECHO wires for the left sonar sensors is very similar to the color of the +5V wire. These wires SHOULD NOT connect, however.

top


Program Design

Before we get into actually writing the obstacle avoidance program we have to decide: how should Colin react to sensor inputs?

The simplest thing we could do is have Colin turn 90º to the left whenever one of his sensors sees an obstacle in front of him. But what if there is also an obstacle to his left? He would turn directly into the obstacle on his left while trying to avoid the one in front of him. What if there is an obstacle on Colin’s left or right but no obstacle in front? Clearly there are several possibilities here.

We need to identify the set of situations Colin might encounter that require him to react. Then we need to identify what those situations look like to Colin in terms of sensor inputs. Lastly, we need to specify an action for Colin to take in each situation.

Let’s assume Colin only needs to take action when an obstacle is within a certain distance. We can call this distance, dr for reaction distance. When the distance from one or more of Colin’s sensors to the nearest obstacle is less than dr Colin needs to take action to avoid the obstacle(s). The table below breaks down the situations and sensor inputs that require Colin to react and the action Colin could take.

Reaction Matrix

Obstacle Locations Left Distance Front Distance Right Distance Response
No Obstacles > dr > dr > dr Drive forward
Front > dr < dr > dr Turn left 90°
Front and right > dr < dr < dr Turn left 90°
Front and left < dr < dr > dr Turn right 90°
Front, left and right < dr < dr < dr Turn left 180°
Left and right < dr > dr < dr Turn left 180°
Right > dr > dr < dr Turn left 45°
Left < dr > dr > dr Turn right 45°

Notice that our reaction matrix requires Colin to turn by a number of degrees for most of his reactions. But Colin has no way of knowing how far his wheels have turned, which would be required for him to know how many degrees he’s turned. The best we can do for now is set Colin’s motors to run at different speeds for a certain time interval. Through trial and error we can find the speed differential and time interval required to get a specific amount of turning. This is an approximate solution but we can’t do any better until we add encoders to Colin’s motors.

top


Example Sketch

/*
 * Obstacle avoidance example
 * by Andrew Kramer
 * 8/3/2015
 *
 * Uses 3 ultrasonic sensors to determine
 * if nearest obstacle is too close.
 * Outlines 8 possible cases for
 * positions of obstacles.
 */

#include <NewPing.h>

#define RH_PWM 3 // PWM pin for right hand motor
#define RH_DIR1 4 // direction control for right hand motor
                  // BIN1 pin on motor controller
#define RH_DIR2 5 // direction control for right hand motor
                    // BIN2 pin on motor controller
#define LH_PWM 9 // PWM pin for left hand motor
#define LH_DIR1 7 // direction control for right hand motor
                     // AIN1 pin on motor controller
#define LH_DIR2 8 // direction control for left hand motor
                     // AIN2 pin on motor controller
#define DEFAULT_SPEED 25 // default PWM level for the motors
#define TURN_DIST 25 // distance at which the bot will turn
#define MAX_DISTANCE 200 // max range of sonar sensors
#define NUM_SONAR 3 // number of sonar sensors
#define NUM_CASES 8 // number of reaction cases

#define MS_PER_DEGREE 10 // milliseconds per degree of turning

NewPing sonar[NUM_SONAR] = { // array of sonar sensor objects
  NewPing(13, 13, MAX_DISTANCE), // left
  NewPing(12, 12, MAX_DISTANCE), // front
  NewPing(11, 11, MAX_DISTANCE) // right
};

/*  
 *  stores a bool for each sensor (left, front, and right respectively
 *  true if nearest obstacle is within TURN_DIST
 *  true if not
 */
bool sensor[3] = {false, false, false}; 

// stores all possible sensor states
bool reactions[NUM_CASES][NUM_SONAR] = { 
   {false, false, false}, // 0: no obstacles
   {false, true, false},  // 1: obstacle in front
   {false, true, true},   // 2: obstacles front and right
   {true, true, false},   // 3: obstacles front and left
   {true, true, true},    // 4: obstacles front, left, and right
   {true, false, true},   // 5: obstacles left and right
   {false, false, true},  // 6: obstacle to the right
   {true, false, false} }; // 7: obstacle to the left

void setup() {
  for (int pin = 3; pin <= 9; pin++) {
    pinMode(pin, OUTPUT); // set pins 3 through 9 to OUTPUT
  }
  Serial.begin(9600);
}

void loop() {
  updateSensor();
  switch (compareCases()) {    
    case 0: // no obstacles
      straightForward();
      break;
    case 1: // obstacle in front
      turnLeft(90);
      break;
    case 2: // obstacles front and right
      turnLeft(90);
      break;
    case 3: // obstacles front and left
      turnRight(90);
      break;
    case 4: // obstacles front, left, and right
      turnLeft(180);
      break;
    case 5: // obstacles left and right
      turnLeft(180);
      break;
    case 6: // obstacle to the right
      turnLeft(30);
      break;
    case 7: // obstacle to the left
      turnRight(30);
      break;
  }
  delay(100);
}

void updateSensor() {
  for (int i = 0; i < NUM_SONAR; i++) {
    int dist = sonar[i].ping_cm();
    // if sonar returns 0 nearest obstacle is out of range
    if (dist == 0) sensor[i] = false;
    else sensor[i] = dist < TURN_DIST;
  }
}

int compareCases() {
  for (int i = 0; i < NUM_CASES; i++) {
    bool flag = true;
    for (int j = 0; j < NUM_SONAR; j++) {
      if (reactions[i][j] != sensor[j]) flag = false;
    }
    if (flag) return i;
  }
}

void setLeftForward() {
  digitalWrite(LH_DIR1, HIGH);
  digitalWrite(LH_DIR2, LOW);
}

void setRightForward() {
  digitalWrite(RH_DIR1, HIGH);
  digitalWrite(RH_DIR2, LOW);
}

void setBothForward() {
  setLeftForward();
  setRightForward();
}

void setLeftBackward() {
  digitalWrite(LH_DIR1, LOW);
  digitalWrite(LH_DIR2, HIGH);
}



void setRightBackward() {
  digitalWrite(RH_DIR1, LOW);
  digitalWrite(RH_DIR2, HIGH);
}

void setBothBackward() {
  setRightBackward();
  setLeftBackward();
}

void setLeftSpeed(int speed) {
  analogWrite(LH_PWM, speed);
}

void setRightSpeed(int speed) {
  analogWrite(RH_PWM, speed);
}

void setBothSpeeds(int speed) {
  setLeftSpeed(speed);
  setRightSpeed(speed);
}

// sets direction of both motors to forward and sets both speeds
// to default speed
void straightForward() {
  setBothForward();
  setBothSpeeds(DEFAULT_SPEED);
}

void turnLeft(int deg) {
  setBothSpeeds(0);
  delay(100); // delay to allow motors to stop before direction change
  setLeftBackward();
  setBothSpeeds(DEFAULT_SPEED);
  delay(MS_PER_DEGREE * deg); // allow time for the bot to turn
  straightForward(); // resume driving forward at default speed
}

void turnRight(int deg) {
  setBothSpeeds(0);
  delay(100); // delay to allow motors to stop before direction change 
  setRightBackward(); 
  setBothSpeeds(DEFAULT_SPEED); 
  delay(MS_PER_DEGREE * deg); // allow time for the bot to turn
  straightForward(); // resume driving forward at default speed
}

You probably won’t be able to load up the code on your differential drive robot and run it, even if you have it wired properly. Depending on how you have the motors wired, one or both of them might run backward. To fix this you should just swap the values in the DIR1 and DIR2 fields for the problematic motor. Also, you may have to adjust the value of MS_PER_DEGREE to get accurate turning.

You’ll notice most of the code in the above sketch is devoted to simply controlling the two motors: setting motor directions, PWM levels, etc. In fact, very little of the above sketch codes for higher level behaviors like deciding when and how to react to obstacles. This makes the sketch more difficult to read and it will only get worse when we add encoders to the mix.

To fix this I’ve developed a motor control library. Encapsulating the motor control code in separate motor objects allows us to focus on programming high-level behaviors without worrying too much about how we’re controlling the motors. I’ll present my motor control library (and make it available for download) in my next post.

top


Video

Below you can see a video of Colin running the above example sketch.

You’ll notice that Colin always stops before making a turn. This slows him down and makes his behavior appear jerky. New methods could be added to the sketch to allow Colin to turn while still moving forward in some situations. These methods would simply slow down the wheel on the inside of the turn rather than reversing it. This could be useful when Colin approaches an obstacle obliquely. In this case only a minor course correction is required so a small, smooth turn is better than stopping, rotating, and starting forward again.

That’s all for today. Check back in a couple of weeks for posts on my motor control library and a refinement to obstacle avoidance that uses bit math!

top