OdometryThread.cpp
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 #include <rtabmap/core/OdometryF2M.h>
00029 #include "rtabmap/core/OdometryThread.h"
00030 #include "rtabmap/core/Odometry.h"
00031 #include "rtabmap/core/OdometryMono.h"
00032 #include "rtabmap/core/OdometryInfo.h"
00033 #include "rtabmap/core/CameraEvent.h"
00034 #include "rtabmap/core/OdometryEvent.h"
00035 #include "rtabmap/utilite/ULogger.h"
00036 
00037 namespace rtabmap {
00038 
00039 OdometryThread::OdometryThread(Odometry * odometry, unsigned int dataBufferMaxSize) :
00040         _odometry(odometry),
00041         _dataBufferMaxSize(dataBufferMaxSize),
00042         _resetOdometry(false),
00043         _resetPose(Transform::getIdentity()),
00044         _lastImuStamp(0.0),
00045         _imuEstimatedDelay(0.0)
00046 {
00047         UASSERT(_odometry != 0);
00048 }
00049 
00050 OdometryThread::~OdometryThread()
00051 {
00052         this->unregisterFromEventsManager();
00053         this->join(true);
00054         delete _odometry;
00055         UDEBUG("");
00056 }
00057 
00058 bool OdometryThread::handleEvent(UEvent * event)
00059 {
00060         if(this->isRunning())
00061         {
00062                 if(event->getClassName().compare("CameraEvent") == 0)
00063                 {
00064                         CameraEvent * cameraEvent = (CameraEvent*)event;
00065                         if(cameraEvent->getCode() == CameraEvent::kCodeData)
00066                         {
00067                                 this->addData(cameraEvent->data());
00068                         }
00069                 }
00070                 else if(event->getClassName().compare("IMUEvent") == 0)
00071                 {
00072                         IMUEvent * imuEvent = (IMUEvent*)event;
00073                         if(!imuEvent->getData().empty())
00074                         {
00075                                 this->addData(SensorData(imuEvent->getData(), 0, imuEvent->getStamp()));
00076                         }
00077                 }
00078         }
00079         if(event->getClassName().compare("OdometryResetEvent") == 0)
00080         {
00081                 OdometryResetEvent * odomEvent = (OdometryResetEvent*)event;
00082                 _resetPose.setIdentity();
00083                 if(!odomEvent->getPose().isNull())
00084                 {
00085                         _resetPose = odomEvent->getPose();
00086                 }
00087                 _resetOdometry = true;
00088         }
00089         return false;
00090 }
00091 
00092 void OdometryThread::mainLoopBegin()
00093 {
00094         ULogger::registerCurrentThread("Odometry");
00095 }
00096 
00097 void OdometryThread::mainLoopKill()
00098 {
00099         _dataAdded.release();
00100 }
00101 
00102 //============================================================
00103 // MAIN LOOP
00104 //============================================================
00105 void OdometryThread::mainLoop()
00106 {
00107         if(_resetOdometry)
00108         {
00109                 _odometry->reset(_resetPose);
00110                 _resetOdometry = false;
00111         }
00112 
00113         SensorData data;
00114         if(getData(data))
00115         {
00116                 OdometryInfo info;
00117                 UDEBUG("Processing data...");
00118                 Transform pose = _odometry->process(data, &info);
00119                 if(!data.imageRaw().empty() || (pose.isNull() && data.imu().empty()))
00120                 {
00121                         UDEBUG("Odom pose = %s", pose.prettyPrint().c_str());
00122                         // a null pose notify that odometry could not be computed
00123                         this->post(new OdometryEvent(data, pose, info));
00124                 }
00125         }
00126 }
00127 
00128 void OdometryThread::addData(const SensorData & data)
00129 {
00130         if(data.imu().empty())
00131         {
00132                 if(dynamic_cast<OdometryMono*>(_odometry) == 0)
00133                 {
00134                         if(data.imageRaw().empty() || data.depthOrRightRaw().empty() || (data.cameraModels().size()==0 && !data.stereoCameraModel().isValidForProjection()))
00135                         {
00136                                 ULOGGER_ERROR("Missing some information (images empty or missing calibration)!?");
00137                                 return;
00138                         }
00139                 }
00140                 else
00141                 {
00142                         // Mono can accept RGB only
00143                         if(data.imageRaw().empty() || (data.cameraModels().size()==0 && !data.stereoCameraModel().isValidForProjection()))
00144                         {
00145                                 ULOGGER_ERROR("Missing some information (image empty or missing calibration)!?");
00146                                 return;
00147                         }
00148                 }
00149         }
00150 
00151         bool notify = true;
00152         _dataMutex.lock();
00153         {
00154                 if(data.imu().empty())
00155                 {
00156                         _dataBuffer.push_back(data);
00157                         while(_dataBufferMaxSize > 0 && _dataBuffer.size() > _dataBufferMaxSize)
00158                         {
00159                                 UDEBUG("Data buffer is full, the oldest data is removed to add the new one.");
00160                                 _dataBuffer.erase(_dataBuffer.begin());
00161                                 notify = false;
00162                         }
00163                         if(notify && _imuEstimatedDelay>0.0 && data.stamp() > (_lastImuStamp+_imuEstimatedDelay))
00164                         {
00165                                 // Don't notify if IMU data before this image has not been received yet
00166                                 notify = false;
00167                         }
00168                 }
00169                 else
00170                 {
00171                         _imuBuffer.push_back(data);
00172                         if(_lastImuStamp != 0.0 && data.stamp() > _lastImuStamp)
00173                         {
00174                                 _imuEstimatedDelay = data.stamp() - _lastImuStamp;
00175                         }
00176                         _lastImuStamp = data.stamp();
00177                 }
00178         }
00179         _dataMutex.unlock();
00180 
00181         if(notify)
00182         {
00183                 _dataAdded.release();
00184         }
00185 }
00186 
00187 bool OdometryThread::getData(SensorData & data)
00188 {
00189         bool dataFilled = false;
00190         _dataAdded.acquire();
00191         _dataMutex.lock();
00192         {
00193                 if(!_dataBuffer.empty() || !_imuBuffer.empty())
00194                 {
00195                         if(_dataBuffer.empty() ||
00196                                 (!_dataBuffer.empty() && !_imuBuffer.empty() && _imuBuffer.front().stamp() < _dataBuffer.front().stamp()))
00197                         {
00198                                 data = _imuBuffer.front();
00199                                 _imuBuffer.pop_front();
00200                         }
00201                         else
00202                         {
00203                                 data = _dataBuffer.front();
00204                                 _dataBuffer.pop_front();
00205                         }
00206                         dataFilled = true;
00207                 }
00208         }
00209         _dataMutex.unlock();
00210         return dataFilled;
00211 }
00212 
00213 } // namespace rtabmap


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:21