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 * Henrique Silva <henrique.rd.silva@gmail.com> 00008 * All rights reserved. 00009 * 00010 * Redistribution and use in source and binary forms, with or without 00011 * modification, are permitted provided that the following conditions 00012 * are met: 00013 * 00014 * * Redistributions of source code must retain the above copyright 00015 * notice, this list of conditions and the following disclaimer. 00016 * * Redistributions in binary form must reproduce the above 00017 * copyright notice, this list of conditions and the following 00018 * disclaimer in the documentation and/or other materials provided 00019 * with the distribution. 00020 * * Neither the name of CCNY Robotics Lab nor the names of its 00021 * contributors may be used to endorse or promote products derived 00022 * from this software without specific prior written permission. 00023 * 00024 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00025 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00026 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00027 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00028 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00029 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00030 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00031 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00032 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00033 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00034 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00035 * POSSIBILITY OF SUCH DAMAGE. 00036 */ 00037 00038 #ifndef LASER_HEIGHT_ESTIMATION_LASER_HEIGHT_ESTIMATION_H 00039 #define LASER_HEIGHT_ESTIMATION_LASER_HEIGHT_ESTIMATION_H 00040 00041 #include <ros/ros.h> 00042 #include <sensor_msgs/LaserScan.h> 00043 #include <sensor_msgs/Imu.h> 00044 #include <std_msgs/Float64.h> 00045 #include <tf/transform_datatypes.h> 00046 #include <tf/transform_listener.h> 00047 #include <boost/thread/mutex.hpp> 00048 00049 #include <mav_msgs/Height.h> 00050 00051 namespace mav 00052 { 00053 00054 class LaserHeightEstimation 00055 { 00056 public: 00057 00058 LaserHeightEstimation(ros::NodeHandle nh, ros::NodeHandle nh_private); 00059 virtual ~LaserHeightEstimation(); 00060 00061 private: 00062 00063 // ROS-related variables 00064 00065 ros::NodeHandle nh_; 00066 ros::NodeHandle nh_private_; 00067 ros::Subscriber imu_subscriber_; 00068 ros::Subscriber scan_subscriber_; 00069 ros::Publisher floor_publisher_; 00070 ros::Publisher height_to_base_publisher_; 00071 ros::Publisher height_to_footprint_publisher_; 00072 tf::TransformListener tf_listener_; 00073 00074 // State variables 00075 00076 boost::mutex mutex_; 00077 00078 bool initialized_; 00079 bool first_time_; 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 stabilized_frame_; 00095 std::string imu_topic_; 00096 std::string scan_topic_; 00097 int min_values_; 00098 double max_stdev_; 00099 double max_height_jump_; 00100 bool use_imu_; 00101 bool use_segmentation_; 00102 double bin_size_; // for histogram segmentation 00103 00104 // Member functions 00105 00106 void scanCallback (const sensor_msgs::LaserScanPtr& scan_msg); 00107 void imuCallback (const sensor_msgs::ImuPtr& imu_msg); 00108 bool setBaseToLaserTf(const sensor_msgs::LaserScanPtr& scan_msg); 00109 void getStats(const std::vector<double> values, double& ave, double& stdev); 00110 00111 void histogramSegmentation( 00112 const std::vector<double>& input, 00113 std::vector<double>& output); 00114 00115 }; 00116 00117 }; // namespace mav 00118 00119 #endif // LASER_HEIGHT_ESTIMATION_LASER_HEIGHT_ESTIMATION_H 00120