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_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/sample_consensus/method_types.h>
00045 #include <pcl/sample_consensus/model_types.h>
00046 #include <pcl/segmentation/sac_segmentation.h>
00047 #include <pcl/io/pcd_io.h>
00048 #include <pcl/filters/extract_indices.h>
00049 #include <pcl/filters/passthrough.h>
00050
00051
00052 #include <geometry_msgs/Pose.h>
00053 #include <geometry_msgs/PoseArray.h>
00054 #include <geometry_msgs/PoseWithCovariance.h>
00055 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00056
00057 #include <humanoid_localization/humanoid_localization_defs.h>
00058 #include <humanoid_localization/MotionModel.h>
00059 #include <humanoid_localization/ObservationModel.h>
00060 #include <humanoid_localization/RaycastingModel.h>
00061 #ifndef SKIP_ENDPOINT_MODEL
00062 #include <humanoid_localization/EndpointModel.h>
00063 #endif
00064
00065
00066 #include <octomap/octomap.h>
00067 #include <sensor_msgs/Imu.h>
00068 #include <boost/circular_buffer.hpp>
00069
00070 namespace humanoid_localization{
00071
00072 static inline void getRP(const geometry_msgs::Quaternion& msg_q, double& roll, double& pitch){
00073 tf::Quaternion bt_q;
00074 tf::quaternionMsgToTF(msg_q, bt_q);
00075 double useless_yaw;
00076 tf::Matrix3x3(bt_q).getRPY(roll, pitch, useless_yaw);
00077
00078 if (std::abs(useless_yaw) > 0.00001)
00079 ROS_WARN("Non-zero yaw in IMU quaterion is ignored");
00080 }
00081
00082 class HumanoidLocalization {
00083 public:
00084
00085
00086
00087 public:
00088 HumanoidLocalization(unsigned randomSeed);
00089 virtual ~HumanoidLocalization();
00090 virtual void laserCallback(const sensor_msgs::LaserScanConstPtr& msg);
00091 virtual void pointCloudCallback(const sensor_msgs::PointCloud2::ConstPtr& msg);
00092 void initPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg);
00093 bool globalLocalizationCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
00094 void pauseLocalizationCallback(const std_msgs::BoolConstPtr& msg);
00096 bool pauseLocalizationSrvCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
00098 bool resumeLocalizationSrvCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
00099 void imuCallback(const sensor_msgs::ImuConstPtr& msg);
00100
00107 void resample(unsigned numParticles = 0);
00109 unsigned getBestParticleIdx() const;
00111 tf::Pose getParticlePose(unsigned particleIdx) const;
00113 tf::Pose getBestParticlePose() const;
00115 tf::Pose getMeanParticlePose() const;
00116
00118 void initGlobal();
00119
00120
00121 static void filterGroundPlane(const PointCloud& pc, PointCloud& ground, PointCloud& nonground, double groundFilterDistance, double groundFilterAngle, double groundFilterPlaneDistance);
00122
00123 protected:
00129 void reset();
00130
00131
00132 void publishPoseEstimate(const ros::Time& time, bool publish_eval);
00133
00134
00140 void normalizeWeights();
00141
00143 double getCumParticleWeight() const;
00144
00150 double nEff() const;
00151
00155 void toLogForm();
00156
00165 bool getImuMsg(const ros::Time& stamp, ros::Time& imuStamp, double& angleX, double& angleY) const;
00166
00172 void prepareLaserPointCloud(const sensor_msgs::LaserScanConstPtr& laser, PointCloud& pc, std::vector<float>& ranges) const;
00173
00179 void prepareGeneralPointCloud(const sensor_msgs::PointCloud2::ConstPtr& msg, PointCloud& pc, std::vector<float>& ranges) const;
00180 int filterUniform( const PointCloud & cloud_in, PointCloud & cloud_out, int numSamples) const;
00181
00182 void voxelGridSampling(const PointCloud & pc, pcl::PointCloud<int> & sampledIndices, double searchRadius) 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 void timerCallback(const ros::TimerEvent & e);
00191
00192 unsigned computeBeamStep(unsigned numBeams) const;
00193
00198 void initZRP(double& z, double& roll, double& pitch);
00199
00200 bool lookupPoseHeight(const ros::Time& t, double& poseHeight) const;
00201
00202 EngineT m_rngEngine;
00204 NormalGeneratorT m_rngNormal;
00206 UniformGeneratorT m_rngUniform;
00207 boost::shared_ptr<MotionModel> m_motionModel;
00208 boost::shared_ptr<ObservationModel> m_observationModel;
00209 boost::shared_ptr<MapModel> m_mapModel;
00210
00211 ros::NodeHandle m_nh, m_privateNh;
00212 ros::Subscriber m_pauseIntegrationSub;
00213
00214 message_filters::Subscriber<sensor_msgs::LaserScan>* m_laserSub;
00215 tf::MessageFilter<sensor_msgs::LaserScan>* m_laserFilter;
00216 message_filters::Subscriber<sensor_msgs::PointCloud2>* m_pointCloudSub;
00217 tf::MessageFilter<sensor_msgs::PointCloud2>* m_pointCloudFilter;
00218 message_filters::Subscriber<geometry_msgs::PoseWithCovarianceStamped>* m_initPoseSub;
00219 tf::MessageFilter<geometry_msgs::PoseWithCovarianceStamped>* m_initPoseFilter;
00220
00221 ros::Publisher m_posePub, m_poseEvalPub, m_poseOdomPub, m_poseTruePub,
00222 m_poseArrayPub, m_bestPosePub, m_nEffPub,
00223 m_filteredPointCloudPub;
00224 ros::Subscriber m_imuSub;
00225 ros::ServiceServer m_globalLocSrv, m_pauseLocSrv, m_resumeLocSrv;
00226 tf::TransformListener m_tfListener;
00227 tf::TransformBroadcaster m_tfBroadcaster;
00228 ros::Timer m_timer;
00229
00230 std::string m_odomFrameId;
00231 std::string m_targetFrameId;
00232 std::string m_baseFrameId;
00233 std::string m_baseFootprintId;
00234 std::string m_globalFrameId;
00235
00236 bool m_useRaycasting;
00237 bool m_initFromTruepose;
00238 int m_numParticles;
00239 double m_sensorSampleDist;
00240
00241 double m_nEffFactor;
00242 double m_minParticleWeight;
00243 Vector6d m_initPose;
00244 Vector6d m_initNoiseStd;
00245 bool m_initPoseRealZRP;
00246
00247 double m_filterMaxRange;
00248 double m_filterMinRange;
00249
00250
00251 Particles m_particles;
00252 int m_bestParticleIdx;
00253 tf::Pose m_odomPose;
00254 geometry_msgs::PoseArray m_poseArray;
00255 boost::circular_buffer<sensor_msgs::Imu> m_lastIMUMsgBuffer;
00256
00257 bool m_bestParticleAsMean;
00258 bool m_receivedSensorData;
00259 bool m_initialized;
00260 bool m_initGlobal;
00261 bool m_paused;
00262 bool m_syncedTruepose;
00263
00264 double m_observationThresholdTrans;
00265 double m_observationThresholdRot;
00266 double m_observationThresholdHeadYawRot;
00267 double m_observationThresholdHeadPitchRot;
00268 double m_temporalSamplingRange;
00269 double m_transformTolerance;
00270 ros::Time m_lastLaserTime;
00271 ros::Time m_lastPointCloudTime;
00272
00273
00274
00275
00276 bool m_groundFilterPointCloud;
00277 double m_groundFilterDistance;
00278 double m_groundFilterAngle;
00279 double m_groundFilterPlaneDistance;
00280 double m_sensorSampleDistGroundFactor;
00281
00282
00284 tf::Pose m_lastLocalizedPose;
00285 tf::StampedTransform m_latest_transform;
00286
00288 double m_headYawRotationLastScan;
00290 double m_headPitchRotationLastScan;
00291
00292 bool m_useIMU;
00293 bool m_constrainMotionZ;
00294 bool m_constrainMotionRP;
00295
00296
00297 bool m_useTimer;
00298 double m_timerPeriod;
00299 };
00300 }
00301
00302 #endif