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 static CRL_CONSTEXPR DataSource Source_Pps                    = (1<<26);
00135 
00142 class MULTISENSE_API DirectedStream {
00143 public:
00144 
00146     static CRL_CONSTEXPR uint16_t DFL_UDP_PORT = 10001;
00147 
00149     DataSource  mask;
00151     std::string address;
00153     uint16_t    udpPort;
00155     uint32_t    fpsDecimation;
00156 
00160     DirectedStream() {};
00161 
00174     DirectedStream(DataSource         m,
00175                    const std::string& addr,
00176                    uint16_t           p=DFL_UDP_PORT,
00177                    uint32_t           dec=1) :
00178         mask(m),
00179         address(addr),
00180         udpPort(p),
00181         fpsDecimation(dec) {};
00182 };
00183 
00184 /*
00185  * Trigger sources used to determine which input should be used to trigger
00186  * a frame capture on a device
00187  */
00188 typedef uint32_t TriggerSource;
00189 
00191 static CRL_CONSTEXPR TriggerSource Trigger_Internal    = 0;
00193 static CRL_CONSTEXPR TriggerSource Trigger_External    = 1;
00194 
00195 
00196 
00200 class MULTISENSE_API HeaderBase {
00201 public:
00206     virtual bool inMask(DataSource mask) { return true; };
00207     virtual ~HeaderBase() {};
00208 };
00209 
00210 namespace image {
00211 
00374 class MULTISENSE_API Header : public HeaderBase {
00375 public:
00376 
00378     DataSource  source;
00380     uint32_t    bitsPerPixel;
00382     uint32_t    width;
00384     uint32_t    height;
00386     int64_t     frameId;
00388     uint32_t    timeSeconds;
00390     uint32_t    timeMicroSeconds;
00391 
00393     uint32_t    exposure;
00395     float       gain;
00397     float       framesPerSecond;
00399     uint32_t    imageLength;
00401     const void *imageDataP;
00402 
00406     Header()
00407         : source(Source_Unknown) {};
00408 
00413     virtual bool inMask(DataSource mask) { return (mask & source) != 0;};
00414 };
00415 
00427 typedef void (*Callback)(const Header& header,
00428                          void         *userDataP);
00429 
00515 class MULTISENSE_API Config {
00516 public:
00517 
00518     //
00519     // User configurable member functions
00520 
00529     void setResolution        (uint32_t w,
00530                                uint32_t h) { m_width=w;m_height=h; };
00531 
00541     void setDisparities       (uint32_t d) { m_disparities=d;      };
00542 
00551     void setCamMode          (int m) { m_cam_mode=m; };
00552 
00561     void setOffset         (int o) { m_offset=o; };
00562 
00570     void setWidth             (uint32_t w) { m_width     = w;      };
00571 
00579     void setHeight            (uint32_t h) { m_height    = h;      };
00580 
00590     void setFps               (float f)    { m_fps       = f;      };
00591 
00598     void setGain              (float g)    { m_gain      = g; };
00599 
00607     void setExposure          (uint32_t e) { m_exposure  = e; };
00608 
00615     void setAutoExposure      (bool e)     { m_aeEnabled = e; };
00616 
00623     void setAutoExposureMax   (uint32_t m) { m_aeMax     = m; };
00624 
00631     void setAutoExposureDecay (uint32_t d) { m_aeDecay   = d; };
00632 
00640     void setAutoExposureThresh(float t)    { m_aeThresh  = t; };
00641 
00651     void setWhiteBalance            (float r,
00652                                      float b)    { m_wbRed=r;m_wbBlue=b; };
00653 
00660     void setAutoWhiteBalance        (bool e)     { m_wbEnabled   = e;    };
00661 
00668     void setAutoWhiteBalanceDecay   (uint32_t d) { m_wbDecay     = d;    };
00669 
00676     void setAutoWhiteBalanceThresh  (float t)    { m_wbThresh    = t;    };
00677 
00688     void setStereoPostFilterStrength(float s)    { m_spfStrength = s;    };
00689 
00700     void setHdr                     (bool  e)    { m_hdrEnabled  = e;    };
00701 
00702 
00703     //
00704     // Query
00705 
00711     uint32_t width       () const { return m_width;       };
00712 
00719     uint32_t height      () const { return m_height;      };
00720 
00728     uint32_t disparities () const { return m_disparities; };
00729 
00736     int camMode () const { return m_cam_mode; };
00737 
00744     int offset () const { return m_offset; };
00745 
00752     float    fps         () const { return m_fps;         };
00753 
00760     float    gain              () const { return m_gain;      };
00761 
00762 
00769     uint32_t exposure          () const { return m_exposure;  };
00770 
00777     bool     autoExposure      () const { return m_aeEnabled; };
00778 
00785     uint32_t autoExposureMax   () const { return m_aeMax;     };
00786 
00793     uint32_t autoExposureDecay () const { return m_aeDecay;   };
00794 
00801     float    autoExposureThresh() const { return m_aeThresh;  };
00802 
00809     float    whiteBalanceRed         () const { return m_wbRed;       };
00810 
00817     float    whiteBalanceBlue        () const { return m_wbBlue;      };
00818 
00825     bool     autoWhiteBalance        () const { return m_wbEnabled;   };
00826 
00833     uint32_t autoWhiteBalanceDecay   () const { return m_wbDecay;     };
00834 
00841     float    autoWhiteBalanceThresh  () const { return m_wbThresh;    };
00842 
00849     float    stereoPostFilterStrength() const { return m_spfStrength; };
00850 
00856     bool     hdrEnabled              () const { return m_hdrEnabled;  };
00857 
00858 
00859 
00860     //
00861     // Query camera calibration (read-only)
00862     //
00863     // These parameters are adjusted for the current operating resolution of the device.
00864 
00874     float fx()    const { return m_fx;    };
00875 
00885     float fy()    const { return m_fy;    };
00886 
00897     float cx()    const { return m_cx;    };
00898 
00909     float cy()    const { return m_cy;    };
00910 
00919     float tx()    const { return m_tx;    };
00920 
00930     float ty()    const { return m_ty;    };
00931 
00941     float tz()    const { return m_tz;    };
00942 
00951     float roll()  const { return m_roll;  };
00952 
00961     float pitch() const { return m_pitch; };
00962 
00971     float yaw()   const { return m_yaw;   };
00972 
00977     Config() : m_fps(5.0f), m_gain(1.0f),
00978                m_exposure(10000), m_aeEnabled(true), m_aeMax(5000000), m_aeDecay(7), m_aeThresh(0.75f),
00979                m_wbBlue(1.0f), m_wbRed(1.0f), m_wbEnabled(true), m_wbDecay(3), m_wbThresh(0.5f),
00980                m_width(1024), m_height(544), m_disparities(128), m_cam_mode(0), m_offset(-1), m_spfStrength(0.5f), m_hdrEnabled(false),
00981                m_fx(0), m_fy(0), m_cx(0), m_cy(0),
00982                m_tx(0), m_ty(0), m_tz(0), m_roll(0), m_pitch(0), m_yaw(0) {};
00983 private:
00984 
00985     float    m_fps, m_gain;
00986     uint32_t m_exposure;
00987     bool     m_aeEnabled;
00988     uint32_t m_aeMax;
00989     uint32_t m_aeDecay;
00990     float    m_aeThresh;
00991     float    m_wbBlue;
00992     float    m_wbRed;
00993     bool     m_wbEnabled;
00994     uint32_t m_wbDecay;
00995     float    m_wbThresh;
00996     uint32_t m_width, m_height;
00997     uint32_t m_disparities;
00998     int      m_cam_mode;
00999     int      m_offset;
01000     float    m_spfStrength;
01001     bool     m_hdrEnabled;
01002 
01003 protected:
01004 
01005     float    m_fx, m_fy, m_cx, m_cy;
01006     float    m_tx, m_ty, m_tz;
01007     float    m_roll, m_pitch, m_yaw;
01008 };
01009 
01092 class MULTISENSE_API Calibration {
01093 public:
01094 
01098     class MULTISENSE_API Data {
01099     public:
01100 
01102         float M[3][3];
01105         float D[8];
01107         float R[3][3];
01109         float P[3][4];
01110     };
01111 
01113     Data left;
01115     Data right;
01116 };
01117 
01199 class MULTISENSE_API SensorCalibration {
01200 public:
01201 
01204     uint8_t adc_gain[2];
01205 
01208     int16_t bl_offset[2];
01209 
01210 };
01211 
01212 class MULTISENSE_API TransmitDelay {
01213 public:
01214 
01216     int delay;
01217 
01218 };
01219 
01258 class MULTISENSE_API Histogram {
01259 public:
01260 
01264     Histogram() : channels(0),
01265                   bins(0),
01266                   data() {};
01269     uint32_t              channels;
01271     uint32_t              bins;
01274     std::vector<uint32_t> data;
01275 };
01276 
01277 }; // namespace image
01278 
01279 
01280 
01281 
01282 namespace lidar {
01283 
01285 typedef uint32_t RangeType;
01287 typedef uint32_t IntensityType;
01288 
01295 class MULTISENSE_API Header : public HeaderBase {
01296 public:
01297 
01301     Header()
01302         : pointCount(0) {};
01303 
01305     uint32_t scanId;
01307     uint32_t timeStartSeconds;
01309     uint32_t timeStartMicroSeconds;
01311     uint32_t timeEndSeconds;
01313     uint32_t timeEndMicroSeconds;
01315     int32_t  spindleAngleStart;
01317     int32_t  spindleAngleEnd;
01319     int32_t  scanArc;
01321     uint32_t maxRange;
01323     uint32_t pointCount;
01324 
01327     const RangeType     *rangesP;
01330     const IntensityType *intensitiesP;  // device units
01331 };
01332 
01342 typedef void (*Callback)(const Header& header,
01343                          void         *userDataP);
01344 
01425 class MULTISENSE_API Calibration {
01426 public:
01427 
01430     float laserToSpindle[4][4];
01433     float cameraToSpindleFixed[4][4];
01434 };
01435 
01436 }; // namespace lidar
01437 
01438 
01439 
01440 namespace lighting {
01441 
01442 
01444 static CRL_CONSTEXPR uint32_t MAX_LIGHTS     = 8;
01446 static CRL_CONSTEXPR float    MAX_DUTY_CYCLE = 100.0;
01448 static CRL_CONSTEXPR float    MAX_AMBIENT_LIGHTING = 100.0;
01449 
01535 class MULTISENSE_API Config {
01536 public:
01537 
01546     void setFlash(bool onOff) { m_flashEnabled = onOff; };
01547 
01554     bool getFlash()     const { return m_flashEnabled;  };
01555 
01564     bool setDutyCycle(float percent) {
01565         if (percent < 0.0 || percent > MAX_DUTY_CYCLE)
01566             return false;
01567 
01568         std::fill(m_dutyCycle.begin(),
01569                   m_dutyCycle.end(),
01570                   percent);
01571         return true;
01572     };
01573 
01585     bool setDutyCycle(uint32_t i,
01586                       float    percent) {
01587         if (i >= MAX_LIGHTS ||
01588             percent < 0.0 || percent > MAX_DUTY_CYCLE)
01589             return false;
01590 
01591         m_dutyCycle[i] = percent;
01592         return true;
01593     };
01594 
01604     float getDutyCycle(uint32_t i) const {
01605         if (i >= MAX_LIGHTS)
01606             return 0.0f;
01607         return m_dutyCycle[i];
01608     };
01609 
01614     Config() : m_flashEnabled(false), m_dutyCycle(MAX_LIGHTS, -1.0f) {};
01615 
01616 private:
01617 
01618     bool               m_flashEnabled;
01619     std::vector<float> m_dutyCycle;
01620 };
01621 
01658 class MULTISENSE_API SensorStatus {
01659 public:
01660 
01666     float ambientLightPercentage;
01667 
01668     SensorStatus() : ambientLightPercentage(100.0f) {};
01669 };
01670 
01671 }; // namespace lighting
01672 
01673 
01674 
01675 
01676 namespace pps {
01677 
01687 class MULTISENSE_API Header : public HeaderBase {
01688 public:
01689 
01691     int64_t sensorTime;
01692 
01694     uint32_t timeSeconds;
01696     uint32_t timeMicroSeconds;
01697 };
01698 
01702 typedef void (*Callback)(const Header& header,
01703                          void         *userDataP);
01704 
01705 }; // namespace pps
01706 
01707 
01708 
01709 namespace imu {
01710 
01715 class MULTISENSE_API Sample {
01716 public:
01717 
01719     typedef uint16_t Type;
01720 
01721     static CRL_CONSTEXPR Type Type_Accelerometer = 1;
01722     static CRL_CONSTEXPR Type Type_Gyroscope     = 2;
01723     static CRL_CONSTEXPR Type Type_Magnetometer  = 3;
01724 
01726     Type       type;
01728     uint32_t   timeSeconds;
01730     uint32_t   timeMicroSeconds;
01731 
01738     float x;
01739 
01746     float y;
01747 
01754     float z;
01755 
01762     double time() const {
01763         return (static_cast<double>(timeSeconds) +
01764                 1e-6 * static_cast<double>(timeMicroSeconds));
01765     };
01766 };
01767 
01776 class MULTISENSE_API Header : public HeaderBase {
01777 public:
01778 
01781     uint32_t            sequence;
01785     std::vector<Sample> samples;
01786 };
01787 
01791 typedef void (*Callback)(const Header& header,
01792                          void         *userDataP);
01793 
01839 class MULTISENSE_API Info {
01840 public:
01841 
01845     typedef struct {
01847         float sampleRate;
01849         float bandwidthCutoff;
01850     } RateEntry;
01851 
01855     typedef struct {
01858         float range;
01860         float resolution;
01861     } RangeEntry;
01862 
01864     std::string             name;
01866     std::string             device;
01868     std::string             units;
01870     std::vector<RateEntry>  rates;
01872     std::vector<RangeEntry> ranges;
01873 };
01874 
01971 class MULTISENSE_API Config {
01972 public:
01973 
01976     std::string name;
01978     bool        enabled;
01981     uint32_t    rateTableIndex;
01984     uint32_t    rangeTableIndex;
01985 };
01986 
01987 }; // namespace imu
01988 
01989 
01990 
01991 
01992 namespace system {
01993 
02018 class MULTISENSE_API DeviceMode {
02019 public:
02020 
02022     uint32_t   width;
02024     uint32_t   height;
02026     DataSource supportedDataSources;
02028     int32_t    disparities;
02029 
02041     DeviceMode(uint32_t   w=0,
02042                uint32_t   h=0,
02043                DataSource d=0,
02044                int32_t    s=-1) :
02045         width(w),
02046         height(h),
02047         supportedDataSources(d),
02048         disparities(s) {};
02049 };
02050 
02087 class MULTISENSE_API VersionInfo {
02088 public:
02089 
02091     std::string apiBuildDate;
02093     VersionType apiVersion;
02094 
02096     std::string sensorFirmwareBuildDate;
02098     VersionType sensorFirmwareVersion;
02099 
02101     uint64_t    sensorHardwareVersion;
02103     uint64_t    sensorHardwareMagic;
02105     uint64_t    sensorFpgaDna;
02106 
02110     VersionInfo() :
02111         apiVersion(0),
02112         sensorFirmwareVersion(0),
02113         sensorHardwareVersion(0),
02114         sensorHardwareMagic(0),
02115         sensorFpgaDna(0) {};
02116 };
02117 
02122 class MULTISENSE_API PcbInfo {
02123 public:
02124 
02126     std::string name;
02128     uint32_t    revision;
02129 
02133     PcbInfo() : revision(0) {};
02134 };
02135 
02173 class MULTISENSE_API DeviceInfo {
02174 public:
02175 
02177     static CRL_CONSTEXPR uint32_t MAX_PCBS                   = 8;
02178 
02179     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_SL    = 1;
02180     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7    = 2;
02181     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S     = HARDWARE_REV_MULTISENSE_S7; // alias for backward source compatibility
02182     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_M     = 3;
02183     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7S   = 4;
02184     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S21   = 5;
02185     static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_ST21  = 6;
02186     static CRL_CONSTEXPR uint32_t HARDWARE_REV_BCAM             = 100;
02187 
02188     static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_GREY   = 1;
02189     static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_COLOR  = 2;
02190     static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_GREY   = 3;
02191     static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_COLOR  = 4;
02192     static CRL_CONSTEXPR uint32_t IMAGER_TYPE_IMX104_COLOR   = 100;
02193 
02194     static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_NONE = 0;
02195     static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_SL_INTERNAL = 1;
02196     static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_S21_EXTERNAL = 2;
02197 
02199     std::string name;
02201     std::string buildDate;
02203     std::string serialNumber;
02205     uint32_t    hardwareRevision;
02206 
02208     std::vector<PcbInfo> pcbs;
02209 
02211     std::string imagerName;
02213     uint32_t    imagerType;
02215     uint32_t    imagerWidth;
02217     uint32_t    imagerHeight;
02218 
02220     std::string lensName;
02222     uint32_t    lensType;
02224     float       nominalBaseline;
02226     float       nominalFocalLength;
02228     float       nominalRelativeAperture;
02229 
02231     uint32_t    lightingType;
02233     uint32_t    numberOfLights;
02234 
02236     std::string laserName;
02238     uint32_t    laserType;
02239 
02241     std::string motorName;
02243     uint32_t    motorType;
02245     float       motorGearReduction;
02246 
02250     DeviceInfo() :
02251         hardwareRevision(0),
02252         imagerType(0),
02253         imagerWidth(0),
02254         imagerHeight(0),
02255         lensType(0),
02256         nominalBaseline(0.0),
02257         nominalFocalLength(0.0),
02258         nominalRelativeAperture(0.0),
02259         lightingType(0),
02260         numberOfLights(0),
02261         laserType(0),
02262         motorType(0),
02263         motorGearReduction(0.0) {};
02264 };
02265 
02333 class MULTISENSE_API NetworkConfig {
02334 public:
02335 
02337     std::string ipv4Address;
02339     std::string ipv4Gateway;
02341     std::string ipv4Netmask;
02342 
02346     NetworkConfig() :
02347         ipv4Address("10.66.171.21"),
02348         ipv4Gateway("10.66.171.1"),
02349         ipv4Netmask("255.255.240.0") {};
02350 
02360     NetworkConfig(const std::string& a,
02361                   const std::string& g,
02362                   const std::string& n) :
02363         ipv4Address(a),
02364         ipv4Gateway(g),
02365         ipv4Netmask(n) {};
02366 };
02367 
02404 class MULTISENSE_API StatusMessage {
02405     public:
02406 
02409         double uptime;
02410 
02413         bool systemOk;
02414 
02417         bool laserOk;
02418 
02421         bool laserMotorOk;
02422 
02425         bool camerasOk;
02426 
02429         bool imuOk;
02430 
02433         bool externalLedsOk;
02434 
02436         bool processingPipelineOk;
02437 
02440         float powerSupplyTemperature;
02441 
02443         float fpgaTemperature;
02444 
02446         float leftImagerTemperature;
02447 
02449         float rightImagerTemperature;
02450 
02452         float inputVoltage;
02453 
02456         float inputCurrent;
02457 
02459         float fpgaPower;
02460 
02462         float logicPower;
02463 
02465         float imagerPower;
02466 
02468         StatusMessage():
02469             uptime(0.),
02470             systemOk(false),
02471             laserOk(false),
02472             laserMotorOk(false),
02473             camerasOk(false),
02474             imuOk(false),
02475             externalLedsOk(false),
02476             processingPipelineOk(false),
02477             powerSupplyTemperature(0.),
02478             fpgaTemperature(0.),
02479             leftImagerTemperature(0.),
02480             rightImagerTemperature(0.),
02481             inputVoltage(0.),
02482             inputCurrent(0.),
02483             fpgaPower(0.),
02484             logicPower(0.),
02485             imagerPower(0.) {};
02486 };
02487 
02567 class MULTISENSE_API ExternalCalibration {
02568     public:
02569 
02571         float x;
02572 
02574         float y;
02575 
02577         float z;
02578 
02580         float roll;
02581 
02583         float pitch;
02584 
02586         float yaw;
02587 
02589         ExternalCalibration():
02590             x(0.),
02591             y(0.),
02592             z(0.),
02593             roll(0.),
02594             pitch(0.),
02595             yaw(0.) {};
02596 };
02597 
02598 }; // namespace system
02599 }; // namespace multisense
02600 }; // namespace crl
02601 
02602 #if defined (_MSC_VER)
02603 #pragma warning (pop)
02604 #endif
02605 
02606 #endif // LibMultiSense_MultiSenseTypes_hh


multisense_lib
Author(s):
autogenerated on Mon Oct 9 2017 03:06:21