Skip to content

Commit

Permalink
Improved Sphinx documentation.
Browse files Browse the repository at this point in the history
Reduced number of errors generated by Sphinx. Added SimplexSigmaPoints.
  • Loading branch information
rlabbe committed Sep 15, 2016
1 parent 520c6c9 commit c315f2a
Show file tree
Hide file tree
Showing 12 changed files with 76 additions and 60 deletions.
2 changes: 2 additions & 0 deletions docs/conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@
# ones.
extensions = [
'sphinx.ext.autodoc',
'sphinx.ext.autosummary',
'sphinx.ext.doctest',
'numpydoc',
'sphinx.ext.intersphinx',
Expand All @@ -57,6 +58,7 @@
'sphinx.ext.autodoc',
'numpydoc'
]
numpydoc_show_class_members = False

# Add any paths that contain templates here, relative to this directory.
templates_path = ['_templates']
Expand Down
7 changes: 7 additions & 0 deletions docs/kalman/UnscentedKalmanFilter.rst
Original file line number Diff line number Diff line change
Expand Up @@ -36,3 +36,10 @@ This implements the unscented Kalman filter.
.. automethod:: __init__


--------


.. autoclass:: SimplexSigmaPoints
:members:

.. automethod:: __init__
2 changes: 1 addition & 1 deletion filterpy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,4 @@
for more information.
"""

__version__ = "0.1.3"
__version__ = "0.1.4"
10 changes: 4 additions & 6 deletions filterpy/changelog.txt
Original file line number Diff line number Diff line change
@@ -1,13 +1,11 @@
Version 0.1.5
=============

* Bug in Q_continuous_white_noise(). The first term in the matrix should be (dt**3)/3, not (dt**4)/3.

Version 0.1.4
=============

* Added Cubature Kalman filter.

* Bug in Q_continuous_white_noise(). The first term in the matrix should be (dt**3)/3, not (dt**4)/3.
* Added log-likelihood computation to UKF.
* Added simplex points for UKF
* fixed bug in KF matrix size check

Version 0.1.3
=============
Expand Down
4 changes: 2 additions & 2 deletions filterpy/common/discretization.py
Original file line number Diff line number Diff line change
Expand Up @@ -106,8 +106,8 @@ def van_loan_discretization(F, G, dt):
Given y'' + y = 2u(t), we create the continuous state model of
x' = | 0 1| * x + |0|*u(t)
|-1 0| |2|
x' = [ 0 1] * x + [0]*u(t)
[-1 0] [2]
and a time step of 0.1:
Expand Down
5 changes: 3 additions & 2 deletions filterpy/hinfinity/hinfinity_filter.py
Original file line number Diff line number Diff line change
Expand Up @@ -250,7 +250,7 @@ def measurement_of_state(self, x):

@property
def x(self):
""" state vector property"""
""" state vector"""
return self._x


Expand All @@ -271,7 +271,7 @@ def G(self, value):

@property
def P(self):
""" covariance matrix property"""
""" covariance matrix"""
return self._P


Expand All @@ -282,6 +282,7 @@ def P(self, value):

@property
def F(self):
""" State transition matrix"""
return self._F


Expand Down
12 changes: 10 additions & 2 deletions filterpy/kalman/EKF.py
Original file line number Diff line number Diff line change
Expand Up @@ -224,23 +224,25 @@ def predict(self, u=0):

@property
def Q(self):
""" Process uncertainty"""
""" Process uncertainty matrix"""
return self._Q


@Q.setter
def Q(self, value):
""" Process uncertainty matrix"""
self._Q = setter_scalar(value, self.dim_x)


@property
def P(self):
""" covariance matrix"""
""" state covariance matrix"""
return self._P


@P.setter
def P(self, value):
""" state covariance matrix"""
self._P = setter_scalar(value, self.dim_x)


Expand All @@ -252,21 +254,25 @@ def R(self):

@R.setter
def R(self, value):
""" measurement uncertainty"""
self._R = setter_scalar(value, self.dim_z)


@property
def F(self):
"""State Transition matrix"""
return self._F


@F.setter
def F(self, value):
"""State Transition matrix"""
self._F = setter(value, self.dim_x, self.dim_x)


@property
def B(self):
""" control transition matrix"""
return self._B


Expand All @@ -278,10 +284,12 @@ def B(self, value):

@property
def x(self):
""" state estimate vector """
return self._x

@x.setter
def x(self, value):
""" state estimate vector """
self._x = setter_1d(value, self.dim_x)

@property
Expand Down
34 changes: 12 additions & 22 deletions filterpy/kalman/fading_memory.py
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ def __init__(self, alpha, dim_x, dim_z, dim_u=0):
You will have to assign reasonable values to all of these before
running the filter. All must have dtype of float
X : ndarray (dim_x, 1), default = [0,0,0...0]
x : ndarray (dim_x, 1), default = [0,0,0...0]
state of the filter
P : ndarray (dim_x, dim_x), default identity matrix
Expand Down Expand Up @@ -93,7 +93,7 @@ def __init__(self, alpha, dim_x, dim_z, dim_u=0):
self.dim_z = dim_z
self.dim_u = dim_u

self._X = zeros((dim_x,1)) # state
self._x = zeros((dim_x,1)) # state
self._P = eye(dim_x) # uncertainty covariance
self._Q = eye(dim_x) # process uncertainty
self._B = 0 # control transition matrix
Expand Down Expand Up @@ -139,7 +139,7 @@ def update(self, z, R=None):
# rename for readability and a tiny extra bit of speed
H = self._H
P = self._P
x = self._X
x = self._x

# y = z - Hx
# error (residual) between measurement and prediction
Expand All @@ -155,7 +155,7 @@ def update(self, z, R=None):

# x = x + Ky
# predict new x with residual scaled by the kalman gain
self._X = x + dot(K, self._y)
self._x = x + dot(K, self._y)

# P = (I-KH)P(I-KH)' + KRK'
I_KH = self._I - dot(K, H)
Expand All @@ -177,7 +177,7 @@ def predict(self, u=0):
"""

