CameraTango.h
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 #ifndef CAMERATANGO_H_
00029 #define CAMERATANGO_H_
00030 
00031 #include <rtabmap/core/Camera.h>
00032 #include <rtabmap/utilite/UMutex.h>
00033 #include <rtabmap/utilite/USemaphore.h>
00034 #include <rtabmap/utilite/UEventsSender.h>
00035 #include <rtabmap/utilite/UThread.h>
00036 #include <rtabmap/utilite/UEvent.h>
00037 #include <boost/thread/mutex.hpp>
00038 
00039 class TangoPoseData;
00040 
00041 namespace rtabmap {
00042 
00043 class PoseEvent: public UEvent
00044 {
00045 public:
00046         PoseEvent(const Transform & pose) : pose_(pose) {}
00047         virtual std::string getClassName() const {return "PoseEvent";}
00048         const Transform & pose() const {return pose_;}
00049 
00050 private:
00051         Transform pose_;
00052 };
00053 
00054 class CameraTangoEvent: public UEvent
00055 {
00056 public:
00057         CameraTangoEvent(int type, const std::string & key, const std::string & value) : type_(type), key_(key), value_(value) {}
00058         virtual std::string getClassName() const {return "CameraTangoEvent";}
00059         int type() const {return type_;}
00060         const std::string & key() const {return key_;}
00061         const std::string & value() const {return value_;}
00062 
00063 private:
00064         int type_;
00065         std::string key_;
00066         std::string value_;
00067 
00068 };
00069 
00070 class CameraTango : public Camera, public UThread, public UEventsSender {
00071 public:
00072         CameraTango(int decimation, bool autoExposure);
00073         virtual ~CameraTango();
00074 
00075         virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00076         void close(); // close Tango connection
00077         virtual bool isCalibrated() const;
00078         virtual std::string getSerial() const;
00079         rtabmap::Transform tangoPoseToTransform(const TangoPoseData * tangoPose, bool inOpenGLFrame) const;
00080         void setDecimation(int value) {decimation_ = value;}
00081         void setAutoExposure(bool enabled) {autoExposure_ = enabled;}
00082 
00083         void cloudReceived(const cv::Mat & cloud, double timestamp);
00084         void rgbReceived(const cv::Mat & tangoImage, int type, double timestamp);
00085         void poseReceived(const Transform & pose);
00086         void tangoEventReceived(int type, const char * key, const char * value);
00087 
00088 protected:
00089         virtual SensorData captureImage(CameraInfo * info = 0);
00090 
00091 private:
00092         rtabmap::Transform getPoseAtTimestamp(double timestamp, bool inOpenGLFrame);
00093 
00094         virtual void mainLoopBegin();
00095         virtual void mainLoop();
00096 
00097 private:
00098         void * tango_config_;
00099         bool firstFrame_;
00100         int decimation_;
00101         bool autoExposure_;
00102         cv::Mat cloud_;
00103         double cloudStamp_;
00104         cv::Mat tangoColor_;
00105         int tangoColorType_;
00106         double tangoColorStamp_;
00107         boost::mutex dataMutex_;
00108         USemaphore dataReady_;
00109         rtabmap::Transform imuTDevice_;
00110         rtabmap::Transform imuTDepthCamera_;
00111         rtabmap::Transform deviceTDepth_;
00112         CameraModel model_;
00113 };
00114 
00115 } /* namespace rtabmap */
00116 #endif /* CAMERATANGO_H_ */


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