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))

Intro To LIDAR SLAM

I’m two years in to my PhD in robotics and things are going well. I’m working on robotic perception at the NASA Jet Propulsion Laboratory over the summer and I recently had a paper accepted to the conference on Field and Service Robotics. There’s just one problem: I still haven’t won the bet that led me to return to grad school in the first place; I haven’t built a robotic system for autonomous indoor mapping. Today we’ll take a big step toward that goal by starting our development of a 2D LIDAR-based SLAM system.

In this post I’ll propose a strategy for solving the localization and mapping portion of my problem. I’ll also introduce the Intel Research Center (IRC) dataset as a means for evaluating my SLAM efforts. I’ll demonstrate my developments first on the IRC dataset, but the eventual goal will be to use them on a real robot.

The Strategy

The goal of this series is to develop LIDAR-based 2 dimensional SLAM. Of course, numerous open source packages already exist for LIDAR SLAM but, as always, my goal is to understand SLAM on a fundamental level. That’s why I’m building everything from scratch and taking a detailed look at the underlying math.

I start by introducing the dataset below. In subsequent posts I present tutorials on basic methods for LIDAR odometry via matching between LIDAR scans and then matching scans to a persistent map representation. I then develop a method for LIDAR SLAM that fuses information from scan matching and wheel odometry. Lastly I present a full SLAM method which estimates both a globally-consistent pose graph and map. This last step will require all the previously presented methods as well as methods we haven’t discussed such as place recognition and loop closure. Links to all the posts in the series can be found below (these will be populated incrementally as work on this project progresses):

Why LIDAR?

LIDAR is an interesting and versatile sensor. In many ways 2D LIDAR measurements are very similar to the measurements we used in the UTIAS dataset in my EKF SLAM tutorial. As with the UTIAS dataset, the measurement model is simply the range and bearing to the measured landmark or obstacle. No complicated projection or distortion models are required to extract this information, so LIDAR is a pretty gentle introduction to the use of raw sensor data.

Unlike the UTIAS dataset, however, our sensor measurements are not associated with particular landmarks in the environment. Instead a LIDAR measurement is associated with whatever surface happened to get in the way of the laser. This makes data association more difficult. Luckily LIDAR makes up for this ambiguity by giving us much more information per timestep. At a given timestep in the UTIAS dataset we get just a few range and bearing measurements to nearby landmarks. With LIDAR, on the other hand, we get range and bearing measurements to everything in the robot’s vicinity. So instead of just estimating the locations of discrete landmarks we can estimate a continuous map of the whole environment. This is exactly what we need for an indoor mapping robot.

A SICK LMS sensor, similar to the one used to create the IRC Dataset.

Lastly, LIDAR sensors have a (mostly deserved) reputation for being extremely expensive and therefore out of reach for the robotics hobbyist. For instance, the 2D scanning LIDAR used to create the IRC dataset costs thousands of US dollars. How many basement tinkerers have that kind of money to spend on their hobby?

rplidar A3, an inexpensive scanning 2D lidar sensor

Luckily for us, cheaper LIDAR sensors, such as the Rplidar A3, have recently been introduced. These have lower range and lower precision than their more expensive cousins. They are totally sufficient for hobby projects though, and their cost is in the hundreds of dollars rather than the thousands.

Of course, publicly available datasets like the IRC dataset make it possible to do robotics work without spending any money. So let’s start there!

The IRC Dataset

The IRC dataset is an indoor localization and mapping dataset recorded at the Intel Research Center in Seattle in 2003. It is available on the MPRT website but I’d recommend getting it from my github repo instead. The raw data is the same in either case, but my repo has a few helpful scripts for loading, aligning, and visualizing the data. The original dataset has some ambiguities. For instance, it doesn’t specify the angular spacing between the lidar beams or the transformation between the odometry coordinate frame and the lidar coordinate frame. My DataLoader.py script resolves these problems for you!

The DataLoader reads the dataset from the txt files. It converts the odometry measurements into transformation matrices. It also converts the raw LIDAR measurements into cartesian points in the robot’s coordinate frame. Finally, it packages these measurements in Measurement objects. This is a much easier way to interact with the data than reading the txt files line by line.

You can see the LIDAR data in the robot’s frame of reference by running my script, VisializeLaser.py. A short bit of that script’s visualization is shown below:

Raw LIDAR measurements shown in the robot’s frame of reference.

Also, to make sure I got the sensor coordinate frame transformation correct, I made VisualizeMeasurements.py. It plots the pose of the robot in the global coordinate frame calculated by integrating the odometry measurements. We can also see the LIDAR measurements transformed into the global frame. As is shown below, the robot’s moves while the LIDAR measurements stay (more or less) static. This indicates we have the robot-to-LIDAR transformation correct. The visualization also shows the LIDAR measurements don’t stay completely static. This indicates the odometry is pretty noisy and accumulates drift quickly. We also notice the odometry noise is biased pretty heavily in rotation. This will be significant when we try to use it later.

Visualization of the odometry and lidar measurements together.

Beyond EKF SLAM

My series of tutorials on SLAM with the extended Kalman filter is finally done. At this point it’s a good idea to reflect on where we’re trying to go and what motivates us. My goal is to make a mobile robot that can autonomously map indoor spaces. I’m doing this mainly because it’s fascinating, but also to win a bet. Learning state estimation with EKFs was a great step toward that goal; it gave us an initial introduction to probabilistic state estimation. But we have a long way to go. We need to develop a SLAM system that’s more robust and better suited to our problem. 


Mapping Methods

My eventual goal is to develop a SLAM system capable of accurately mapping an indoor environment. This gives us a couple of requirements. First, its map representation must be human readable and metrically accurate. A sparse collection of point landmarks, like we used in our EKF, is not sufficient for this. Some sort of dense map representation like an occupancy grid or signed distance function is required.

