humanoid_localization_defs.h
Go to the documentation of this file.
00001 // SVN $HeadURL$
00002 // SVN $Id$
00003 
00004 /*
00005  * 6D localization for humanoid robots
00006  *
00007  * Copyright 2009-2012 Armin Hornung, University of Freiburg
00008  * http://www.ros.org/wiki/humanoid_localization
00009  *
00010  *
00011  * This program is free software: you can redistribute it and/or modify
00012  * it under the terms of the GNU General Public License as published by
00013  * the Free Software Foundation, version 3.
00014  *
00015  * This program is distributed in the hope that it will be useful,
00016  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00017  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00018  * GNU General Public License for more details.
00019  *
00020  * You should have received a copy of the GNU General Public License
00021  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
00022  */
00023 
00024 #ifndef HUMANOID_LOCALIZATION_HUMANOID_LOCALIZATION_DEFS_H_
00025 #define HUMANOID_LOCALIZATION_HUMANOID_LOCALIZATION_DEFS_H_
00026 
00027 #include <vector>
00028 #include <boost/random/variate_generator.hpp>
00029 #include <boost/random/mersenne_twister.hpp>
00030 #include <boost/random/normal_distribution.hpp>
00031 #include <boost/random/uniform_real.hpp>
00032 
00033 #include <tf/transform_datatypes.h>
00034 
00035 #include <Eigen/Core>
00036 
00037 #include <pcl_ros/point_cloud.h>
00038 #include <pcl/point_types.h>
00039 
00040 namespace humanoid_localization{
00041 
00043 struct Particle{
00044   double weight;
00045   tf::Pose pose;
00046 };
00047 
00048 typedef std::vector<Particle> Particles;
00049 
00050 typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
00051 
00052 
00054 typedef boost::mt19937                  EngineT;
00056 typedef boost::normal_distribution<>    NormalDistributionT;
00057 // Ugh! boost uniform_01 noise sucks: http://www.bnikolic.co.uk/blog/cpp-boost-uniform01.html
00058 // => using uniform_real instead
00059 typedef boost::uniform_real<>                   UniformDistributionT;
00061 typedef boost::variate_generator<EngineT&, NormalDistributionT>   NormalGeneratorT;
00063 typedef boost::variate_generator<EngineT&, UniformDistributionT>   UniformGeneratorT;
00064 
00065 
00066 typedef Eigen::Matrix<float, 6, 6> Matrix6f;
00067 typedef Eigen::Matrix<float, 6, 1> Vector6f;
00068 typedef Eigen::Matrix<double, 6, 6> Matrix6d;
00069 typedef Eigen::Matrix<double, 6, 1> Vector6d;
00070 
00071 }
00072 #endif


humanoid_localization
Author(s): Armin Hornung, Stefan Osswald, Daniel Maier
autogenerated on Wed Aug 26 2015 11:54:40