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 
48 
49 namespace rtabmap {
50 class Odometry;
51 }
52 
53 namespace rtabmap_ros {
54 
56 {
57 
58 public:
59  OdometryROS(bool stereoParams, bool visParams, bool icpParams);
60  virtual ~OdometryROS();
61 
62  void processData(rtabmap::SensorData & data, const std_msgs::Header & header);
63 
64  bool reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
65  bool resetToPose(rtabmap_ros::ResetPose::Request&, rtabmap_ros::ResetPose::Response&);
66  bool pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
67  bool resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
68  bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
69  bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
70  bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
71  bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
72 
73  const std::string & frameId() const {return frameId_;}
74  const std::string & odomFrameId() const {return odomFrameId_;}
75  const std::string & guessFrameId() const {return guessFrameId_;}
76  const rtabmap::ParametersMap & parameters() const {return parameters_;}
77  bool isPaused() const {return paused_;}
78 
79 protected:
80  void startWarningThread(const std::string & subscribedTopicsMsg, bool approxSync);
81  void callbackCalled() {callbackCalled_ = true;}
82 
83  virtual void flushCallbacks() = 0;
84  tf::TransformListener & tfListener() {return tfListener_;}
85  double waitForTransformDuration() const {return waitForTransform_?waitForTransformDuration_:0.0;}
86  rtabmap::Transform velocityGuess() const;
87  double previousStamp() const {return previousStamp_;}
88  virtual void postProcessData(const rtabmap::SensorData & data, const std_msgs::Header & header) const {}
89 
90 private:
91  void warningLoop(const std::string & subscribedTopicsMsg, bool approxSync);
92  virtual void onInit();
93  virtual void onOdomInit() = 0;
94  virtual void updateParameters(rtabmap::ParametersMap & parameters) {}
95 
96  void callbackIMU(const sensor_msgs::ImuConstPtr& msg);
97  void reset(const rtabmap::Transform & pose = rtabmap::Transform::getIdentity());
98 
99 private:
101  boost::thread * warningThread_;
103 
104  // parameters
105  std::string frameId_;
106  std::string odomFrameId_;
107  std::string groundTruthFrameId_;
109  std::string guessFrameId_;
118 
137 
138  bool paused_;
153  std::map<double, rtabmap::IMU> imus_;
154  std::pair<rtabmap::SensorData, std_msgs::Header > bufferedData_;
155 
157 };
158 
159 }
160 
161 #endif
std::string groundTruthBaseFrameId_
Definition: OdometryROS.h:108
std::pair< rtabmap::SensorData, std_msgs::Header > bufferedData_
Definition: OdometryROS.h:154
ros::Publisher odomRgbdImagePub_
Definition: OdometryROS.h:125
tf2_ros::TransformBroadcaster tfBroadcaster_
Definition: OdometryROS.h:134
virtual void updateParameters(rtabmap::ParametersMap &parameters)
Definition: OdometryROS.h:94
static Transform getIdentity()
const std::string & frameId() const
Definition: OdometryROS.h:73
boost::thread * warningThread_
Definition: OdometryROS.h:101
const std::string & odomFrameId() const
Definition: OdometryROS.h:74
ros::Publisher odomLocalScanMap_
Definition: OdometryROS.h:123
data
double previousStamp() const
Definition: OdometryROS.h:87
ros::ServiceServer setLogInfoSrv_
Definition: OdometryROS.h:131
std::map< std::string, std::string > ParametersMap
virtual void postProcessData(const rtabmap::SensorData &data, const std_msgs::Header &header) const
Definition: OdometryROS.h:88
std::string groundTruthFrameId_
Definition: OdometryROS.h:107
ros::ServiceServer setLogDebugSrv_
Definition: OdometryROS.h:130
ULogToRosout ulogToRosout_
Definition: OdometryROS.h:156
ros::Publisher odomPub_
Definition: OdometryROS.h:119
tf::TransformListener & tfListener()
Definition: OdometryROS.h:84
ros::ServiceServer setLogWarnSrv_
Definition: OdometryROS.h:132
ros::ServiceServer resetToPoseSrv_
Definition: OdometryROS.h:127
rtabmap::ParametersMap parameters_
Definition: OdometryROS.h:117
double waitForTransformDuration() const
Definition: OdometryROS.h:85
ros::ServiceServer setLogErrorSrv_
Definition: OdometryROS.h:133
ros::ServiceServer resetSrv_
Definition: OdometryROS.h:126
std::map< double, rtabmap::IMU > imus_
Definition: OdometryROS.h:153
ros::Subscriber imuSub_
Definition: OdometryROS.h:136
ros::ServiceServer pauseSrv_
Definition: OdometryROS.h:128
ros::ServiceServer resumeSrv_
Definition: OdometryROS.h:129
ros::Publisher odomLocalMap_
Definition: OdometryROS.h:122
rtabmap::Transform guessPreviousPose_
Definition: OdometryROS.h:145
rtabmap::Odometry * odometry_
Definition: OdometryROS.h:100
ros::Publisher odomInfoPub_
Definition: OdometryROS.h:120
tf::TransformListener tfListener_
Definition: OdometryROS.h:135
rtabmap::Transform guess_
Definition: OdometryROS.h:144
const std::string header
ros::Publisher odomInfoLitePub_
Definition: OdometryROS.h:121
const std::string & guessFrameId() const
Definition: OdometryROS.h:75
const rtabmap::ParametersMap & parameters() const
Definition: OdometryROS.h:76
ros::Publisher odomLastFrame_
Definition: OdometryROS.h:124


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40