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 
35 #include <ros/ros.h>
36 
37 #include <mcl_3dl/pf.h>
38 #include <mcl_3dl/point_types.h>
39 #include <mcl_3dl/quat.h>
40 #include <mcl_3dl/vec3.h>
41 
42 namespace mcl_3dl
43 {
44 class State6DOF : public mcl_3dl::pf::ParticleBase<float>
45 {
46 public:
49  bool diff_;
50  float noise_ll_;
51  float noise_la_;
52  float noise_al_;
53  float noise_aa_;
56  class RPYVec
57  {
58  public:
61  {
62  }
63  explicit RPYVec(const mcl_3dl::Vec3& v)
64  {
65  v_ = v;
66  }
67  RPYVec(const float r, const float p, const float y)
68  {
69  v_.x_ = r;
70  v_.y_ = p;
71  v_.z_ = y;
72  }
73  };
75  float& operator[](const size_t i)override
76  {
77  switch (i)
78  {
79  case 0:
80  return pos_.x_;
81  case 1:
82  return pos_.y_;
83  case 2:
84  return pos_.z_;
85  case 3:
86  return rot_.x_;
87  case 4:
88  return rot_.y_;
89  case 5:
90  return rot_.z_;
91  case 6:
92  return rot_.w_;
93  case 7:
94  return odom_err_integ_lin_.x_;
95  case 8:
96  return odom_err_integ_lin_.y_;
97  case 9:
98  return odom_err_integ_lin_.z_;
99  case 10:
100  return odom_err_integ_ang_.x_;
101  case 11:
102  return odom_err_integ_ang_.y_;
103  case 12:
104  return odom_err_integ_ang_.z_;
105  default:
106  assert(false);
107  }
108  return pos_.x_;
109  }
110  float operator[](const size_t i) const
111  {
112  switch (i)
113  {
114  case 0:
115  return pos_.x_;
116  case 1:
117  return pos_.y_;
118  case 2:
119  return pos_.z_;
120  case 3:
121  return rot_.x_;
122  case 4:
123  return rot_.y_;
124  case 5:
125  return rot_.z_;
126  case 6:
127  return rot_.w_;
128  case 7:
129  return odom_err_integ_lin_.x_;
130  case 8:
131  return odom_err_integ_lin_.y_;
132  case 9:
133  return odom_err_integ_lin_.z_;
134  case 10:
135  return odom_err_integ_ang_.x_;
136  case 11:
137  return odom_err_integ_ang_.y_;
138  case 12:
139  return odom_err_integ_ang_.z_;
140  default:
141  assert(false);
142  }
143  return 0;
144  }
145  size_t size() const override
146  {
147  return 13;
148  }
149  void normalize() override
150  {
151  rot_.normalize();
152  }
154  {
155  diff_ = false;
156  noise_ll_ = noise_la_ = noise_aa_ = noise_al_ = 0.0;
157  odom_err_integ_lin_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
158  odom_err_integ_ang_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
159  }
160  State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Quat rot)
161  {
162  pos_ = pos;
163  rot_ = rot;
164  noise_ll_ = noise_la_ = noise_aa_ = noise_al_ = 0.0;
165  odom_err_integ_lin_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
166  odom_err_integ_ang_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
167  diff_ = false;
168  }
169  State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Vec3 rpy)
170  {
171  pos_ = pos;
172  rpy_ = RPYVec(rpy);
173  noise_ll_ = noise_la_ = noise_aa_ = noise_al_ = 0.0;
174  odom_err_integ_lin_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
175  odom_err_integ_ang_ = mcl_3dl::Vec3(0.0, 0.0, 0.0);
176  diff_ = true;
177  }
178  bool isDiff() const
179  {
180  return diff_;
181  }
182  template <typename PointType>
183  void transform(pcl::PointCloud<PointType>& pc) const
184  {
185  const auto r = rot_.normalized();
186  for (auto& p : pc.points)
187  {
188  const Vec3 t = r * Vec3(p.x, p.y, p.z) + pos_;
189  p.x = t.x_;
190  p.y = t.y_;
191  p.z = t.z_;
192  }
193  }
195  std::default_random_engine& engine_,
196  const State6DOF& mean, const State6DOF& sigma)
197  {
198  State6DOF noise;
199  if (mean.isDiff() || !sigma.isDiff())
200  {
201  ROS_ERROR("Failed to generate noise. mean must be mcl_3dl::Quat and sigma must be rpy vec.");
202  }
203  for (size_t i = 0; i < 3; i++)
204  {
205  std::normal_distribution<float> nd(mean[i], sigma[i]);
206  noise[i] = noise[i + 7] = nd(engine_);
207  }
208  mcl_3dl::Vec3 rpy_noise;
209  for (size_t i = 0; i < 3; i++)
210  {
211  std::normal_distribution<float> nd(0.0, sigma.rpy_.v_[i]);
212  rpy_noise[i] = noise[i + 10] = nd(engine_);
213  }
214  noise.rot_ = mcl_3dl::Quat(rpy_noise) * mean.rot_;
215  return noise;
216  }
217  State6DOF operator+(const State6DOF& a) const
218  {
219  State6DOF in = a;
220  State6DOF ret;
221  for (size_t i = 0; i < size(); i++)
222  {
223  if (3 <= i && i <= 6)
224  continue;
225  ret[i] = (*this)[i] + in[i];
226  }
227  ret.rot_ = a.rot_ * rot_;
228  return ret;
229  }
230  State6DOF operator-(const State6DOF& a) const
231  {
232  State6DOF in = a;
233  State6DOF ret;
234  for (size_t i = 0; i < size(); i++)
235  {
236  if (3 <= i && i <= 6)
237  continue;
238  ret[i] = (*this)[i] - in[i];
239  }
240  ret.rot_ = a.rot_.inv() * rot_;
241  return ret;
242  }
243 };
245 {
246 protected:
249 
250 public:
252  : ParticleWeightedMean()
253  , front_sum_(0.0, 0.0, 0.0)
254  , up_sum_(0.0, 0.0, 0.0)
255  {
256  }
257 
258  void add(const State6DOF& s, const float& prob)
259  {
260  p_sum_ += prob;
261 
262  State6DOF e1 = s;
263  e_.pos_ += e1.pos_ * prob;
264 
265  const mcl_3dl::Vec3 front = s.rot_ * mcl_3dl::Vec3(1.0, 0.0, 0.0) * prob;
266  const mcl_3dl::Vec3 up = s.rot_ * mcl_3dl::Vec3(0.0, 0.0, 1.0) * prob;
267 
268  front_sum_ += front;
269  up_sum_ += up;
270  }
271 
273  {
274  assert(p_sum_ > 0.0);
275 
276  return State6DOF(e_.pos_ / p_sum_, mcl_3dl::Quat(front_sum_, up_sum_));
277  }
278 
280  {
281  return p_sum_;
282  }
283 };
284 } // namespace mcl_3dl
285 
286 #endif // MCL_3DL_STATE_6DOF_H
float z_
Definition: vec3.h:40
void transform(pcl::PointCloud< PointType > &pc) const
Definition: state_6dof.h:183
float & operator[](const size_t i) override
Definition: state_6dof.h:75
State6DOF operator-(const State6DOF &a) const
Definition: state_6dof.h:230
float y_
Definition: quat.h:43
mcl_3dl::Vec3 pos_
Definition: state_6dof.h:47
mcl_3dl::Vec3 odom_err_integ_ang_
Definition: state_6dof.h:55
mcl_3dl::Vec3 odom_err_integ_lin_
Definition: state_6dof.h:54
State6DOF operator+(const State6DOF &a) const
Definition: state_6dof.h:217
State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Vec3 rpy)
Definition: state_6dof.h:169
geometry_msgs::TransformStamped t
void add(const State6DOF &s, const float &prob)
Definition: state_6dof.h:258
size_t size() const override
Definition: state_6dof.h:145
float operator[](const size_t i) const
Definition: state_6dof.h:110
RPYVec(const mcl_3dl::Vec3 &v)
Definition: state_6dof.h:63
void normalize()
Definition: quat.h:182
float w_
Definition: quat.h:45
float y_
Definition: vec3.h:39
bool isDiff() const
Definition: state_6dof.h:178
Quat normalized() const
Definition: quat.h:172
Quat inv() const
Definition: quat.h:190
mcl_3dl::Quat rot_
Definition: state_6dof.h:48
void normalize() override
Definition: state_6dof.h:149
float x_
Definition: vec3.h:38
static State6DOF generateNoise(std::default_random_engine &engine_, const State6DOF &mean, const State6DOF &sigma)
Definition: state_6dof.h:194
RPYVec(const float r, const float p, const float y)
Definition: state_6dof.h:67
State6DOF(const mcl_3dl::Vec3 pos, const mcl_3dl::Quat rot)
Definition: state_6dof.h:160
#define ROS_ERROR(...)
float z_
Definition: quat.h:44
float x_
Definition: quat.h:42


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36