laser_height_estimation.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2010,
00005  *  Ivan Dryanovski <ivan.dryanovski@gmail.com>
00006  *  William Morris <morris@ee.ccny.cuny.edu>
00007  * All rights reserved.
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions
00011  * are met:
00012  *
00013  *  * Redistributions of source code must retain the above copyright
00014  *    notice, this list of conditions and the following disclaimer.
00015  *  * Redistributions in binary form must reproduce the above
00016  *    copyright notice, this list of conditions and the following
00017  *    disclaimer in the documentation and/or other materials provided
00018  *    with the distribution.
00019  *  * Neither the name of CCNY Robotics Lab nor the names of its
00020  *    contributors may be used to endorse or promote products derived
00021  *    from this software without specific prior written permission.
00022  *
00023  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  * POSSIBILITY OF SUCH DAMAGE.
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     // **** ros-related variables
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     // **** state variables
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     // **** parameters
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_;         // for histogram segmentation
00101 
00102     // **** member functions
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 }; // namespace mav
00125 
00126 #endif // LASER_HEIGHT_ESTIMATION_LASER_HEIGHT_ESTIMATION_H
00127 


laser_height_estimation
Author(s): Ivan Dryanovski
autogenerated on Thu Jan 2 2014 11:28:33