Example of an occupancy grid map build with RTAB-map. Black cells indicate occupied areas, white cells indicate unoccupied, and gray cells indicate uncertain areas.

 


Sensor Selection

Second, we need to select sensors suited to the task. Our sensors must be able to give us a metrically accurate picture of the local environment’s structure, not just the locations of discrete landmarks as in the UTIAS dataset. A 2D scanning LIDAR is ideal for taking dense measurements of the surrounding environment and they can be found relatively cheaply. Wheel encoders will also provide useful information on the robot’s motion between LIDAR measurements. Also, because we’re trying to build a globally consistent map, we need a topological understanding of the whole environment. That is, we need to understand how different areas in the environment are connected. This means we must be able to detect when the robot revisits a previously-visited location. This can be done using LIDAR data alone, but cameras using visual bag-of-words or deep place recognition could also be helpful here.

Visual depiction of loop closure using ORB-SLAM. Map on left is prior to loop closure with place association indicated by blue line. Map on right is after loop closure and reoptimization of the map and robot trajectory.


SLAM Formulation

Lastly, we need an estimation framework that can solve our problem quickly and efficiently. We want to estimate a global map of the environment and the robot’s full path through the environment. Filtering approaches are ill-suited to this task because they do not allow for re-estimation of previous poses. This makes it difficult to constrain drift in the robot’s state estimate. One would normally use loop closures to do this, but this is difficult with filtering since ideally the full map and robot trajectory should be re-estimated when a loop closure is detected. That is why we will be using a factor graph approach. A factor graph is a representation of the SLAM problem that visualizes the quantities to be estimated (the robot trajectory, map, etc) as nodes and sensor measurements as constraints between those nodes. The graph model can be translated into a single cost function that can be solved through nonlinear optimization. Best of all, this framework allows for the use of an arbitrary combination of sensors as long as we’re able to correctly incorporate the sensor models into the cost function.

SLAM factor graph example: Blue circles denote robot poses at consecutive time steps (x1, x2 , . . .), green circles denote landmark positions (l1 , l2 , . . .), red circle denotes the variable associated with the intrinsic calibration parameters (K). Factors are shown as black squares: the label “u” marks factors corresponding to odometry constraints, “v” marks factors corresponding to camera observations, “c” denotes loop closures, and “p” denotes prior factors. Taken from Cadena et al, 2016.


Moving Forward

So the plan is to design a graph SLAM system for indoor mapping that uses 2D scanning LIDAR and wheel encoders. It should be able to accurately map and estimate its position within its local environment, as well as perform reliable place recognition and loop closure. It should ideally be able to run in real time on a Raspberry Pi or similar single board computer, so careful attention must be paid to the sparsity of the problem’s factor graph. The graph should be as sparse as possible for efficient optimization. This means I will need to include mechanisms to avoid adding redundant information and to sparsify the problem as it proceeds.

I will first be testing my software on a publicly available dataset. The IRC dataset includes sensor streams from odometry and a 2D scanning LIDAR on a wheeled mobile robot as it traverses the Intel Research Center. It will allow us to test all the requirements on our algorithm including accurate mapping and place recognition. After we’re getting good results on the IRC dataset we can implement it on Colin!

Weighted Linear Regression for Wall Following

I’m currently working on a wall-following program for Colin, my mobile robot. True to form, I’ve added an extra complication to the problem: Colin won’t respond directly to his sensor inputs. Instead, he’ll use his sensor inputs to create a simple model of his environment. Then he’ll decide how to move based on this model.

In order to follow a wall, Colin only needs to know the position of the wall relative to himself. To do this Colin will calculate the (x, y) coordinates of each obstacle detected by his rangefinders. Then he’ll fit a line to those points and assume that line represents the wall he’s supposed to be following.

I’ll discuss the actual wall following algorithm in detail in my next post. I’m laying out my method for fitting lines to Colin’s sensor readings in a separate post so I don’t get bogged down in the underlying maths when I’m presenting the wall-following algorithm. If you’re not interested in the maths feel free to skip this post; you can use my line fitting classes without understanding their inner workings. If you want to see what’s going on under the hood, read on.


Interpreting Range Readings

The first thing Colin does is take the range readings from his sonar sensors and convert them into (x, y) points in his local coordinate system. To do this Colin combines his the range readings from his sensors with the orientations of those sensors relative to his heading, which are constant. This turns his range readings into points in a polar coordinate system defined by (r, θ). Then converting these polar points to Cartesian coordinates is pretty easy. Colin calculates the x and y coordinates of each point as follows:

x_{i}=r_{i}cos(\theta_{i})

y_{i}=r_{i}sin(\theta_{i})

In the above two equations, r_{i} is the range reading from sensor i and \theta_{i} is the angle of sensor i relative to Colin’s heading.

My Point data structure does this conversion automatically. Its constructor takes the polar coordinates of the point as arguments and automatically calculates the Cartesian coordinates. It also stores r, as this is used to assign weight to the point later in the program.


Line Fitting

After converting his sensor readings to an array of Cartesian points, Colin fits a line to them. One of the simplest ways to do this is with least-squares linear regression, which works as follows. Assume the following equation describes all of the points:

y_{i}=a+bx_{i}+\epsilon_{i}

Where y_{i} and x_{i} are coordinates of point i, a and b are the slope and intercept of the fitted line, and \epsilon_{i} is the error between the line and point i. Least squares regression determines coefficients a and b such that the sum of squares of the errors, \sum_{i=0}^{n}\epsilon_{i}^{2} is minimized.

In terms of linear algebra, the line equation is represented byAx=B where A is an n by 2 matrix containing the x values of Colin’s points:

A=\begin{bmatrix} 1 & x_{0} \\ 1 & x_{1} \\ 1 & x_{2} \\ ... & ... \\ 1 & x_{n} \\ \end{bmatrix}

B is an n by 1 vector containing the y values of Colin’s points:

