diff --git a/config/example-delta.cfg b/config/example-delta.cfg
index 3ae4c3120..76d0cfc07 100644
--- a/config/example-delta.cfg
+++ b/config/example-delta.cfg
@@ -107,3 +107,28 @@ delta_radius: 174.75
 #   axis towers. This parameter may also be calculated as:
 #    delta_radius = smooth_rod_offset - effector_offset - carriage_offset
 #   This parameter must be provided.
+
+# The delta_calibrate section enables a DELTA_CALIBRATE extended
+# g-code command that can calibrate the tower endstop positions and
+# angles.
+[delta_calibrate]
+radius: 50
+#   Radius (in mm) of the area that may be probed. This is typically
+#   the size of the printer bed. This parameter must be provided.
+#speed: 50
+#   The speed (in mm/s) of non-probing moves during the
+#   calibration. The default is 50.
+#horizontal_move_z: 5
+#   The height (in mm) that the head should be commanded to move to
+#   just prior to starting a probe operation. The default is 5.
+#probe_z_offset: 0
+#   The Z height (in mm) of the head when the probe triggers. The
+#   default is 0.
+#manual_probe:
+#   If true, then DELTA_CALIBRATE will perform manual probing. If
+#   false, then a PROBE command will be run at each probe
+#   point. Manual probing is accomplished by manually jogging the Z
+#   position of the print head at each probe point and then issuing a
+#   NEXT extended g-code command to record the position at that
+#   point. The default is false if a [probe] config section is present
+#   and true otherwise.
diff --git a/klippy/delta.py b/klippy/delta.py
index 6d2490e59..7a294833d 100644
--- a/klippy/delta.py
+++ b/klippy/delta.py
@@ -24,10 +24,11 @@ class DeltaKinematics:
             default_position=stepper_a.position_endstop)
         self.steppers = [stepper_a, stepper_b, stepper_c]
         self.need_motor_enable = self.need_home = True
-        radius = config.getfloat('delta_radius', above=0.)
+        self.radius = radius = config.getfloat('delta_radius', above=0.)
         arm_length_a = stepper_configs[0].getfloat('arm_length', above=radius)
-        arm_lengths = [sconfig.getfloat('arm_length', arm_length_a, above=radius)
-                       for sconfig in stepper_configs]
+        self.arm_lengths = arm_lengths = [
+            sconfig.getfloat('arm_length', arm_length_a, above=radius)
+            for sconfig in stepper_configs]
         self.arm2 = [arm**2 for arm in arm_lengths]
         self.endstops = [s.position_endstop + math.sqrt(arm2 - radius**2)
                          for s, arm2 in zip(self.steppers, self.arm2)]
@@ -48,11 +49,12 @@ class DeltaKinematics:
         for s in self.steppers:
             s.set_max_jerk(max_halt_velocity, self.max_accel)
         # Determine tower locations in cartesian space
-        angles = [sconfig.getfloat('angle', angle)
-                  for sconfig, angle in zip(stepper_configs, [210., 330., 90.])]
+        self.angles = [sconfig.getfloat('angle', angle)
+                       for sconfig, angle in zip(stepper_configs,
+                                                 [210., 330., 90.])]
         self.towers = [(math.cos(math.radians(angle)) * radius,
                         math.sin(math.radians(angle)) * radius)
-                       for angle in angles]
+                       for angle in self.angles]
         # Find the point where an XY move could result in excessive
         # tower movement
         half_min_step_dist = min([s.step_dist for s in self.steppers]) * .5
@@ -77,30 +79,7 @@ class DeltaKinematics:
                           - (self.towers[i][1] - coord[1])**2) + coord[2]
                 for i in StepList]
     def _actuator_to_cartesian(self, pos):
