24 #ifndef HUMANOID_LOCALIZATION_HUMANOIDLOCALIZATION_H_    25 #define HUMANOID_LOCALIZATION_HUMANOIDLOCALIZATION_H_    28 #include <boost/shared_ptr.hpp>    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>    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>    52 #include <geometry_msgs/Pose.h>    53 #include <geometry_msgs/PoseArray.h>    54 #include <geometry_msgs/PoseWithCovariance.h>    55 #include <geometry_msgs/PoseWithCovarianceStamped.h>    61 #ifndef SKIP_ENDPOINT_MODEL    67 #include <sensor_msgs/Imu.h>    68 #include <boost/circular_buffer.hpp>    72 static inline void getRP(
const geometry_msgs::Quaternion& msg_q, 
double& roll, 
double& pitch){
    78   if (std::abs(useless_yaw) > 0.00001)
    79     ROS_WARN(
"Non-zero yaw in IMU quaterion is ignored");
    90   virtual void laserCallback(
const sensor_msgs::LaserScanConstPtr& msg);
    92   void initPoseCallback(
const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg);
    99   void imuCallback(
const sensor_msgs::ImuConstPtr& msg);
   107   void resample(
unsigned numParticles = 0);
   198   void initZRP(
double& 
z, 
double& roll, 
double& pitch);
 tf::TransformBroadcaster m_tfBroadcaster
 
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)
 
ros::Publisher m_poseOdomPub
 
double m_observationThresholdRot
 
void initPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
 
std::string m_baseFrameId
 
std::string m_targetFrameId
 
double m_sensorSampleDistGroundFactor
 
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 
 
double m_observationThresholdHeadPitchRot
 
bool isAboveMotionThreshold(const tf::Pose &odomTransform)
 
bool m_bestParticleAsMean
 
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 
 
double m_observationThresholdHeadYawRot
 
ros::Publisher m_filteredPointCloudPub
 
bool lookupPoseHeight(const ros::Time &t, double &poseHeight) const 
 
ros::Publisher m_poseArrayPub
 
double m_minParticleWeight
 
ros::Publisher m_poseTruePub
 
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
 
ros::Publisher m_poseEvalPub
 
ros::Time m_lastLaserTime
 
message_filters::Subscriber< sensor_msgs::LaserScan > * m_laserSub
 
ros::Time m_lastPointCloudTime
 
void prepareGeneralPointCloud(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloud &pc, std::vector< float > &ranges) const 
 
virtual ~HumanoidLocalization()
 
bool m_useIMU
True = use IMU for initialization and observation models, false = use orientation from odometry...
 
void timerCallback(const ros::TimerEvent &e)
 
tf::Pose getMeanParticlePose() const 
Returns the 6D pose of the weighted mean particle. 
 
boost::shared_ptr< MapModel > m_mapModel
 
boost::shared_ptr< ObservationModel > m_observationModel
 
tf::TransformListener m_tfListener
 
double m_temporalSamplingRange
 
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
 
void constrainMotion(const tf::Pose &odomPose)
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > * m_pointCloudSub
 
double m_groundFilterAngle
 
tf::StampedTransform m_latest_transform
 
void initGlobal()
function call for global initialization (called by globalLocalizationCallback) 
 
ros::NodeHandle m_privateNh
 
message_filters::Subscriber< geometry_msgs::PoseWithCovarianceStamped > * m_initPoseSub
 
ros::ServiceServer m_pauseLocSrv
 
boost::variate_generator< EngineT &, UniformDistributionT > UniformGeneratorT
uniform noise in range [0,1) 
 
double m_sensorSampleDist
 
boost::circular_buffer< sensor_msgs::Imu > m_lastIMUMsgBuffer
 
Eigen::Matrix< double, 6, 1 > Vector6d
 
std::string m_globalFrameId
 
boost::shared_ptr< MotionModel > m_motionModel
 
ros::Subscriber m_pauseIntegrationSub
 
tf::Pose getParticlePose(unsigned particleIdx) const 
Returns the 6D pose of a particle. 
 
UniformGeneratorT m_rngUniform
uniform distribution [0:1] 
 
ros::ServiceServer m_globalLocSrv
 
bool globalLocalizationCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 
TFSIMD_FORCE_INLINE const tfScalar & z() const 
 
HumanoidLocalization(unsigned randomSeed)
 
unsigned computeBeamStep(unsigned numBeams) const 
 
geometry_msgs::PoseArray m_poseArray
 
ros::Publisher m_bestPosePub
 
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) 
 
void resample(unsigned numParticles=0)
 
ros::ServiceServer m_resumeLocSrv
 
bool m_receivedSensorData
 
bool getImuMsg(const ros::Time &stamp, ros::Time &imuStamp, double &angleX, double &angleY) const 
 
bool m_groundFilterPointCloud
 
virtual void laserCallback(const sensor_msgs::LaserScanConstPtr &msg)
 
double m_observationThresholdTrans
 
void initZRP(double &z, double &roll, double &pitch)
 
std::string m_baseFootprintId
 
double m_transformTolerance
 
double m_groundFilterDistance
 
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)
 
std::string m_odomFrameId
 
double m_groundFilterPlaneDistance
 
NormalGeneratorT m_rngNormal
standard normal distribution