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 
42 
43 #include <rtabmap_msgs/ResetPose.h>
47 
48 #include <boost/thread.hpp>
49 
52 
53 namespace rtabmap {
54 class Odometry;
55 }
56 
57 namespace rtabmap_odom {
58 
59 class OdometryROS : public nodelet::Nodelet, public UThread
60 {
61 
62 public:
63  OdometryROS(bool stereoParams, bool visParams, bool icpParams);
64  virtual ~OdometryROS();
65 
66  void processData(rtabmap::SensorData & data, const std_msgs::Header & header);
67 
68  bool reset(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
69  bool resetToPose(rtabmap_msgs::ResetPose::Request&, rtabmap_msgs::ResetPose::Response&);
70  bool pause(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
71  bool resume(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
72  bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
73  bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
74  bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
75  bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
76 
77  const std::string & frameId() const {return frameId_;}
78  const std::string & odomFrameId() const {return odomFrameId_;}
79  const std::string & guessFrameId() const {return guessFrameId_;}
80  const rtabmap::ParametersMap & parameters() const {return parameters_;}
81  bool isPaused() const {return paused_;}
82 
83 protected:
84  void initDiagnosticMsg(const std::string & subscribedTopicsMsg, bool approxSync, const std::string & subscribedTopic = "");
85 
86  virtual void flushCallbacks() = 0;
90  double previousStamp() const {return previousStamp_;}
91  virtual void postProcessData(const rtabmap::SensorData & data, const std_msgs::Header & header) const {}
92 
93 private:
94  virtual void onInit();
95  virtual void onOdomInit() = 0;
97 
98  virtual void mainLoop();
99  virtual void mainLoopKill();
100 
101  void callbackIMU(const sensor_msgs::ImuConstPtr& msg);
103 
104 private:
106 
107  // parameters
108  std::string frameId_;
109  std::string odomFrameId_;
110  std::string groundTruthFrameId_;
112  std::string guessFrameId_;
122 
144 
145  // Safe-threading
150  std_msgs::Header dataHeaderToProcess_;
152 
153  bool paused_;
170  std::map<double, rtabmap::IMU> imus_;
171 
173 
175  {
176  public:
177  OdomStatusTask();
178  void setStatus(bool isLost);
180  private:
181  bool lost_;
183  };
185  std::unique_ptr<rtabmap_sync::SyncDiagnostic> syncDiagnostic_;
186 };
187 
188 }
189 
190 #endif
rtabmap::SensorData
rtabmap_odom
Definition: OdometryROS.h:57
rtabmap_odom::OdometryROS::resumeSrv_
ros::ServiceServer resumeSrv_
Definition: OdometryROS.h:136
rtabmap_odom::OdometryROS::processData
void processData(rtabmap::SensorData &data, const std_msgs::Header &header)
Definition: OdometryROS.cpp:461
rtabmap_odom::OdometryROS::odometry_
rtabmap::Odometry * odometry_
Definition: OdometryROS.h:105
rtabmap_odom::OdometryROS::dataMutex_
UMutex dataMutex_
Definition: OdometryROS.h:147
rtabmap_odom::OdometryROS::publishCompressedSensorData_
bool publishCompressedSensorData_
Definition: OdometryROS.h:120
rtabmap_odom::OdometryROS::imuProcessed_
bool imuProcessed_
Definition: OdometryROS.h:169
rtabmap_odom::OdometryROS::imus_
std::map< double, rtabmap::IMU > imus_
Definition: OdometryROS.h:170
rtabmap_odom::OdometryROS::groundTruthBaseFrameId_
std::string groundTruthBaseFrameId_
Definition: OdometryROS.h:111
rtabmap_odom::OdometryROS::statusDiagnostic_
OdomStatusTask statusDiagnostic_
Definition: OdometryROS.h:184
rtabmap_odom::OdometryROS::stereoParams_
bool stereoParams_
Definition: OdometryROS.h:156
ros::Publisher
rtabmap_odom::OdometryROS::resume
bool resume(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1154
rtabmap_odom::OdometryROS::odomPub_
ros::Publisher odomPub_
Definition: OdometryROS.h:123
rtabmap_odom::OdometryROS::visParams_
bool visParams_
Definition: OdometryROS.h:157
rtabmap_odom::OdometryROS::OdomStatusTask::run
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: OdometryROS.cpp:1205
rtabmap_odom::OdometryROS::odomInfoLitePub_
ros::Publisher odomInfoLitePub_
Definition: OdometryROS.h:125
rtabmap_odom::OdometryROS::waitIMUToinit_
bool waitIMUToinit_
Definition: OdometryROS.h:168
rtabmap_odom::OdometryROS::velocityGuess
rtabmap::Transform velocityGuess() const
Definition: OdometryROS.cpp:405
ros.h
rtabmap_odom::OdometryROS::odomSensorDataFeaturesPub_
ros::Publisher odomSensorDataFeaturesPub_
Definition: OdometryROS.h:131
rtabmap::Transform::getIdentity
static Transform getIdentity()
rtabmap_odom::OdometryROS::ulogToRosout_
rtabmap_util::ULogToRosout ulogToRosout_
Definition: OdometryROS.h:172
SyncDiagnostic.h
rtabmap_odom::OdometryROS::odomLocalMap_
ros::Publisher odomLocalMap_
Definition: OdometryROS.h:126
rtabmap_odom::OdometryROS::imuSub_
ros::Subscriber imuSub_
Definition: OdometryROS.h:143
rtabmap_odom::OdometryROS::maxUpdateRate_
double maxUpdateRate_
Definition: OdometryROS.h:163
rtabmap_odom::OdometryROS::previousStamp
double previousStamp() const
Definition: OdometryROS.h:90
rtabmap_odom::OdometryROS::initDiagnosticMsg
void initDiagnosticMsg(const std::string &subscribedTopicsMsg, bool approxSync, const std::string &subscribedTopic="")
Definition: OdometryROS.cpp:388
UThread.h
rtabmap_odom::OdometryROS::onInit
virtual void onInit()
Definition: OdometryROS.cpp:100
rtabmap_odom::OdometryROS::imuMutex_
UMutex imuMutex_
Definition: OdometryROS.h:146
rtabmap_odom::OdometryROS::OdomStatusTask::OdomStatusTask
OdomStatusTask()
Definition: OdometryROS.cpp:1193
rtabmap_odom::OdometryROS::tfListener_
tf::TransformListener tfListener_
Definition: OdometryROS.h:142
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
rtabmap_odom::OdometryROS::dataHeaderToProcess_
std_msgs::Header dataHeaderToProcess_
Definition: OdometryROS.h:150
rtabmap_odom::OdometryROS::publishNullWhenLost_
bool publishNullWhenLost_
Definition: OdometryROS.h:119
rtabmap_odom::OdometryROS::guessPreviousPose_
rtabmap::Transform guessPreviousPose_
Definition: OdometryROS.h:160
SensorData.h
rtabmap_odom::OdometryROS::callbackIMU
void callbackIMU(const sensor_msgs::ImuConstPtr &msg)
Definition: OdometryROS.cpp:414
data
data
transform_broadcaster.h
rtabmap_odom::OdometryROS::OdometryROS
OdometryROS(bool stereoParams, bool visParams, bool icpParams)
Definition: OdometryROS.cpp:60
diagnostic_updater.h
ros::ServiceServer
rtabmap_odom::OdometryROS::odomFrameId_
std::string odomFrameId_
Definition: OdometryROS.h:109
rtabmap_odom::OdometryROS::pause
bool pause(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1140
rtabmap_odom::OdometryROS::compressionImgFormat_
std::string compressionImgFormat_
Definition: OdometryROS.h:165
rtabmap_odom::OdometryROS::waitForTransform_
bool waitForTransform_
Definition: OdometryROS.h:117
rtabmap_odom::OdometryROS::OdomStatusTask
Definition: OdometryROS.h:174
rtabmap_odom::OdometryROS::parameters_
rtabmap::ParametersMap parameters_
Definition: OdometryROS.h:121
diagnostic_updater::DiagnosticTask
rtabmap_odom::OdometryROS::odomFrameId
const std::string & odomFrameId() const
Definition: OdometryROS.h:78
rtabmap_odom::OdometryROS::compressionParallelized_
bool compressionParallelized_
Definition: OdometryROS.h:166
rtabmap_odom::OdometryROS::guessMinTime_
double guessMinTime_
Definition: OdometryROS.h:115
rtabmap_odom::OdometryROS::flushCallbacks
virtual void flushCallbacks()=0
rtabmap_odom::OdometryROS::syncDiagnostic_
std::unique_ptr< rtabmap_sync::SyncDiagnostic > syncDiagnostic_
Definition: OdometryROS.h:185
rtabmap_odom::OdometryROS::odomSensorDataCompressedPub_
ros::Publisher odomSensorDataCompressedPub_
Definition: OdometryROS.h:132
UMutex
rtabmap_odom::OdometryROS::odomStrategy_
int odomStrategy_
Definition: OdometryROS.h:167
rtabmap_odom::OdometryROS::OdomStatusTask::lost_
bool lost_
Definition: OdometryROS.h:181
rtabmap_odom::OdometryROS::minUpdateRate_
double minUpdateRate_
Definition: OdometryROS.h:164
rtabmap_odom::OdometryROS::icpParams_
bool icpParams_
Definition: OdometryROS.h:158
rtabmap_odom::OdometryROS::odomSensorDataPub_
ros::Publisher odomSensorDataPub_
Definition: OdometryROS.h:130
rtabmap_odom::OdometryROS::resetSrv_
ros::ServiceServer resetSrv_
Definition: OdometryROS.h:133
rtabmap_odom::OdometryROS::expectedUpdateRate_
double expectedUpdateRate_
Definition: OdometryROS.h:162
rtabmap_odom::OdometryROS::mainLoop
virtual void mainLoop()
Definition: OdometryROS.cpp:488
rtabmap_odom::OdometryROS::waitForTransformDuration
double waitForTransformDuration() const
Definition: OdometryROS.h:88
rtabmap_odom::OdometryROS::dataReady_
USemaphore dataReady_
Definition: OdometryROS.h:148
rtabmap_odom::OdometryROS::resetCurrentCount_
int resetCurrentCount_
Definition: OdometryROS.h:155
rtabmap_odom::OdometryROS::setLogWarn
bool setLogWarn(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1180
rtabmap_odom::OdometryROS::parameters
const rtabmap::ParametersMap & parameters() const
Definition: OdometryROS.h:80
rtabmap_odom::OdometryROS::guessMinRotation_
double guessMinRotation_
Definition: OdometryROS.h:114
rtabmap_odom::OdometryROS
Definition: OdometryROS.h:59
rtabmap_odom::OdometryROS::setLogErrorSrv_
ros::ServiceServer setLogErrorSrv_
Definition: OdometryROS.h:140
rtabmap_odom::OdometryROS::~OdometryROS
virtual ~OdometryROS()
Definition: OdometryROS.cpp:94
transform_listener.h
rtabmap_odom::OdometryROS::paused_
bool paused_
Definition: OdometryROS.h:153
rtabmap::Transform
rtabmap_odom::OdometryROS::odomLastFrame_
ros::Publisher odomLastFrame_
Definition: OdometryROS.h:128
UThread
rtabmap_odom::OdometryROS::resetCountdown_
int resetCountdown_
Definition: OdometryROS.h:154
nodelet::Nodelet
rtabmap_odom::OdometryROS::guessFrameId
const std::string & guessFrameId() const
Definition: OdometryROS.h:79
rtabmap_odom::OdometryROS::odomInfoPub_
ros::Publisher odomInfoPub_
Definition: OdometryROS.h:124
nodelet.h
USemaphore
rtabmap_odom::OdometryROS::odomLocalScanMap_
ros::Publisher odomLocalScanMap_
Definition: OdometryROS.h:127
rtabmap_odom::OdometryROS::setLogInfo
bool setLogInfo(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1174
rtabmap_odom::OdometryROS::setLogError
bool setLogError(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1186
tf2_ros::TransformBroadcaster
rtabmap_odom::OdometryROS::publishTf_
bool publishTf_
Definition: OdometryROS.h:116
tf::TransformListener
rtabmap_odom::OdometryROS::guess_
rtabmap::Transform guess_
Definition: OdometryROS.h:159
rtabmap::Odometry
rtabmap_odom::OdometryROS::tfBroadcaster_
tf2_ros::TransformBroadcaster tfBroadcaster_
Definition: OdometryROS.h:141
diagnostic_updater::DiagnosticStatusWrapper
rtabmap_odom::OdometryROS::previousStamp_
double previousStamp_
Definition: OdometryROS.h:161
rtabmap_odom::OdometryROS::bufferedDataToProcess_
bool bufferedDataToProcess_
Definition: OdometryROS.h:151
rtabmap_odom::OdometryROS::tfListener
tf::TransformListener & tfListener()
Definition: OdometryROS.h:87
rtabmap_odom::OdometryROS::onOdomInit
virtual void onOdomInit()=0
rtabmap_odom::OdometryROS::OdomStatusTask::dataReceived_
bool dataReceived_
Definition: OdometryROS.h:182
Parameters.h
rtabmap_odom::OdometryROS::reset
bool reset(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1107
rtabmap_odom::OdometryROS::odomRgbdImagePub_
ros::Publisher odomRgbdImagePub_
Definition: OdometryROS.h:129
rtabmap_odom::OdometryROS::guessFrameId_
std::string guessFrameId_
Definition: OdometryROS.h:112
rtabmap_odom::OdometryROS::isPaused
bool isPaused() const
Definition: OdometryROS.h:81
rtabmap_odom::OdometryROS::setLogDebug
bool setLogDebug(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
Definition: OdometryROS.cpp:1168
rtabmap_util::ULogToRosout
rtabmap_odom::OdometryROS::pauseSrv_
ros::ServiceServer pauseSrv_
Definition: OdometryROS.h:135
header
const std::string header
rtabmap
rtabmap_odom::OdometryROS::postProcessData
virtual void postProcessData(const rtabmap::SensorData &data, const std_msgs::Header &header) const
Definition: OdometryROS.h:91
rtabmap_odom::OdometryROS::updateParameters
virtual void updateParameters(rtabmap::ParametersMap &parameters)
Definition: OdometryROS.h:96
rtabmap_odom::OdometryROS::setLogInfoSrv_
ros::ServiceServer setLogInfoSrv_
Definition: OdometryROS.h:138
rtabmap_odom::OdometryROS::setLogDebugSrv_
ros::ServiceServer setLogDebugSrv_
Definition: OdometryROS.h:137
rtabmap_odom::OdometryROS::frameId_
std::string frameId_
Definition: OdometryROS.h:108
ULogToRosout.h
rtabmap_odom::OdometryROS::groundTruthFrameId_
std::string groundTruthFrameId_
Definition: OdometryROS.h:110
rtabmap_odom::OdometryROS::waitForTransformDuration_
double waitForTransformDuration_
Definition: OdometryROS.h:118
ros::Subscriber
rtabmap_odom::OdometryROS::OdomStatusTask::setStatus
void setStatus(bool isLost)
Definition: OdometryROS.cpp:1199
rtabmap_odom::OdometryROS::resetToPoseSrv_
ros::ServiceServer resetToPoseSrv_
Definition: OdometryROS.h:134
rtabmap_odom::OdometryROS::resetToPose
bool resetToPose(rtabmap_msgs::ResetPose::Request &, rtabmap_msgs::ResetPose::Response &)
Definition: OdometryROS.cpp:1114
Odometry
GenericOdometry< Point2 > Odometry
rtabmap_odom::OdometryROS::setLogWarnSrv_
ros::ServiceServer setLogWarnSrv_
Definition: OdometryROS.h:139
rtabmap_odom::OdometryROS::mainLoopKill
virtual void mainLoopKill()
Definition: OdometryROS.cpp:482
rtabmap_odom::OdometryROS::frameId
const std::string & frameId() const
Definition: OdometryROS.h:77
rtabmap_odom::OdometryROS::dataToProcess_
rtabmap::SensorData dataToProcess_
Definition: OdometryROS.h:149
rtabmap_odom::OdometryROS::guessMinTranslation_
double guessMinTranslation_
Definition: OdometryROS.h:113


rtabmap_odom
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:42:24