OdometryROS.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
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     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef ODOMETRYROS_H_
00029 #define ODOMETRYROS_H_
00030 
00031 #include <ros/ros.h>
00032 
00033 #include <tf/tf.h>
00034 #include <tf/transform_broadcaster.h>
00035 #include <tf/transform_listener.h>
00036 
00037 #include <std_srvs/Empty.h>
00038 #include <std_msgs/Header.h>
00039 
00040 #include <rtabmap_ros/ResetPose.h>
00041 #include <rtabmap/core/SensorData.h>
00042 #include <rtabmap/core/Parameters.h>
00043 
00044 namespace rtabmap {
00045 class Odometry;
00046 }
00047 
00048 namespace rtabmap_ros {
00049 
00050 class OdometryROS
00051 {
00052 public:
00053         OdometryROS(int argc, char * argv[]);
00054         ~OdometryROS();
00055 
00056         void processArguments(int argc, char * argv[]);
00057         void processData(const rtabmap::SensorData & data, const std_msgs::Header & header);
00058 
00059         bool reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00060         bool resetToPose(rtabmap_ros::ResetPose::Request&, rtabmap_ros::ResetPose::Response&);
00061         bool pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00062         bool resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00063 
00064         const std::string & frameId() const {return frameId_;}
00065         const std::string & odomFrameId() const {return odomFrameId_;}
00066         const rtabmap::ParametersMap & parameters() const {return parameters_;}
00067         const tf::TransformListener & tfListener() const {return tfListener_;}
00068         bool isPaused() const {return paused_;}
00069         bool isOdometryBOW() const;
00070         bool waitForTransform() const {return waitForTransform_;}
00071 
00072 private:
00073         rtabmap::Odometry * odometry_;
00074 
00075         // parameters
00076         std::string frameId_;
00077         std::string odomFrameId_;
00078         std::string groundTruthFrameId_;
00079         bool publishTf_;
00080         bool waitForTransform_;
00081         rtabmap::ParametersMap parameters_;
00082 
00083         ros::Publisher odomPub_;
00084         ros::Publisher odomInfoPub_;
00085         ros::Publisher odomLocalMap_;
00086         ros::Publisher odomLastFrame_;
00087         ros::ServiceServer resetSrv_;
00088         ros::ServiceServer resetToPoseSrv_;
00089         ros::ServiceServer pauseSrv_;
00090         ros::ServiceServer resumeSrv_;
00091         tf::TransformBroadcaster tfBroadcaster_;
00092         tf::TransformListener tfListener_;
00093 
00094         bool paused_;
00095 };
00096 
00097 }
00098 
00099 #endif


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Aug 27 2015 15:00:25