target.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2020 Northwestern University
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
25  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
26  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
27  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
29  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
30  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  *********************************************************************/
38 #ifndef TARGET_HPP
39 #define TARGET_HPP
40 
41 #include <armadillo>
42 
43 #include <visualization_msgs/MarkerArray.h>
44 
47 
48 namespace ergodic_exploration
49 {
50 using arma::mat;
51 using arma::vec;
52 struct Gaussian;
53 typedef std::vector<Gaussian> GaussianList;
54 
56 struct Gaussian
57 {
60  {
61  }
62 
68  Gaussian(const vec& mu, const vec& sigmas)
69  : mu(mu), cov(arma::diagmat(square(sigmas))), cov_inv(inv(cov))
70  {
71  }
72 
78  double operator()(const vec& pt) const
79  {
80  const vec diff = pt - mu;
81  return std::exp(-0.5 * dot(diff.t() * cov_inv, diff));
82  }
83 
91  double operator()(const vec& pt, const vec& trans) const
92  {
93  // DEBUG
94  // if (any(mu - trans) < 0.0)
95  // {
96  // std::cout << "WARNING: Targert mean not within fourier domain" << std::endl;
97  // }
98 
99  // translate mu into frame of fourier domain
100  const vec diff = pt - (mu - trans);
101  return std::exp(-0.5 * dot(diff.t() * cov_inv, diff));
102  }
103 
104  vec mu; // mean
105  mat cov; // covariance
106  mat cov_inv; // inverse of covariance
107 };
108 
110 class Target
111 {
112 public:
114  Target();
115 
120  Target(const GaussianList& gaussians);
121 
126  void addGaussian(const Gaussian& g);
127 
132  void deleteGaussian(unsigned int idx);
133 
141  double evaluate(const vec& pt, const vec& trans) const;
142 
150  vec fill(const vec& trans, const mat& phi_grid) const;
151 
157  visualization_msgs::MarkerArray markers(const std::string& frame) const;
158 
159 private:
160  GaussianList gaussians_; // list of target gaussians
161 };
162 } // namespace ergodic_exploration
163 #endif
ergodic_exploration::Gaussian::Gaussian
Gaussian(const vec &mu, const vec &sigmas)
Constructor.
Definition: target.hpp:68
ergodic_exploration::Gaussian::cov_inv
mat cov_inv
Definition: target.hpp:106
ergodic_exploration::Target::markers
visualization_msgs::MarkerArray markers(const std::string &frame) const
Visualize target distribution.
Definition: target.cpp:91
ergodic_exploration::Target::gaussians_
GaussianList gaussians_
Definition: target.hpp:160
ergodic_exploration::Target::evaluate
double evaluate(const vec &pt, const vec &trans) const
Evaluate the list of gaussians.
Definition: target.cpp:68
ergodic_exploration::Target::Target
Target()
Constructor.
Definition: target.cpp:50
ergodic_exploration::Gaussian::cov
mat cov
Definition: target.hpp:105
ergodic_exploration::Target::addGaussian
void addGaussian(const Gaussian &g)
Adds gaussian to list.
Definition: target.cpp:58
dot
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
ergodic_exploration
Definition: basis.hpp:43
ergodic_exploration::Gaussian::operator()
double operator()(const vec &pt) const
Evaluate gaussian.
Definition: target.hpp:78
ergodic_exploration::Target
Target distribution.
Definition: target.hpp:110
ergodic_exploration::Target::deleteGaussian
void deleteGaussian(unsigned int idx)
Remove gaussian from list.
Definition: target.cpp:63
ergodic_exploration::Gaussian
2D gaussian
Definition: target.hpp:56
ergodic_exploration::Gaussian::Gaussian
Gaussian()
Constructor.
Definition: target.hpp:59
numerics.hpp
Useful numerical utilities.
grid.hpp
2D grid represented in row major order
ergodic_exploration::Target::fill
vec fill(const vec &trans, const mat &phi_grid) const
Evaluate the target distribution.
Definition: target.cpp:78
ergodic_exploration::Gaussian::operator()
double operator()(const vec &pt, const vec &trans) const
Evaluate gaussian.
Definition: target.hpp:91
ergodic_exploration::Gaussian::mu
vec mu
Definition: target.hpp:104
ergodic_exploration::GaussianList
std::vector< Gaussian > GaussianList
Definition: target.hpp:52


ergodic_exploration
Author(s): bostoncleek
autogenerated on Wed Mar 2 2022 00:17:13