-        # Find nozzle position using trilateration (see wikipedia)
-        carriage1 = list(self.towers[0]) + [pos[0]]
-        carriage2 = list(self.towers[1]) + [pos[1]]
-        carriage3 = list(self.towers[2]) + [pos[2]]
-
-        s21 = matrix_sub(carriage2, carriage1)
-        s31 = matrix_sub(carriage3, carriage1)
-
-        d = math.sqrt(matrix_magsq(s21))
-        ex = matrix_mul(s21, 1. / d)
-        i = matrix_dot(ex, s31)
-        vect_ey = matrix_sub(s31, matrix_mul(ex, i))
-        ey = matrix_mul(vect_ey, 1. / math.sqrt(matrix_magsq(vect_ey)))
-        ez = matrix_cross(ex, ey)
-        j = matrix_dot(ey, s31)
-
-        x = (self.arm2[0] - self.arm2[1] + d**2) / (2. * d)
-        y = (self.arm2[0] - self.arm2[2] - x**2 + (x-i)**2 + j**2) / (2. * j)
-        z = -math.sqrt(self.arm2[0] - x**2 - y**2)
-
-        ex_x = matrix_mul(ex, x)
-        ey_y = matrix_mul(ey, y)
-        ez_z = matrix_mul(ez, z)
-        return matrix_add(carriage1, matrix_add(ex_x, matrix_add(ey_y, ez_z)))
+        return actuator_to_cartesian(self.towers, self.arm2, pos)
     def get_position(self):
         spos = [s.mcu_stepper.get_commanded_position() for s in self.steppers]
         return self._actuator_to_cartesian(spos)
@@ -225,6 +204,21 @@ class DeltaKinematics:
             if decel_d:
                 step_delta(move_time, decel_d, cruise_v, -accel,
                            vt_startz, vt_startxy_d, vt_arm_d, movez_r)
+    # Helper functions for DELTA_CALIBRATE script
+    def get_stable_position(self):
+        return [int((ep - s.mcu_stepper.get_commanded_position())
+                    /  s.mcu_stepper.get_step_dist() + .5)
+                * s.mcu_stepper.get_step_dist()
+                for ep, s in zip(self.endstops, self.steppers)]
+    def get_calibrate_params(self):
+        return {
+            'endstop_a': self.steppers[0].position_endstop,
+            'endstop_b': self.steppers[1].position_endstop,
+            'endstop_c': self.steppers[2].position_endstop,
+            'angle_a': self.angles[0], 'angle_b': self.angles[1],
+            'angle_c': self.angles[2], 'radius': self.radius,
+            'arm_a': self.arm_lengths[0], 'arm_b': self.arm_lengths[1],
+            'arm_c': self.arm_lengths[2] }
 
 
 ######################################################################
@@ -250,3 +244,41 @@ def matrix_sub(m1, m2):
 
 def matrix_mul(m1, s):
     return [m1[0]*s, m1[1]*s, m1[2]*s]
