humanoid_localization_defs.h
Go to the documentation of this file.
1 // SVN $HeadURL$
2 // SVN $Id$
3 
4 /*
5  * 6D localization for humanoid robots
6  *
7  * Copyright 2009-2012 Armin Hornung, University of Freiburg
8  * http://www.ros.org/wiki/humanoid_localization
9  *
10  *
11  * This program is free software: you can redistribute it and/or modify
12  * it under the terms of the GNU General Public License as published by
13  * the Free Software Foundation, version 3.
14  *
15  * This program is distributed in the hope that it will be useful,
16  * but WITHOUT ANY WARRANTY; without even the implied warranty of
17  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
18  * GNU General Public License for more details.
19  *
20  * You should have received a copy of the GNU General Public License
21  * along with this program. If not, see <http://www.gnu.org/licenses/>.
22  */
23 
24 #ifndef HUMANOID_LOCALIZATION_HUMANOID_LOCALIZATION_DEFS_H_
25 #define HUMANOID_LOCALIZATION_HUMANOID_LOCALIZATION_DEFS_H_
26 
27 #include <vector>
28 #include <boost/random/variate_generator.hpp>
29 #include <boost/random/mersenne_twister.hpp>
30 #include <boost/random/normal_distribution.hpp>
31 #include <boost/random/uniform_real.hpp>
32 
33 #include <tf/transform_datatypes.h>
34 
35 #include <eigen3/Eigen/Core>
36 
37 #include <pcl_ros/point_cloud.h>
38 #include <pcl/point_types.h>
39 
40 namespace humanoid_localization{
41 
43 struct Particle{
44  double weight;
46 };
47 
48 typedef std::vector<Particle> Particles;
49 
50 typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
51 
52 
54 typedef boost::mt19937 EngineT;
56 typedef boost::normal_distribution<> NormalDistributionT;
57 // Ugh! boost uniform_01 noise sucks: http://www.bnikolic.co.uk/blog/cpp-boost-uniform01.html
58 // => using uniform_real instead
59 typedef boost::uniform_real<> UniformDistributionT;
61 typedef boost::variate_generator<EngineT&, NormalDistributionT> NormalGeneratorT;
63 typedef boost::variate_generator<EngineT&, UniformDistributionT> UniformGeneratorT;
64 
65 
66 typedef Eigen::Matrix<float, 6, 6> Matrix6f;
67 typedef Eigen::Matrix<float, 6, 1> Vector6f;
68 typedef Eigen::Matrix<double, 6, 6> Matrix6d;
69 typedef Eigen::Matrix<double, 6, 1> Vector6d;
70 
71 }
72 #endif
boost::uniform_real UniformDistributionT
boost::variate_generator< EngineT &, NormalDistributionT > NormalGeneratorT
standard normal-distributed noise
boost::mt19937 EngineT
Boost RNG engine:
Particle consists of a pose and a weight.
boost::normal_distribution NormalDistributionT
Boost RNG distribution:
Eigen::Matrix< double, 6, 6 > Matrix6d
boost::variate_generator< EngineT &, UniformDistributionT > UniformGeneratorT
uniform noise in range [0,1)
Eigen::Matrix< double, 6, 1 > Vector6d
Eigen::Matrix< float, 6, 6 > Matrix6f
Eigen::Matrix< float, 6, 1 > Vector6f
std::vector< Particle > Particles
pcl::PointCloud< pcl::PointXYZ > PointCloud


humanoid_localization
Author(s): Armin Hornung, Stefan Osswald, Daniel Maier
autogenerated on Mon Jun 10 2019 13:38:31