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 {
00044         UASSERT(_odometry != 0);
00045 }
00046 
00047 OdometryThread::~OdometryThread()
00048 {
00049         this->unregisterFromEventsManager();
00050         this->join(true);
00051         if(_odometry)
00052         {
00053                 delete _odometry;
00054         }
00055         UDEBUG("");
00056 }
00057 
00058 void 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("OdometryResetEvent") == 0)
00071                 {
00072                         _resetOdometry = true;
00073                 }
00074         }
00075 }
00076 
00077 void OdometryThread::mainLoopKill()
00078 {
00079         _dataAdded.release();
00080 }
00081 
00082 //============================================================
00083 // MAIN LOOP
00084 //============================================================
00085 void OdometryThread::mainLoop()
00086 {
00087         if(_resetOdometry)
00088         {
00089                 _odometry->reset();
00090                 _resetOdometry = false;
00091         }
00092 
00093         SensorData data;
00094         if(getData(data))
00095         {
00096                 OdometryInfo info;
00097                 Transform pose = _odometry->process(data, &info);
00098                 // a null pose notify that odometry could not be computed
00099                 double variance = info.variance>0?info.variance:1;
00100                 this->post(new OdometryEvent(data, pose, variance, variance, info));
00101         }
00102 }
00103 
00104 void OdometryThread::addData(const SensorData & data)
00105 {
00106         if(dynamic_cast<OdometryMono*>(_odometry) == 0 && dynamic_cast<OdometryF2M*>(_odometry) == 0)
00107         {
00108                 if(data.imageRaw().empty() || data.depthOrRightRaw().empty() || (data.cameraModels().size()==0 && !data.stereoCameraModel().isValidForProjection()))
00109                 {
00110                         ULOGGER_ERROR("Missing some information (images empty or missing calibration)!?");
00111                         return;
00112                 }
00113         }
00114         else
00115         {
00116                 // Mono and BOW can accept RGB only
00117                 if(data.imageRaw().empty() || (data.cameraModels().size()==0 && !data.stereoCameraModel().isValidForProjection()))
00118                 {
00119                         ULOGGER_ERROR("Missing some information (image empty or missing calibration)!?");
00120                         return;
00121                 }
00122         }
00123 
00124         bool notify = true;
00125         _dataMutex.lock();
00126         {
00127                 _dataBuffer.push_back(data);
00128                 while(_dataBufferMaxSize > 0 && _dataBuffer.size() > _dataBufferMaxSize)
00129                 {
00130                         UDEBUG("Data buffer is full, the oldest data is removed to add the new one.");
00131                         _dataBuffer.pop_front();
00132                         notify = false;
00133                 }
00134         }
00135         _dataMutex.unlock();
00136 
00137         if(notify)
00138         {
00139                 _dataAdded.release();
00140         }
00141 }
00142 
00143 bool OdometryThread::getData(SensorData & data)
00144 {
00145         bool dataFilled = false;
00146         _dataAdded.acquire();
00147         _dataMutex.lock();
00148         {
00149                 if(!_dataBuffer.empty())
00150                 {
00151                         data = _dataBuffer.front();
00152                         _dataBuffer.pop_front();
00153                         dataFilled = true;
00154                 }
00155         }
00156         _dataMutex.unlock();
00157         return dataFilled;
00158 }
00159 
00160 } // namespace rtabmap


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:17