+
+def actuator_to_cartesian(towers, arm2, pos):
+    # Find nozzle position using trilateration (see wikipedia)
+    carriage1 = list(towers[0]) + [pos[0]]
+    carriage2 = list(towers[1]) + [pos[1]]
+    carriage3 = list(towers[2]) + [pos[2]]
+
+    s21 = matrix_sub(carriage2, carriage1)
+    s31 = matrix_sub(carriage3, carriage1)
+
+    d = math.sqrt(matrix_magsq(s21))
+    ex = matrix_mul(s21, 1. / d)
+    i = matrix_dot(ex, s31)
+    vect_ey = matrix_sub(s31, matrix_mul(ex, i))
+    ey = matrix_mul(vect_ey, 1. / math.sqrt(matrix_magsq(vect_ey)))
+    ez = matrix_cross(ex, ey)
+    j = matrix_dot(ey, s31)
+
+    x = (arm2[0] - arm2[1] + d**2) / (2. * d)
+    y = (arm2[0] - arm2[2] - x**2 + (x-i)**2 + j**2) / (2. * j)
+    z = -math.sqrt(arm2[0] - x**2 - y**2)
+
+    ex_x = matrix_mul(ex, x)
+    ey_y = matrix_mul(ey, y)
+    ez_z = matrix_mul(ez, z)
+    return matrix_add(carriage1, matrix_add(ex_x, matrix_add(ey_y, ez_z)))
+
+def get_position_from_stable(spos, params):
+    angles = [params['angle_a'], params['angle_b'], params['angle_c']]
+    radius = params['radius']
+    radius2 = radius**2
+    towers = [(math.cos(angle) * radius, math.sin(angle) * radius)
+              for angle in map(math.radians, angles)]
+    arm2 = [a**2 for a in [params['arm_a'], params['arm_b'], params['arm_c']]]
+    endstops = [params['endstop_a'], params['endstop_b'], params['endstop_c']]
+    pos = [es + math.sqrt(a2 - radius2) - p
+           for es, a2, p in zip(endstops, arm2, spos)]
+    return actuator_to_cartesian(towers, arm2, pos)
diff --git a/klippy/extras/delta_calibrate.py b/klippy/extras/delta_calibrate.py
new file mode 100644
index 000000000..5c69aa8d6
--- /dev/null
+++ b/klippy/extras/delta_calibrate.py
@@ -0,0 +1,76 @@
+# Delta calibration support
+#
+# Copyright (C) 2017-2018  Kevin O'Connor <kevin@koconnor.net>
+#
+# This file may be distributed under the terms of the GNU GPLv3 license.
+import math, logging
+import probe, delta
+
+class DeltaCalibrate:
+    def __init__(self, config):
+        self.printer = config.get_printer()
+        if config.getsection('printer').get('kinematics') != 'delta':
+            raise config.error("Delta calibrate is only for delta printers")
+        self.radius = config.getfloat('radius', above=0.)
+        self.speed = config.getfloat('speed', 50., above=0.)
+        self.horizontal_move_z = config.getfloat('horizontal_move_z', 5.)
+        self.probe_z_offset = config.getfloat('probe_z_offset', 0.)
+        self.manual_probe = config.getboolean('manual_probe', None)
+        if self.manual_probe is None:
+            self.manual_probe = not config.has_section('probe')
+        self.gcode = self.printer.lookup_object('gcode')
+        self.gcode.register_command(
+            'DELTA_CALIBRATE', self.cmd_DELTA_CALIBRATE,
+            desc=self.cmd_DELTA_CALIBRATE_help)
+    cmd_DELTA_CALIBRATE_help = "Delta calibration script"
+    def cmd_DELTA_CALIBRATE(self, params):
+        # Setup probe points
+        points = [(0., 0.)]
+        scatter = [.95, .90, .85, .70, .75, .80]
+        for i in range(6):
+            r = math.radians(90. + 60. * i)
+            dist = self.radius * scatter[i]
+            points.append((math.cos(r) * dist, math.sin(r) * dist))
+        # Probe them
+        self.gcode.run_script("G28")
+        probe.ProbePointsHelper(self.printer, points, self.horizontal_move_z,
+                                self.speed, self.manual_probe, self)
+    def get_position(self):
+        kin = self.printer.lookup_object('toolhead').get_kinematics()
+        return kin.get_stable_position()
+    def finalize(self, positions):
+        kin = self.printer.lookup_object('toolhead').get_kinematics()
+        logging.debug("Got: %s", positions)
+        params = kin.get_calibrate_params()
+        logging.debug("Params: %s", params)
+        adj_params = ('endstop_a', 'endstop_b', 'endstop_c', 'radius',
+                      'angle_a', 'angle_b')
+        def delta_errorfunc(params):
+            total_error = 0.
+            for spos in positions:
+                x, y, z = delta.get_position_from_stable(spos, params)
+                total_error += (z - self.probe_z_offset)**2
+            return total_error
+        new_params = probe.coordinate_descent(
+            adj_params, params, delta_errorfunc)
+        logging.debug("Got2: %s", new_params)
+        for spos in positions:
+            logging.debug("orig: %s new: %s",
+                          delta.get_position_from_stable(spos, params),
+                          delta.get_position_from_stable(spos, new_params))
+        self.gcode.respond_info(
+            "stepper_a: position_endstop: %.6f angle: %.6f\n"
+            "stepper_b: position_endstop: %.6f angle: %.6f\n"
+            "stepper_c: position_endstop: %.6f angle: %.6f\n"
+            "radius: %.6f\n"
+            "To use these parameters, update the printer config file with\n"
+            "the above and then issue a RESTART command" % (
+                new_params['endstop_a'], new_params['angle_a'],
+                new_params['endstop_b'], new_params['angle_b'],
+                new_params['endstop_c'], new_params['angle_c'],
+                new_params['radius']))
+
+def load_config(config):
+    if config.get_name() != 'delta_calibrate':
+        raise config.error("Invalid delta_calibrate config name")
+    return DeltaCalibrate(config)
diff --git a/klippy/extras/probe.py b/klippy/extras/probe.py
index 73bdfafaf..aeebf725c 100644
--- a/klippy/extras/probe.py
+++ b/klippy/extras/probe.py
@@ -3,6 +3,7 @@
 # Copyright (C) 2017-2018  Kevin O'Connor <kevin@koconnor.net>
 #
 # This file may be distributed under the terms of the GNU GPLv3 license.
