OdometryROS.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef ODOMETRYROS_H_
29 #define ODOMETRYROS_H_
30 
31 #include <ros/ros.h>
32 #include <nodelet/nodelet.h>
33 
35 #include <tf/transform_listener.h>
36 
37 #include <std_srvs/Empty.h>
38 #include <std_msgs/Header.h>
39 #include <sensor_msgs/Imu.h>
40 
41 #include <rtabmap_ros/ResetPose.h>
44 
45 #include <boost/thread.hpp>
46 
47 namespace rtabmap {
48 class Odometry;
49 }
50 
51 namespace rtabmap_ros {
52 
54 {
55 
56 public:
57  OdometryROS(bool stereoParams, bool visParams, bool icpParams);
58  virtual ~OdometryROS();
59 
60  void processData(const rtabmap::SensorData & data, const ros::Time & stamp, const std::string & sensorFrameId);
61 
62  bool reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
63  bool resetToPose(rtabmap_ros::ResetPose::Request&, rtabmap_ros::ResetPose::Response&);
64  bool pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
65  bool resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
66  bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
67  bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
68  bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
69  bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
70 
71  const std::string & frameId() const {return frameId_;}
72  const std::string & odomFrameId() const {return odomFrameId_;}
73  const rtabmap::ParametersMap & parameters() const {return parameters_;}
74  bool isPaused() const {return paused_;}
75  rtabmap::Transform getTransform(const std::string & fromFrameId, const std::string & toFrameId, const ros::Time & stamp) const;
76 
77 protected:
78  void startWarningThread(const std::string & subscribedTopicsMsg, bool approxSync);
79  void callbackCalled() {callbackCalled_ = true;}
80 
81  virtual void flushCallbacks() = 0;
82  tf::TransformListener & tfListener() {return tfListener_;}
83 
84 private:
85  void warningLoop(const std::string & subscribedTopicsMsg, bool approxSync);
86  virtual void onInit();
87  virtual void onOdomInit() = 0;
88  virtual void updateParameters(rtabmap::ParametersMap & parameters) {}
89 
90  void callbackIMU(const sensor_msgs::ImuConstPtr& msg);
91  void reset(const rtabmap::Transform & pose = rtabmap::Transform::getIdentity());
92 
93 private:
95  boost::thread * warningThread_;
97 
98  // parameters
99  std::string frameId_;
100  std::string odomFrameId_;
101  std::string groundTruthFrameId_;
103  std::string guessFrameId_;
112 
130 
131  bool paused_;
145  std::map<double, rtabmap::IMU> imus_;
146  std::pair<rtabmap::SensorData, std::pair<ros::Time, std::string> > bufferedData_;
147 };
148 
149 }
150 
151 #endif
std::string groundTruthBaseFrameId_
Definition: OdometryROS.h:102
const rtabmap::ParametersMap & parameters() const
Definition: OdometryROS.h:73
ros::Publisher odomRgbdImagePub_
Definition: OdometryROS.h:118
const std::string & frameId() const
Definition: OdometryROS.h:71
tf2_ros::TransformBroadcaster tfBroadcaster_
Definition: OdometryROS.h:127
virtual void updateParameters(rtabmap::ParametersMap &parameters)
Definition: OdometryROS.h:88
static Transform getIdentity()
boost::thread * warningThread_
Definition: OdometryROS.h:95
ros::Publisher odomLocalScanMap_
Definition: OdometryROS.h:116
ros::ServiceServer setLogInfoSrv_
Definition: OdometryROS.h:124
std::map< std::string, std::string > ParametersMap
std::string groundTruthFrameId_
Definition: OdometryROS.h:101
ros::ServiceServer setLogDebugSrv_
Definition: OdometryROS.h:123
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
ros::Publisher odomPub_
Definition: OdometryROS.h:113
tf::TransformListener & tfListener()
Definition: OdometryROS.h:82
ros::ServiceServer setLogWarnSrv_
Definition: OdometryROS.h:125
ros::ServiceServer resetToPoseSrv_
Definition: OdometryROS.h:120
rtabmap::ParametersMap parameters_
Definition: OdometryROS.h:111
ros::ServiceServer setLogErrorSrv_
Definition: OdometryROS.h:126
ros::ServiceServer resetSrv_
Definition: OdometryROS.h:119
std::map< double, rtabmap::IMU > imus_
Definition: OdometryROS.h:145
ros::Subscriber imuSub_
Definition: OdometryROS.h:129
ros::ServiceServer pauseSrv_
Definition: OdometryROS.h:121
ros::ServiceServer resumeSrv_
Definition: OdometryROS.h:122
ros::Publisher odomLocalMap_
Definition: OdometryROS.h:115
rtabmap::Transform guessPreviousPose_
Definition: OdometryROS.h:138
const std::string & odomFrameId() const
Definition: OdometryROS.h:72
rtabmap::Odometry * odometry_
Definition: OdometryROS.h:94
ros::Publisher odomInfoPub_
Definition: OdometryROS.h:114
tf::TransformListener tfListener_
Definition: OdometryROS.h:128
rtabmap::Transform guess_
Definition: OdometryROS.h:137
bool isPaused() const
Definition: OdometryROS.h:74
ros::Publisher odomLastFrame_
Definition: OdometryROS.h:117
std::pair< rtabmap::SensorData, std::pair< ros::Time, std::string > > bufferedData_
Definition: OdometryROS.h:146


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19