Go to the documentation of this file.
43 #include <visualization_msgs/MarkerArray.h>
80 const vec diff = pt -
mu;
81 return std::exp(-0.5 *
dot(diff.t() *
cov_inv, diff));
100 const vec diff = pt - (
mu - trans);
101 return std::exp(-0.5 *
dot(diff.t() *
cov_inv, diff));
141 double evaluate(
const vec& pt,
const vec& trans)
const;
150 vec
fill(
const vec& trans,
const mat& phi_grid)
const;
157 visualization_msgs::MarkerArray
markers(
const std::string& frame)
const;
Gaussian(const vec &mu, const vec &sigmas)
Constructor.
visualization_msgs::MarkerArray markers(const std::string &frame) const
Visualize target distribution.
double evaluate(const vec &pt, const vec &trans) const
Evaluate the list of gaussians.
void addGaussian(const Gaussian &g)
Adds gaussian to list.
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
double operator()(const vec &pt) const
Evaluate gaussian.
void deleteGaussian(unsigned int idx)
Remove gaussian from list.
Useful numerical utilities.
2D grid represented in row major order
vec fill(const vec &trans, const mat &phi_grid) const
Evaluate the target distribution.
double operator()(const vec &pt, const vec &trans) const
Evaluate gaussian.
std::vector< Gaussian > GaussianList