HumanoidLocalization.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_HUMANOIDLOCALIZATION_H_
25 #define HUMANOID_LOCALIZATION_HUMANOIDLOCALIZATION_H_
26 
27 #include <ctime>
28 #include <boost/shared_ptr.hpp>
29 
30 #include <ros/ros.h>
31 #include <tf/transform_datatypes.h>
32 #include <tf/transform_listener.h>
34 #include <tf/message_filter.h>
36 #include <std_msgs/Float32.h>
37 #include <std_msgs/Bool.h>
38 #include <std_srvs/Empty.h>
39 #include <sensor_msgs/LaserScan.h>
40 #include <sensor_msgs/PointCloud2.h>
41 
42 #include <pcl_ros/point_cloud.h>
43 #include <pcl/point_types.h>
44 #include <pcl/sample_consensus/method_types.h>
45 #include <pcl/sample_consensus/model_types.h>
46 #include <pcl/segmentation/sac_segmentation.h>
47 #include <pcl/io/pcd_io.h>
48 #include <pcl/filters/extract_indices.h>
49 #include <pcl/filters/passthrough.h>
50 
51 
52 #include <geometry_msgs/Pose.h>
53 #include <geometry_msgs/PoseArray.h>
54 #include <geometry_msgs/PoseWithCovariance.h>
55 #include <geometry_msgs/PoseWithCovarianceStamped.h>
56 
61 #ifndef SKIP_ENDPOINT_MODEL
63 #endif
64 
65 
66 #include <octomap/octomap.h>
67 #include <sensor_msgs/Imu.h>
68 #include <boost/circular_buffer.hpp>
69 
70 namespace humanoid_localization{
71 
72 static inline void getRP(const geometry_msgs::Quaternion& msg_q, double& roll, double& pitch){
73  tf::Quaternion bt_q;
74  tf::quaternionMsgToTF(msg_q, bt_q);
75  double useless_yaw;
76  tf::Matrix3x3(bt_q).getRPY(roll, pitch, useless_yaw);
77 
78  if (std::abs(useless_yaw) > 0.00001)
79  ROS_WARN("Non-zero yaw in IMU quaterion is ignored");
80 }
81 
83 public:
84  // some typedefs
85  //typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
86 
87 public:
88  HumanoidLocalization(unsigned randomSeed);
89  virtual ~HumanoidLocalization();
90  virtual void laserCallback(const sensor_msgs::LaserScanConstPtr& msg);
91  virtual void pointCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& msg);
92  void initPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg);
93  bool globalLocalizationCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
94  void pauseLocalizationCallback(const std_msgs::BoolConstPtr& msg);
96  bool pauseLocalizationSrvCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
98  bool resumeLocalizationSrvCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
99  void imuCallback(const sensor_msgs::ImuConstPtr& msg);
100 
107  void resample(unsigned numParticles = 0);
109  unsigned getBestParticleIdx() const;
111  tf::Pose getParticlePose(unsigned particleIdx) const;
116 
118  void initGlobal();
119 
120  // needed for pointcloud callback (from OctomapServer)
121  static void filterGroundPlane(const PointCloud& pc, PointCloud& ground, PointCloud& nonground, double groundFilterDistance, double groundFilterAngle, double groundFilterPlaneDistance);
122 
123 protected:
129  void reset();
130 
131  // converts particles into PoseArray and publishes them for visualization
132  void publishPoseEstimate(const ros::Time& time, bool publish_eval);
133 
134 
140  void normalizeWeights();
141 
143  double getCumParticleWeight() const;
144 
150  double nEff() const;
151 
155  void toLogForm();
156 
165  bool getImuMsg(const ros::Time& stamp, ros::Time& imuStamp, double& angleX, double& angleY) const;
166 
172  void prepareLaserPointCloud(const sensor_msgs::LaserScanConstPtr& laser, PointCloud& pc, std::vector<float>& ranges) const;
173 
179  void prepareGeneralPointCloud(const sensor_msgs::PointCloud2::ConstPtr& msg, PointCloud& pc, std::vector<float>& ranges) const;
180  int filterUniform( const PointCloud & cloud_in, PointCloud & cloud_out, int numSamples) const;
181 
182  void voxelGridSampling(const PointCloud & pc, pcl::PointCloud<int> & sampledIndices, double searchRadius) const;
183 
184  bool isAboveMotionThreshold(const tf::Pose& odomTransform);
185 
186  bool localizeWithMeasurement(const PointCloud& pc_filtered, const std::vector<float>& ranges, double max_range);
187 
188  void constrainMotion(const tf::Pose& odomPose);
189 
190  void timerCallback(const ros::TimerEvent & e);
191 
192  unsigned computeBeamStep(unsigned numBeams) const;
193 
198  void initZRP(double& z, double& roll, double& pitch);
199 
200  bool lookupPoseHeight(const ros::Time& t, double& poseHeight) const;
201 
210 
213 
220 
229 
230  std::string m_odomFrameId;
231  std::string m_targetFrameId;
232  std::string m_baseFrameId;
233  std::string m_baseFootprintId;
234  std::string m_globalFrameId;
235 
240 
241  double m_nEffFactor;
243  Vector6d m_initPose; // fixed init. pose (from params)
244  Vector6d m_initNoiseStd; // Std.dev for init. pose
245  bool m_initPoseRealZRP; // override z, roll, pitch with real values from robot
246 
249 
250 
253  tf::Pose m_odomPose; // incrementally added odometry pose (=dead reckoning)
254  geometry_msgs::PoseArray m_poseArray; // particles as PoseArray (preallocated)
255  boost::circular_buffer<sensor_msgs::Imu> m_lastIMUMsgBuffer;
256 
261  bool m_paused;
263 
272 
273 
274  // PointCloud parameters
275 
281 
282 
286 
291 
292  bool m_useIMU;
295 
296  // timer stuff
299 };
300 }
301 
302 #endif
bool pauseLocalizationSrvCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
pause localization by service call
virtual void pointCloudCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
void initPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
bool resumeLocalizationSrvCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
unpause localization by service call
double m_headPitchRotationLastScan
absolute, summed pitch angle since last measurement integraton
bool isAboveMotionThreshold(const tf::Pose &odomTransform)
double m_headYawRotationLastScan
absolute, summed yaw angle since last measurement integraton
tf::MessageFilter< sensor_msgs::PointCloud2 > * m_pointCloudFilter
boost::variate_generator< EngineT &, NormalDistributionT > NormalGeneratorT
standard normal-distributed noise
boost::mt19937 EngineT
Boost RNG engine:
int filterUniform(const PointCloud &cloud_in, PointCloud &cloud_out, int numSamples) const
void prepareLaserPointCloud(const sensor_msgs::LaserScanConstPtr &laser, PointCloud &pc, std::vector< float > &ranges) const
unsigned getBestParticleIdx() const
Returns index of particle with highest weight (log or normal scale)
bool m_useTimer
< True = do not estimate roll and pitch, directly use odometry pose
bool lookupPoseHeight(const ros::Time &t, double &poseHeight) const
double getCumParticleWeight() const
cumulative weight of all particles (=1 when normalized)
void voxelGridSampling(const PointCloud &pc, pcl::PointCloud< int > &sampledIndices, double searchRadius) const
void publishPoseEstimate(const ros::Time &time, bool publish_eval)
tf::MessageFilter< sensor_msgs::LaserScan > * m_laserFilter
message_filters::Subscriber< sensor_msgs::LaserScan > * m_laserSub
#define ROS_WARN(...)
void prepareGeneralPointCloud(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloud &pc, std::vector< float > &ranges) const
bool m_useIMU
True = use IMU for initialization and observation models, false = use orientation from odometry...
tf::Pose getMeanParticlePose() const
Returns the 6D pose of the weighted mean particle.
boost::shared_ptr< ObservationModel > m_observationModel
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
tf::MessageFilter< geometry_msgs::PoseWithCovarianceStamped > * m_initPoseFilter
message_filters::Subscriber< sensor_msgs::PointCloud2 > * m_pointCloudSub
void initGlobal()
function call for global initialization (called by globalLocalizationCallback)
message_filters::Subscriber< geometry_msgs::PoseWithCovarianceStamped > * m_initPoseSub
boost::variate_generator< EngineT &, UniformDistributionT > UniformGeneratorT
uniform noise in range [0,1)
boost::circular_buffer< sensor_msgs::Imu > m_lastIMUMsgBuffer
Eigen::Matrix< double, 6, 1 > Vector6d
boost::shared_ptr< MotionModel > m_motionModel
tf::Pose getParticlePose(unsigned particleIdx) const
Returns the 6D pose of a particle.
UniformGeneratorT m_rngUniform
uniform distribution [0:1]
bool globalLocalizationCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
TFSIMD_FORCE_INLINE const tfScalar & z() const
unsigned computeBeamStep(unsigned numBeams) const
bool localizeWithMeasurement(const PointCloud &pc_filtered, const std::vector< float > &ranges, double max_range)
bool m_constrainMotionRP
< True = do not estimate height, directly use odometry pose
tf::Pose getBestParticlePose() const
Returns the 6D pose of the best particle (highest weight)
bool getImuMsg(const ros::Time &stamp, ros::Time &imuStamp, double &angleX, double &angleY) const
virtual void laserCallback(const sensor_msgs::LaserScanConstPtr &msg)
void initZRP(double &z, double &roll, double &pitch)
static void filterGroundPlane(const PointCloud &pc, PointCloud &ground, PointCloud &nonground, double groundFilterDistance, double groundFilterAngle, double groundFilterPlaneDistance)
std::vector< Particle > Particles
pcl::PointCloud< pcl::PointXYZ > PointCloud
tf::Pose m_lastLocalizedPose
sensor data last integrated at this odom pose, to check if moved enough since then ...
void imuCallback(const sensor_msgs::ImuConstPtr &msg)
static void getRP(const geometry_msgs::Quaternion &msg_q, double &roll, double &pitch)
void pauseLocalizationCallback(const std_msgs::BoolConstPtr &msg)
NormalGeneratorT m_rngNormal
standard normal distribution


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