+import logging
 import homing
 
 class PrinterProbe:
@@ -48,6 +49,91 @@ class PrinterProbe:
         self.gcode.respond_info(
             "probe: %s" % (["open", "TRIGGERED"][not not res],))
 
+# Helper code that can probe a series of points and report the
+# position at each point.
+class ProbePointsHelper:
+    def __init__(self, printer, probe_points, horizontal_move_z, speed,
+                 manual_probe, callback):
+        self.printer = printer
+        self.probe_points = probe_points
+        self.horizontal_move_z = horizontal_move_z
+        self.speed = speed
+        self.callback = callback
+        self.toolhead = self.printer.lookup_object('toolhead')
+        self.results = []
+        self.busy = True
+        self.gcode = self.printer.lookup_object('gcode')
+        self.gcode.register_command(
+            'NEXT', self.cmd_NEXT, desc=self.cmd_NEXT_help)
+        # Begin probing
+        self.move_next()
+        if not manual_probe:
+            while self.busy:
+                self.gcode.run_script("PROBE")
+                self.cmd_NEXT({})
+    def move_next(self):
+        x, y = self.probe_points[len(self.results)]
+        curpos = self.toolhead.get_position()
+        curpos[0] = x
+        curpos[1] = y
+        curpos[2] = self.horizontal_move_z
+        self.toolhead.move(curpos, self.speed)
+        self.gcode.reset_last_position()
+    cmd_NEXT_help = "Move to the next XY position to probe"
+    def cmd_NEXT(self, params):
+        # Record current position
+        self.toolhead.wait_moves()
+        self.results.append(self.callback.get_position())
+        # Move to next position
+        curpos = self.toolhead.get_position()
+        curpos[2] = self.horizontal_move_z
+        self.toolhead.move(curpos, self.speed)
+        if len(self.results) == len(self.probe_points):
+            self.toolhead.get_last_move_time()
+            self.finalize(True)
+            return
+        self.move_next()
+    def finalize(self, success):
+        self.busy = False
+        self.gcode.reset_last_position()
+        self.gcode.register_command('NEXT', None)
+        if success:
+            self.callback.finalize(self.results)
+
+# Helper code that implements coordinate descent
+def coordinate_descent(adj_params, params, error_func):
+    # Define potential changes
+    params = dict(params)
+    dp = {param_name: 1. for param_name in adj_params}
+    # Calculate the error
+    best_err = error_func(params)
+
+    threshold = 0.00001
+    rounds = 0
+
+    while sum(dp.values()) > threshold and rounds < 10000:
+        rounds += 1
+        for param_name in adj_params:
+            orig = params[param_name]
+            params[param_name] = orig + dp[param_name]
+            err = error_func(params)
+            if err < best_err:
+                # There was some improvement
+                best_err = err
+                dp[param_name] *= 1.1
+                continue
+            params[param_name] = orig - dp[param_name]
+            err = error_func(params)
+            if err < best_err:
+                # There was some improvement
+                best_err = err
+                dp[param_name] *= 1.1
+                continue
+            params[param_name] = orig
+            dp[param_name] *= 0.9
+    logging.debug("best_err: %s  rounds: %d", best_err, rounds)
+    return params
+
 def load_config(config):
     if config.get_name() != 'probe':
         raise config.error("Invalid probe config name")