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 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #ifndef LASER_HEIGHT_ESTIMATION_LASER_HEIGHT_ESTIMATION_H
00038 #define LASER_HEIGHT_ESTIMATION_LASER_HEIGHT_ESTIMATION_H
00039 
00040 #include <ros/ros.h>
00041 #include <sensor_msgs/LaserScan.h>
00042 #include <sensor_msgs/Imu.h>
00043 #include <std_msgs/Float64.h>
00044 #include <tf/transform_datatypes.h>
00045 #include <tf/transform_listener.h>
00046 #include <boost/thread/mutex.hpp>
00047 
00048 #include <mav_msgs/Height.h>
00049 
00050 namespace mav
00051 {
00052 
00053 class LaserHeightEstimation
00054 {
00055   public:
00056 
00057     LaserHeightEstimation(ros::NodeHandle nh, ros::NodeHandle nh_private);
00058     virtual ~LaserHeightEstimation();
00059 
00060   private:
00061 
00062     
00063 
00064     ros::NodeHandle nh_;
00065     ros::NodeHandle nh_private_;
00066     ros::Subscriber imu_subscriber_;
00067     ros::Subscriber scan_subscriber_;
00068     ros::Publisher  floor_publisher_;
00069     ros::Publisher  height_to_base_publisher_;
00070     ros::Publisher  height_to_footprint_publisher_;
00071     tf::TransformListener tf_listener_;
00072 
00073     
00074 
00075     boost::mutex mutex_;
00076 
00077     bool initialized_;
00078     bool first_time_;
00079     double floor_height_;
00080     double prev_height_;
00081 
00082     tf::Transform base_to_laser_;
00083     tf::Transform base_to_footprint_;
00084     tf::Transform world_to_base_;
00085 
00086     sensor_msgs::Imu latest_imu_msg_;
00087 
00088     ros::Time last_update_time_;
00089 
00090     
00091 
00092     std::string world_frame_;
00093     std::string base_frame_;
00094     std::string footprint_frame_;
00095     int min_values_;
00096     double max_stdev_;
00097     double max_height_jump_;
00098     bool use_imu_;
00099     bool use_segmentation_;
00100     double bin_size_;         
00101 
00102     
00103 
00104     void scanCallback (const sensor_msgs::LaserScanPtr& scan_msg);
00105     void imuCallback  (const sensor_msgs::ImuPtr&       imu_msg);
00106     bool setBaseToLaserTf(const sensor_msgs::LaserScanPtr& scan_msg);
00107     void getStats(const std::vector<double> values, double& ave, double& stdev);
00108 
00109     void histogramSegmentation(
00110       const std::vector<double>& input,
00111       std::vector<double>& output);
00112 
00113     void kMeansSegmentation(
00114       const std::vector<double>& input,
00115       std::vector<double>& output);
00116 
00117     bool kMeansSegmentation(
00118       const std::vector<double>& input,
00119       std::vector<bool>& mask,
00120       double& mean_a, double& mean_b,
00121       int& count_a, int& count_b);
00122 };
00123 
00124 }; 
00125 
00126 #endif // LASER_HEIGHT_ESTIMATION_LASER_HEIGHT_ESTIMATION_H
00127