B=\begin{bmatrix} y_{0} \\ y_{1} \\ y_{2} \\ ... \\ y_{n} \\ \end{bmatrix}

and x is a 2 by 1 vector containing the y intercept and slope of the fitted line.

x=\begin{bmatrix} a \\ b \\ \end{bmatrix}

Unfortunately, there is usually no x vector that satisfies Ax=B for every entry in the A and B matrices because all of the points will not lie on the same line. What we want, then, is a vector \hat{x} that minimizes the sum of squares of the errors for each entry. The equation for \hat{x} is as follows:

A^{T}A\hat{x}=A^{T}B

This equation can be solved pretty simply by multiplying both sides by the inverse of A^{T}A:

\hat{x}=(A^{T}A)^{-1}A^{T}B

The above equation calculates the slope and y intercept of the line that best fits all of Colin’s sensor readings. That brings us a step closer to our goal!

Also, the math presented above is only a very high-level overview. If you’d like to go more in-depth I’d recommend this very thorough textbook chapter from MIT.


Weighting the Points

You may have noticed a problem with the idea of using simple linear regression to model walls. Most of Colin’s sensors will either detect no obstacle or they will detect a far-away obstacle that is not part of the wall Colin is following. This means that most of the points are not relevant. At most three or four of these points will actually represent a wall.

Very distant points are likely to represent failed readings or obstacles that aren’t relevant to Colin’s decision making. So I decided that points that are more distant from Colin should be less significant and closer points should be more significant. Using this criteria, Colin uses a simple weighting function to assign significance to his points:

w_{i}=\exp(-\frac{d_{i}^{2}}{c})

where w_{i} is the weight assigned to point i, d_{i} is the distance between Colin and point i, and c is a constant. The weighting function’s graph looks like this:

weight-functionThe function assigns a weight of 1 for a distance of 0. Varying the value of c adjusts the distance at which the weight decays to 0.


Weighted Linear Regression

Colin uses the above weighting function to create a weights matrix, W:

W=\begin{bmatrix} w_{0} & 0 & ... & 0 \\ 0 & w_{1} & ... & 0 \\ ... & ... & ... & ... \\ 0 & 0 & ... & w_{n} \\ \end{bmatrix}

As you can see, W is a diagonal matrix of the weights assigned to each point. It fits into the linear regression equation as follows:

A^{T}WA\hat{x}=A^{T}WB

Similar to the unweighted regression, this is solved for \hat{x} by multiplying both sides by the inverse of A^{T}WA:

\hat{x}=(A^{T}WA)^{-1}A^{T}WB

Using the above function Colin calculates the equation of a line fitted to the obstacles that are closest to him and therefore most likely to be relevant to his decision making.

My class, LineFitter, stores an array of Points and automatically fits a line to those points using the above method for weighted linear regression. This makes it very easy to use in my wall following program, which I will present in my next post.


Alternate Methods

A more sophisticated method would incorporate RANSAC to determine which points actually represent the wall and then fit a line to those points, ignoring the others. It would be very interesting to try to implement this method and compare its performance to my simple weighted linear regression. However, I don’t believe Colin would benefit much from using the more sophisticated method in his current configuration.

This is because Colin is working with a very small data set of only 8 points. This means the both my method and RANSAC could easily find spurious relationships in the data. Further, RANSAC is probably overkill; a brute-force search for relationships between Colin’s points would probably be more efficient on such a small data set. Since both are workable and weighted regression is much easier to implement, that’s where I’m starting. This is a good excuse to do further research on RANSAC, though, and I may do a post on that topic in the future.

 

ATtiny Sonar Controller

HC-SR04 sensor

Remember these guys? HC-SR04 ultrasonic rangefinders. Colin used to have three of them, but I’ve recently been reworking his sensor layout. I’m starting by adding five more sensors for a total of eight. Colin’s Arduino has just barely enough free pins to accommodate eight sensors, but I don’t want to spend all of my available pins on sensors. That would leave me no room to expand. Further, I’m not totally sure eight sonar sensors will be enough. My HC-SR04 sensors have a range of about 15 degrees, so it would take 24 sonar sensors to cover 360 degrees. I don’t know if that will be necessary, but I’d like to have the option.

There are a couple of ways to do this. The simplest would probably be to use a shift register. Shift registers allow you to use three I/O pins to control more than a thousand additional pins, but operating them involves some computing overhead and the Arduino still has to be involved in every sensor reading operation.

The chip for my sonar controller, an ATtiny84

An Atmel ATtiny84

The method I’ve chosen is to use a separate microcontroller, an ATtiny84, to handle the sonar sensors. The Aduino tells the ATtiny that it needs new sensor readings. Then it goes and performs some other computations while the ATtiny pings its sensors. Then, when the new sensor data is ready, the ATtiny sends back the new readings all at once. Using this scheme, the Arduino doesn’t have to spend processor time reading sensors. Instead it can focus on other problems. Also, since it can communicate with the Arduino via I2C, it only requires 2 I/O pins! Here’s what Colin looks like with his new sonar layout.

Colin with his new sonar

Colin with his new sonar ring

As with my earlier post on Raspberry Pi to Arduino communication, there’s several steps to this process. Luckily it’s a lot simpler this time.


The Communication Protocol

The communication protocol is going to be very similar to the one that I outlined for communicating between a Raspberry Pi and an Arduino, only simplified. Basically, the Arduino tells the ATtiny when it needs updated sonar readings. The ATtiny then pings all of its sensors and sends back the readings when it’s done. This is how it works:

  • The Arduino sends a byte to the ATtiny
    • The byte has no meaning, it’s just a flag to signal the ATtiny to ping its sensors
  • The ATtiny pings its sensors
  • The ATtiny sends its readings back to the Arduino as 16 bytes
  • The Arduino assembles the bytes into 8 16-bit ints

One other difference with the Raspberry Pi to Arduino protocol is that we’ll be using I2C instead of serial. If you’re not familiar with I2C I’d suggest reading up on it. Sparkfun has a great tutorial.

