OdometryROS.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, 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 #include <nodelet/nodelet.h>
00033 
00034 #include <tf2_ros/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 : public nodelet::Nodelet
00051 {
00052 
00053 public:
00054         OdometryROS(bool stereo);
00055         virtual ~OdometryROS();
00056 
00057         void processData(const rtabmap::SensorData & data, const ros::Time & stamp);
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         bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00064         bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00065         bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00066         bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00067 
00068         const std::string & frameId() const {return frameId_;}
00069         const std::string & odomFrameId() const {return odomFrameId_;}
00070         const rtabmap::ParametersMap & parameters() const {return parameters_;}
00071         const tf::TransformListener & tfListener() const {return tfListener_;}
00072         bool isPaused() const {return paused_;}
00073         bool isOdometryF2M() const;
00074         rtabmap::Transform getTransform(const std::string & fromFrameId, const std::string & toFrameId, const ros::Time & stamp) const;
00075 
00076 protected:
00077         virtual void flushCallbacks() = 0;
00078 
00079 private:
00080         virtual void onInit();
00081         virtual void onOdomInit() = 0;
00082 
00083 private:
00084         rtabmap::Odometry * odometry_;
00085 
00086         // parameters
00087         std::string frameId_;
00088         std::string odomFrameId_;
00089         std::string groundTruthFrameId_;
00090         bool publishTf_;
00091         bool waitForTransform_;
00092         double waitForTransformDuration_;
00093         bool publishNullWhenLost_;
00094         bool guessFromTf_;
00095         rtabmap::ParametersMap parameters_;
00096 
00097         ros::Publisher odomPub_;
00098         ros::Publisher odomInfoPub_;
00099         ros::Publisher odomLocalMap_;
00100         ros::Publisher odomLastFrame_;
00101         ros::ServiceServer resetSrv_;
00102         ros::ServiceServer resetToPoseSrv_;
00103         ros::ServiceServer pauseSrv_;
00104         ros::ServiceServer resumeSrv_;
00105         ros::ServiceServer setLogDebugSrv_;
00106         ros::ServiceServer setLogInfoSrv_;
00107         ros::ServiceServer setLogWarnSrv_;
00108         ros::ServiceServer setLogErrorSrv_;
00109         tf2_ros::TransformBroadcaster tfBroadcaster_;
00110         tf::TransformListener tfListener_;
00111 
00112         bool paused_;
00113         int resetCountdown_;
00114         int resetCurrentCount_;
00115         bool stereo_;
00116 };
00117 
00118 }
00119 
00120 #endif


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Sun Jul 24 2016 03:49:08