00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 */ 00030 00039 #ifndef GRAPH_SLAM_ODOMETER_H 00040 #define GRAPH_SLAM_ODOMETER_H 00041 00042 #include <tf/transform_listener.h> 00043 #include <ros/ros.h> 00044 00045 namespace graph_slam 00046 { 00047 00055 class Odometer 00056 { 00057 public: 00058 00065 Odometer (tf::TransformListener* tf, const std::string& base_frame, 00066 const std::string& fixed_frame, const ros::Duration& timeout = ros::Duration(0.0)); 00067 00070 void reset (const ros::Time& t, const ros::Duration& timeout = ros::Duration(0.0)); 00071 00074 ros::Time reset (const ros::Duration& timeout = ros::Duration(0.0)); 00075 00079 tf::Pose getDisplacement (const ros::Time& t = ros::Time()); 00080 00081 private: 00082 00083 const ros::Duration wait_inc_; // How often status messages get printed when waiting 00084 00085 tf::TransformListener* tf_; 00086 std::string base_frame_; 00087 std::string fixed_frame_; 00088 tf::Stamped<tf::Pose> reference_pose_; 00089 00090 }; 00091 00092 00093 } // namespace 00094 00095 #endif // include guard