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  }
159  {
160  diff_ = false;
161  noise_ll_ = noise_la_ = noise_aa_ = noise_al_ = 0.0;
162  odom_err_integ_lin_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
163  odom_err_integ_ang_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
164  }
165  State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Quat rot)
166  {
167  pos_ = pos;
168  rot_ = rot;
169  noise_ll_ = noise_la_ = noise_aa_ = noise_al_ = 0.0;
170  odom_err_integ_lin_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
171  odom_err_integ_ang_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
172  diff_ = false;
173  }
174  State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Vec3 rpy)
175  {
176  pos_ = pos;
177  rpy_ = RPYVec(rpy);
178  noise_ll_ = noise_la_ = noise_aa_ = noise_al_ = 0.0;
179  odom_err_integ_lin_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
180  odom_err_integ_ang_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
181  diff_ = true;
182  }
183  bool isDiff() const
184  {
185  return diff_;
186  }
187  template <typename PointType>
188  void transform(pcl::PointCloud<PointType>& pc) const
189  {
190  const auto r = rot_.normalized();
191  for (auto& p : pc.points)
192  {
193  const Vec3 t = r * Vec3(p.x, p.y, p.z) + pos_;
194  p.x = t.x_;
195  p.y = t.y_;
196  p.z = t.z_;
197  }
198  }
199  template <typename T, typename RANDOM_ENGINE, typename NOISE_GEN>
200  static State6DOF generateNoise(RANDOM_ENGINE& engine, const NOISE_GEN& gen)
201  {
202  if (gen.getDimension() != 6)
203  {
204  ROS_ERROR("Dimension of noise must be 6. Passed: %lu", gen.getDimension());
205  }
206  State6DOF noise;
207  const std::vector<float> org_noise = gen(engine);
208  const std::vector<float>& mean = gen.getMean();
209  for (size_t i = 0; i < 3; i++)
210  {
211  noise[i] = noise[i + 7] = org_noise[i];
212  }
213  mcl_3dl::Vec3 rpy_noise;
214  for (size_t i = 0; i < 3; i++)
215  {
216  rpy_noise[i] = org_noise[i + 3];
217  noise[i + 10] = org_noise[i + 3] - mean[i + 3];
218  }
219  noise.rot_ = mcl_3dl::Quat(rpy_noise);
220  return noise;
221  }
222  State6DOF operator+(const State6DOF& a) const
223  {
224  State6DOF in = a;
225  State6DOF ret;
226  for (size_t i = 0; i < size(); i++)
227  {
228  if (3 <= i && i <= 6)
229  continue;
230  ret[i] = (*this)[i] + in[i];
231  }
232  ret.rot_ = a.rot_ * rot_;
233  return ret;
234  }
235  State6DOF operator-(const State6DOF& a) const
236  {
237  State6DOF in = a;
238  State6DOF ret;
239  for (size_t i = 0; i < size(); i++)
240  {
241  if (3 <= i && i <= 6)
242  continue;
243  ret[i] = (*this)[i] - in[i];
244  }
245  ret.rot_ = a.rot_.inv() * rot_;
246  return ret;
247  }
248 };
249 
250 template <>
251 template <>
253 {
254  mean_.resize(6);
255  if (mean.isDiff())
256  {
257  ROS_ERROR("Failed to generate noise. mean must be mcl_3dl::Quat.");
258  }
259  for (size_t i = 0; i < 3; i++)
260  {
261  mean_[i] = mean[i];
262  }
263  const Vec3 rpy = mean.rot_.getRPY();
264  for (size_t i = 0; i < 3; i++)
265  {
266  mean_[i + 3] = rpy[i];
267  }
268 }
269 
270 template <>
271 template <>
273 {
274  sigma_.resize(6);
275  if (!sigma.isDiff())
276  {
277  ROS_ERROR("Failed to generate noise. sigma must be rpy vec.");
278  }
279  for (size_t i = 0; i < 3; i++)
280  {
281  sigma_[i] = sigma[i];
282  }
283  for (size_t i = 0; i < 3; i++)
284  {
285  sigma_[i + 3] = sigma.rpy_.v_[i];
286  }
287 }
288 
290 {
291 protected:
294 
295 public:
297  : ParticleWeightedMean()
298  , front_sum_(0.0, 0.0, 0.0)
299  , up_sum_(0.0, 0.0, 0.0)
300  {
301  }
302 
303  void add(const State6DOF& s, const float& prob)
304  {
305  p_sum_ += prob;
306 
307  State6DOF e1 = s;
308  e_.pos_ += e1.pos_ * prob;
309 
310  const mcl_3dl::Vec3 front = s.rot_ * mcl_3dl::Vec3(1.0, 0.0, 0.0) * prob;
311  const mcl_3dl::Vec3 up = s.rot_ * mcl_3dl::Vec3(0.0, 0.0, 1.0) * prob;
312 
313  front_sum_ += front;
314  up_sum_ += up;
315  }
316 
318  {
319  assert(p_sum_ > 0.0);
320 
321  return State6DOF(e_.pos_ / p_sum_, mcl_3dl::Quat(front_sum_, up_sum_));
322  }
323 
325  {
326  return p_sum_;
327  }
328 };
329 } // namespace mcl_3dl
330 
331 #endif // MCL_3DL_STATE_6DOF_H
float z_
Definition: vec3.h:42
void transform(pcl::PointCloud< PointType > &pc) const
Definition: state_6dof.h:188
float & operator[](const size_t i) override
Definition: state_6dof.h:80
static State6DOF generateNoise(RANDOM_ENGINE &engine, const NOISE_GEN &gen)
Definition: state_6dof.h:200
State6DOF operator-(const State6DOF &a) const
Definition: state_6dof.h:235
float y_
Definition: quat.h:44
mcl_3dl::Vec3 pos_
Definition: state_6dof.h:52
mcl_3dl::Vec3 odom_err_integ_ang_
Definition: state_6dof.h:60
mcl_3dl::Vec3 odom_err_integ_lin_
Definition: state_6dof.h:59
State6DOF operator+(const State6DOF &a) const
Definition: state_6dof.h:222
State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Vec3 rpy)
Definition: state_6dof.h:174
geometry_msgs::TransformStamped t
void add(const State6DOF &s, const float &prob)
Definition: state_6dof.h:303
size_t size() const override
Definition: state_6dof.h:150
float operator[](const size_t i) const
Definition: state_6dof.h:115
RPYVec(const mcl_3dl::Vec3 &v)
Definition: state_6dof.h:68
constexpr Vec3 getRPY() const
Definition: quat.h:191
void normalize()
Definition: quat.h:179
float w_
Definition: quat.h:46
float y_
Definition: vec3.h:41
constexpr Quat inv() const
Definition: quat.h:187
bool isDiff() const
Definition: state_6dof.h:183
Quat normalized() const
Definition: quat.h:175
mcl_3dl::Quat rot_
Definition: state_6dof.h:53
void normalize() override
Definition: state_6dof.h:154
float x_
Definition: vec3.h:40
RPYVec(const float r, const float p, const float y)
Definition: state_6dof.h:72
State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Quat rot)
Definition: state_6dof.h:165
#define ROS_ERROR(...)
float z_
Definition: quat.h:45
float x_
Definition: quat.h:43


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:16:29