$search
00001 // SVN $HeadURL: http://alufr-ros-pkg.googlecode.com/svn/trunk/humanoid_stacks/humanoid_navigation/humanoid_localization/include/humanoid_localization/HumanoidLocalization.h $ 00002 // SVN $Id: HumanoidLocalization.h 3851 2013-01-30 11:24:11Z hornunga@informatik.uni-freiburg.de $ 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_HUMANOIDLOCALIZATION_H_ 00025 #define HUMANOID_LOCALIZATION_HUMANOIDLOCALIZATION_H_ 00026 00027 #include <ctime> 00028 #include <boost/shared_ptr.hpp> 00029 00030 #include <ros/ros.h> 00031 #include <tf/transform_datatypes.h> 00032 #include <tf/transform_listener.h> 00033 #include <tf/transform_broadcaster.h> 00034 #include <tf/message_filter.h> 00035 #include <message_filters/subscriber.h> 00036 #include <std_msgs/Float32.h> 00037 #include <std_msgs/Bool.h> 00038 #include <std_srvs/Empty.h> 00039 #include <sensor_msgs/LaserScan.h> 00040 #include <sensor_msgs/PointCloud2.h> 00041 00042 #include <pcl_ros/point_cloud.h> 00043 #include <pcl/point_types.h> 00044 #include <pcl/ros/conversions.h> 00045 #include <pcl_ros/transforms.h> 00046 #include <pcl/sample_consensus/method_types.h> 00047 #include <pcl/sample_consensus/model_types.h> 00048 #include <pcl/segmentation/sac_segmentation.h> 00049 #include <pcl/io/pcd_io.h> 00050 #include <pcl/filters/extract_indices.h> 00051 #include <pcl/filters/passthrough.h> 00052 00053 00054 #include <geometry_msgs/Pose.h> 00055 #include <geometry_msgs/PoseArray.h> 00056 #include <geometry_msgs/PoseWithCovariance.h> 00057 #include <geometry_msgs/PoseWithCovarianceStamped.h> 00058 00059 #include <humanoid_localization/humanoid_localization_defs.h> 00060 #include <humanoid_localization/MotionModel.h> 00061 #include <humanoid_localization/ObservationModel.h> 00062 #include <humanoid_localization/RaycastingModel.h> 00063 #ifndef SKIP_ENDPOINT_MODEL 00064 #include <humanoid_localization/EndpointModel.h> 00065 #endif 00066 00067 00068 #include <octomap/octomap.h> 00069 #include <sensor_msgs/Imu.h> 00070 #include <boost/circular_buffer.hpp> 00071 00072 namespace humanoid_localization{ 00073 00074 static inline void getRP(const geometry_msgs::Quaternion& msg_q, double& roll, double& pitch){ 00075 tf::Quaternion bt_q; 00076 tf::quaternionMsgToTF(msg_q, bt_q); 00077 double useless_yaw; 00078 tf::Matrix3x3(bt_q).getRPY(roll, pitch, useless_yaw); 00079 00080 if (std::abs(useless_yaw) > 0.00001) 00081 ROS_WARN("Non-zero yaw in IMU quaterion is ignored"); 00082 } 00083 00084 class HumanoidLocalization { 00085 public: 00086 // some typedefs 00087 //typedef pcl::PointCloud<pcl::PointXYZ> PointCloud; 00088 00089 public: 00090 HumanoidLocalization(unsigned randomSeed); 00091 virtual ~HumanoidLocalization(); 00092 virtual void laserCallback(const sensor_msgs::LaserScanConstPtr& msg); 00093 virtual void pointCloudCallback(const PointCloud::ConstPtr& msg); 00094 void initPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg); 00095 bool globalLocalizationCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res); 00096 void pauseLocalizationCallback(const std_msgs::BoolConstPtr& msg); 00098 bool pauseLocalizationSrvCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res); 00100 bool resumeLocalizationSrvCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res); 00101 void imuCallback(const sensor_msgs::ImuConstPtr& msg); 00102 00109 void resample(unsigned numParticles = 0); 00111 unsigned getBestParticleIdx() const; 00113 tf::Pose getParticlePose(unsigned particleIdx) const; 00115 tf::Pose getBestParticlePose() const; 00117 tf::Pose getMeanParticlePose() const; 00118 00120 void initGlobal(); 00121 00122 // needed for pointcloud callback (from OctomapServer) 00123 static void filterGroundPlane(const PointCloud& pc, PointCloud& ground, PointCloud& nonground, double groundFilterDistance, double groundFilterAngle, double groundFilterPlaneDistance); 00124 00125 protected: 00131 void reset(); 00132 00133 // converts particles into PoseArray and publishes them for visualization 00134 void publishPoseEstimate(const ros::Time& time, bool publish_eval); 00135 00136 00142 void normalizeWeights(); 00143 00145 double getCumParticleWeight() const; 00146 00152 double nEff() const; 00153 00157 void toLogForm(); 00158 00167 bool getImuMsg(const ros::Time& stamp, ros::Time& imuStamp, double& angleX, double& angleY) const; 00168 00174 void prepareLaserPointCloud(const sensor_msgs::LaserScanConstPtr& laser, PointCloud& pc, std::vector<float>& ranges) const; 00175 00181 void prepareGeneralPointCloud(const PointCloud::ConstPtr & msg, PointCloud& pc, std::vector<float>& ranges) const; 00182 int filterUniform( const PointCloud & cloud_in, PointCloud & cloud_out, int numSamples) const; 00183 00184 bool isAboveMotionThreshold(const tf::Pose& odomTransform); 00185 00186 bool localizeWithMeasurement(const PointCloud& pc_filtered, const std::vector<float>& ranges, double max_range); 00187 00188 void constrainMotion(const tf::Pose& odomPose); 00189 00190 unsigned computeBeamStep(unsigned numBeams) const; 00191 00192 bool lookupPoseHeight(const ros::Time& t, double& poseHeight) const; 00193 00194 EngineT m_rngEngine; 00195 NormalGeneratorT m_rngNormal; 00196 UniformGeneratorT m_rngUniform; 00197 boost::shared_ptr<MotionModel> m_motionModel; 00198 boost::shared_ptr<ObservationModel> m_observationModel; 00199 boost::shared_ptr<MapModel> m_mapModel; 00200 00201 ros::NodeHandle m_nh, m_privateNh; 00202 ros::Subscriber m_pauseIntegrationSub; 00203 00204 message_filters::Subscriber<sensor_msgs::LaserScan>* m_laserSub; 00205 tf::MessageFilter<sensor_msgs::LaserScan>* m_laserFilter; 00206 message_filters::Subscriber< PointCloud >* m_pointCloudSub; 00207 tf::MessageFilter< PointCloud >* m_pointCloudFilter; 00208 message_filters::Subscriber<geometry_msgs::PoseWithCovarianceStamped>* m_initPoseSub; 00209 tf::MessageFilter<geometry_msgs::PoseWithCovarianceStamped>* m_initPoseFilter; 00210 00211 ros::Publisher m_posePub, m_poseEvalPub, m_poseOdomPub, m_poseTruePub, 00212 m_poseArrayPub, m_bestPosePub, m_nEffPub, 00213 m_filteredPointCloudPub; 00214 ros::Subscriber m_imuSub; 00215 ros::ServiceServer m_globalLocSrv, m_pauseLocSrv, m_resumeLocSrv; 00216 tf::TransformListener m_tfListener; 00217 tf::TransformBroadcaster m_tfBroadcaster; 00218 00219 std::string m_odomFrameId; 00220 std::string m_baseFrameId; 00221 std::string m_baseFootprintId; 00222 std::string m_globalFrameId; 00223 00224 bool m_useRaycasting; 00225 bool m_initFromTruepose; 00226 int m_numParticles; 00227 int m_numSensorBeams; 00228 double m_sensorSampleDist; 00229 00230 double m_nEffFactor; 00231 double m_minParticleWeight; 00232 Vector6d m_initPose; // fixed init. pose (from params) 00233 Vector6d m_initNoiseStd; // Std.dev for init. pose 00234 bool m_initPoseRealZRP; // override z, roll, pitch with real values from robot 00235 00236 double m_filterMaxRange; 00237 double m_filterMinRange; 00238 00239 00240 Particles m_particles; 00241 int m_bestParticleIdx; 00242 tf::Pose m_odomPose; // incrementally added odometry pose (=dead reckoning) 00243 geometry_msgs::PoseArray m_poseArray; // particles as PoseArray (preallocated) 00244 boost::circular_buffer<sensor_msgs::Imu> m_lastIMUMsgBuffer; 00245 00246 bool m_bestParticleAsMean; 00247 bool m_receivedSensorData; 00248 bool m_initialized; 00249 bool m_initGlobal; 00250 bool m_paused; 00251 bool m_syncedTruepose; 00252 00253 double m_observationThresholdTrans; 00254 double m_observationThresholdRot; 00255 double m_observationThresholdHeadYawRot; 00256 double m_observationThresholdHeadPitchRot; 00257 double m_temporalSamplingRange; 00258 double m_transformTolerance; 00259 ros::Time m_lastLaserTime; 00260 ros::Time m_lastPointCloudTime; 00261 00262 00264 tf::Pose m_lastLocalizedPose; 00265 00267 double m_headYawRotationLastScan; 00269 double m_headPitchRotationLastScan; 00270 00271 bool m_useIMU; 00272 bool m_constrainMotionZ; 00273 bool m_constrainMotionRP; 00274 }; 00275 } 00276 00277 #endif