That’s really all there is to it! The protocol is simple, but there’s some fiddly details to work out in the code.

Top of page


The Sonar Controller

sonar controller with ATtiny84

My ATtiny84-based sonar controller

My sonar controller basically consists of an ATtiny84, with eight inputs for HC-SR04 ultrasonic rangefinders. If you’re interested in making your own, you can download my eagle files for the schematic, board layout, and the gerber files for fabbing the PCB. The gerbers are formatted for fabrication by OSH Park, which I highly recommend for low-volume jobs.

The controllers each have two sets of inputs for power and I2C communication so multiple controllers can be chained together on the same bus. Note that there are two spots for 4.7 kOhm resistors on each controller. These are pull-ups for the I2C buses. If you’re chaining multiple controllers together, only one of them needs pull-up resistors. The resistor spots on the other controllers can be left empty.

I also designed a laser-cut frame to hold the sonar sensors and controller, as well as some fittings to attach the whole business to Colin. The design is pictured below, and you can download the SVG files to make your own parts here.

Colin's new sonar arrangement

Colin with his new sensor arrangement and fittings

If you’d rather not fab a custom circuit board, you can set it up on a breadboard as shown below. It’s not particularly useful on a breadboard, but it will allow you to experiment with and test it.

breadboard wiring

Breadboard wiring for ATtiny sonar controller

Top of page


The Code!

ATtiny Code

Let’s start out with a couple of preliminaries. First, for I2C communication I’m using the TinyWireS and TinyWireM libraries. We need our ATtiny to perform as both master and slave, but there is no existing library that allows this. Fortunately there’s a way to hack around this problem.

I’m also using the NewPing library. The NewPing library doesn’t work with ATtinies, but there’s a hack for this too. You just need to comment out the functions for Timer2 and Timer4 because the ATtiny does not have these timers.

You can find the complete program for the ATtiny here. If you’re not familiar with how to program ATtinies, I’d suggest going through this very thorough tutorial.

Initiating A Sensor Update

The function below pings the eight sonar sensors and records the ping times in microseconds.

void updatePingTimes(uint8_t bytes)
{
  TinyWireS.receive();
  for (int i = 0; i < NUM_SONAR; i++)
  {
    pingTimes[i] = sonar[i].ping();
  }
  sendTimes();
}

The function above is invoked using an interrupt when the ATtiny receives a byte from the Arduino. The line below is called in the setup() function to tell the ATtiny to generate an interrupt and call the updatePingTimes() function whenever data is received from the Arduino.

TinyWireS.onReceive(updatePingTimes);

Sending Data Back To The Arduino

When the sonar sensors have been updated, the sendTimes() function is called to send the updated ping times back to the Arduino. It is important to note that the ATtiny must be functioning as a slave in order to use the onReceive() function. To send data back to the Arduino, the ATtiny must function as a master. This makes the sendTimes() function a bit more complicated.

void sendTimes()
{
  // clear the I2C registers
  USICR = 0;
  USISR = 0;
  USIDR = 0;

  // start I2C with ATtiny as master
  TinyWireM.begin();

  // transmit ping times to Arduino
  TinyWireM.beginTransmission(MASTER_ADDRESS);
  for (int i = 0; i < NUM_SONAR; i++)
  {
    int thisTime = pingTimes[i];
    if (thisTime == 0) thisTime = (double)MAX_DISTANCE / speedOfSound;
    uint8_t firstByte = thisTime & 0xFF;
    uint8_t secondByte = (thisTime >> 8) & 0xFF;
    TinyWireM.write(firstByte);
    TinyWireM.write(secondByte);
  }
  TinyWireM.endTransmission();

  // clear I2C registers again
  USICR = 0;
  USISR = 0;
  USIDR = 0;

  // put ATtiny back in slave mode
  TinyWireS.begin(OWN_ADDRESS);
}

As I said before, I don’t know of any library that allows an ATtiny to function as both master and slave. Fortunately we can hack our way around this problem by clearing the ATtiny’s I2C registers and restarting communication in master mode. After we’ve transmitted the ping times back to the Arduino we need to clear the I2C registers again and put the ATtiny back in slave mode so it can be ready for the next request from the Arduino. I don’t mind telling you it took me a lot of time with the ATtiny’s datasheet to figure out how to make that work.


Arduino Code

For reference you can find the complete program for the Arduino here. To get things going we need to include the Wire library and put the following two lines in the setup() function:

// begin communication with sonar controller
Wire.begin(OWN_ADDRESS);
Wire.onReceive(updateDistances);

Adding the onReceive() function is particularly important because it allows the Arduino to do other processing tasks while the ATtiny pings its sensors. When the ATtiny sends data it generates an interrupt, the Arduino stops what it’s currently doing and receives the new data, then goes back to whatever it was doing before.

Receiving Data

The updateDistances() function works as follows:

// updates sonar distance measurements when a new reading is available
void updateDistances(int bytes)
{
  for (int i = 0; i < NUM_SONAR; i++)
    readSonar(i);
  distancesRead = true;
}

// reads the distance for a single sonar sensor
// expects to receive values as ints broken into 2 byte pairs,
// least significant byte first
void readSonar(int index)
{
  int firstByte = Wire.read();
  int secondByte = Wire.read();
  sonarDistances[index] = ((double)((secondByte << 8) | firstByte)) * speedOfSound * 0.5;
}

Notice that the sonar distance is multiplied by 0.5 when it’s added to the sonarDistances array. This is because the ATtiny returns the total time of flight for the ultrasonic ping. The ping needs to go from the sensor, to the obstacle, and back. This means multiplying the ping time by the speed of sound would result in twice the distance between the obstacle and the sensor.

Requesting An Update

Fortunately, requesting an update is pretty simple. The Arduino just needs to send a byte, any byte, to the ATtiny to let it know it needs new sensor readings.

