OdometryThread.cpp
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 
29 #include "rtabmap/core/Odometry.h"
35 
36 namespace rtabmap {
37 
38 OdometryThread::OdometryThread(Odometry * odometry, unsigned int dataBufferMaxSize) :
39  _odometry(odometry),
40  _dataBufferMaxSize(dataBufferMaxSize),
41  _resetOdometry(false),
42  _resetPose(Transform::getIdentity()),
43  _lastImuStamp(0.0),
44  _imuEstimatedDelay(0.0)
45 {
46  UASSERT(_odometry != 0);
47 }
48 
50 {
52  this->join(true);
53  delete _odometry;
54  UDEBUG("");
55 }
56 
58 {
59  if(this->isRunning())
60  {
61  if(event->getClassName().compare("CameraEvent") == 0)
62  {
63  CameraEvent * cameraEvent = (CameraEvent*)event;
64  if(cameraEvent->getCode() == CameraEvent::kCodeData)
65  {
66  this->addData(cameraEvent->data());
67  }
68  }
69  else if(event->getClassName().compare("IMUEvent") == 0)
70  {
71  IMUEvent * imuEvent = (IMUEvent*)event;
72  if(!imuEvent->getData().empty())
73  {
74  this->addData(SensorData(imuEvent->getData(), 0, imuEvent->getStamp()));
75  }
76  }
77  }
78  if(event->getClassName().compare("OdometryResetEvent") == 0)
79  {
80  OdometryResetEvent * odomEvent = (OdometryResetEvent*)event;
82  if(!odomEvent->getPose().isNull())
83  {
84  _resetPose = odomEvent->getPose();
85  }
86  _resetOdometry = true;
87  }
88  return false;
89 }
90 
92 {
94 }
95 
97 {
99 }
100 
101 //============================================================
102 // MAIN LOOP
103 //============================================================
105 {
106  if(_resetOdometry)
107  {
109  _resetOdometry = false;
110  UScopeMutex lock(_dataMutex);
111  _dataBuffer.clear();
112  _imuBuffer.clear();
113  _lastImuStamp = 0.0f;
114  }
115 
117  if(getData(data))
118  {
119  OdometryInfo info;
120  UDEBUG("Processing data...");
121  Transform pose = _odometry->process(data, &info);
122  if(!data.imageRaw().empty() || !data.laserScanRaw().empty() || (pose.isNull() && data.imu().empty()))
123  {
124  UDEBUG("Odom pose = %s", pose.prettyPrint().c_str());
125  // a null pose notify that odometry could not be computed
126  this->post(new OdometryEvent(data, pose, info));
127  }
128  }
129 }
130 
132 {
133  if(data.imu().empty())
134  {
135  if(dynamic_cast<OdometryMono*>(_odometry) == 0)
136  {
137  if((data.imageRaw().empty() || data.depthOrRightRaw().empty() || (data.cameraModels().empty() && data.stereoCameraModels().empty())) &&
138  data.laserScanRaw().empty())
139  {
140  ULOGGER_ERROR("Missing some information (images/scans empty or missing calibration)!?");
141  return;
142  }
143  }
144  else
145  {
146  // Mono can accept RGB only
147  if(data.imageRaw().empty() || (data.cameraModels().empty() && data.stereoCameraModels().empty()))
148  {
149  ULOGGER_ERROR("Missing some information (image empty or missing calibration)!?");
150  return;
151  }
152  }
153  }
154 
155  bool notify = true;
156  _dataMutex.lock();
157  {
158  if(!data.imageRaw().empty() || !data.laserScanRaw().isEmpty() || data.imu().empty())
159  {
160  _dataBuffer.push_back(data);
161  while(_dataBufferMaxSize > 0 && _dataBuffer.size() > _dataBufferMaxSize)
162  {
163  UDEBUG("Data buffer is full, the oldest data is removed to add the new one.");
164  _dataBuffer.erase(_dataBuffer.begin());
165  notify = false;
166  }
167  }
168  else
169  {
170  _imuBuffer.push_back(data);
171  if(_lastImuStamp != 0.0 && data.stamp() > _lastImuStamp)
172  {
174  }
175  _lastImuStamp = data.stamp();
176  }
177  }
178  _dataMutex.unlock();
179 
180  if(notify)
181  {
183  }
184 }
185 
187 {
188  bool dataFilled = false;
190  _dataMutex.lock();
191  {
192  if(!_dataBuffer.empty())
193  {
194  if(!_imuBuffer.empty())
195  {
196  // Send IMU up to stamp greater than image (OpenVINS needs this).
197  while(!_imuBuffer.empty())
198  {
199  _odometry->process(_imuBuffer.front());
200  double stamp = _imuBuffer.front().stamp();
201  _imuBuffer.pop_front();
202  if(stamp > _dataBuffer.front().stamp())
203  {
204  break;
205  }
206  }
207  }
208 
209  data = _dataBuffer.front();
210  _dataBuffer.pop_front();
211  dataFilled = true;
212  }
213  }
214  _dataMutex.unlock();
215  return dataFilled;
216 }
217 
218 } // namespace rtabmap
void release(int n=1)
Definition: USemaphore.h:168
Definition: UEvent.h:57
virtual void reset(const Transform &initialPose=Transform::getIdentity())
Definition: Odometry.cpp:203
double getStamp() const
Definition: IMU.h:98
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:184
data
const std::vector< StereoCameraModel > & stereoCameraModels() const
Definition: SensorData.h:237
virtual void mainLoopBegin()
bool acquire(int n=1, int ms=0)
Definition: USemaphore.h:101
bool isEmpty() const
Definition: LaserScan.h:125
void post(UEvent *event, bool async=true) const
int getCode() const
Definition: UEvent.h:74
Transform process(SensorData &data, OdometryInfo *info=0)
Definition: Odometry.cpp:291
bool isRunning() const
Definition: UThread.cpp:245
virtual void mainLoopKill()
#define UASSERT(condition)
int lock() const
Definition: UMutex.h:87
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:236
std::list< SensorData > _dataBuffer
virtual std::string getClassName() const =0
const cv::Mat & imageRaw() const
Definition: SensorData.h:183
void addData(const SensorData &data)
static void registerCurrentThread(const std::string &name)
Definition: ULogger.cpp:218
std::string prettyPrint() const
Definition: Transform.cpp:316
int unlock() const
Definition: UMutex.h:113
bool empty() const
Definition: LaserScan.h:124
unsigned int _dataBufferMaxSize
bool isNull() const
Definition: Transform.cpp:107
#define false
Definition: ConvertUTF.c:56
const LaserScan & laserScanRaw() const
Definition: SensorData.h:185
#define UDEBUG(...)
bool empty() const
Definition: IMU.h:67
ULogger class and convenient macros.
double stamp() const
Definition: SensorData.h:176
bool getData(SensorData &data)
const Transform & getPose() const
void unregisterFromEventsManager()
void join(bool killFirst=false)
Definition: UThread.cpp:85
virtual bool handleEvent(UEvent *event)
const IMU & imu() const
Definition: SensorData.h:290
#define ULOGGER_ERROR(...)
Definition: ULogger.h:56
const IMU & getData() const
Definition: IMU.h:97
OdometryThread(Odometry *odometry, unsigned int dataBufferMaxSize=1)
std::list< SensorData > _imuBuffer
const SensorData & data() const
Definition: CameraEvent.h:79


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:29