# x = Fx + Bu
self._X = dot(self._F, self._X) + dot(self._B, u)
self._x = dot(self._F, self._x) + dot(self._B, u)

# P = FPF' + Q
self._P = self.alpha_sq*dot3(self._F, self._P, self._F.T) + self._Q
Expand Down Expand Up @@ -239,20 +239,20 @@ def batch_filter(self, zs, Rs=None, update_first=False):
if update_first:
for i,(z,r) in enumerate(zip(zs,Rs)):
self.update(z,r)
means[i,:] = self._X
means[i,:] = self._x
covariances[i,:,:] = self._P

self.predict()
means_p[i,:] = self._X
means_p[i,:] = self._x
covariances_p[i,:,:] = self._P
else:
for i,(z,r) in enumerate(zip(zs,Rs)):
self.predict()
means_p[i,:] = self._X
means_p[i,:] = self._x
covariances_p[i,:,:] = self._P

self.update(z,r)
means[i,:] = self._X
means[i,:] = self._x
covariances[i,:,:] = self._P

return (means, covariances, means_p, covariances_p)
Expand All @@ -275,7 +275,7 @@ def get_prediction(self, u=0):
State vector and covariance array of the prediction.
"""

x = dot(self._F, self._X) + dot(self._B, u)
x = dot(self._F, self._x) + dot(self._B, u)
P = self.alpha_sq*dot3(self._F, self._P, self._F.T) + self.Q
return (x, P)

Expand All @@ -284,7 +284,7 @@ def residual_of(self, z):
""" returns the residual for the given measurement (z). Does not alter
the state of the filter.
"""
return z - dot(self._H, self._X)
return z - dot(self._H, self._x)


def measurement_of_state(self, x):
Expand Down Expand Up @@ -369,19 +369,9 @@ def B(self, value):
self._B = setter (value, self.dim_x, self.dim_u)


@property
def X(self):
""" filter state vector."""
return self._X


@X.setter
def X(self, value):
self._X = setter(value, self.dim_x, 1)


@property
def x(self):
""" state vector."""
assert False

@x.setter
Expand Down
7 changes: 5 additions & 2 deletions filterpy/kalman/information_filter.py
Original file line number Diff line number Diff line change
Expand Up @@ -284,7 +284,7 @@ def measurement_of_state(self, x):

@property
def Q(self):
""" Process uncertainty"""
"""Process uncertainty"""
return self._Q


Expand All @@ -305,7 +305,7 @@ def P_inv(self, value):

@property
def R_inv(self):
""" measurement uncertainty"""
"""inverse measurement uncertainty"""
return self._R_inv


Expand All @@ -315,6 +315,7 @@ def R_inv(self, value):

@property
def H(self):
"""Measurement function"""
return self._H


Expand All @@ -325,6 +326,7 @@ def H(self, value):

@property
def F(self):
"""State Transition matrix"""
return self._F


Expand All @@ -347,6 +349,7 @@ def B(self, value):

@property
def x(self):
""" State estimate vector """
return self._x


Expand Down
12 changes: 8 additions & 4 deletions filterpy/kalman/kalman_filter.py
Original file line number Diff line number Diff line change
Expand Up @@ -700,6 +700,7 @@ def alpha(self):

@property
def likelihood(self):
""" likelihood of measurement"""
return math.exp(self.log_likelihood)


Expand All @@ -712,22 +713,24 @@ def alpha(self, value):

@property
def Q(self):
""" Process uncertainty"""
""" Process uncertainty matrix"""
return self._Q


@Q.setter
def Q(self, value):
""" Process uncertainty matrix"""
self._Q = setter_scalar(value, self.dim_x)

@property
def P(self):
""" covariance matrix"""
""" state covariance matrix"""
return self._P


@P.setter
def P(self, value):
""" state covariance matrix"""
self._P = setter_scalar(value, self.dim_x)


Expand All @@ -739,6 +742,7 @@ def F(self):

@F.setter
def F(self, value):
""" state transition matrix"""
self._F = setter(value, self.dim_x, self.dim_x)

@property
Expand All @@ -749,7 +753,6 @@ def B(self):

@B.setter
def B(self, value):
self._B = value
""" control transition matrix"""
if np.isscalar(value):
self._B = value
Expand All @@ -759,12 +762,13 @@ def B(self, value):

@property
def x(self):
""" filter state vector."""
""" state vector."""
return self._x


@x.setter
def x(self, value):
""" state vector."""
self._x = setter_1d(value, self.dim_x)


Expand Down
Loading

0 comments on commit c315f2a

Please sign in to comment.