// requests a sonar update from the sonar controller at the given address
// by sending a meaningless value via I2C to trigger an update
void requestSonarUpdate(int address)
{
  Wire.beginTransmission(address);
  Wire.write(trig);
  Wire.endTransmission();
}

After this function executes, the Arduino can perform other processing tasks until the ATtiny sends back updated sonar readings.

Top of page


Going Further

There are a number of ways to solve the problem of coordinating large numbers of sonar sensors, and the above method is only one possibility. It takes a long time to update sonar sensors, up to 15 milliseconds for 8 sensors. For an Arduino running at 16 MHz, that’s 240,000 processor cycles. So it’s advantageous to use a method that allows the Arduino to do something else while the sensors are being updated. My method does this, but one could also take the Arduino out of the loop entirely and have the Raspberry Pi talk to the sonar controller directly. It would be interesting to implement this method and compare it to the one presented above.

Top of page

Raspberry Pi to Arduino Communication For Robot Control


Arduino to Raspberry Pi communicationGood news, everyone! I’ve come up with a good way for Colin’s Raspberry Pi to talk to his Arduino. To review, the idea was that the Arduino could handle low-level control functions like speed control, odometry, and sensor reading. This leaves the Raspberry Pi free to handle high-level control like obstacle avoidance, motion planning, and state estimation.

There are a few steps in this process:


Freeing Up the Raspberry Pi’s Serial Port

The first problem we have to deal with is that the Raspbian reserves its serial port for use by a serial console. So the Raspberry Pi’s GPIO serial port is totally useless until you free it up. I’m not going into all the details here, but I found this guide really helpful. The important things to remember are that you need to enable uart in config.txt and disable the serial console. This will allow our program to use the serial port.

Top of page


The Communication Protocol

The communication protocol works like this:

  • The Raspberry Pi sends 2 16-bit ints to the Arduino
    • The first int is the commanded translational velocity
    • The second int is the commanded angular velocity
  • The Arduino sets its speeds accordingly and then updates its sonar sensors
  • After the sensors are updated, the Arduino sends 11 16-bit ints back to the Raspberry Pi
    • The first 8 ints are the distance readings from the 8 sonar sensors
    • The last 3 ints are the Colin’s x and y position and his heading, calculated from odometry

Using this protocol, Colin will run at the commanded speeds until he receives another command. This causes a problem: Colin will continue to run even if the serial communication fails and the Raspberry Pi stops sending commands all together. This means he could run off a cliff and there would be nothing to stop him!

To fix this I have the Raspberry Pi send commands at a regular interval. If, for example, Colin expects to get a new command every quarter second and he doesn’t get a command at the expected time, he will know there’s a communication problem. If Colin detects a communication fault he can respond in a fail-safe manner by stopping.

Communication Formatting

How do we send ints over serial though? Arduino’s Serial.print()  function converts int and float values to strings of chars before sending them. At first this might seem really convenient, but it actually causes more problems than it solves. First, Arduino and C++ don’t have a great function for converting char strings to int or float values. Second, C++ doesn’t automatically convert numerical types to strings before sending them via serial, so you’d need to write your own function for that. Lastly, if we convert numbers to strings, their lengths will be variable. This means we would need to define some way to tell when one value ends and the next begins.

The good news is none of that is necessary! You know why? Every command and sensor packet will be exactly the same length: 2 16-bit ints for commands and 11 16-bit ints for responses. Further, the ints will always come in the same order. So the meaning of each byte is predictable.

The only problem is you can only send individual bytes over serial. But this is easily solved by splitting the ints into their component bytes before sending:

char firstByte = (byte)(value & 0xFF);
char secondByte = (byte)((value >> 8) & 0xFF);

and reassembling them on the other end:

int value = (secondByte << 8) | firstByte;

Top of page


Wiring It Up

Wiring up the Raspberry Pi to the Arduino is pretty simple, but there’s an important catch. The Raspberry Pi uses 3.3 volt logic and the Arduino uses 5 volt logic. So we need to use a level shifter to allow communication between the two devices. If the level shifter gets a 3.3 volt signal on the low side, it sends out a 5 volt signal on the high side. If it gets a 5 volt signal on the high side it sends out a 3.3 volt signal on the low side. Pretty simple, right? Wire it up as shown below:

wiring for serial between an rPi and an Arduino

Wiring for serial between a Raspberry Pi and an Arduino


Top of page


The Code!


Okay, enough talk. Let’s get into the code. I’m going present the code for the Raspberry Pi side first, and follow it up with the Arduino code. The complete code for the Raspberry Pi can be found here and the Arduino code can be found here.

Raspberry Pi Code

Opening the Serial connection

First, we need to open a serial connection with the Arduino. This is handled by the following function, which I adapted from this extremely helpful site. Check out that site if you want details on how all of this works.

void SerialBot::openSerial()
{
	serialFd_ = open("/dev/serial0", O_RDWR);
																						// to allow blocking read
	if (serialFd_ == -1)
	{
		cerr << "Error - unable to open uart" << endl;
		exit(-1);
	}	
	
	struct termios options;
	tcgetattr(serialFd_, &options);
	options.c_cflag = B9600 | CS8 | CLOCAL | CREAD;
	options.c_iflag = IGNPAR;
	options.c_oflag = 0;
	options.c_lflag = 0;
	tcflush(serialFd_, TCIFLUSH);
	tcsetattr(serialFd_, TCSANOW, &options);
}

There is one important difference between my function above and the one it’s adapted from: I dropped the O_NOCTTY and O_NDELAY flags from the open command in line 3. This means my serial connection will be blocking. In other words, when I call the read() function the program execution stops until there is data to read in the serial buffer. In other words, my program will wait for a response from the Arduino before continuing.

Sending Commands

Sending a command works as follows:

int SerialBot::transmit(char* commandPacket)
{
	int result = -1;
	if (serialFd_ != -1) 
	{
		result = write(serialFd_, commandPacket, commandPacketSize);
	}
	return result;
}

And, in case you’re wondering, the function that assembles the commandPacket is below.

void SerialBot::makeCommandPacket(char* commandPacket)
{
	int16_t intAngular = (int)(angular_ * 1000.0);
	commandPacket[0] = (char)(translational_ & 0xFF);
	commandPacket[1] = (char)((translational_ >> 8) & 0xFF);
	commandPacket[2] = (char)(intAngular & 0xFF);
	commandPacket[3] = (char)((intAngular >> 8) & 0xFF);
}

Note that angular_ is a double representing Colin’s commanded angular velocity. The size and representation of doubles is inconsistent, however, so it’s difficult to break them up and reassemble them on a different machine. Int representations are very consistent, however, so I just multiply angular_ by 1000 to save the first three decimal places and cast it to an int. The loss of accuracy is pretty negligible for our purposes.

Receiving Data

The function below is how we receive data from the Arduino. Note that I’ve set the read to time out after 0.25 seconds. The Raspberry Pi expects to get a response from the Arduino after every command is sent. If it doesn’t receive a response before it’s time to send the next command, it throws an error.

int SerialBot::receive(char* sensorPacket)
{
	memset(sensorPacket, '\0', sensorPacketSize_);
	int rxBytes;
	if (serialFd_ != -1)
	{
		// set up blocking read with timeout at .25 seconds
		fd_set set;
		FD_ZERO(&set); // clear the file descriptor set
		FD_SET(serialFd_, &set); // add serial file descriptor to the set
		struct timeval timeout;
		timeout.tv_sec = 0;
		timeout.tv_usec = 250000;
		
		// wait for serial to become available
		int selectResult = select(serialFd_ + 1, &set, NULL, NULL, &timeout);
		if (selectResult < 0)
		{
			cerr << "blocking read failed" << endl;
			return -1;
		}
		else if (selectResult == 0)
		{
			cerr << "read failed: timeout occurred" << endl;
			return 0;
		}
		else
		{
			rxBytes = read(serialFd_, sensorPacket, numSonar_ + numPoseVariables);
		}
	}
	return rxBytes;
}

Once we’ve read data from the Arduino, we need to parse it:

int SerialBot::parseSensorPacket(char* sensorPacket)
{
	int16_t firstByte;
	int16_t secondByte;
	int16_t inValues[numSonar_ + numPoseVariables];
	for (int i = 0; i < numSonar_ + numPoseVariables; i++)
	{
		firstByte = sensorPacket[2 * i];
		secondByte = sensorPacket[(2 * i) + 1];
		inValues[i] = (secondByte << 8) | firstByte;
	}

	for (int i = 0; i < numSonar_; i++)
	{
		distances_[i] = inValues[i];
	}
	
	x_ = inValues[8];
	y_ = inValues[9];
	theta_ = ((double)inValues[10]) / 1000.0;
}

Note again that Colin’s heading, theta_ , is a double. To save some bother in programming, the double value is multiplied by 1000 and casted to an int before it’s sent. So it needs to be casted to a double and divided by 1000 after it’s received.

Putting It All Together

Okay, last thing: we’ll put all of these things together in a communication function that runs every 0.25 seconds in its own thread:

void SerialBot::commThreadFunction()
{
	while (true) 
	{
		char commandPacket[commandPacketSize];
		makeCommandPacket(commandPacket);
		if (transmit(commandPacket) < 1)
			cerr << "command packet transmission failed" << endl;
		char sensorPacket[sensorPacketSize_];
		memset(sensorPacket, '\0', sensorPacketSize_);
		int receiveResult = receive(sensorPacket);
		if (receiveResult < 1)
		{
			cerr << "sensor packet not received" << endl;
		}
		else if (receiveResult < commandPacketSize)
		{
			cerr << "incomplete sensor packet received" << endl;
		}
		else
		{
			parseSensorPacket(sensorPacket);
		}
		usleep(readPeriod_);
	}
}

Top of page


The Arduino Code

Are you still with me? That took a while, but we got one side of it done. So we just have the Arduino code left to deal with.

Receiving

Let’s start with receiving a command from the Raspberry Pi:

void readCommandPacket()
{
  byte buffer[4];
  int result = Serial.readBytes((char*)buffer, 4);

  if (result == 4) // if the correct number of bytes has been received
  {
    int commands[2];
    
    // assemble 16 bit ints from the received bytes in the buffer
    for (int i = 0; i < 2; i++)
    {
      int firstByte = buffer[2 * i];
      int secondByte = buffer[(2 * i) + 1];
      commands[i] = (secondByte << 8) | firstByte;
    }
    translational = commands[0]; 
    angular = (double)commands[1] / 1000.0; // convert received int to double angular velocity
    colin.drive(translational, angular); // set Colin's speeds
    commandReceived = true; // note that a command has been received
    lastCommandTime = millis();
  }
  else if (result > 0)
  {
    Serial.println("incomplete command");
  }
  // else do nothing and try again later
}

Note that I’m using the Serial.readBytes() function rather than the more common Serial.read() function. There’s a couple of reasons for this. First, Serial.read() only reads a char at a time, but we know we need 4 bytes. Serial.readBytes() also blocks the program’s execution until it receives the requested number of bytes. This is perfect, since it means we’ll get a complete packet, instead of just receiving part of one.

Transmitting

The transmit function first puts all the data that needs to be sent into an array, buffer. Then the buffer is sent to the Raspberry Pi using Serial.write() . Note that I’m not using Serial.print() because it automatically converts int values to characters, and we want to send the bytes exactly as-is.

