MultiSenseTypes.hh
Go to the documentation of this file.
00001 
00037 #ifndef LibMultiSense_MultiSenseTypes_hh
00038 #define LibMultiSense_MultiSenseTypes_hh
00039 
00040 #include <stdint.h>
00041 
00042 #include <string>
00043 #include <vector>
00044 
00045 //
00046 // Add compatibility for C++ 11
00047 #if __cplusplus > 199711L
00048 // This compiler supports C++11.
00049 #define CRL_CONSTEXPR constexpr
00050 #else
00051 // This compiler does not support C++11.
00052 #define CRL_CONSTEXPR const
00053 #endif
00054 
00055 // Define MULTISENSE_API appropriately. This is needed to correctly link with
00056 // LibMultiSense when it is built as a DLL on Windows.
00057 #if !defined(MULTISENSE_API)
00058 #if defined (_MSC_VER)
00059 #if defined (MultiSense_EXPORTS)
00060 #define MULTISENSE_API __declspec(dllexport)
00061 #else
00062 #define MULTISENSE_API __declspec(dllimport)
00063 #endif
00064 #else
00065 #define MULTISENSE_API
00066 #endif
00067 #endif
00068 
00069 #if defined (_MSC_VER)
00070 /*
00071  * C4251 warns about exporting classes with members not marked as __declspec(export).
00072  * It is not easy to work around this without breaking the MultiSense API, but it
00073  * is safe to ignore this warning as long as the MultiSense DLL is compiled with the
00074  * same compiler version and STL version.
00075  */
00076 #pragma warning (push)
00077 #pragma warning (disable: 4251)
00078 #endif
00079 
00080 namespace crl {
00081 namespace multisense {
00082 
00083 
00087 typedef uint32_t VersionType;
00088 
00093 typedef int32_t  Status;
00094 
00095 //
00096 // General status codes
00097 
00098 static CRL_CONSTEXPR Status Status_Ok          =  0;
00099 static CRL_CONSTEXPR Status Status_TimedOut    = -1;
00100 static CRL_CONSTEXPR Status Status_Error       = -2;
00101 static CRL_CONSTEXPR Status Status_Failed      = -3;
00102 static CRL_CONSTEXPR Status Status_Unsupported = -4;
00103 static CRL_CONSTEXPR Status Status_Unknown     = -5;
00104 static CRL_CONSTEXPR Status Status_Exception   = -6;
00105 
00114 typedef uint32_t DataSource;
00115 
00116 static CRL_CONSTEXPR DataSource Source_Unknown                = 0;
00117 static CRL_CONSTEXPR DataSource Source_All                    = 0xffffffff;
00118 static CRL_CONSTEXPR DataSource Source_Raw_Left               = (1<<0);
00119 static CRL_CONSTEXPR DataSource Source_Raw_Right              = (1<<1);
00120 static CRL_CONSTEXPR DataSource Source_Luma_Left              = (1<<2);
00121 static CRL_CONSTEXPR DataSource Source_Luma_Right             = (1<<3);
00122 static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Left    = (1<<4);
00123 static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Right   = (1<<5);
00124 static CRL_CONSTEXPR DataSource Source_Chroma_Left            = (1<<6);
00125 static CRL_CONSTEXPR DataSource Source_Chroma_Right           = (1<<7);
00126 static CRL_CONSTEXPR DataSource Source_Disparity              = (1<<10);
00127 static CRL_CONSTEXPR DataSource Source_Disparity_Left         = (1<<10); // same as Source_Disparity
00128 static CRL_CONSTEXPR DataSource Source_Disparity_Right        = (1<<11);
00129 static CRL_CONSTEXPR DataSource Source_Disparity_Cost         = (1<<12);
00130 static CRL_CONSTEXPR DataSource Source_Jpeg_Left              = (1<<16);
00131 static CRL_CONSTEXPR DataSource Source_Rgb_Left               = (1<<17);
00132 static CRL_CONSTEXPR DataSource Source_Lidar_Scan             = (1<<24);
00133 static CRL_CONSTEXPR DataSource Source_Imu                    = (1<<25);
00134 
00141 class MULTISENSE_API DirectedStream {
00142 public:
00143 
00145     static CRL_CONSTEXPR uint16_t DFL_UDP_PORT = 10001;
00146 
00148     DataSource  mask;
00150     std::string address;
00152     uint16_t    udpPort;
00154     uint32_t    fpsDecimation;
00155 
00159     DirectedStream() {};
00160 
00173     DirectedStream(DataSource         m,
00174                    const std::string& addr,
00175                    uint16_t           p=DFL_UDP_PORT,
00176                    uint32_t           dec=1) :
00177         mask(m),
00178         address(addr),
00179         udpPort(p),
00180         fpsDecimation(dec) {};
00181 };
00182 
00183 /*
00184  * Trigger sources used to determine which input should be used to trigger
00185  * a frame capture on a device
00186  */
00187 typedef uint32_t TriggerSource;
00188 
00190 static CRL_CONSTEXPR TriggerSource Trigger_Internal    = 0;
00192 static CRL_CONSTEXPR TriggerSource Trigger_External    = 1;
00193 
00194 
00195 
00199 class MULTISENSE_API HeaderBase {
00200 public:
00205     virtual bool inMask(DataSource mask) { return true; };
00206     virtual ~HeaderBase() {};
00207 };
00208 
00209 namespace image {
00210 
00373 class MULTISENSE_API Header : public HeaderBase {
00374 public:
00375 
00377     DataSource  source;
00379     uint32_t    bitsPerPixel;
00381     uint32_t    width;
00383     uint32_t    height;
00385     int64_t     frameId;
00387     uint32_t    timeSeconds;
00389     uint32_t    timeMicroSeconds;
00390 
00392     uint32_t    exposure;
00394     float       gain;
00396     float       framesPerSecond;
00398     uint32_t    imageLength;
00400     const void *imageDataP;
00401 
00405     Header()
00406         : source(Source_Unknown) {};
00407 
00412     virtual bool inMask(DataSource mask) { return (mask & source) != 0;};
00413 };
00414 
00426 typedef void (*Callback)(const Header& header,
00427                          void         *userDataP);
00428 
00514 class MULTISENSE_API Config {
00515 public:
00516 
00517     //
00518     // User configurable member functions
00519 
00528     void setResolution        (uint32_t w,
00529                                uint32_t h) { m_width=w;m_height=h; };
00530 
00540     void setDisparities       (uint32_t d) { m_disparities=d;      };
00541 
00549     void setWidth             (uint32_t w) { m_width     = w;      };
00550 
00558     void setHeight            (uint32_t h) { m_height    = h;      };
00559 
00566     void setFps               (float f)    { m_fps       = f;      };
00567 
00574     void setGain              (float g)    { m_gain      = g; };
00575 
00583     void setExposure          (uint32_t e) { m_exposure  = e; };
00584 
00591     void setAutoExposure      (bool e)     { m_aeEnabled = e; };
00592 
00599     void setAutoExposureMax   (uint32_t m) { m_aeMax     = m; };
00600 
00607     void setAutoExposureDecay (uint32_t d) { m_aeDecay   = d; };
00608 
00616     void setAutoExposureThresh(float t)    { m_aeThresh  = t; };
00617 
00627     void setWhiteBalance            (float r,
00628                                      float b)    { m_wbRed=r;m_wbBlue=b; };
00629 
00636     void setAutoWhiteBalance        (bool e)     { m_wbEnabled   = e;    };
00637 
00644     void setAutoWhiteBalanceDecay   (uint32_t d) { m_wbDecay     = d;    };
00645 
00652     void setAutoWhiteBalanceThresh  (float t)    { m_wbThresh    = t;    };
00653 
00664     void setStereoPostFilterStrength(float s)    { m_spfStrength = s;    };
00665 
00676     void setHdr                     (bool  e)    { m_hdrEnabled  = e;    };
00677 
00678 
00679     //
00680     // Query
00681 
00687     uint32_t width       () const { return m_width;       };
00688 
00695     uint32_t height      () const { return m_height;      };
00696 
00704     uint32_t disparities () const { return m_disparities; };
00705 
00712     float    fps         () const { return m_fps;         };
00713 
00720     float    gain              () const { return m_gain;      };
00721 
00728     uint32_t exposure          () const { return m_exposure;  };
00729 
00736     bool     autoExposure      () const { return m_aeEnabled; };
00737 
00744     uint32_t autoExposureMax   () const { return m_aeMax;     };
00745 
00752     uint32_t autoExposureDecay () const { return m_aeDecay;   };
00753 
00760     float    autoExposureThresh() const { return m_aeThresh;  };
00761 
00768     float    whiteBalanceRed         () const { return m_wbRed;       };
00769 
00776     float    whiteBalanceBlue        () const { return m_wbBlue;      };
00777 
00784     bool     autoWhiteBalance        () const { return m_wbEnabled;   };
00785 
00792     uint32_t autoWhiteBalanceDecay   () const { return m_wbDecay;     };
00793 
00800     float    autoWhiteBalanceThresh  () const { return m_wbThresh;    };
00801 
00808     float    stereoPostFilterStrength() const { return m_spfStrength; };
00809 
00815     bool     hdrEnabled              () const { return m_hdrEnabled;  };
00816 
00817 
00818 
00819     //
00820     // Query camera calibration (read-only)
00821     //
00822     // These parameters are adjusted for the current operating resolution of the device.
00823 
00833     float fx()    const { return m_fx;    };
00834 
00844     float fy()    const { return m_fy;    };
00845 
00856     float cx()    const { return m_cx;    };
00857 
00868     float cy()    const { return m_cy;    };
00869 
00878     float tx()    const { return m_tx;    };
00879 
00889     float ty()    const { return m_ty;    };
00890 
00900     float tz()    const { return m_tz;    };
00901 
00910     float roll()  const { return m_roll;  };
00911 
00920     float pitch() const { return m_pitch; };
00921 
00930     float yaw()   const { return m_yaw;   };
00931 
00936     Config() : m_fps(5.0f), m_gain(1.0f),
00937                m_exposure(10000), m_aeEnabled(true), m_aeMax(5000000), m_aeDecay(7), m_aeThresh(0.75f),
00938                m_wbBlue(1.0f), m_wbRed(1.0f), m_wbEnabled(true), m_wbDecay(3), m_wbThresh(0.5f),
00939                m_width(1024), m_height(544), m_disparities(128), m_spfStrength(0.5f), m_hdrEnabled(false),
00940                m_fx(0), m_fy(0), m_cx(0), m_cy(0),
00941                m_tx(0), m_ty(0), m_tz(0), m_roll(0), m_pitch(0), m_yaw(0) {};
00942 private:
00943 
00944     float    m_fps, m_gain;
00945     uint32_t m_exposure;
00946     bool     m_aeEnabled;
00947     uint32_t m_aeMax;
00948     uint32_t m_aeDecay;
00949     float    m_aeThresh;
00950     float    m_wbBlue;
00951     float    m_wbRed;
00952     bool     m_wbEnabled;
00953     uint32_t m_wbDecay;
00954     float    m_wbThresh;
00955     uint32_t m_width, m_height;
00956     uint32_t m_disparities;
00957     float    m_spfStrength;
00958     bool     m_hdrEnabled;
00959 
00960 protected:
00961 
00962     float    m_fx, m_fy, m_cx, m_cy;
00963     float    m_tx, m_ty, m_tz;
00964     float    m_roll, m_pitch, m_yaw;
00965 };
00966 
01049 class MULTISENSE_API Calibration {
01050 public:
01051 
01055     class MULTISENSE_API Data {
01056     public:
01057 
01059         float M[3][3];
01062         float D[8];
01064         float R[3][3];
01066         float P[3][4];
01067     };
01068 
01070     Data left;
01072     Data right;
01073 };
01074 
01113 class MULTISENSE_API Histogram {
01114 public:
01115 
01119     Histogram() : channels(0),
01120                   bins(0),
01121                   data() {};
01124     uint32_t              channels;
01126     uint32_t              bins;
01129     std::vector<uint32_t> data;
01130 };
01131 
01132 }; // namespace image
01133 
01134 
01135 
01136 
01137 namespace lidar {
01138 
01140 typedef uint32_t RangeType;
01142 typedef uint32_t IntensityType;
01143 
01150 class MULTISENSE_API Header : public HeaderBase {
01151 public:
01152 
01156     Header()
01157         : pointCount(0) {};
01158 
01160     uint32_t scanId;
01162     uint32_t timeStartSeconds;
01164     uint32_t timeStartMicroSeconds;
01166     uint32_t timeEndSeconds;
01168     uint32_t timeEndMicroSeconds;
01170     int32_t  spindleAngleStart;
01172     int32_t  spindleAngleEnd;
01174     int32_t  scanArc;
01176     uint32_t maxRange;
01178     uint32_t pointCount;
01179 
01182     const RangeType     *rangesP;
01185     const IntensityType *intensitiesP;  // device units
01186 };
01187 
01197 typedef void (*Callback)(const Header& header,
01198                          void         *userDataP);
01199 
01280 class MULTISENSE_API Calibration {
01281 public:
01282 
01285     float laserToSpindle[4][4];
01288     float cameraToSpindleFixed[4][4];
01289 };
01290 
01291 }; // namespace lidar
01292 
01293 
01294 
01295 namespace lighting {
01296 
01297 
01299 static CRL_CONSTEXPR uint32_t MAX_LIGHTS     = 8;
01301 static CRL_CONSTEXPR float    MAX_DUTY_CYCLE = 100.0;
01302 
01388 class MULTISENSE_API Config {
01389 public:
01390 
01399     void setFlash(bool onOff) { m_flashEnabled = onOff; };
01400 
01407     bool getFlash()     const { return m_flashEnabled;  };
01408 
01417     bool setDutyCycle(float percent) {
01418         if (percent < 0.0 || percent > MAX_DUTY_CYCLE)
01419             return false;
01420 
01421         std::fill(m_dutyCycle.begin(),
01422                   m_dutyCycle.end(),
01423                   percent);
01424         return true;
01425     };
01426 
01438     bool setDutyCycle(uint32_t i,
01439                       float    percent) {
01440         if (i >= MAX_LIGHTS ||
01441             percent < 0.0 || percent > MAX_DUTY_CYCLE)
01442             return false;
01443 
01444         m_dutyCycle[i] = percent;
01445         return true;
01446     };
01447 
01457     float getDutyCycle(uint32_t i) const {
01458         if (i >= MAX_LIGHTS)
01459             return 0.0f;
01460         return m_dutyCycle[i];
01461     };
01462 
01467     Config() : m_flashEnabled(false), m_dutyCycle(MAX_LIGHTS, -1.0f) {};
01468 
01469 private:
01470 
01471     bool               m_flashEnabled;
01472     std::vector<float> m_dutyCycle;
01473 };
01474 
01475 }; // namespace lighting
01476 
01477 
01478 
01479 
01480 namespace pps {
01481 
01491 class MULTISENSE_API Header : public HeaderBase {
01492 public:
01493 
01495     int64_t sensorTime;
01496 
01498     uint32_t timeSeconds;
01500     uint32_t timeMicroSeconds;
01501 };
01502 
01506 typedef void (*Callback)(const Header& header,
01507                          void         *userDataP);
01508 
01509 }; // namespace pps
01510 
01511 
01512 
01513 namespace imu {
01514 
01519 class MULTISENSE_API Sample {
01520 public:
01521 
01523     typedef uint16_t Type;
01524 
01525     static CRL_CONSTEXPR Type Type_Accelerometer = 1;
01526     static CRL_CONSTEXPR Type Type_Gyroscope     = 2;
01527     static CRL_CONSTEXPR Type Type_Magnetometer  = 3;
01528 
01530     Type       type;
01532     uint32_t   timeSeconds;
01534     uint32_t   timeMicroSeconds;
01535 
01542     float x;
01543 
01550     float y;
01551 
01558     float z;
01559 
01566     double time() const {
01567         return (static_cast<double>(timeSeconds) +
01568                 1e-6 * static_cast<double>(timeMicroSeconds));
01569     };
01570 };
01571 
01580 class MULTISENSE_API Header : public HeaderBase {
01581 public:
01582 
01585     uint32_t            sequence;
01589     std::vector<Sample> samples;
01590 };
01591 
01595 typedef void (*Callback)(const Header& header,
01596                          void         *userDataP);
01597 
01643 class MULTISENSE_API Info {
01644 public:
01645 
01649     typedef struct {
01651         float sampleRate;
01653         float bandwidthCutoff;
01654     } RateEntry;
01655 
01659     typedef struct {
01662         float range;
01664         float resolution;
01665     } RangeEntry;
01666 
01668     std::string             name;
01670     std::string             device;
01672     std::string             units;
01674     std::vector<RateEntry>  rates;
01676     std::vector<RangeEntry> ranges;
01677 };
01678 
01775 class MULTISENSE_API Config {
01776 public:
01777 
01780     std::string name;
01782     bool        enabled;
01785     uint32_t    rateTableIndex;
01788     uint32_t    rangeTableIndex;
01789 };
01790 
01791 }; // namespace imu
01792 
01793 
01794 
01795 
01796 namespace system {
01797 
01822 class MULTISENSE_API DeviceMode {
01823 public:
01824 
01826     uint32_t   width;
01828     uint32_t   height;
01830     DataSource supportedDataSources;
01832     int32_t    disparities;
01833 
01845     DeviceMode(uint32_t   w=0,
01846                uint32_t   h=0,
01847                DataSource d=0,
01848                int32_t    s=-1) :
01849         width(w),
01850         height(h),
01851         supportedDataSources(d),
01852         disparities(s) {};
01853 };
01854 
01891 class MULTISENSE_API VersionInfo {
01892 public:
01893 
01895     std::string apiBuildDate;
01897     VersionType apiVersion;
01898 
01900     std::string sensorFirmwareBuildDate;
01902     VersionType sensorFirmwareVersion;
01903 
01905     uint64_t    sensorHardwareVersion;
01907     uint64_t    sensorHardwareMagic;
01909     uint64_t    sensorFpgaDna;
01910 
01914     VersionInfo() :
01915         apiVersion(0),
01916         sensorFirmwareVersion(0),
01917         sensorHardwareVersion(0),
01918         sensorHardwareMagic(0),
01919         sensorFpgaDna(0) {};
01920 };
01921 
01926 class MULTISENSE_API PcbInfo {
01927 public:
01928 
01930     std::string name;
01932     uint32_t    revision;
01933 
01937     PcbInfo() : revision(0) {};
01938 };
01939 
01977 class MULTISENSE_API DeviceInfo {
01978 public:
01979 
01981     static CRL_CONSTEXPR uint32_t MAX_PCBS                   = 8;
01982 
01983     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_SL    = 1;
01984     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7    = 2;
01985     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S     = HARDWARE_REV_MULTISENSE_S7; // alias for backward source compatibility
01986     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_M     = 3;
01987     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7S   = 4;
01988     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S21   = 5;
01989     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_ST21  = 6;
01990     static CRL_CONSTEXPR uint32_t HARDWARE_REV_BCAM             = 100;
01991 
01992     static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_GREY   = 1;
01993     static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_COLOR  = 2;
01994     static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_GREY   = 3;
01995     static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_COLOR  = 4;
01996     static CRL_CONSTEXPR uint32_t IMAGER_TYPE_IMX104_COLOR   = 100;
01997 
01999     std::string name;
02001     std::string buildDate;
02003     std::string serialNumber;
02005     uint32_t    hardwareRevision;
02006 
02008     std::vector<PcbInfo> pcbs;
02009 
02011     std::string imagerName;
02013     uint32_t    imagerType;
02015     uint32_t    imagerWidth;
02017     uint32_t    imagerHeight;
02018 
02020     std::string lensName;
02022     uint32_t    lensType;
02024     float       nominalBaseline;
02026     float       nominalFocalLength;
02028     float       nominalRelativeAperture;
02029 
02031     uint32_t    lightingType;
02033     uint32_t    numberOfLights;
02034 
02036     std::string laserName;
02038     uint32_t    laserType;
02039 
02041     std::string motorName;
02043     uint32_t    motorType;
02045     float       motorGearReduction;
02046 
02050     DeviceInfo() :
02051         hardwareRevision(0),
02052         imagerType(0),
02053         imagerWidth(0),
02054         imagerHeight(0),
02055         lensType(0),
02056         nominalBaseline(0.0),
02057         nominalFocalLength(0.0),
02058         nominalRelativeAperture(0.0),
02059         lightingType(0),
02060         numberOfLights(0),
02061         laserType(0),
02062         motorType(0),
02063         motorGearReduction(0.0) {};
02064 };
02065 
02133 class MULTISENSE_API NetworkConfig {
02134 public:
02135 
02137     std::string ipv4Address;
02139     std::string ipv4Gateway;
02141     std::string ipv4Netmask;
02142 
02146     NetworkConfig() :
02147         ipv4Address("10.66.171.21"),
02148         ipv4Gateway("10.66.171.1"),
02149         ipv4Netmask("255.255.240.0") {};
02150 
02160     NetworkConfig(const std::string& a,
02161                   const std::string& g,
02162                   const std::string& n) :
02163         ipv4Address(a),
02164         ipv4Gateway(g),
02165         ipv4Netmask(n) {};
02166 };
02167 
02168 }; // namespace system
02169 }; // namespace multisense
02170 }; // namespace crl
02171 
02172 #if defined (_MSC_VER)
02173 #pragma warning (pop)
02174 #endif
02175 
02176 #endif // LibMultiSense_MultiSenseTypes_hh


multisense_lib
Author(s):
autogenerated on Thu Aug 27 2015 14:01:11