Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
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
00058
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