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 #include <boost/thread.hpp>
00045 
00046 namespace rtabmap {
00047 class Odometry;
00048 }
00049 
00050 namespace rtabmap_ros {
00051 
00052 class OdometryROS : public nodelet::Nodelet
00053 {
00054 
00055 public:
00056         OdometryROS(bool stereoParams, bool visParams, bool icpParams);
00057         virtual ~OdometryROS();
00058 
00059         void processData(const rtabmap::SensorData & data, const ros::Time & stamp);
00060 
00061         bool reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00062         bool resetToPose(rtabmap_ros::ResetPose::Request&, rtabmap_ros::ResetPose::Response&);
00063         bool pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00064         bool resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00065         bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00066         bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00067         bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00068         bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
00069 
00070         const std::string & frameId() const {return frameId_;}
00071         const std::string & odomFrameId() const {return odomFrameId_;}
00072         const rtabmap::ParametersMap & parameters() const {return parameters_;}
00073         bool isPaused() const {return paused_;}
00074         rtabmap::Transform getTransform(const std::string & fromFrameId, const std::string & toFrameId, const ros::Time & stamp) const;
00075 
00076 protected:
00077         void startWarningThread(const std::string & subscribedTopicsMsg, bool approxSync);
00078         void callbackCalled() {callbackCalled_ = true;}
00079 
00080         virtual void flushCallbacks() = 0;
00081         tf::TransformListener & tfListener() {return tfListener_;}
00082 
00083 private:
00084         void warningLoop(const std::string & subscribedTopicsMsg, bool approxSync);
00085         virtual void onInit();
00086         virtual void onOdomInit() = 0;
00087         virtual void updateParameters(rtabmap::ParametersMap & parameters) {}
00088 
00089 private:
00090         rtabmap::Odometry * odometry_;
00091         boost::thread * warningThread_;
00092         bool callbackCalled_;
00093 
00094         // parameters
00095         std::string frameId_;
00096         std::string odomFrameId_;
00097         std::string groundTruthFrameId_;
00098         std::string groundTruthBaseFrameId_;
00099         std::string guessFrameId_;
00100         double guessMinTranslation_;
00101         double guessMinRotation_;
00102         bool publishTf_;
00103         bool waitForTransform_;
00104         double waitForTransformDuration_;
00105         bool publishNullWhenLost_;
00106         rtabmap::ParametersMap parameters_;
00107 
00108         ros::Publisher odomPub_;
00109         ros::Publisher odomInfoPub_;
00110         ros::Publisher odomLocalMap_;
00111         ros::Publisher odomLocalScanMap_;
00112         ros::Publisher odomLastFrame_;
00113         ros::ServiceServer resetSrv_;
00114         ros::ServiceServer resetToPoseSrv_;
00115         ros::ServiceServer pauseSrv_;
00116         ros::ServiceServer resumeSrv_;
00117         ros::ServiceServer setLogDebugSrv_;
00118         ros::ServiceServer setLogInfoSrv_;
00119         ros::ServiceServer setLogWarnSrv_;
00120         ros::ServiceServer setLogErrorSrv_;
00121         tf2_ros::TransformBroadcaster tfBroadcaster_;
00122         tf::TransformListener tfListener_;
00123 
00124         bool paused_;
00125         int resetCountdown_;
00126         int resetCurrentCount_;
00127         bool stereoParams_;
00128         bool visParams_;
00129         bool icpParams_;
00130         rtabmap::Transform guess_;
00131         double guessStamp_;
00132 };
00133 
00134 }
00135 
00136 #endif


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:30:49