state_6dof.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, the mcl_3dl authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef MCL_3DL_STATE_6DOF_H
31 #define MCL_3DL_STATE_6DOF_H
32 
33 #include <algorithm>
34 #include <cassert>
35 #include <vector>
36 
37 #include <ros/ros.h>
38 
39 #include <mcl_3dl/pf.h>
40 #include <mcl_3dl/point_types.h>
41 #include <mcl_3dl/quat.h>
42 #include <mcl_3dl/vec3.h>
43 
46 
47 namespace mcl_3dl
48 {
49 class State6DOF : public mcl_3dl::pf::ParticleBase<float>
50 {
51 public:
54  bool diff_;
55  float noise_ll_;
56  float noise_la_;
57  float noise_al_;
58  float noise_aa_;
61  class RPYVec
62  {
63  public:
66  {
67  }
68  explicit RPYVec(const mcl_3dl::Vec3& v)
69  {
70  v_ = v;
71  }
72  RPYVec(const float r, const float p, const float y)
73  {
74  v_.x_ = r;
75  v_.y_ = p;
76  v_.z_ = y;
77  }
78  };
80  float& operator[](const size_t i) override
81  {
82  switch (i)
83  {
84  case 0:
85  return pos_.x_;
86  case 1:
87  return pos_.y_;
88  case 2:
89  return pos_.z_;
90  case 3:
91  return rot_.x_;
92  case 4:
93  return rot_.y_;
94  case 5:
95  return rot_.z_;
96  case 6:
97  return rot_.w_;
98  case 7:
99  return odom_err_integ_lin_.x_;
100  case 8:
101  return odom_err_integ_lin_.y_;
102  case 9:
103  return odom_err_integ_lin_.z_;
104  case 10:
105  return odom_err_integ_ang_.x_;
106  case 11:
107  return odom_err_integ_ang_.y_;
108  case 12:
109  return odom_err_integ_ang_.z_;
110  default:
111  assert(false);
112  }
113  return pos_.x_;
114  }
115  float operator[](const size_t i) const
116  {
117  switch (i)
118  {
119  case 0:
120  return pos_.x_;
121  case 1:
122  return pos_.y_;
123  case 2:
124  return pos_.z_;
125  case 3:
126  return rot_.x_;
127  case 4:
128  return rot_.y_;
129  case 5:
130  return rot_.z_;
131  case 6:
132  return rot_.w_;
133  case 7:
134  return odom_err_integ_lin_.x_;
135  case 8:
136  return odom_err_integ_lin_.y_;
137  case 9:
138  return odom_err_integ_lin_.z_;
139  case 10:
140  return odom_err_integ_ang_.x_;
141  case 11:
142  return odom_err_integ_ang_.y_;
143  case 12:
144  return odom_err_integ_ang_.z_;
145  default:
146  assert(false);
147  }
148  return 0;
149  }
150  size_t size() const override
151  {
152  return 13;
153  }
154  void normalize() override
155  {
156  rot_.normalize();
157  }
158  size_t covDimension() const override
159  {
160  return 6;
161  }
162  float covElement(const State6DOF& e, const size_t& j, const size_t& k)
163  {
164  const mcl_3dl::Vec3 exp_rpy = e.isDiff() ? e.rpy_.v_ : e.rot_.getRPY();
165  const mcl_3dl::Vec3 rpy = isDiff() ? rpy_.v_ : rot_.getRPY();
166  float val = 1.0f, diff = 0.0f;
167  for (size_t i : {j, k})
168  {
169  if (i < 3)
170  {
171  diff = (*this)[i] - e[i];
172  }
173  else
174  {
175  diff = rpy[i - 3] - exp_rpy[i - 3];
176  while (diff > M_PI)
177  diff -= 2 * M_PI;
178  while (diff < -M_PI)
179  diff += 2 * M_PI;
180  }
181  val *= diff;
182  }
183  return val;
184  }
186  {
187  diff_ = false;
189  odom_err_integ_lin_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
190  odom_err_integ_ang_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
191  }
192  State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Quat rot)
193  {
194  pos_ = pos;
195  rot_ = rot;
197  odom_err_integ_lin_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
198  odom_err_integ_ang_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
199  diff_ = false;
200  }
201  State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Vec3 rpy)
202  {
203  pos_ = pos;
204  rpy_ = RPYVec(rpy);
206  odom_err_integ_lin_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
207  odom_err_integ_ang_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
208  diff_ = true;
209  }
210  bool isDiff() const
211  {
212  return diff_;
213  }
214  template <typename PointType>
215  void transform(pcl::PointCloud<PointType>& pc) const
216  {
217  const auto r = rot_.normalized();
218  for (auto& p : pc.points)
219  {
220  const Vec3 t = r * Vec3(p.x, p.y, p.z) + pos_;
221  p.x = t.x_;
222  p.y = t.y_;
223  p.z = t.z_;
224  }
225  }
226  template <typename T, typename RANDOM_ENGINE, typename NOISE_GEN>
227  static State6DOF generateNoise(RANDOM_ENGINE& engine, const NOISE_GEN& gen)
228  {
229  if (gen.getDimension() != 6)
230  {
231  ROS_ERROR("Dimension of noise must be 6. Passed: %lu", gen.getDimension());
232  }
233  State6DOF noise;
234  const std::vector<float> org_noise = gen(engine);
235  const std::vector<float>& mean = gen.getMean();
236  for (size_t i = 0; i < 3; i++)
237  {
238  noise[i] = noise[i + 7] = org_noise[i];
239  }
240  mcl_3dl::Vec3 rpy_noise;
241  for (size_t i = 0; i < 3; i++)
242  {
243  rpy_noise[i] = org_noise[i + 3];
244  noise[i + 10] = org_noise[i + 3] - mean[i + 3];
245  }
246  noise.rot_ = mcl_3dl::Quat(rpy_noise);
247  return noise;
248  }
249  State6DOF operator+(const State6DOF& a) const
250  {
251  State6DOF in = a;
252  State6DOF ret;
253  for (size_t i = 0; i < size(); i++)
254  {
255  if (3 <= i && i <= 6)
256  continue;
257  ret[i] = (*this)[i] + in[i];
258  }
259  ret.rot_ = a.rot_ * rot_;
260  return ret;
261  }
262  State6DOF operator-(const State6DOF& a) const
263  {
264  State6DOF in = a;
265  State6DOF ret;
266  for (size_t i = 0; i < size(); i++)
267  {
268  if (3 <= i && i <= 6)
269  continue;
270  ret[i] = (*this)[i] - in[i];
271  }
272  ret.rot_ = a.rot_.inv() * rot_;
273  return ret;
274  }
275 };
276 
277 template <>
278 template <>
280 {
281  mean_.resize(6);
282  if (mean.isDiff())
283  {
284  ROS_ERROR("Failed to generate noise. mean must be mcl_3dl::Quat.");
285  }
286  for (size_t i = 0; i < 3; i++)
287  {
288  mean_[i] = mean[i];
289  }
290  const Vec3 rpy = mean.rot_.getRPY();
291  for (size_t i = 0; i < 3; i++)
292  {
293  mean_[i + 3] = rpy[i];
294  }
295 }
296 
297 template <>
298 template <>
300 {
301  sigma_.resize(6);
302  if (!sigma.isDiff())
303  {
304  ROS_ERROR("Failed to generate noise. sigma must be rpy vec.");
305  }
306  for (size_t i = 0; i < 3; i++)
307  {
308  sigma_[i] = sigma[i];
309  }
310  for (size_t i = 0; i < 3; i++)
311  {
312  sigma_[i + 3] = sigma.rpy_.v_[i];
313  }
314 }
315 
317 {
318 protected:
321 
322 public:
325  , front_sum_(0.0, 0.0, 0.0)
326  , up_sum_(0.0, 0.0, 0.0)
327  {
328  }
329 
330  void add(const State6DOF& s, const float& prob)
331  {
332  p_sum_ += prob;
333 
334  State6DOF e1 = s;
335  e_.pos_ += e1.pos_ * prob;
336 
337  const mcl_3dl::Vec3 front = s.rot_ * mcl_3dl::Vec3(1.0, 0.0, 0.0) * prob;
338  const mcl_3dl::Vec3 up = s.rot_ * mcl_3dl::Vec3(0.0, 0.0, 1.0) * prob;
339 
340  front_sum_ += front;
341  up_sum_ += up;
342  }
343 
345  {
346  assert(p_sum_ > 0.0);
347 
349  }
350 
352  {
353  return p_sum_;
354  }
355 };
356 } // namespace mcl_3dl
357 
358 #endif // MCL_3DL_STATE_6DOF_H
mcl_3dl::State6DOF::State6DOF
State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Vec3 rpy)
Definition: state_6dof.h:201
noise_generator_base.h
mcl_3dl::pf::ParticleWeightedMean< State6DOF, float >::e_
State6DOF e_
Definition: pf.h:116
pf.h
mcl_3dl::DiagonalNoiseGenerator::setSigma
void setSigma(const T &sigma)
Definition: diagonal_noise_generator.h:54
mcl_3dl::State6DOF::noise_la_
float noise_la_
Definition: state_6dof.h:56
mcl_3dl::State6DOF::odom_err_integ_ang_
mcl_3dl::Vec3 odom_err_integ_ang_
Definition: state_6dof.h:60
mcl_3dl::Vec3::x_
float x_
Definition: vec3.h:40
s
XmlRpcServer s
mcl_3dl::pf::ParticleWeightedMean< State6DOF, float >::p_sum_
float p_sum_
Definition: pf.h:117
ros.h
mcl_3dl::State6DOF::isDiff
bool isDiff() const
Definition: state_6dof.h:210
mcl_3dl::State6DOF::noise_ll_
float noise_ll_
Definition: state_6dof.h:55
mcl_3dl::Quat::inv
constexpr Quat inv() const
Definition: quat.h:187
mcl_3dl::Quat::y_
float y_
Definition: quat.h:44
mcl_3dl::State6DOF::transform
void transform(pcl::PointCloud< PointType > &pc) const
Definition: state_6dof.h:215
point_types.h
mcl_3dl::NoiseGeneratorBase::setMean
void setMean(const T &mean)
Definition: noise_generator_base.h:46
mcl_3dl::State6DOF::RPYVec::RPYVec
RPYVec(const float r, const float p, const float y)
Definition: state_6dof.h:72
vec3.h
mcl_3dl::pf::ParticleWeightedMean< State6DOF, float >::ParticleWeightedMean
ParticleWeightedMean()
Definition: pf.h:120
mcl_3dl::Quat::getRPY
constexpr Vec3 getRPY() const
Definition: quat.h:191
mcl_3dl::Quat::normalized
Quat normalized() const
Definition: quat.h:175
mcl_3dl::State6DOF::operator[]
float & operator[](const size_t i) override
Definition: state_6dof.h:80
mcl_3dl::Vec3::z_
float z_
Definition: vec3.h:42
mcl_3dl::State6DOF::noise_aa_
float noise_aa_
Definition: state_6dof.h:58
mcl_3dl::Quat
Definition: quat.h:40
mcl_3dl::State6DOF::RPYVec
Definition: state_6dof.h:61
mcl_3dl::State6DOF::normalize
void normalize() override
Definition: state_6dof.h:154
mcl_3dl::Quat::w_
float w_
Definition: quat.h:46
diagonal_noise_generator.h
mcl_3dl::Quat::normalize
void normalize()
Definition: quat.h:179
mcl_3dl::State6DOF::odom_err_integ_lin_
mcl_3dl::Vec3 odom_err_integ_lin_
Definition: state_6dof.h:59
mcl_3dl::State6DOF::RPYVec::RPYVec
RPYVec()
Definition: state_6dof.h:65
mcl_3dl::Vec3::y_
float y_
Definition: vec3.h:41
mcl_3dl::State6DOF::diff_
bool diff_
Definition: state_6dof.h:54
mcl_3dl::State6DOF::State6DOF
State6DOF()
Definition: state_6dof.h:185
mcl_3dl::ParticleWeightedMeanQuat::getMean
State6DOF getMean()
Definition: state_6dof.h:344
quat.h
mcl_3dl::State6DOF::noise_al_
float noise_al_
Definition: state_6dof.h:57
mcl_3dl::State6DOF::operator[]
float operator[](const size_t i) const
Definition: state_6dof.h:115
mcl_3dl::State6DOF::size
size_t size() const override
Definition: state_6dof.h:150
mcl_3dl::State6DOF::operator-
State6DOF operator-(const State6DOF &a) const
Definition: state_6dof.h:262
mcl_3dl::pf::ParticleWeightedMean
Definition: pf.h:113
mcl_3dl
Definition: chunked_kdtree.h:43
mcl_3dl::State6DOF::covDimension
size_t covDimension() const override
Definition: state_6dof.h:158
mcl_3dl::State6DOF::RPYVec::v_
mcl_3dl::Vec3 v_
Definition: state_6dof.h:64
mcl_3dl::ParticleWeightedMeanQuat::add
void add(const State6DOF &s, const float &prob)
Definition: state_6dof.h:330
mcl_3dl::State6DOF::covElement
float covElement(const State6DOF &e, const size_t &j, const size_t &k)
Definition: state_6dof.h:162
mcl_3dl::ParticleWeightedMeanQuat::getTotalProbability
float getTotalProbability()
Definition: state_6dof.h:351
mcl_3dl::ParticleWeightedMeanQuat::ParticleWeightedMeanQuat
ParticleWeightedMeanQuat()
Definition: state_6dof.h:323
mcl_3dl::State6DOF::generateNoise
static State6DOF generateNoise(RANDOM_ENGINE &engine, const NOISE_GEN &gen)
Definition: state_6dof.h:227
mcl_3dl::pf::ParticleBase
Definition: pf.h:47
mcl_3dl::ParticleWeightedMeanQuat
Definition: state_6dof.h:316
mcl_3dl::State6DOF::State6DOF
State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Quat rot)
Definition: state_6dof.h:192
mcl_3dl::ParticleWeightedMeanQuat::front_sum_
mcl_3dl::Vec3 front_sum_
Definition: state_6dof.h:319
ROS_ERROR
#define ROS_ERROR(...)
mcl_3dl::State6DOF::rot_
mcl_3dl::Quat rot_
Definition: state_6dof.h:53
mcl_3dl::State6DOF::operator+
State6DOF operator+(const State6DOF &a) const
Definition: state_6dof.h:249
mcl_3dl::State6DOF::pos_
mcl_3dl::Vec3 pos_
Definition: state_6dof.h:52
mcl_3dl::Vec3
Definition: vec3.h:37
mcl_3dl::Quat::z_
float z_
Definition: quat.h:45
mcl_3dl::State6DOF
Definition: state_6dof.h:49
mcl_3dl::ParticleWeightedMeanQuat::up_sum_
mcl_3dl::Vec3 up_sum_
Definition: state_6dof.h:320
t
geometry_msgs::TransformStamped t
mcl_3dl::State6DOF::rpy_
RPYVec rpy_
Definition: state_6dof.h:79
mcl_3dl::State6DOF::RPYVec::RPYVec
RPYVec(const mcl_3dl::Vec3 &v)
Definition: state_6dof.h:68
mcl_3dl::Quat::x_
float x_
Definition: quat.h:43


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Oct 17 2024 02:18:04