void sendSensorPacket()
{
  colin.getPosition(x, y, theta); // updates Colin's position
  byte buffer[22];
  addDistances(buffer); // adds sonar readings to buffer
  int sendX = (int)x;
  int sendY = (int)y;
  int sendTheta = (int)(theta * 1000.0);
  buffer[16] = (byte)(sendX & 0xFF);
  buffer[17] = (byte)((sendX >> 8) & 0xFF);
  buffer[18] = (byte)(sendY & 0xFF);
  buffer[19] = (byte)((sendY >> 8) & 0xFF);
  buffer[20] = (byte)(sendTheta & 0xFF);
  buffer[21] = (byte)((sendTheta >> 8) & 0xFF);
  Serial.write(buffer, 22);
}

void addDistances(byte* buffer)
{
  for (int i = 0; i < NUM_SONAR; i++)
  {
    buffer[2 * i] = (byte)(sonarDistances[i] & 0xFF);
    buffer[(2 * i) + 1] = (byte)((sonarDistances[i] >> 8) & 0xFF);
  }
}

Bringing It All Together

The loop() function below brings everything together. It checks to see if there is data in the serial buffer and, if so, attempts to interpret it as a command. If it successfully reads a command, it requests an update from the sonar controller. After the Arduino gets updated sensor readings it assembles a response packet and sends it back to the Raspberry Pi.

Lastly, the Arduino checks to see if more than 1 second has passed since the last command was received. If so, it assumes that a communication fault has occurred and it stops Colin.

void loop() 
{ 
  // check if a command packet is available to read
  readCommandPacket();
  
  // request a sensor update if a command has been received
  if (commandReceived)
  {
    commandReceived = false;
    requestSonarUpdate(SONAR_ADDRESS);
  }
  // send sensor packet if sonar has finished updating
  if (distancesRead)
  {
    distancesRead = false; 
    sendSensorPacket();
  }
  currentTime = millis();
  
  // stop colin if a command packet has not been received for 1 second
  if (currentTime - lastCommandTime > 1000)
  {
    Serial.println("command not received for 1 second");
    lastCommandTime = millis();
    colin.drive(0, 0.0);
  }
}

Top of page


Where Do We Go From Here?

Now we have a good way to communicate between Colin’s Raspberry Pi and Arduino. Colin doesn’t have a way to perceive the world around him, however, so that’s our next step. I designed an independent controller to read Colin’s sonar sensors and relay the information to the Arduino via I2C. My next post will cover the finer details of my sonar controller and the associated communication protocol.

After we sort these details out and get the system working like we want, we can get to programming higher level behaviors. For example, I’m currently working on a wall-following program. I’m hoping it will be ready to present in a couple of weeks! Lots of good stuff to come, stay tuned!

Top of page

Motor Encoders with Arduino

If Colin is going to create a map of the space he’s in, he needs to be able to find the distance between objects in the space. If he’s going to accurately control his own motion, he needs to be able to control the speed of his motors. For both of these things he needs information about how far and how fast his motors are turning. To give Colin that information I added encoders to his motors. Encoders are special sensors that track both how far his motor shafts have turned, and in what direction.

The following tutorial will discuss how to use shaft encoders with DC motors. First I’ll discuss the principles the encoders work on, then I’ll show you how to wire up an encoder and verify that it’s working. This tutorial owes a large dept to the Penn State Robotics Club Wiki, which has an excellent page on wheel encoders.

For this tutorial I’ll be using these magnetic encoders from Pololu. They are great for use with an Arduino because their output is a nice, easy to read, digital square wave. Pololu also offers an analog optical encoder, but to reliably read its output you need to use a ADC (analog to digital converter). Also, the optical encoder is susceptible to interference from bright light. So magnetic encoders are easier to use and more reliable for our purposes.


Encoder Principles

Pololu’s shaft encoders add a 6 pole magnetic disc to the shaft of the motor, as well as two Hall effect sensors. As the motor turns the disc rotates past the sensors. Each time a magnetic pole passes a sensor, the encoder outputs a digital pulse, also called a “tick.” The encoder setup is pictured below.

motor encoder installation

motor encoder installation example (from pololu.com)

The encoder has two outputs, one for each Hall effect sensor. The sensors are separated by 90 degrees. This means the square wave outputs of the sensors are 90 degrees out of phase. This is called a quadrature output. The picture below (taken from Pololu’s website) shows the typical output of an encoder.

encoder output

Output of an encoder (from pololu.com)

Why is it important that the output pulses are 90 degrees out of phase? This allows us to determine both the magnitude and the direction of the motor’s rotation. If output A is ahead of output B, then the motor is turning forward. If output A is behind B, the motor is turning backward. Pretty cool, right?


Encoder Setup and Wiring

Wiring up the encoders is pretty simple. See the diagram below for details on wiring up the encoder for motor B, and repeat for motor A.

wiring for a single motor and encoder

wiring for a single motor and encoder

Note that the encoder pin OUTA needs to be connected to a hardware interrupt pin (digital pin 2 or 3 on an Arduino Duemilanove or Uno). For this example it’s not really necessary to use hardware interrupts but if you don’t your Arduino won’t be able to do anything but track the encoder. Interrupts allow your Arduino to keep track of the encoders while it’s running another program.

It’s also important when installing your motors to not mount them too close to each other. If your motors are mounted back-to-back, the magnetic encoder wheels will interfere with each other. I initially had only about 5mm between the two encoder wheels. The magnets in the encoder wheels linked with each other and made it impossible for the two motors to turn at different speeds. Keeping the encoder wheels at least 20mm apart seems to avoid any interference problems.


Hardware Interrupts

It’s pretty easy to write a program that simply counts the number of ticks. But if, for some reason, you want your program to do anything but track the encoders you need to use hardware interrupts.

With hardware interrupts your main program runs until the state of one of the Arduino’s interrupt pins changes. Then the main program is stopped, a special interrupt method is run, then the main program is resumed. For example, an obstacle avoidance routine can run in the foreground but if one of the interrupt pins changes from low to high the position or speed of the motor can be updated in the interrupt method.

