Stats
stats¶
A collection of functions used to compute and plot statistics relevant to Bayesian filters.
Gaussian¶
gaussian(x, mean, var, normed=True)
¶
returns probability density function (pdf) for x given a Gaussian with the specified mean and variance. All must be scalars.
gaussian (1,2,3) is equivalent to scipy.stats.norm(2, math.sqrt(3)).pdf(1) It is quite a bit faster albeit much less flexible than the latter.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
x
|
scalar or array - like
|
The value(s) for which we compute the distribution |
required |
mean
|
scalar
|
Mean of the Gaussian |
required |
var
|
scalar
|
Variance of the Gaussian |
required |
normed
|
bool
|
Normalize the output if the input is an array of values. |
True
|
Returns:
| Name | Type | Description |
|---|---|---|
pdf |
float
|
probability distribution of x for the Gaussian (mean, var). E.g. 0.101 denotes 10.1%. |
Examples:
Source code in bayesian_filters/stats/stats.py
Multiply Gaussians¶
mul(mean1, var1, mean2, var2)
¶
Multiply Gaussian (mean1, var1) with (mean2, var2) and return the results as a tuple (mean, var).
Strictly speaking the product of two Gaussian PDFs is a Gaussian function, not Gaussian PDF. It is, however, proportional to a Gaussian PDF, so it is safe to treat the output as a PDF for any filter using Bayes equation, which normalizes the result anyway.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
mean1
|
scalar
|
mean of first Gaussian |
required |
var1
|
scalar
|
variance of first Gaussian |
required |
mean2
|
scalar
|
mean of second Gaussian |
required |
var2
|
scalar
|
variance of second Gaussian |
required |
Returns:
| Name | Type | Description |
|---|---|---|
mean |
scalar
|
mean of product |
var |
scalar
|
variance of product |
Examples:
References
Bromily. "Products and Convolutions of Gaussian Probability Functions", Tina Memo No. 2003-003. http://www.tina-vision.net/docs/memos/2003-003.pdf
Source code in bayesian_filters/stats/stats.py
Add Gaussians¶
add(mean1, var1, mean2, var2)
¶
Add the Gaussians (mean1, var1) with (mean2, var2) and return the results as a tuple (mean,var).
var1 and var2 are variances - sigma squared in the usual parlance.
Source code in bayesian_filters/stats/stats.py
Log Likelihood¶
log_likelihood(z, x, P, H, R)
¶
Returns log-likelihood of the measurement z given the Gaussian posterior (x, P) using measurement function H and measurement covariance error R
Source code in bayesian_filters/stats/stats.py
Likelihood¶
likelihood(z, x, P, H, R)
¶
Returns likelihood of the measurement z given the Gaussian posterior (x, P) using measurement function H and measurement covariance error R
Log PDF¶
logpdf(x, mean=None, cov=1, allow_singular=True)
¶
Computes the log of the probability density function of the normal N(mean, cov) for the data x. The normal may be univariate or multivariate.
Wrapper for older versions of scipy.multivariate_normal.logpdf which don't support support the allow_singular keyword prior to verion 0.15.0.
If it is not supported, and cov is singular or not PSD you may get an exception.
x and mean may be column vectors, row vectors, or lists.
Source code in bayesian_filters/stats/stats.py
Multivariate Gaussian¶
multivariate_gaussian(x, mu, cov)
¶
This is designed to replace scipy.stats.multivariate_normal which is not available before version 0.14. You may either pass in a multivariate set of data:
.. code-block:: Python
multivariate_gaussian (array([1,1]), array([3,4]), eye(2)*1.4) multivariate_gaussian (array([1,1,1]), array([3,4,5]), 1.4)
or unidimensional data:
.. code-block:: Python
multivariate_gaussian(1, 3, 1.4)
In the multivariate case if cov is a scalar it is interpreted as eye(n)*cov
The function gaussian() implements the 1D (univariate)case, and is much faster than this function.
equivalent calls:
.. code-block:: Python
multivariate_gaussian(1, 2, 3) scipy.stats.multivariate_normal(2,3).pdf(1)
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
x
|
float, or np.array-like
|
Value to compute the probability for. May be a scalar if univariate, or any type that can be converted to an np.array (list, tuple, etc). np.array is best for speed. |
required |
mu
|
float, or np.array-like
|
mean for the Gaussian . May be a scalar if univariate, or any type that can be converted to an np.array (list, tuple, etc).np.array is best for speed. |
required |
cov
|
float, or np.array-like
|
Covariance for the Gaussian . May be a scalar if univariate, or any type that can be converted to an np.array (list, tuple, etc).np.array is best for speed. |
required |
Returns:
| Name | Type | Description |
|---|---|---|
probability |
float
|
probability for x for the Gaussian (mu,cov) |
Source code in bayesian_filters/stats/stats.py
318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 | |
Multivariate Multiply¶
multivariate_multiply(m1, c1, m2, c2)
¶
Multiplies the two multivariate Gaussians together and returns the results as the tuple (mean, covariance).
Examples:
.. code-block:: Python
m, c = multivariate_multiply([7.0, 2], [[1.0, 2.0], [2.0, 1.0]],
[3.2, 0], [[8.0, 1.1], [1.1,8.0]])
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
m1
|
array - like
|
Mean of first Gaussian. Must be convertable to an 1D array via numpy.asarray(), For example 6, [6], [6, 5], np.array([3, 4, 5, 6]) are all valid. |
required |
c1
|
matrix - like
|
Covariance of first Gaussian. Must be convertable to an 2D array via numpy.asarray(). m2 : array-like Mean of second Gaussian. Must be convertable to an 1D array via numpy.asarray(), For example 6, [6], [6, 5], np.array([3, 4, 5, 6]) are all valid. |
required |
c2
|
matrix - like
|
Covariance of second Gaussian. Must be convertable to an 2D array via numpy.asarray(). |
required |
Returns:
| Name | Type | Description |
|---|---|---|
m |
ndarray
|
mean of the result |
c |
ndarray
|
covariance of the result |
Source code in bayesian_filters/stats/stats.py
Plot Gaussian CDF¶
plot_gaussian_cdf(mean=0.0, variance=1.0, ax=None, xlim=None, ylim=(0.0, 1.0), xlabel=None, ylabel=None, label=None)
¶
Plots a normal distribution CDF with the given mean and variance. x-axis contains the mean, the y-axis shows the cumulative probability.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
mean
|
scalar
|
mean for the normal distribution. |
0.
|
variance
|
scalar
|
variance for the normal distribution. |
0.
|
ax
|
matplotlib axes object
|
If provided, the axes to draw on, otherwise plt.gca() is used. |
None
|
xlim
|
specify the limits for the x or y axis as tuple (low,high). If not specified, limits will be automatically chosen to be 'nice' |
None
|
|
ylim
|
specify the limits for the x or y axis as tuple (low,high). If not specified, limits will be automatically chosen to be 'nice' |
None
|
|
xlabel
|
(str, optional)
|
label for the x-axis |
None
|
ylabel
|
str
|
label for the y-axis |
None
|
label
|
str
|
label for the legend |
None
|
Returns:
| Type | Description |
|---|---|
axis of plot
|
|
Source code in bayesian_filters/stats/stats.py
Plot Gaussian PDF¶
plot_gaussian_pdf(mean=0.0, variance=1.0, std=None, ax=None, mean_line=False, xlim=None, ylim=None, xlabel=None, ylabel=None, label=None)
¶
Plots a normal distribution PDF with the given mean and variance. x-axis contains the mean, the y-axis shows the probability density.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
mean
|
scalar
|
mean for the normal distribution. |
0.
|
variance
|
scalar
|
variance for the normal distribution. |
1., optional
|
std
|
standard deviation of the normal distribution. Use instead of
|
None
|
|
ax
|
matplotlib axes object
|
If provided, the axes to draw on, otherwise plt.gca() is used. |
None
|
mean_line
|
boolean
|
draws a line at x=mean |
False
|
xlim
|
specify the limits for the x or y axis as tuple (low,high). If not specified, limits will be automatically chosen to be 'nice' |
None
|
|
ylim
|
specify the limits for the x or y axis as tuple (low,high). If not specified, limits will be automatically chosen to be 'nice' |
None
|
|
xlabel
|
(str, optional)
|
label for the x-axis |
None
|
ylabel
|
str
|
label for the y-axis |
None
|
label
|
str
|
label for the legend |
None
|
Returns:
| Type | Description |
|---|---|
axis of plot
|
|
Source code in bayesian_filters/stats/stats.py
569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 | |
Plot Discrete CDF¶
plot_discrete_cdf(xs, ys, ax=None, xlabel=None, ylabel=None, label=None)
¶
Plots a normal distribution CDF with the given mean and variance. x-axis contains the mean, the y-axis shows the cumulative probability.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
xs
|
list-like of scalars
|
x values corresponding to the values in |
required |
ys
|
list-like of scalars
|
list of probabilities to be plotted which should sum to 1. |
required |
ax
|
matplotlib axes object
|
If provided, the axes to draw on, otherwise plt.gca() is used. |
None
|
xlim
|
specify the limits for the x or y axis as tuple (low,high). If not specified, limits will be automatically chosen to be 'nice' |
required | |
ylim
|
specify the limits for the x or y axis as tuple (low,high). If not specified, limits will be automatically chosen to be 'nice' |
required | |
xlabel
|
(str, optional)
|
label for the x-axis |
None
|
ylabel
|
str
|
label for the y-axis |
None
|
label
|
str
|
label for the legend |
None
|
Returns:
| Type | Description |
|---|---|
axis of plot
|
|
Source code in bayesian_filters/stats/stats.py
Plot Gaussian¶
plot_gaussian(mean=0.0, variance=1.0, ax=None, mean_line=False, xlim=None, ylim=None, xlabel=None, ylabel=None, label=None)
¶
DEPRECATED. Use plot_gaussian_pdf() instead. This is poorly named, as there are multiple ways to plot a Gaussian.
Source code in bayesian_filters/stats/stats.py
Covariance Ellipse¶
covariance_ellipse(P, deviations=1)
¶
Returns a tuple defining the ellipse representing the 2 dimensional covariance matrix P.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
P
|
nd.array shape (2,2)
|
covariance matrix |
required |
deviations
|
int (optional
|
of standard deviations. Default is 1.¶ |
= 1)
|
Returns
|
|
required |
Source code in bayesian_filters/stats/stats.py
Plot Covariance Ellipse¶
plot_covariance_ellipse(mean, cov=None, variance=1.0, std=None, ellipse=None, title=None, axis_equal=True, show_semiaxis=False, facecolor=None, edgecolor=None, fc='none', ec='#004080', alpha=1.0, xlim=None, ylim=None, ls='solid')
¶
Deprecated function to plot a covariance ellipse. Use plot_covariance instead.
See Also
plot_covariance
Source code in bayesian_filters/stats/stats.py
Normal CDF¶
norm_cdf(x_range, mu, var=1, std=None)
¶
Computes the probability that a Gaussian distribution lies within a range of values.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
x_range
|
(float, float)
|
tuple of range to compute probability for |
required |
mu
|
float
|
mean of the Gaussian |
required |
var
|
float
|
variance of the Gaussian. Ignored if |
1
|
std
|
float
|
standard deviation of the Gaussian. This overrides the |
None
|
Returns:
| Name | Type | Description |
|---|---|---|
probability |
float
|
probability that Gaussian is within x_range. E.g. .1 means 10%. |
Source code in bayesian_filters/stats/stats.py
Random Student-t¶
rand_student_t(df, mu=0, std=1)
¶
return random number distributed by student's t distribution with
df degrees of freedom with the specified mean and standard deviation.
Source code in bayesian_filters/stats/stats.py
NEES¶
NEES(xs, est_xs, ps)
¶
Computes the normalized estimated error squared (NEES) test on a sequence of estimates. The estimates are optimal if the mean error is zero and the covariance matches the Kalman filter's covariance. If this holds, then the mean of the NEES should be equal to or less than the dimension of x.
Examples:
.. code-block: Python
xs = ground_truth()
est_xs, ps, _, _ = kf.batch_filter(zs)
NEES(xs, est_xs, ps)
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
xs
|
list - like
|
sequence of true values for the state x |
required |
est_xs
|
list - like
|
sequence of estimates from an estimator (such as Kalman filter) |
required |
ps
|
list - like
|
sequence of covariance matrices from the estimator |
required |
Returns:
| Name | Type | Description |
|---|---|---|
errs |
list of floats
|
list of NEES computed for each estimate |
Source code in bayesian_filters/stats/stats.py
Mahalanobis Distance¶
mahalanobis(x, mean, cov)
¶
Computes the Mahalanobis distance between the state vector x from the
Gaussian mean with covariance cov. This can be thought as the number
of standard deviations x is from the mean, i.e. a return value of 3 means
x is 3 std from mean.
Parameters:
| Name | Type | Description | Default |
|---|---|---|---|
x
|
(N,) array_like, or float
|
Input state vector |
required |
mean
|
(N,) array_like, or float
|
mean of multivariate Gaussian |
required |
cov
|
(N, N) array_like or float
|
covariance of the multivariate Gaussian |
required |
Returns:
| Name | Type | Description |
|---|---|---|
mahalanobis |
double
|
The Mahalanobis distance between vectors |
Examples: