Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef CAMERATANGO_H_
00029 #define CAMERATANGO_H_
00030
00031 #include <rtabmap/core/Camera.h>
00032 #include <rtabmap/core/GeodeticCoords.h>
00033 #include <rtabmap/utilite/UMutex.h>
00034 #include <rtabmap/utilite/USemaphore.h>
00035 #include <rtabmap/utilite/UEventsSender.h>
00036 #include <rtabmap/utilite/UThread.h>
00037 #include <rtabmap/utilite/UEvent.h>
00038 #include <rtabmap/utilite/UTimer.h>
00039 #include <boost/thread/mutex.hpp>
00040 #include <tango_support_api.h>
00041
00042 class TangoPoseData;
00043
00044 namespace rtabmap {
00045
00046 class PoseEvent: public UEvent
00047 {
00048 public:
00049 PoseEvent(const Transform & pose) : pose_(pose) {}
00050 virtual std::string getClassName() const {return "PoseEvent";}
00051 const Transform & pose() const {return pose_;}
00052
00053 private:
00054 Transform pose_;
00055 };
00056
00057 class CameraTangoEvent: public UEvent
00058 {
00059 public:
00060 CameraTangoEvent(int type, const std::string & key, const std::string & value) : type_(type), key_(key), value_(value) {}
00061 virtual std::string getClassName() const {return "CameraTangoEvent";}
00062 int type() const {return type_;}
00063 const std::string & key() const {return key_;}
00064 const std::string & value() const {return value_;}
00065
00066 private:
00067 int type_;
00068 std::string key_;
00069 std::string value_;
00070
00071 };
00072
00073 class CameraTango : public Camera, public UThread, public UEventsSender {
00074 public:
00075 static const float bilateralFilteringSigmaS;
00076 static const float bilateralFilteringSigmaR;
00077
00078 public:
00079 CameraTango(bool colorCamera, int decimation, bool publishRawScan, bool smoothing);
00080 virtual ~CameraTango();
00081
00082 virtual bool init(const std::string & calibrationFolder = ".", const std::string & cameraName = "");
00083 void close();
00084 void resetOrigin();
00085 virtual bool isCalibrated() const;
00086 virtual std::string getSerial() const;
00087 const CameraModel & getCameraModel() const {return model_;}
00088 rtabmap::Transform tangoPoseToTransform(const TangoPoseData * tangoPose) const;
00089 void setColorCamera(bool enabled) {if(!this->isRunning()) colorCamera_ = enabled;}
00090 void setDecimation(int value) {decimation_ = value;}
00091 void setSmoothing(bool enabled) {smoothing_ = enabled;}
00092 void setRawScanPublished(bool enabled) {rawScanPublished_ = enabled;}
00093 void setScreenRotation(TangoSupportRotation colorCameraToDisplayRotation) {colorCameraToDisplayRotation_ = colorCameraToDisplayRotation;}
00094 void setGPS(const GPS & gps);
00095
00096 void cloudReceived(const cv::Mat & cloud, double timestamp);
00097 void rgbReceived(const cv::Mat & tangoImage, int type, double timestamp);
00098 void poseReceived(const Transform & pose);
00099 void tangoEventReceived(int type, const char * key, const char * value);
00100
00101 protected:
00102 virtual SensorData captureImage(CameraInfo * info = 0);
00103
00104 private:
00105 rtabmap::Transform getPoseAtTimestamp(double timestamp);
00106
00107 virtual void mainLoopBegin();
00108 virtual void mainLoop();
00109
00110 private:
00111 void * tango_config_;
00112 Transform previousPose_;
00113 double previousStamp_;
00114 UTimer cameraStartedTime_;
00115 double stampEpochOffset_;
00116 bool colorCamera_;
00117 int decimation_;
00118 bool rawScanPublished_;
00119 bool smoothing_;
00120 cv::Mat cloud_;
00121 double cloudStamp_;
00122 cv::Mat tangoColor_;
00123 int tangoColorType_;
00124 double tangoColorStamp_;
00125 boost::mutex dataMutex_;
00126 USemaphore dataReady_;
00127 CameraModel model_;
00128 Transform deviceTColorCamera_;
00129 TangoSupportRotation colorCameraToDisplayRotation_;
00130 cv::Mat fisheyeRectifyMapX_;
00131 cv::Mat fisheyeRectifyMapY_;
00132 GPS lastKnownGPS_;
00133 Transform originOffset_;
00134 bool originUpdate_;
00135 };
00136
00137 }
00138 #endif