Because the main program is stopped when the interrupt method is triggered, the length of the interrupt method should be kept as short as possible. If the interrupt method is too long, then the Arduino will spend all of its time running the interrupt method and it will never actually run the main program.

For more details on hardware interrupts check out this page on the Arduino playground.


Example Sketch

The sketch below simply prints the values of the two count variables. When the motors are moved, the encoder output triggers the appropriate encoder event method. The encoder event methods either increment or decrement the count variables, keeping track of the number of ticks from each encoder. If the motor is turned forward, the count is incremented and it is decremented if the motor is turned backward.

The motors need to be moved manually for this sketch. They won’t move themselves. We will expand this to do simple motor speed control in a later tutorial.

We’ll define motor direction somewhat arbitrarily: If RH_ENCODER_A is HIGH and RH_ENCODER_B is LOW then the motor is turning forward. If RH_ENCODER_A is HIGH and RH_ENCODER_B is also HIGH, then the motor is turning backward. You can swap the wires for ENCODER_A and ENCODER_B to change the direction if required.

/*
 * Encoder example sketch
 * by Andrew Kramer
 * 1/1/2016
 *
 * Records encoder ticks for each wheel
 * and prints the number of ticks for
 * each encoder every 500ms
 *
 */

// pins for the encoder inputs
#define RH_ENCODER_A 3 
#define RH_ENCODER_B 5
#define LH_ENCODER_A 2
#define LH_ENCODER_B 4

// variables to store the number of encoder pulses
// for each motor
volatile unsigned long leftCount = 0;
volatile unsigned long rightCount = 0;

void setup() {
  pinMode(LH_ENCODER_A, INPUT);
  pinMode(LH_ENCODER_B, INPUT);
  pinMode(RH_ENCODER_A, INPUT);
  pinMode(RH_ENCODER_B, INPUT);
  
  // initialize hardware interrupts
  attachInterrupt(0, leftEncoderEvent, CHANGE);
  attachInterrupt(1, rightEncoderEvent, CHANGE);
  
  Serial.begin(9600);
}

void loop() {
  Serial.print("Right Count: ");
  Serial.println(rightCount);
  Serial.print("Left Count: ");
  Serial.println(leftCount);
  Serial.println();
  delay(500);
}

// encoder event for the interrupt call
void leftEncoderEvent() {
  if (digitalRead(LH_ENCODER_A) == HIGH) {
    if (digitalRead(LH_ENCODER_B) == LOW) {
      leftCount++;
    } else {
      leftCount--;
    }
  } else {
    if (digitalRead(LH_ENCODER_B) == LOW) {
      leftCount--;
    } else {
      leftCount++;
    }
  }
}

// encoder event for the interrupt call
void rightEncoderEvent() {
  if (digitalRead(RH_ENCODER_A) == HIGH) {
    if (digitalRead(RH_ENCODER_B) == LOW) {
      rightCount++;
    } else {
      rightCount--;
    }
  } else {
    if (digitalRead(RH_ENCODER_B) == LOW) {
      rightCount--;
    } else {
      rightCount++;
    }
  }
}

That’s all for today. In my next post I’ll take what we learned about using encoders with hardware interrupts and incorporate that into a simple speed control routine. After that we can dive into real PID control!

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

ICRA 2015 days 2-5

I’ve been at the conference on robotics and automation for five days now and all I can say is: “Did you know robots can play football?!”

https://www.youtube.com/watch?v=XLKKbz2mNyo

I stopped by the Robotis booth at the exhibition during lunch one day and they showed me the above video. Robotis makes the Darwin OP robots that make up the American team in the above video. Not only are they adorable, they’re also frighteningly smart. Their goal-blocking behaviors are pretty funny too.

On Wednesday I got to hear a talk from Peter Hart on making Shakey, one of the first autonomous mobile robots. Colin shares Shakey’s basic physical design and I think I can learn a lot from how Shakey’s software was organized. Shakey used a hierarchical system where one program controls low level functions like moving and sensing and separate programs handle motion planning, map building and localization. It seems like a good way to organize Colin’s functions. That’s a long way off though. I’m still busy writing Colin’s motor control library.

On Friday there were two sessions on Simultaneous Localization and Mapping (SLaM). I made sure to attend both of them since my ultimate goal for Colin is to program him for SLaM.

It seems a lot of implementations of SLaM rely on vision via Microsoft Kinect sensors. Those are out of my league for the moment; I have no idea how to program for them and Colin does not have the power to run any such program anyway. Laser rangefinders and LiDAR are also popular and, while I could potentially add one to Colin, they are expensive as hell. I’m still getting some good ideas though. Hopefully I can implement them on a robot that uses cheap ultrasonic and touch sensors instead of fancy RGB+D cameras.

Saturday was my favorite day at the conference by far. I attended an all-day workshop on building a career in robotics research called “Becoming a Robot Guru.” The speakers and panelists got me very excited about working toward a career in robotics. I was encouraged to learn that one doesn’t have to follow the traditional academic career path to be a robotics researcher. I have been worried lately that it may be too late for me to start a PhD in computer science or robotics, but many of the speakers on Saturday took more than a decade to start their PhD after they completed their bachelor’s degree. That gives me hope that a career in research is still an option for me. I’m starting my master’s degree this fall. All I really have to do is keep working at it and I’ll get there eventually.

First Pictures of Colin

I have an increasing number of friends and family members who use Facebook mainly as a vehicle for posting pictures of their toddlers. I try to counterbalance that by posting lots of pictures of Colin. Here’s Colin at 11 months old:

Isn't he adorable?

11 month old Colin!

Look at his cute little bluetooth radio!

Look at his cute little bluetooth radio!

I’m going to add more ultrasonic sensors soon, but this is what he looks like for now.

So far I’ve gotten him to avoid obstacles, follow walls, and I’m working on a PID motor control library. I’ll be doing a post with the technical details of motor control very soon. Stay tuned!