LibMultiSense
LibMultiSense Documentation
MultiSenseTypes.hh
Go to the documentation of this file.
1 
37 #ifndef LibMultiSense_MultiSenseTypes_hh
38 #define LibMultiSense_MultiSenseTypes_hh
39 
40 #include <stdint.h>
41 
42 #include <string>
43 #include <vector>
44 
45 #if defined (CRL_HAVE_CONSTEXPR)
46 #define CRL_CONSTEXPR constexpr
47 #else
48 #define CRL_CONSTEXPR const
49 #endif
50 
51 // Define MULTISENSE_API appropriately. This is needed to correctly link with
52 // LibMultiSense when it is built as a DLL on Windows.
53 #if !defined(MULTISENSE_API)
54 #if defined (_MSC_VER)
55 #if defined (MultiSense_STATIC)
56 #define MULTISENSE_API __declspec(dllexport)
57 #elif defined (MultiSense_EXPORTS)
58 #define MULTISENSE_API __declspec(dllexport)
59 #else
60 #define MULTISENSE_API __declspec(dllimport)
61 #endif
62 
63 #else
64 #define MULTISENSE_API
65 #endif
66 
67 #endif
68 
69 #if defined (_MSC_VER)
70 /*
71  * C4251 warns about exporting classes with members not marked as __declspec(export).
72  * It is not easy to work around this without breaking the MultiSense API, but it
73  * is safe to ignore this warning as long as the MultiSense DLL is compiled with the
74  * same compiler version and STL version.
75  */
76 #pragma warning (push)
77 #pragma warning (disable: 4251)
78 #endif
79 
80 namespace crl {
81 namespace multisense {
82 
83 
87 typedef uint32_t VersionType;
88 
93 typedef int32_t Status;
94 
95 //
96 // General status codes
97 
105 
114 typedef uint32_t DataSource;
115 
117 static CRL_CONSTEXPR DataSource Source_All = 0xffffffff;
128 static CRL_CONSTEXPR DataSource Source_Disparity_Left = (1U<<10); // same as Source_Disparity
149 
158 
165 typedef uint32_t CameraProfile;
166 
188 
189 
194 typedef uint32_t ImageCompressionCodec;
195 
198 
206 public:
207 
209  static CRL_CONSTEXPR uint16_t DFL_UDP_PORT = 10001;
210 
214  std::string address;
216  uint16_t udpPort;
218  uint32_t fpsDecimation;
219 
224 
238  const std::string& addr,
239  uint16_t p=DFL_UDP_PORT,
240  uint32_t dec=1) :
241  mask(m),
242  address(addr),
243  udpPort(p),
244  fpsDecimation(dec) {};
245 };
246 
247 /*
248  * Trigger sources used to determine which input should be used to trigger
249  * a frame capture on a device
250  */
251 typedef uint32_t TriggerSource;
252 
261 
262 
263 
268 public:
273  virtual bool inMask(DataSource mask) { (void) mask; return true; };
274  virtual ~HeaderBase() {};
275 };
276 
277 namespace image {
278 
442 public:
443 
447  uint32_t bitsPerPixel;
449  uint32_t width;
451  uint32_t height;
453  int64_t frameId;
455  uint32_t timeSeconds;
458 
460  uint32_t exposure;
462  float gain;
466  uint32_t imageLength;
468  const void *imageDataP;
470  uint32_t headId;
475  : source(Source_Unknown) {};
476 
481  virtual bool inMask(DataSource mask) { return (mask & source) != 0;};
482 };
483 
495 typedef void (*Callback)(const Header& header,
496  void *userDataP);
497 
499 public:
501  m_exposure(10000), m_aeEnabled(true), m_aeMax(5000000), m_aeDecay(7), m_aeThresh(0.75f),
502  m_autoExposureRoiX(0), m_autoExposureRoiY(0),
503  m_autoExposureRoiWidth(Roi_Full_Image), m_autoExposureRoiHeight(Roi_Full_Image),
504  m_exposureSource(Exposure_Default_Source), m_aeTargetIntensity(Exposure_Default_Target_Intensity),
505  m_gain(Exposure_Default_Gain) {};
506 
514  void setExposure (uint32_t e) { m_exposure = e; };
515 
522  void setAutoExposure (bool e) { m_aeEnabled = e; };
523 
530  void setAutoExposureMax (uint32_t m) { m_aeMax = m; };
531 
538  void setAutoExposureDecay (uint32_t d) { m_aeDecay = d; };
539 
546  void setAutoExposureTargetIntensity (float d) { m_aeTargetIntensity = d; };
547 
555  void setAutoExposureThresh(float t) { m_aeThresh = t; };
556 
572  void setAutoExposureRoi(uint16_t start_x, uint16_t start_y, uint16_t width, uint16_t height)
573  {
574  m_autoExposureRoiX = start_x;
575  m_autoExposureRoiY = start_y;
576  m_autoExposureRoiWidth = width;
577  m_autoExposureRoiHeight = height;
578  }
579 
586  void setExposureSource(const DataSource &s) { m_exposureSource = s; };
587 
594  void setGain(const float &g) { m_gain = g; };
595 
596  //
597  // Query
598 
605  uint32_t exposure () const { return m_exposure; };
606 
613  bool autoExposure () const { return m_aeEnabled; };
614 
621  uint32_t autoExposureMax () const { return m_aeMax; };
622 
629  uint32_t autoExposureDecay () const { return m_aeDecay; };
630 
637  float autoExposureTargetIntensity () const { return m_aeTargetIntensity; };
638 
645  float autoExposureThresh() const { return m_aeThresh; };
646 
652  uint16_t autoExposureRoiX () const { return m_autoExposureRoiX; };
653 
659  uint16_t autoExposureRoiY () const { return m_autoExposureRoiY; };
660 
668  uint16_t autoExposureRoiWidth () const { return m_autoExposureRoiWidth; };
669 
677  uint16_t autoExposureRoiHeight () const { return m_autoExposureRoiHeight; };
678 
684  DataSource exposureSource() const { return m_exposureSource; };
685 
691  float gain() const { return m_gain; };
692 
693  private:
694  uint32_t m_exposure;
696  uint32_t m_aeMax;
697  uint32_t m_aeDecay;
698  float m_aeThresh;
699 
705 
707  float m_gain;
708 };
709 
796 public:
797 
798  //
799  // User configurable member functions
800 
809  void setResolution (uint32_t w,
810  uint32_t h) { m_width=w;m_height=h; };
811 
821  void setDisparities (uint32_t d) { m_disparities=d; };
822 
831  void setCamMode (int m) { m_cam_mode=m; };
832 
841  void setOffset (int o) { m_offset=o; };
842 
850  void setWidth (uint32_t w) { m_width = w; };
851 
859  void setHeight (uint32_t h) { m_height = h; };
860 
870  void setFps (float f) { m_fps = f; };
871 
878  void setGain (float g) { m_gain = g; };
879 
887  void setExposure (uint32_t e) { m_primary_exposure.setExposure(e); };
888 
895  void setAutoExposure (bool e) { m_primary_exposure.setAutoExposure(e); };
896 
903  void setAutoExposureMax (uint32_t m) { m_primary_exposure.setAutoExposureMax(m); };
904 
911  void setAutoExposureDecay (uint32_t d) { m_primary_exposure.setAutoExposureDecay(d); };
912 
919  void setAutoExposureTargetIntensity (float d) { m_primary_exposure.setAutoExposureTargetIntensity(d); };
920 
928  void setAutoExposureThresh(float t) { m_primary_exposure.setAutoExposureThresh(t); };
929 
939  void setWhiteBalance (float r,
940  float b) { m_wbRed=r;m_wbBlue=b; };
941 
948  void setAutoWhiteBalance (bool e) { m_wbEnabled = e; };
949 
956  void setAutoWhiteBalanceDecay (uint32_t d) { m_wbDecay = d; };
957 
964  void setAutoWhiteBalanceThresh (float t) { m_wbThresh = t; };
965 
976  void setStereoPostFilterStrength(float s) { m_spfStrength = s; };
977 
988  void setHdr (bool e) { m_hdrEnabled = e; };
989 
999  void setStoreSettingsInFlash (bool e) {m_storeSettingsInFlash = e; };
1000 
1016  void setAutoExposureRoi(uint16_t start_x, uint16_t start_y, uint16_t width, uint16_t height)
1017  {
1018  m_primary_exposure.setAutoExposureRoi(start_x, start_y, width, height);
1019  }
1020 
1027  void setExposureSource(const DataSource &s) { m_primary_exposure.setExposureSource(s); };
1028 
1034  void setCameraProfile(const CameraProfile &profile)
1035  {
1036  m_profile = profile;
1037  }
1038 
1044  void setPrimaryExposure (const ExposureConfig &c ) { m_primary_exposure = c; };
1045 
1055  void setSecondaryExposures(const std::vector<ExposureConfig> &c) { m_secondary_exposures = c; };
1056 
1065  void setGamma(const float g) { m_gamma = g; };
1066 
1067  //
1068  // Query
1069 
1075  uint32_t width () const { return m_width; };
1076 
1083  uint32_t height () const { return m_height; };
1084 
1092  uint32_t disparities () const { return m_disparities; };
1093 
1100  int camMode () const { return m_cam_mode; };
1101 
1108  int offset () const { return m_offset; };
1109 
1116  float fps () const { return m_fps; };
1117 
1124  float gain () const { return m_gain; };
1125 
1126 
1133  uint32_t exposure () const { return m_primary_exposure.exposure(); };
1134 
1141  bool autoExposure () const { return m_primary_exposure.autoExposure(); };
1142 
1149  uint32_t autoExposureMax () const { return m_primary_exposure.autoExposureMax(); };
1150 
1157  uint32_t autoExposureDecay () const { return m_primary_exposure.autoExposureDecay(); };
1158 
1165  float autoExposureTargetIntensity () const { return m_primary_exposure.autoExposureTargetIntensity(); };
1166 
1173  float autoExposureThresh() const { return m_primary_exposure.autoExposureThresh(); };
1174 
1181  float whiteBalanceRed () const { return m_wbRed; };
1182 
1189  float whiteBalanceBlue () const { return m_wbBlue; };
1190 
1197  bool autoWhiteBalance () const { return m_wbEnabled; };
1198 
1205  uint32_t autoWhiteBalanceDecay () const { return m_wbDecay; };
1206 
1213  float autoWhiteBalanceThresh () const { return m_wbThresh; };
1214 
1221  float stereoPostFilterStrength() const { return m_spfStrength; };
1222 
1228  bool hdrEnabled () const { return m_hdrEnabled; };
1229 
1235  bool storeSettingsInFlash () const { return m_storeSettingsInFlash; };
1236 
1242  uint16_t autoExposureRoiX () const { return m_primary_exposure.autoExposureRoiX(); };
1243 
1249  uint16_t autoExposureRoiY () const { return m_primary_exposure.autoExposureRoiY(); };
1250 
1258  uint16_t autoExposureRoiWidth () const { return m_primary_exposure.autoExposureRoiWidth(); };
1259 
1267  uint16_t autoExposureRoiHeight () const { return m_primary_exposure.autoExposureRoiHeight(); };
1268 
1274  DataSource exposureSource() const { return m_primary_exposure.exposureSource(); };
1275 
1281  CameraProfile cameraProfile () const { return m_profile; };
1282 
1288  ExposureConfig primaryExposure() const { return m_primary_exposure; };
1289 
1297  std::vector<ExposureConfig> secondaryExposures() const { return m_secondary_exposures; };
1298 
1305  float gamma() const { return m_gamma; };
1306 
1307  //
1308  // Query camera calibration (read-only)
1309  //
1310  // These parameters are adjusted for the current operating resolution of the device.
1311 
1321  float fx() const { return m_fx; };
1322 
1332  float fy() const { return m_fy; };
1333 
1344  float cx() const { return m_cx; };
1345 
1356  float cy() const { return m_cy; };
1357 
1366  float tx() const { return m_tx; };
1367 
1377  float ty() const { return m_ty; };
1378 
1388  float tz() const { return m_tz; };
1389 
1398  float roll() const { return m_roll; };
1399 
1408  float pitch() const { return m_pitch; };
1409 
1418  float yaw() const { return m_yaw; };
1419 
1424  Config() : m_fps(5.0f), m_gain(1.0f),
1425  m_primary_exposure(),
1426  m_wbBlue(1.0f), m_wbRed(1.0f), m_wbEnabled(true), m_wbDecay(3), m_wbThresh(0.5f),
1427  m_width(1024), m_height(544), m_disparities(128), m_cam_mode(0), m_offset(-1), m_spfStrength(0.5f),
1428  m_hdrEnabled(false), m_storeSettingsInFlash(false),
1429  m_profile(User_Control),
1430  m_secondary_exposures(),
1431  m_gamma(1.5),
1432  m_fx(0), m_fy(0), m_cx(0), m_cy(0),
1433  m_tx(0), m_ty(0), m_tz(0), m_roll(0), m_pitch(0), m_yaw(0) {};
1434 private:
1435 
1436  float m_fps, m_gain;
1438  float m_wbBlue;
1439  float m_wbRed;
1441  uint32_t m_wbDecay;
1442  float m_wbThresh;
1443  uint32_t m_width, m_height;
1444  uint32_t m_disparities;
1451  std::vector<ExposureConfig> m_secondary_exposures;
1452  float m_gamma;
1453 
1454 protected:
1455 
1456  float m_fx, m_fy, m_cx, m_cy;
1457  float m_tx, m_ty, m_tz;
1458  float m_roll, m_pitch, m_yaw;
1459 };
1460 
1544 public:
1545 
1550  public:
1551 
1553  float M[3][3];
1556  float D[8];
1558  float R[3][3];
1560  float P[3][4];
1561  };
1562 
1569 };
1570 
1653 public:
1654 
1657  uint8_t adc_gain[2];
1658 
1661  int16_t bl_offset[2];
1662 
1665  uint8_t vramp[2];
1666 
1667 };
1668 
1670 public:
1671 
1673  int delay;
1674 
1675 };
1676 
1716 public:
1717 
1721  Histogram() : channels(0),
1722  bins(0),
1723  data() {};
1726  uint32_t channels;
1728  uint32_t bins;
1731  std::vector<uint32_t> data;
1732 };
1733 
1734 } // namespace image
1735 
1736 
1737 
1738 
1739 namespace lidar {
1740 
1742 typedef uint32_t RangeType;
1744 typedef uint32_t IntensityType;
1745 
1753 public:
1754 
1759  : pointCount(0) {};
1760 
1762  uint32_t scanId;
1768  uint32_t timeEndSeconds;
1776  int32_t scanArc;
1778  uint32_t maxRange;
1780  uint32_t pointCount;
1781 
1787  const IntensityType *intensitiesP; // device units
1788 };
1789 
1799 typedef void (*Callback)(const Header& header,
1800  void *userDataP);
1801 
1883 public:
1884 
1887  float laserToSpindle[4][4];
1890  float cameraToSpindleFixed[4][4];
1891 };
1892 
1893 } // namespace lidar
1894 
1895 
1896 namespace lighting {
1897 
1899 static CRL_CONSTEXPR uint32_t MAX_LIGHTS = 8;
1901 static CRL_CONSTEXPR float MAX_DUTY_CYCLE = 100.0;
1902 
1989 public:
1990 
1999  void setFlash(bool onOff) { m_flashEnabled = onOff; };
2000 
2007  bool getFlash() const { return m_flashEnabled; };
2008 
2017  bool setDutyCycle(float percent) {
2018  if (percent < 0.0 || percent > MAX_DUTY_CYCLE)
2019  return false;
2020 
2021  std::fill(m_dutyCycle.begin(),
2022  m_dutyCycle.end(),
2023  percent);
2024  return true;
2025  };
2026 
2038  bool setDutyCycle(uint32_t i,
2039  float percent) {
2040  if (i >= MAX_LIGHTS ||
2041  percent < 0.0 || percent > MAX_DUTY_CYCLE)
2042  return false;
2043 
2044  m_dutyCycle[i] = percent;
2045  return true;
2046  };
2047 
2057  float getDutyCycle(uint32_t i) const {
2058  if (i >= MAX_LIGHTS)
2059  return 0.0f;
2060  return m_dutyCycle[i];
2061  };
2062 
2067  Config() : m_flashEnabled(false), m_dutyCycle(MAX_LIGHTS, -1.0f) {};
2068 
2069 private:
2070 
2071  bool m_flashEnabled;
2072  std::vector<float> m_dutyCycle;
2073 };
2074 
2112 public:
2113 
2120 
2121  SensorStatus() : ambientLightPercentage(100.0f) {};
2122 };
2123 
2124 } // namespace lighting
2125 
2126 
2127 
2128 
2129 namespace pps {
2130 
2141 public:
2142 
2144  int64_t sensorTime;
2145 
2147  uint32_t timeSeconds;
2150 };
2151 
2155 typedef void (*Callback)(const Header& header,
2156  void *userDataP);
2157 
2158 } // namespace pps
2159 
2160 
2161 namespace imu {
2162 
2168 public:
2169 
2171  typedef uint16_t Type;
2172 
2173  static CRL_CONSTEXPR Type Type_Accelerometer = 1;
2174  static CRL_CONSTEXPR Type Type_Gyroscope = 2;
2175  static CRL_CONSTEXPR Type Type_Magnetometer = 3;
2176 
2180  uint32_t timeSeconds;
2183 
2190  float x;
2191 
2198  float y;
2199 
2206  float z;
2207 
2214  double time() const {
2215  return (static_cast<double>(timeSeconds) +
2216  1e-6 * static_cast<double>(timeMicroSeconds));
2217  };
2218 };
2219 
2229 public:
2230 
2233  uint32_t sequence;
2237  std::vector<Sample> samples;
2238 };
2239 
2243 typedef void (*Callback)(const Header& header,
2244  void *userDataP);
2245 
2292 public:
2293 
2297  typedef struct {
2299  float sampleRate;
2302  } RateEntry;
2303 
2307  typedef struct {
2310  float range;
2312  float resolution;
2313  } RangeEntry;
2314 
2316  std::string name;
2318  std::string device;
2320  std::string units;
2322  std::vector<RateEntry> rates;
2324  std::vector<RangeEntry> ranges;
2325 };
2326 
2424 public:
2425 
2428  std::string name;
2430  bool enabled;
2433  uint32_t rateTableIndex;
2437 };
2438 
2439 } // namespace imu
2440 
2441 namespace compressed_image {
2442 
2444 public:
2445 
2449  uint32_t bitsPerPixel;
2453  uint32_t width;
2455  uint32_t height;
2457  int64_t frameId;
2459  uint32_t timeSeconds;
2462 
2464  uint32_t exposure;
2466  float gain;
2470  uint32_t imageLength;
2472  const void *imageDataP;
2474  uint32_t headId;
2479  : source(Source_Unknown) {};
2480 
2485  virtual bool inMask(DataSource mask) { return (mask & source) != 0;};
2486 };
2487 
2491 typedef void (*Callback)(const Header& header,
2492  void *userDataP);
2493 
2494 } // namespace compressed_image
2495 
2496 namespace ground_surface {
2497 
2504 public:
2506  int64_t frameId;
2508  int64_t timestamp;
2509 
2518 
2520  float xzCellOrigin[2];
2522  float xzCellSize[2];
2524  float xzLimit[2];
2526  float minMaxAzimuthAngle[2];
2527 
2530  float extrinsics[6];
2531 
2534  float quadraticParams[6];
2535 };
2536 
2540 typedef void (*Callback)(const Header& header,
2541  void *userDataP);
2542 
2543 } // namespace ground_surface
2544 
2545 namespace system {
2546 
2572 public:
2573 
2575  uint32_t width;
2577  uint32_t height;
2581  int32_t disparities;
2582 
2594  DeviceMode(uint32_t w=0,
2595  uint32_t h=0,
2596  DataSource d=0,
2597  int32_t s=-1) :
2598  width(w),
2599  height(h),
2600  supportedDataSources(d),
2601  disparities(s) {};
2602 };
2603 
2641 public:
2642 
2644  std::string apiBuildDate;
2647 
2652 
2658  uint64_t sensorFpgaDna;
2659 
2664  apiVersion(0),
2665  sensorFirmwareVersion(0),
2666  sensorHardwareVersion(0),
2667  sensorHardwareMagic(0),
2668  sensorFpgaDna(0) {};
2669 };
2670 
2676 public:
2677 
2679  std::string name;
2681  uint32_t revision;
2682 
2686  PcbInfo() : revision(0) {};
2687 };
2688 
2727 public:
2728 
2730  static CRL_CONSTEXPR uint8_t MAX_PCBS = 8;
2731 
2732  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_SL = 1;
2733  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7 = 2;
2734  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S = HARDWARE_REV_MULTISENSE_S7; // alias for backward source compatibility
2735  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_M = 3;
2736  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7S = 4;
2737  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S21 = 5;
2738  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_ST21 = 6;
2739  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_C6S2_S27 = 7;
2740  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S30 = 8;
2741  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7AR = 9;
2742  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_KS21 = 10;
2743  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_MONOCAM = 11;
2744  static CRL_CONSTEXPR uint32_t HARDWARE_REV_BCAM = 100;
2745  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MONO = 101;
2746 
2747  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_GREY = 1;
2748  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_COLOR = 2;
2749  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_GREY = 3;
2750  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_COLOR = 4;
2751  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_IMX104_COLOR = 100;
2752  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_AR0234_GREY = 200;
2753  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_AR0239_COLOR = 202;
2754 
2755  static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_NONE = 0;
2756  static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_SL_INTERNAL = 1;
2757  static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_S21_EXTERNAL = 2;
2758 
2760  std::string name;
2762  std::string buildDate;
2764  std::string serialNumber;
2767 
2769  std::vector<PcbInfo> pcbs;
2770 
2772  std::string imagerName;
2774  uint32_t imagerType;
2776  uint32_t imagerWidth;
2778  uint32_t imagerHeight;
2779 
2781  std::string lensName;
2783  uint32_t lensType;
2790 
2792  uint32_t lightingType;
2794  uint32_t numberOfLights;
2795 
2797  std::string laserName;
2799  uint32_t laserType;
2800 
2802  std::string motorName;
2804  uint32_t motorType;
2807 
2812  hardwareRevision(0),
2813  imagerType(0),
2814  imagerWidth(0),
2815  imagerHeight(0),
2816  lensType(0),
2817  nominalBaseline(0.0),
2818  nominalFocalLength(0.0),
2819  nominalRelativeAperture(0.0),
2820  lightingType(0),
2821  numberOfLights(0),
2822  laserType(0),
2823  motorType(0),
2824  motorGearReduction(0.0) {};
2825 };
2826 
2895 public:
2896 
2898  std::string ipv4Address;
2900  std::string ipv4Gateway;
2902  std::string ipv4Netmask;
2903 
2908  ipv4Address("10.66.171.21"),
2909  ipv4Gateway("10.66.171.1"),
2910  ipv4Netmask("255.255.240.0") {};
2911 
2921  NetworkConfig(const std::string& a,
2922  const std::string& g,
2923  const std::string& n) :
2924  ipv4Address(a),
2925  ipv4Gateway(g),
2926  ipv4Netmask(n) {};
2927 };
2928 
2966  public:
2967 
2970  double uptime;
2971 
2974  bool systemOk;
2975 
2978  bool laserOk;
2979 
2983 
2987 
2990  bool imuOk;
2991 
2995 
2998 
3002 
3005 
3008 
3011 
3014 
3018 
3020  float fpgaPower;
3021 
3023  float logicPower;
3024 
3027 
3030  uptime(0.),
3031  systemOk(false),
3032  laserOk(false),
3033  laserMotorOk(false),
3034  camerasOk(false),
3035  imuOk(false),
3036  externalLedsOk(false),
3037  processingPipelineOk(false),
3038  powerSupplyTemperature(0.),
3039  fpgaTemperature(0.),
3040  leftImagerTemperature(0.),
3041  rightImagerTemperature(0.),
3042  inputVoltage(0.),
3043  inputCurrent(0.),
3044  fpgaPower(0.),
3045  logicPower(0.),
3046  imagerPower(0.) {};
3047 };
3048 
3129  public:
3130 
3132  float x;
3133 
3135  float y;
3136 
3138  float z;
3139 
3141  float roll;
3142 
3144  float pitch;
3145 
3147  float yaw;
3148 
3151  x(0.),
3152  y(0.),
3153  z(0.),
3154  roll(0.),
3155  pitch(0.),
3156  yaw(0.) {};
3157 };
3158 
3163 };
3164 
3165 } // namespace system
3166 } // namespace multisense
3167 } // namespace crl
3168 
3169 #if defined (_MSC_VER)
3170 #pragma warning (pop)
3171 #endif
3172 
3173 #endif // LibMultiSense_MultiSenseTypes_hh
crl::multisense::Trigger_PTP
static CRL_CONSTEXPR TriggerSource Trigger_PTP
Syncronize cameras on integer timestamps when using PTP.
Definition: MultiSenseTypes.hh:260
crl::multisense::image::Config::ty
float ty() const
Query the current camera calibrations stereo baseline.
Definition: MultiSenseTypes.hh:1377
crl::multisense::Status_Failed
static CRL_CONSTEXPR Status Status_Failed
Definition: MultiSenseTypes.hh:101
crl::multisense::compressed_image::Header::exposure
uint32_t exposure
The image exposure time in microseconds.
Definition: MultiSenseTypes.hh:2464
crl::multisense::imu::Config
Class used to store a specific IMU configuration.
Definition: MultiSenseTypes.hh:2423
crl::multisense::imu::Config::enabled
bool enabled
A boolean flag indicating whether the given IMU source is currently enabled.
Definition: MultiSenseTypes.hh:2430
crl::multisense::image::ExposureConfig::m_autoExposureRoiY
uint16_t m_autoExposureRoiY
Definition: MultiSenseTypes.hh:701
crl::multisense::system::DeviceInfo::DeviceInfo
DeviceInfo()
Default constructor.
Definition: MultiSenseTypes.hh:2811
crl::multisense::image::Header::exposure
uint32_t exposure
The image exposure time in microseconds.
Definition: MultiSenseTypes.hh:460
crl::multisense::ground_surface::Header
Class containing Header information for a Ground Surface Spline callback.
Definition: MultiSenseTypes.hh:2503
crl::multisense::image::Config::setAutoExposureRoi
void setAutoExposureRoi(uint16_t start_x, uint16_t start_y, uint16_t width, uint16_t height)
Set the desired ROI to use when computing the auto-exposure.
Definition: MultiSenseTypes.hh:1016
crl::multisense::DirectedStream::address
std::string address
IPv4 Address dotted quad.
Definition: MultiSenseTypes.hh:214
crl::multisense::system::ExternalCalibration::y
float y
The external y translation of the MultiSense in meters.
Definition: MultiSenseTypes.hh:3135
crl::multisense::Status_Ok
static CRL_CONSTEXPR Status Status_Ok
Definition: MultiSenseTypes.hh:98
crl::multisense::Source_Compressed_Aux
static CRL_CONSTEXPR DataSource Source_Compressed_Aux
Definition: MultiSenseTypes.hh:145
crl::multisense::image::Config::autoWhiteBalanceDecay
uint32_t autoWhiteBalanceDecay() const
Query the current image configuration's white-balance decay rate.
Definition: MultiSenseTypes.hh:1205
crl::multisense::image::Config::whiteBalanceBlue
float whiteBalanceBlue() const
Query the current image configuration's blue white-balance setting.
Definition: MultiSenseTypes.hh:1189
crl::multisense::image::Config::m_wbBlue
float m_wbBlue
Definition: MultiSenseTypes.hh:1438
crl::multisense::system::PtpStatus
PTP status data associated with a specific stamped MultiSense message.
Definition: MultiSenseTypes.hh:3162
crl::multisense::system::DeviceInfo::motorType
uint32_t motorType
The type of the sensor's motor.
Definition: MultiSenseTypes.hh:2804
crl::multisense::system::StatusMessage::inputCurrent
float inputCurrent
The current drawn from the input power supply by the MultiSense.
Definition: MultiSenseTypes.hh:3017
crl::multisense::Source_Compressed_Rectified_Aux
static CRL_CONSTEXPR DataSource Source_Compressed_Rectified_Aux
Definition: MultiSenseTypes.hh:148
crl::multisense::image::ExposureConfig::autoExposureTargetIntensity
float autoExposureTargetIntensity() const
Query the current image configuration's auto-exposure target Intensity.
Definition: MultiSenseTypes.hh:637
crl::multisense::system::DeviceInfo::buildDate
std::string buildDate
The date the device was manufactured.
Definition: MultiSenseTypes.hh:2762
crl::multisense::Status_Error
static CRL_CONSTEXPR Status Status_Error
Definition: MultiSenseTypes.hh:100
crl::multisense::image::Header::gain
float gain
The imager gain the image was captured with.
Definition: MultiSenseTypes.hh:462
crl::multisense::image::TransmitDelay::delay
int delay
Delay between completing a frame and actually sending it over the network (in ms)
Definition: MultiSenseTypes.hh:1673
crl::multisense::image::Header::bitsPerPixel
uint32_t bitsPerPixel
Bits per pixel in the image.
Definition: MultiSenseTypes.hh:447
crl::multisense::image::ExposureConfig
Definition: MultiSenseTypes.hh:498
crl::multisense::image::Config::roll
float roll() const
Query the current camera calibrations roll value.
Definition: MultiSenseTypes.hh:1398
crl::multisense::image::Calibration
Class used For querying/setting camera calibration.
Definition: MultiSenseTypes.hh:1543
crl::multisense::Source_Luma_Rectified_Right
static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Right
Definition: MultiSenseTypes.hh:123
crl::multisense::image::ExposureConfig::setAutoExposureRoi
void setAutoExposureRoi(uint16_t start_x, uint16_t start_y, uint16_t width, uint16_t height)
Set the desired ROI to use when computing the auto-exposure.
Definition: MultiSenseTypes.hh:572
crl::multisense::image::Config::pitch
float pitch() const
Query the current camera calibrations pitch value.
Definition: MultiSenseTypes.hh:1408
crl::multisense::Source_Disparity_Aux
static CRL_CONSTEXPR DataSource Source_Disparity_Aux
Definition: MultiSenseTypes.hh:142
crl::multisense::image::Calibration::right
Data right
Full resolution camera calibration corresponding to the right camera.
Definition: MultiSenseTypes.hh:1566
crl::multisense::image::ExposureConfig::autoExposureDecay
uint32_t autoExposureDecay() const
Query the current image configuration's auto-exposure decay rate.
Definition: MultiSenseTypes.hh:629
crl::multisense::system::DeviceInfo::name
std::string name
The name of a given device.
Definition: MultiSenseTypes.hh:2760
crl::multisense::image::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks of image data.
Definition: MultiSenseTypes.hh:495
crl::multisense::compressed_image::Header::height
uint32_t height
Height of the image.
Definition: MultiSenseTypes.hh:2455
crl::multisense::image::ExposureConfig::m_gain
float m_gain
Definition: MultiSenseTypes.hh:707
crl::multisense::imu::Header::samples
std::vector< Sample > samples
A vector of samples from the sensor.
Definition: MultiSenseTypes.hh:2237
crl::multisense::image::Config::m_profile
CameraProfile m_profile
Definition: MultiSenseTypes.hh:1450
crl::multisense::Source_Raw_Aux
static CRL_CONSTEXPR DataSource Source_Raw_Aux
Definition: MultiSenseTypes.hh:138
crl::multisense::system::StatusMessage::StatusMessage
StatusMessage()
Default constructor for a single StatusMessage object.
Definition: MultiSenseTypes.hh:3029
crl::multisense::image::Config::setAutoWhiteBalanceDecay
void setAutoWhiteBalanceDecay(uint32_t d)
Set the white-balance decay rate.
Definition: MultiSenseTypes.hh:956
crl::multisense::VersionType
uint32_t VersionType
Sensor version typedef used to store a given version number.
Definition: MultiSenseTypes.hh:87
crl::multisense::compressed_image::Header
Definition: MultiSenseTypes.hh:2443
crl::multisense::lidar::Header::spindleAngleEnd
int32_t spindleAngleEnd
The spindle angle in microradians corresponding to the end of a laser scan.
Definition: MultiSenseTypes.hh:1774
crl::multisense::Source_Compressed_Left
static CRL_CONSTEXPR DataSource Source_Compressed_Left
Definition: MultiSenseTypes.hh:143
crl::multisense::image::Config::autoExposureDecay
uint32_t autoExposureDecay() const
Query the current image configuration's auto-exposure decay rate.
Definition: MultiSenseTypes.hh:1157
crl::multisense::image::Config::autoWhiteBalance
bool autoWhiteBalance() const
Query the current image configuration's white-balance enable setting.
Definition: MultiSenseTypes.hh:1197
crl::multisense::DataSource
uint32_t DataSource
Data sources typedef representing the various data sources available from sensors in the MultiSense-S...
Definition: MultiSenseTypes.hh:114
crl::multisense::imu::Info::ranges
std::vector< RangeEntry > ranges
The various ranges and resolutions available for a specific IMU source.
Definition: MultiSenseTypes.hh:2324
crl::multisense::ground_surface::Header::controlPointsBitsPerPixel
uint32_t controlPointsBitsPerPixel
Bits per pixel in the dynamically-sized control points array.
Definition: MultiSenseTypes.hh:2511
crl::multisense::image::ExposureConfig::exposureSource
DataSource exposureSource() const
Query the image source which the exposure parameters correspond with.
Definition: MultiSenseTypes.hh:684
crl::multisense::image::Config::exposure
uint32_t exposure() const
Query the current image configuration's exposure setting.
Definition: MultiSenseTypes.hh:1133
crl::multisense::image::Config::cameraProfile
CameraProfile cameraProfile() const
Query the current image configurations camera profile.
Definition: MultiSenseTypes.hh:1281
crl::multisense::HeaderBase::inMask
virtual bool inMask(DataSource mask)
This default implementation of the inMask member function will be overridden by derived classes.
Definition: MultiSenseTypes.hh:273
MULTISENSE_API
#define MULTISENSE_API
Definition: MultiSenseTypes.hh:64
crl::multisense::DirectedStream::DirectedStream
DirectedStream()
Default constructor.
Definition: MultiSenseTypes.hh:223
crl::multisense::ImageCompressionCodec
uint32_t ImageCompressionCodec
Image compression codec typedef indicating the compression scheme which was used on the compressed ou...
Definition: MultiSenseTypes.hh:194
crl::multisense::lidar::Header
Class which stores Header information for a lidar scan.
Definition: MultiSenseTypes.hh:1752
crl::multisense::image::Config::autoExposureRoiX
uint16_t autoExposureRoiX() const
Query the current image configuration's auto-exposure ROI X value.
Definition: MultiSenseTypes.hh:1242
crl::multisense::imu::Info::device
std::string device
The device name for a specific IMU source.
Definition: MultiSenseTypes.hh:2318
crl::multisense::Source_Compressed_Rectified_Right
static CRL_CONSTEXPR DataSource Source_Compressed_Rectified_Right
Definition: MultiSenseTypes.hh:147
crl::multisense::imu::Info::RangeEntry::resolution
float resolution
The resolution setting for a given IMU source.
Definition: MultiSenseTypes.hh:2312
crl::multisense::system::DeviceInfo::laserType
uint32_t laserType
The type of the sensor's laser.
Definition: MultiSenseTypes.hh:2799
crl::multisense::system::ExternalCalibration::pitch
float pitch
The external pitch translation of the MultiSense in degrees.
Definition: MultiSenseTypes.hh:3144
crl::multisense::image::Config::autoExposureRoiY
uint16_t autoExposureRoiY() const
Query the current image configuration's auto-exposure ROI Y value.
Definition: MultiSenseTypes.hh:1249
crl::multisense::Source_Luma_Left
static CRL_CONSTEXPR DataSource Source_Luma_Left
Definition: MultiSenseTypes.hh:120
crl::multisense::compressed_image::Header::bitsPerPixel
uint32_t bitsPerPixel
Bits per pixel in the image.
Definition: MultiSenseTypes.hh:2449
crl::multisense::image::Header::height
uint32_t height
Height of the image.
Definition: MultiSenseTypes.hh:451
crl::multisense::system::DeviceInfo::imagerHeight
uint32_t imagerHeight
The maximum height of the sensor's imager.
Definition: MultiSenseTypes.hh:2778
crl::multisense::image::Config::setAutoExposure
void setAutoExposure(bool e)
Set auto-exposure enable flag.
Definition: MultiSenseTypes.hh:895
crl::multisense::image::Config::setSecondaryExposures
void setSecondaryExposures(const std::vector< ExposureConfig > &c)
Set the secondary exposures configurations.
Definition: MultiSenseTypes.hh:1055
crl::multisense::lidar::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks of lidar data.
Definition: MultiSenseTypes.hh:1799
crl::multisense::Source_Imu
static CRL_CONSTEXPR DataSource Source_Imu
Definition: MultiSenseTypes.hh:136
crl::multisense::image::Config::Config
Config()
Default constructor for a image configuration.
Definition: MultiSenseTypes.hh:1424
crl::multisense::image::Config::m_cam_mode
int m_cam_mode
Definition: MultiSenseTypes.hh:1445
crl::multisense::image::Config::secondaryExposures
std::vector< ExposureConfig > secondaryExposures() const
Query the collection of secondary exposures.
Definition: MultiSenseTypes.hh:1297
crl::multisense::image::ExposureConfig::setAutoExposureMax
void setAutoExposureMax(uint32_t m)
Set the desired maximum auto-exposure value.
Definition: MultiSenseTypes.hh:530
crl::multisense::image::Config::m_fy
float m_fy
Definition: MultiSenseTypes.hh:1456
crl::multisense::image::Histogram::Histogram
Histogram()
Default constructor.
Definition: MultiSenseTypes.hh:1721
crl::multisense::system::DeviceInfo::pcbs
std::vector< PcbInfo > pcbs
The information for all the PCBs in the device.
Definition: MultiSenseTypes.hh:2769
crl::multisense::image::ExposureConfig::m_aeThresh
float m_aeThresh
Definition: MultiSenseTypes.hh:698
crl::multisense::system::NetworkConfig::ipv4Address
std::string ipv4Address
An Ipv4 address corresponding to a sensor.
Definition: MultiSenseTypes.hh:2898
crl::multisense::compressed_image::Header::headId
uint32_t headId
The active remote head if any.
Definition: MultiSenseTypes.hh:2474
crl::multisense::image::Calibration::aux
Data aux
Full resolution camera calibration corresponding to aux color camera.
Definition: MultiSenseTypes.hh:1568
crl::multisense::image::Config::setResolution
void setResolution(uint32_t w, uint32_t h)
Set a desired output resolution.
Definition: MultiSenseTypes.hh:809
crl::multisense::Source_Disparity
static CRL_CONSTEXPR DataSource Source_Disparity
Definition: MultiSenseTypes.hh:127
crl::multisense::image::Header::source
DataSource source
DataSource corresponding to imageDataP.
Definition: MultiSenseTypes.hh:445
crl::multisense::imu::Info::name
std::string name
The name of a specific IMU source.
Definition: MultiSenseTypes.hh:2316
crl::multisense::imu::Config::rateTableIndex
uint32_t rateTableIndex
The index into the rate table for a given IMU source specified in crl::multisense::imu::Info::rates.
Definition: MultiSenseTypes.hh:2433
crl::multisense::image::Config::storeSettingsInFlash
bool storeSettingsInFlash() const
Query the current image configuration's flag to write parameters to flash.
Definition: MultiSenseTypes.hh:1235
crl::multisense::system::DeviceInfo::lensType
uint32_t lensType
The type of the sensor's lens.
Definition: MultiSenseTypes.hh:2783
crl::multisense::lidar::Header::intensitiesP
const IntensityType * intensitiesP
Laser intensity values corresponding to each laser range point.
Definition: MultiSenseTypes.hh:1787
crl::multisense::compressed_image::Header::framesPerSecond
float framesPerSecond
The number of frames per second currently streaming from the device.
Definition: MultiSenseTypes.hh:2468
crl::multisense::image::Config::m_offset
int m_offset
Definition: MultiSenseTypes.hh:1446
crl::multisense::system::DeviceInfo::nominalFocalLength
float nominalFocalLength
The nominal focal length for the lens in meters.
Definition: MultiSenseTypes.hh:2787
crl::multisense::Full_Res_Aux_Cam
static CRL_CONSTEXPR CameraProfile Full_Res_Aux_Cam
User would like full resolution images from the aux camera regardless of the requested resolution of ...
Definition: MultiSenseTypes.hh:179
crl::multisense::image::Config::setAutoWhiteBalanceThresh
void setAutoWhiteBalanceThresh(float t)
Set the white-balance threshold.
Definition: MultiSenseTypes.hh:964
crl::multisense::image::Config::m_gain
float m_gain
Definition: MultiSenseTypes.hh:1436
crl::multisense::Detail_Disparity
static CRL_CONSTEXPR CameraProfile Detail_Disparity
User would like more detail in the disparity image.
Definition: MultiSenseTypes.hh:170
crl::multisense::lighting::Config::setDutyCycle
bool setDutyCycle(float percent)
Set a sensors duty cycle in terms of percent for all the on-board lights.
Definition: MultiSenseTypes.hh:2017
crl::multisense::system::DeviceInfo::laserName
std::string laserName
The name of the sensor's laser.
Definition: MultiSenseTypes.hh:2797
crl::multisense::system::VersionInfo::apiBuildDate
std::string apiBuildDate
The build date of libMultiSense.
Definition: MultiSenseTypes.hh:2644
crl::multisense::image::ExposureConfig::setAutoExposureTargetIntensity
void setAutoExposureTargetIntensity(float d)
Set the desired auto-exposure target Intensity .
Definition: MultiSenseTypes.hh:546
crl::multisense::system::DeviceInfo
Class used to store device information specific to a sensor.
Definition: MultiSenseTypes.hh:2726
crl::multisense::lighting::Config::setFlash
void setFlash(bool onOff)
Turn on/off light flashing.
Definition: MultiSenseTypes.hh:1999
crl::multisense::compressed_image::Header::gain
float gain
The imager gain the image was captured with.
Definition: MultiSenseTypes.hh:2466
crl::multisense::Source_Ground_Surface_Spline_Data
static CRL_CONSTEXPR DataSource Source_Ground_Surface_Spline_Data
Definition: MultiSenseTypes.hh:133
crl::multisense::system::NetworkConfig::NetworkConfig
NetworkConfig(const std::string &a, const std::string &g, const std::string &n)
Constructor to initialize the Ipv4 parameters.
Definition: MultiSenseTypes.hh:2921
crl::multisense::system::DeviceMode
Class used query the device modes for a given sensor.
Definition: MultiSenseTypes.hh:2571
crl::multisense::image::Histogram
Class which stores a image histogram from a camera image.
Definition: MultiSenseTypes.hh:1715
crl::multisense::image::Config::cy
float cy() const
Query the current camera calibrations left rectified image center in the y dimension.
Definition: MultiSenseTypes.hh:1356
crl::multisense::system::StatusMessage::fpgaTemperature
float fpgaTemperature
The temperature of the FPGA.
Definition: MultiSenseTypes.hh:3004
crl::multisense::image::Config::fps
float fps() const
Query the current image configuration's frames-per-second setting.
Definition: MultiSenseTypes.hh:1116
crl::multisense::Source_Chroma_Aux
static CRL_CONSTEXPR DataSource Source_Chroma_Aux
Definition: MultiSenseTypes.hh:141
crl::multisense::lidar::Header::Header
Header()
Default constructor.
Definition: MultiSenseTypes.hh:1758
crl::multisense::DirectedStream::mask
DataSource mask
The data source to stream to a given device.
Definition: MultiSenseTypes.hh:212
crl::multisense::imu::Info::RateEntry::sampleRate
float sampleRate
The sample rate of a given IMU source in Hz.
Definition: MultiSenseTypes.hh:2299
crl::multisense::system::StatusMessage::camerasOk
bool camerasOk
A boolean flag indicating if the imagers are functioning.
Definition: MultiSenseTypes.hh:2986
crl::multisense::imu::Sample::y
float y
y data for each sample
Definition: MultiSenseTypes.hh:2198
crl::multisense::system::ExternalCalibration::ExternalCalibration
ExternalCalibration()
Default constructor.
Definition: MultiSenseTypes.hh:3150
crl::multisense::system::VersionInfo::sensorFirmwareVersion
VersionType sensorFirmwareVersion
The version type of the sensor firmware.
Definition: MultiSenseTypes.hh:2651
crl::multisense::image::ExposureConfig::m_autoExposureRoiHeight
uint16_t m_autoExposureRoiHeight
Definition: MultiSenseTypes.hh:703
crl::multisense::image::Config::setAutoExposureMax
void setAutoExposureMax(uint32_t m)
Set the desired maximum auto-exposure value.
Definition: MultiSenseTypes.hh:903
crl::multisense::image::Config::autoExposureThresh
float autoExposureThresh() const
Query the current image configuration's auto-exposure threshold.
Definition: MultiSenseTypes.hh:1173
crl::multisense::Status_Unsupported
static CRL_CONSTEXPR Status Status_Unsupported
Definition: MultiSenseTypes.hh:102
crl::multisense::Source_Disparity_Right
static CRL_CONSTEXPR DataSource Source_Disparity_Right
Definition: MultiSenseTypes.hh:129
crl::multisense::image::Config::hdrEnabled
bool hdrEnabled() const
Query the current image configuration's HDR enable flag.
Definition: MultiSenseTypes.hh:1228
crl::multisense::image::Config::setWidth
void setWidth(uint32_t w)
Set the width of the desired output resolution.
Definition: MultiSenseTypes.hh:850
crl::multisense::Source_Chroma_Left
static CRL_CONSTEXPR DataSource Source_Chroma_Left
Definition: MultiSenseTypes.hh:124
crl::multisense::image::Config::setAutoExposureThresh
void setAutoExposureThresh(float t)
Set the desired auto-exposure threshold.
Definition: MultiSenseTypes.hh:928
crl::multisense::lighting::MAX_DUTY_CYCLE
static CRL_CONSTEXPR float MAX_DUTY_CYCLE
The maximum duty cycle for adjusting light intensity.
Definition: MultiSenseTypes.hh:1901
crl::multisense::image::Header::imageLength
uint32_t imageLength
The length of the image data stored in imageDataP.
Definition: MultiSenseTypes.hh:466
crl::multisense::system::StatusMessage::laserMotorOk
bool laserMotorOk
A boolean flag indicating if the laser motor controller is functioning.
Definition: MultiSenseTypes.hh:2982
crl::multisense::Active_Head_1
static CRL_CONSTEXPR CameraProfile Active_Head_1
User would like to set the active head to remote head 0.
Definition: MultiSenseTypes.hh:183
crl::multisense::system::StatusMessage::powerSupplyTemperature
float powerSupplyTemperature
The temperature of the internal switching mode power supply.
Definition: MultiSenseTypes.hh:3001
crl::multisense::pps::Header
Class containing Header information for a PPS event.
Definition: MultiSenseTypes.hh:2140
crl::multisense::lidar::Calibration
Class used to store a laser calibration.
Definition: MultiSenseTypes.hh:1882
crl::multisense::ground_surface::Header::frameId
int64_t frameId
Unique ID used to describe an image.
Definition: MultiSenseTypes.hh:2506
crl::multisense::image::ExposureConfig::setGain
void setGain(const float &g)
Set the gain applied to the camera.
Definition: MultiSenseTypes.hh:594
crl::multisense::system::DeviceInfo::imagerType
uint32_t imagerType
The type of the sensor's imager.
Definition: MultiSenseTypes.hh:2774
crl::multisense::Source_Compressed_Right
static CRL_CONSTEXPR DataSource Source_Compressed_Right
Definition: MultiSenseTypes.hh:144
crl::multisense::imu::Sample::x
float x
x data for each sample
Definition: MultiSenseTypes.hh:2190
crl::multisense::Exposure_Default_Source
static CRL_CONSTEXPR DataSource Exposure_Default_Source
Definition: MultiSenseTypes.hh:155
crl::multisense::Source_Compressed_Rectified_Left
static CRL_CONSTEXPR DataSource Source_Compressed_Rectified_Left
Definition: MultiSenseTypes.hh:146
crl
Definition: MultiSenseChannel.hh:46
crl::multisense::Status_Unknown
static CRL_CONSTEXPR Status Status_Unknown
Definition: MultiSenseTypes.hh:103
crl::multisense::image::Header::inMask
virtual bool inMask(DataSource mask)
Member function used to determine if the data contained in the header is contained in a specific imag...
Definition: MultiSenseTypes.hh:481
crl::multisense::system::VersionInfo::sensorFirmwareBuildDate
std::string sensorFirmwareBuildDate
The build date of the sensor firmware.
Definition: MultiSenseTypes.hh:2649
crl::multisense::image::Config::setPrimaryExposure
void setPrimaryExposure(const ExposureConfig &c)
Set the primary exposure configuration.
Definition: MultiSenseTypes.hh:1044
crl::multisense::system::StatusMessage::laserOk
bool laserOk
A boolean flag indicating if the laser is functioning.
Definition: MultiSenseTypes.hh:2978
crl::multisense::User_Control
static CRL_CONSTEXPR CameraProfile User_Control
User has direct control over all settings in the image configuration.
Definition: MultiSenseTypes.hh:168
crl::multisense::system::PcbInfo::PcbInfo
PcbInfo()
Default constructor.
Definition: MultiSenseTypes.hh:2686
crl::multisense::compressed_image::Header::width
uint32_t width
Width of the image.
Definition: MultiSenseTypes.hh:2453
crl::multisense::imu::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for IMU data.
Definition: MultiSenseTypes.hh:2243
crl::multisense::system::NetworkConfig::ipv4Netmask
std::string ipv4Netmask
An Ipv4 netmask corresponding to a sensor.
Definition: MultiSenseTypes.hh:2902
crl::multisense::ground_surface::Header::controlPointsHeight
uint32_t controlPointsHeight
Height of the dynamically-sized control points array.
Definition: MultiSenseTypes.hh:2515
crl::multisense::image::Header::headId
uint32_t headId
The active remote head if any.
Definition: MultiSenseTypes.hh:470
crl::multisense::image::Config::height
uint32_t height() const
Query the current image configuration's height.
Definition: MultiSenseTypes.hh:1083
crl::multisense::lighting::SensorStatus::ambientLightPercentage
float ambientLightPercentage
This represents the percentage of light the ambient sensor currently sees.
Definition: MultiSenseTypes.hh:2119
crl::multisense::Active_Head_0
static CRL_CONSTEXPR CameraProfile Active_Head_0
User would like to set the active head to remote head 0.
Definition: MultiSenseTypes.hh:181
crl::multisense::HeaderBase::~HeaderBase
virtual ~HeaderBase()
Definition: MultiSenseTypes.hh:274
crl::multisense::image::Config::gain
float gain() const
Query the current image configuration's gain setting.
Definition: MultiSenseTypes.hh:1124
crl::multisense::system::StatusMessage::rightImagerTemperature
float rightImagerTemperature
The temperature of the right imager.
Definition: MultiSenseTypes.hh:3010
crl::multisense::system::DeviceInfo::hardwareRevision
uint32_t hardwareRevision
The hardware revision of the given sensor.
Definition: MultiSenseTypes.hh:2766
crl::multisense::system::NetworkConfig::ipv4Gateway
std::string ipv4Gateway
An Ipv4 gateway corresponding to a sensor.
Definition: MultiSenseTypes.hh:2900
crl::multisense::Source_Pps
static CRL_CONSTEXPR DataSource Source_Pps
Definition: MultiSenseTypes.hh:137
crl::multisense::lighting::Config::setDutyCycle
bool setDutyCycle(uint32_t i, float percent)
Set a sensors duty cycle in terms of percent for a specific light based off its index.
Definition: MultiSenseTypes.hh:2038
crl::multisense::system::StatusMessage
Class containing status information for a particular device.
Definition: MultiSenseTypes.hh:2965
crl::multisense::imu::Header
Class containing Header information for an IMU callback.
Definition: MultiSenseTypes.hh:2228
crl::multisense::image::Config::cx
float cx() const
Query the current camera calibrations left rectified image center in the x dimension.
Definition: MultiSenseTypes.hh:1344
crl::multisense::HeaderBase
Base Header class for sensor callbacks.
Definition: MultiSenseTypes.hh:267
crl::multisense::system::ExternalCalibration::x
float x
The external x translation of the MultiSense in meters.
Definition: MultiSenseTypes.hh:3132
crl::multisense::lidar::IntensityType
uint32_t IntensityType
The type of a single laser intensity measurement
Definition: MultiSenseTypes.hh:1744
crl::multisense::image::Config::autoExposureMax
uint32_t autoExposureMax() const
Query the current image configuration's maximum auto-exposure value.
Definition: MultiSenseTypes.hh:1149
crl::multisense::image::Config::camMode
int camMode() const
Query the current image configuration's mode.
Definition: MultiSenseTypes.hh:1100
crl::multisense::system::DeviceInfo::motorName
std::string motorName
The name of the sensor's motor.
Definition: MultiSenseTypes.hh:2802
crl::multisense::image::ExposureConfig::autoExposureMax
uint32_t autoExposureMax() const
Query the current image configuration's maximum auto-exposure value.
Definition: MultiSenseTypes.hh:621
crl::multisense::system::DeviceInfo::imagerWidth
uint32_t imagerWidth
The maximum width of the sensor's imager.
Definition: MultiSenseTypes.hh:2776
crl::multisense::system::PcbInfo
Class used to store PCB information for the various circuit boards in a sensor.
Definition: MultiSenseTypes.hh:2675
crl::multisense::image::Config::autoExposureRoiHeight
uint16_t autoExposureRoiHeight() const
Query the current image configuration's auto-exposure ROI height value Will return crl::multisense::R...
Definition: MultiSenseTypes.hh:1267
crl::multisense::Show_ROIs
static CRL_CONSTEXPR CameraProfile Show_ROIs
User would like see the auto exposure Regions of Interest drawn on the image.
Definition: MultiSenseTypes.hh:174
crl::multisense::compressed_image::Header::Header
Header()
Default Constructor.
Definition: MultiSenseTypes.hh:2478
crl::multisense::image::ExposureConfig::m_aeMax
uint32_t m_aeMax
Definition: MultiSenseTypes.hh:696
crl::multisense::H264
static CRL_CONSTEXPR ImageCompressionCodec H264
Image data is compressed with the H.264 Codec.
Definition: MultiSenseTypes.hh:197
crl::multisense::Source_Raw_Right
static CRL_CONSTEXPR DataSource Source_Raw_Right
Definition: MultiSenseTypes.hh:119
crl::multisense::image::ExposureConfig::setAutoExposure
void setAutoExposure(bool e)
Set auto-exposure enable flag.
Definition: MultiSenseTypes.hh:522
crl::multisense::image::ExposureConfig::m_autoExposureRoiX
uint16_t m_autoExposureRoiX
Definition: MultiSenseTypes.hh:700
crl::multisense::image::Config::setExposure
void setExposure(uint32_t e)
Set the exposure time used to capture images.
Definition: MultiSenseTypes.hh:887
crl::multisense::Source_All
static CRL_CONSTEXPR DataSource Source_All
Definition: MultiSenseTypes.hh:117
crl::multisense::image::Config::m_spfStrength
float m_spfStrength
Definition: MultiSenseTypes.hh:1447
crl::multisense::compressed_image::Header::imageDataP
const void * imageDataP
A pointer to the compressed image data.
Definition: MultiSenseTypes.hh:2472
crl::multisense::system::StatusMessage::processingPipelineOk
bool processingPipelineOk
A boolean indicating if the processing pipeline is ok.
Definition: MultiSenseTypes.hh:2997
crl::multisense::image::Config::setStoreSettingsInFlash
void setStoreSettingsInFlash(bool e)
Set the flag to write the image configuration to flash.
Definition: MultiSenseTypes.hh:999
crl::multisense::Source_Ground_Surface_Class_Image
static CRL_CONSTEXPR DataSource Source_Ground_Surface_Class_Image
Definition: MultiSenseTypes.hh:134
crl::multisense::lighting::SensorStatus::SensorStatus
SensorStatus()
Definition: MultiSenseTypes.hh:2121
crl::multisense::image::Config::m_storeSettingsInFlash
bool m_storeSettingsInFlash
Definition: MultiSenseTypes.hh:1449
crl::multisense::imu::Sample::Type
uint16_t Type
Typedef used to determine which data source a sample came from.
Definition: MultiSenseTypes.hh:2171
crl::multisense::image::Config::autoWhiteBalanceThresh
float autoWhiteBalanceThresh() const
Query the current image configuration's white-balance threshold.
Definition: MultiSenseTypes.hh:1213
crl::multisense::system::VersionInfo::VersionInfo
VersionInfo()
Default constructor which initialize all values to 0.
Definition: MultiSenseTypes.hh:2663
crl::multisense::image::ExposureConfig::m_autoExposureRoiWidth
uint16_t m_autoExposureRoiWidth
Definition: MultiSenseTypes.hh:702
crl::multisense::Source_Lidar_Scan
static CRL_CONSTEXPR DataSource Source_Lidar_Scan
Definition: MultiSenseTypes.hh:135
crl::multisense::image::Config::setAutoExposureDecay
void setAutoExposureDecay(uint32_t d)
Set the desired auto-exposure decay rate.
Definition: MultiSenseTypes.hh:911
crl::multisense::image::Config::yaw
float yaw() const
Query the current camera calibrations yaw value.
Definition: MultiSenseTypes.hh:1418
crl::multisense::lidar::Header::maxRange
uint32_t maxRange
The maximum range of the laser scanner in millimeters.
Definition: MultiSenseTypes.hh:1778
crl::multisense::system::DeviceInfo::lightingType
uint32_t lightingType
The lighting type supported by the sensor.
Definition: MultiSenseTypes.hh:2792
crl::multisense::image::Header::Header
Header()
Default Constructor.
Definition: MultiSenseTypes.hh:474
crl::multisense::image::ExposureConfig::m_exposureSource
DataSource m_exposureSource
Definition: MultiSenseTypes.hh:704
crl::multisense::image::Histogram::bins
uint32_t bins
The number of possible pixel values for each color channel.
Definition: MultiSenseTypes.hh:1728
crl::multisense::image::Calibration::left
Data left
Full resolution camera calibration corresponding to the left camera.
Definition: MultiSenseTypes.hh:1564
crl::multisense::Source_Luma_Right
static CRL_CONSTEXPR DataSource Source_Luma_Right
Definition: MultiSenseTypes.hh:121
crl::multisense::system::DeviceMode::supportedDataSources
DataSource supportedDataSources
A listing of all the data sources available for a specific device mode.
Definition: MultiSenseTypes.hh:2579
crl::multisense::system::DeviceMode::DeviceMode
DeviceMode(uint32_t w=0, uint32_t h=0, DataSource d=0, int32_t s=-1)
Constructor.
Definition: MultiSenseTypes.hh:2594
crl::multisense::image::ExposureConfig::setExposureSource
void setExposureSource(const DataSource &s)
Set the stream source which these exposure parameters should apply to.
Definition: MultiSenseTypes.hh:586
crl::multisense::Source_Luma_Aux
static CRL_CONSTEXPR DataSource Source_Luma_Aux
Definition: MultiSenseTypes.hh:139
crl::multisense::system::DeviceMode::disparities
int32_t disparities
The number of valid disparities for a given device mode.
Definition: MultiSenseTypes.hh:2581
crl::multisense::image::Config::m_gamma
float m_gamma
Definition: MultiSenseTypes.hh:1452
crl::multisense::image::Config::m_width
uint32_t m_width
Definition: MultiSenseTypes.hh:1443
crl::multisense::Source_Raw_Left
static CRL_CONSTEXPR DataSource Source_Raw_Left
Definition: MultiSenseTypes.hh:118
crl::multisense::ground_surface::Header::controlPointsWidth
uint32_t controlPointsWidth
Width of the dynamically-sized control points array.
Definition: MultiSenseTypes.hh:2513
crl::multisense::image::Config::primaryExposure
ExposureConfig primaryExposure() const
Query the primary exposure config.
Definition: MultiSenseTypes.hh:1288
crl::multisense::lidar::Header::scanArc
int32_t scanArc
The total angular range of a individual laser scan in microradians.
Definition: MultiSenseTypes.hh:1776
crl::multisense::Trigger_Internal
static CRL_CONSTEXPR TriggerSource Trigger_Internal
Default internal trigger source.
Definition: MultiSenseTypes.hh:254
crl::multisense::image::Config::disparities
uint32_t disparities() const
Query the current image configuration's number of disparities.
Definition: MultiSenseTypes.hh:1092
crl::multisense::imu::Info::RangeEntry
Class containing a one valid IMU range configuration.
Definition: MultiSenseTypes.hh:2307
crl::multisense::system::DeviceInfo::serialNumber
std::string serialNumber
The serial number of the device.
Definition: MultiSenseTypes.hh:2764
crl::multisense::lighting::Config
Class used to store a specific lighting configuration.
Definition: MultiSenseTypes.hh:1988
crl::multisense::image::ExposureConfig::m_aeTargetIntensity
float m_aeTargetIntensity
Definition: MultiSenseTypes.hh:706
crl::multisense::system::DeviceInfo::nominalBaseline
float nominalBaseline
The nominal sensor baseline in meters.
Definition: MultiSenseTypes.hh:2785
crl::multisense::ground_surface::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for Ground Surface Spline data.
Definition: MultiSenseTypes.hh:2540
crl::multisense::image::Header::width
uint32_t width
Width of the image.
Definition: MultiSenseTypes.hh:449
crl::multisense::image::Config::m_disparities
uint32_t m_disparities
Definition: MultiSenseTypes.hh:1444
crl::multisense::imu::Config::rangeTableIndex
uint32_t rangeTableIndex
The index into the range table for a given IMU source specified in crl::multisense::imu::Info::ranges...
Definition: MultiSenseTypes.hh:2436
crl::multisense::imu::Info::RateEntry
Class containing a one valid IMU rate configuration.
Definition: MultiSenseTypes.hh:2297
crl::multisense::image::Config::setWhiteBalance
void setWhiteBalance(float r, float b)
Set the desired image white-balance.
Definition: MultiSenseTypes.hh:939
crl::multisense::image::Config::fx
float fx() const
Query the current camera calibrations rectified projection focal length in the x dimension.
Definition: MultiSenseTypes.hh:1321
crl::multisense::Source_Disparity_Left
static CRL_CONSTEXPR DataSource Source_Disparity_Left
Definition: MultiSenseTypes.hh:128
crl::multisense::image::Header::framesPerSecond
float framesPerSecond
The number of frames per second currently streaming from the device.
Definition: MultiSenseTypes.hh:464
crl::multisense::lidar::Header::spindleAngleStart
int32_t spindleAngleStart
The spindle angle in microradians corresponding to the start of a laser scan.
Definition: MultiSenseTypes.hh:1772
crl::multisense::Source_Disparity_Cost
static CRL_CONSTEXPR DataSource Source_Disparity_Cost
Definition: MultiSenseTypes.hh:130
crl::multisense::image::ExposureConfig::autoExposure
bool autoExposure() const
Query the current image configuration's auto-exposure enable setting.
Definition: MultiSenseTypes.hh:613
crl::multisense::image::ExposureConfig::exposure
uint32_t exposure() const
Query the current image configuration's exposure setting.
Definition: MultiSenseTypes.hh:605
crl::multisense::system::ExternalCalibration
A external calibration associated with the MultiSense.
Definition: MultiSenseTypes.hh:3128
crl::multisense::Active_Head_2
static CRL_CONSTEXPR CameraProfile Active_Head_2
User would like to set the active head to remote head 0.
Definition: MultiSenseTypes.hh:185
crl::multisense::imu::Sample::timeMicroSeconds
uint32_t timeMicroSeconds
The time microseconds value corresponding to the specific sample.
Definition: MultiSenseTypes.hh:2182
crl::multisense::image::Config::setCamMode
void setCamMode(int m)
Set a desired output mode.
Definition: MultiSenseTypes.hh:831
crl::multisense::system::VersionInfo::sensorHardwareMagic
uint64_t sensorHardwareMagic
The hardware magic number.
Definition: MultiSenseTypes.hh:2656
crl::multisense::ground_surface::Header::timestamp
int64_t timestamp
Trigger time of the disparity image which was used to generate the spline.
Definition: MultiSenseTypes.hh:2508
crl::multisense::TriggerSource
uint32_t TriggerSource
Definition: MultiSenseTypes.hh:251
crl::multisense::image::Header::imageDataP
const void * imageDataP
A pointer to the image data.
Definition: MultiSenseTypes.hh:468
crl::multisense::image::Config::autoExposure
bool autoExposure() const
Query the current image configuration's auto-exposure enable setting.
Definition: MultiSenseTypes.hh:1141
crl::multisense::system::VersionInfo::apiVersion
VersionType apiVersion
The version of libMultiSense.
Definition: MultiSenseTypes.hh:2646
crl::multisense::system::StatusMessage::uptime
double uptime
The system uptime of the MultiSense in seconds.
Definition: MultiSenseTypes.hh:2970
crl::multisense::image::Config::setOffset
void setOffset(int o)
Set a desired crop offset between 0 and 960 px.
Definition: MultiSenseTypes.hh:841
crl::multisense::compressed_image::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for compressed image data.
Definition: MultiSenseTypes.hh:2491
crl::multisense::image::Config::m_wbRed
float m_wbRed
Definition: MultiSenseTypes.hh:1439
crl::multisense::Status
int32_t Status
General status typdef used as a return value for get/set crl::multisense::Channel methods.
Definition: MultiSenseTypes.hh:93
crl::multisense::DirectedStream::DirectedStream
DirectedStream(DataSource m, const std::string &addr, uint16_t p=DFL_UDP_PORT, uint32_t dec=1)
Constructor to initialize a directed stream between a MultiSense device and a host machine.
Definition: MultiSenseTypes.hh:237
crl::multisense::system::StatusMessage::inputVoltage
float inputVoltage
The input voltage supplied to the MultiSense.
Definition: MultiSenseTypes.hh:3013
crl::multisense::lidar::Header::pointCount
uint32_t pointCount
The number of points in the laser scan.
Definition: MultiSenseTypes.hh:1780
crl::multisense::image::ExposureConfig::autoExposureRoiX
uint16_t autoExposureRoiX() const
Query the current image configuration's auto-exposure ROI X value.
Definition: MultiSenseTypes.hh:652
crl::multisense::Source_Unknown
static CRL_CONSTEXPR DataSource Source_Unknown
Definition: MultiSenseTypes.hh:116
crl::multisense::system::StatusMessage::systemOk
bool systemOk
A boolean flag indicating if the overall system status is good.
Definition: MultiSenseTypes.hh:2974
crl::multisense::Exposure_Default_Target_Intensity
static CRL_CONSTEXPR float Exposure_Default_Target_Intensity
Definition: MultiSenseTypes.hh:156
crl::multisense::image::Config::setStereoPostFilterStrength
void setStereoPostFilterStrength(float s)
Set the desired stereo post-filter strength.
Definition: MultiSenseTypes.hh:976
crl::multisense::system::StatusMessage::logicPower
float logicPower
The power consumed by the MicroBlaze CPU.
Definition: MultiSenseTypes.hh:3023
CRL_CONSTEXPR
#define CRL_CONSTEXPR
Definition: MultiSenseTypes.hh:48
crl::multisense::pps::Header::timeSeconds
uint32_t timeSeconds
The local time's seconds value.
Definition: MultiSenseTypes.hh:2147
crl::multisense::ground_surface::Header::controlPointsImageDataP
const void * controlPointsImageDataP
A pointer to the dynamically-sized control points array data.
Definition: MultiSenseTypes.hh:2517
crl::multisense::image::Config::m_hdrEnabled
bool m_hdrEnabled
Definition: MultiSenseTypes.hh:1448
crl::multisense::system::DeviceMode::height
uint32_t height
The image height configuration for a given device mode.
Definition: MultiSenseTypes.hh:2577
crl::multisense::compressed_image::Header::inMask
virtual bool inMask(DataSource mask)
Member function used to determine if the data contained in the header is contained in a specific imag...
Definition: MultiSenseTypes.hh:2485
crl::multisense::imu::Header::sequence
uint32_t sequence
The sequence number for each header containing IMU samples.
Definition: MultiSenseTypes.hh:2233
crl::multisense::pps::Header::sensorTime
int64_t sensorTime
The sensor time in nanoseconds when a given PPS event occurred
Definition: MultiSenseTypes.hh:2144
crl::multisense::system::DeviceInfo::numberOfLights
uint32_t numberOfLights
The number of lights supported by the sensor.
Definition: MultiSenseTypes.hh:2794
crl::multisense::image::Config::whiteBalanceRed
float whiteBalanceRed() const
Query the current image configuration's red white-balance setting.
Definition: MultiSenseTypes.hh:1181
crl::multisense::Status_Exception
static CRL_CONSTEXPR Status Status_Exception
Definition: MultiSenseTypes.hh:104
crl::multisense::image::Header::timeMicroSeconds
uint32_t timeMicroSeconds
The time microseconds value corresponding to when the image was captured.
Definition: MultiSenseTypes.hh:457
crl::multisense::Source_Jpeg_Left
static CRL_CONSTEXPR DataSource Source_Jpeg_Left
Definition: MultiSenseTypes.hh:131
crl::multisense::imu::Config::name
std::string name
The name of a specific IMU source corresponding to crl::multisense::imu::Info::name.
Definition: MultiSenseTypes.hh:2428
crl::multisense::image::ExposureConfig::autoExposureRoiWidth
uint16_t autoExposureRoiWidth() const
Query the current image configuration's auto-exposure ROI width value Will return crl::multisense::Ro...
Definition: MultiSenseTypes.hh:668
crl::multisense::system::PcbInfo::name
std::string name
The name of a PCB.
Definition: MultiSenseTypes.hh:2679
crl::multisense::image::Header::timeSeconds
uint32_t timeSeconds
The time seconds value corresponding to when the image was captured.
Definition: MultiSenseTypes.hh:455
crl::multisense::compressed_image::Header::timeMicroSeconds
uint32_t timeMicroSeconds
The time microseconds value corresponding to when the image was captured.
Definition: MultiSenseTypes.hh:2461
crl::multisense::system::StatusMessage::imuOk
bool imuOk
A boolean flag indicating if the imu is functioning.
Definition: MultiSenseTypes.hh:2990
crl::multisense::image::Header::frameId
int64_t frameId
Unique ID used to describe an image.
Definition: MultiSenseTypes.hh:453
crl::multisense::image::Config::setCameraProfile
void setCameraProfile(const CameraProfile &profile)
Set the operation profile for the camera to use.
Definition: MultiSenseTypes.hh:1034
crl::multisense::image::ExposureConfig::ExposureConfig
ExposureConfig()
Definition: MultiSenseTypes.hh:500
crl::multisense::image::ExposureConfig::setAutoExposureThresh
void setAutoExposureThresh(float t)
Set the desired auto-exposure threshold.
Definition: MultiSenseTypes.hh:555
crl::multisense::pps::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for PPS events.
Definition: MultiSenseTypes.hh:2155
crl::multisense::system::NetworkConfig::NetworkConfig
NetworkConfig()
Default constructor with the sensor factory default IP configuration.
Definition: MultiSenseTypes.hh:2907
crl::multisense::compressed_image::Header::source
DataSource source
DataSource corresponding to imageDataP.
Definition: MultiSenseTypes.hh:2447
crl::multisense::image::Config::tz
float tz() const
Query the current camera calibrations stereo baseline.
Definition: MultiSenseTypes.hh:1388
crl::multisense::system::DeviceMode::width
uint32_t width
The image width configuration for a given device mode.
Definition: MultiSenseTypes.hh:2575
crl::multisense::system::VersionInfo::sensorHardwareVersion
uint64_t sensorHardwareVersion
The hardware version of the sensor.
Definition: MultiSenseTypes.hh:2654
crl::multisense::Source_Chroma_Right
static CRL_CONSTEXPR DataSource Source_Chroma_Right
Definition: MultiSenseTypes.hh:125
crl::multisense::system::StatusMessage::externalLedsOk
bool externalLedsOk
A boolean flag indicating if the external LEDs are OK.
Definition: MultiSenseTypes.hh:2994
crl::multisense::system::NetworkConfig
Class containing the network configuration for a specific sensor.
Definition: MultiSenseTypes.hh:2894
crl::multisense::Source_Rgb_Left
static CRL_CONSTEXPR DataSource Source_Rgb_Left
Definition: MultiSenseTypes.hh:132
crl::multisense::image::Config::offset
int offset() const
Query the current image configuration's offset.
Definition: MultiSenseTypes.hh:1108
crl::multisense::image::ExposureConfig::autoExposureRoiHeight
uint16_t autoExposureRoiHeight() const
Query the current image configuration's auto-exposure ROI height value Will return crl::multisense::R...
Definition: MultiSenseTypes.hh:677
crl::multisense::image::Histogram::data
std::vector< uint32_t > data
The histogram data concatinated serially in GRBG order.
Definition: MultiSenseTypes.hh:1731
crl::multisense::image::ExposureConfig::m_aeEnabled
bool m_aeEnabled
Definition: MultiSenseTypes.hh:695
crl::multisense::image::Config::exposureSource
DataSource exposureSource() const
Query the image source which the exposure parameters correspond with.
Definition: MultiSenseTypes.hh:1274
crl::multisense::system::VersionInfo::sensorFpgaDna
uint64_t sensorFpgaDna
The FPGA DNA.
Definition: MultiSenseTypes.hh:2658
crl::multisense::pps::Header::timeMicroSeconds
uint32_t timeMicroSeconds
The local time's microseconds value.
Definition: MultiSenseTypes.hh:2149
crl::multisense::system::DeviceInfo::motorGearReduction
float motorGearReduction
The gear reduction for the sensor's laser assembly.
Definition: MultiSenseTypes.hh:2806
crl::multisense::lidar::Header::timeEndMicroSeconds
uint32_t timeEndMicroSeconds
The microseconds value of the time corresponding to the end of laser scan.
Definition: MultiSenseTypes.hh:1770
crl::multisense::Roi_Full_Image
static CRL_CONSTEXPR int Roi_Full_Image
Use Roi_Full_Image as the height and width when setting the autoExposureRoi to set the ROI to the ful...
Definition: MultiSenseTypes.hh:154
crl::multisense::image::Config::setHdr
void setHdr(bool e)
Set the HDR enable flag.
Definition: MultiSenseTypes.hh:988
crl::multisense::lidar::Header::timeStartMicroSeconds
uint32_t timeStartMicroSeconds
The microseconds value of the time corresponding to the start of laser scan.
Definition: MultiSenseTypes.hh:1766
crl::multisense::Status_TimedOut
static CRL_CONSTEXPR Status Status_TimedOut
Definition: MultiSenseTypes.hh:99
crl::multisense::image::SensorCalibration
Class to store sensor gains used to perform a DC level adjustment to calibrate the left imager to the...
Definition: MultiSenseTypes.hh:1652
crl::multisense::image::Config::m_wbThresh
float m_wbThresh
Definition: MultiSenseTypes.hh:1442
crl::multisense::image::Config::tx
float tx() const
Query the current camera calibrations stereo baseline.
Definition: MultiSenseTypes.hh:1366
crl::multisense::imu::Sample
Class containing a single IMU sample.
Definition: MultiSenseTypes.hh:2167
crl::multisense::system::DeviceInfo::nominalRelativeAperture
float nominalRelativeAperture
The nominal relative aperature for the sensor.
Definition: MultiSenseTypes.hh:2789
crl::multisense::imu::Info::RateEntry::bandwidthCutoff
float bandwidthCutoff
The bandwith cutoff for a given IMU source in Hz.
Definition: MultiSenseTypes.hh:2301
crl::multisense::lighting::MAX_LIGHTS
static CRL_CONSTEXPR uint32_t MAX_LIGHTS
The maximum number of lights for a given sensor.
Definition: MultiSenseTypes.hh:1899
crl::multisense::system::StatusMessage::imagerPower
float imagerPower
The power consumed by the imager chips.
Definition: MultiSenseTypes.hh:3026
crl::multisense::image::Config::setGain
void setGain(float g)
Set the desired output image's gain.
Definition: MultiSenseTypes.hh:878
crl::multisense::lidar::Header::timeEndSeconds
uint32_t timeEndSeconds
The seconds value of the time corresponding to the end of laser scan.
Definition: MultiSenseTypes.hh:1768
crl::multisense::image::Config::setGamma
void setGamma(const float g)
Set the secondary exposures gamma correction factor.
Definition: MultiSenseTypes.hh:1065
crl::multisense::Trigger_External
static CRL_CONSTEXPR TriggerSource Trigger_External
External OPTO_RX trigger input.
Definition: MultiSenseTypes.hh:256
crl::multisense::image::TransmitDelay
Definition: MultiSenseTypes.hh:1669
crl::multisense::Exposure_Default_Gain
static CRL_CONSTEXPR float Exposure_Default_Gain
Definition: MultiSenseTypes.hh:157
crl::multisense::system::StatusMessage::fpgaPower
float fpgaPower
The power consumed by the FPGA.
Definition: MultiSenseTypes.hh:3020
crl::multisense::image::Config::setFps
void setFps(float f)
Set the desired output frames per second.
Definition: MultiSenseTypes.hh:870
crl::multisense::image::Config::m_yaw
float m_yaw
Definition: MultiSenseTypes.hh:1458
crl::multisense::imu::Info
Class containing detailed information for the IMU.
Definition: MultiSenseTypes.hh:2291
crl::multisense::lighting::Config::getDutyCycle
float getDutyCycle(uint32_t i) const
Get the current duty cycle in terms of percent for a specific light.
Definition: MultiSenseTypes.hh:2057
crl::multisense::compressed_image::Header::imageLength
uint32_t imageLength
The length of the image data stored in imageDataP.
Definition: MultiSenseTypes.hh:2470
crl::multisense::image::ExposureConfig::setExposure
void setExposure(uint32_t e)
Set the exposure time used to capture images.
Definition: MultiSenseTypes.hh:514
crl::multisense::image::Config::setHeight
void setHeight(uint32_t h)
Set the height of the desired output resolution.
Definition: MultiSenseTypes.hh:859
crl::multisense::image::Config::m_tz
float m_tz
Definition: MultiSenseTypes.hh:1457
crl::multisense::lighting::Config::getFlash
bool getFlash() const
Get the current lighting flash setting.
Definition: MultiSenseTypes.hh:2007
crl::multisense::image::Config::m_secondary_exposures
std::vector< ExposureConfig > m_secondary_exposures
Definition: MultiSenseTypes.hh:1451
crl::multisense::system::StatusMessage::leftImagerTemperature
float leftImagerTemperature
The temperature of the left imager.
Definition: MultiSenseTypes.hh:3007
crl::multisense::system::DeviceInfo::imagerName
std::string imagerName
The name of the sensor's imager.
Definition: MultiSenseTypes.hh:2772
crl::multisense::High_Contrast
static CRL_CONSTEXPR CameraProfile High_Contrast
User would like more contrast in images.
Definition: MultiSenseTypes.hh:172
crl::multisense::lighting::Config::m_dutyCycle
std::vector< float > m_dutyCycle
Definition: MultiSenseTypes.hh:2072
crl::multisense::image::Config::autoExposureTargetIntensity
float autoExposureTargetIntensity() const
Query the current image configuration's auto-exposure target intensity.
Definition: MultiSenseTypes.hh:1165
crl::multisense::image::Calibration::Data
Class to store camera calibration matrices.
Definition: MultiSenseTypes.hh:1549
crl::multisense::compressed_image::Header::frameId
int64_t frameId
Unique ID used to describe an image.
Definition: MultiSenseTypes.hh:2457
crl::multisense::system::VersionInfo
Class containing version info for a specific sensor.
Definition: MultiSenseTypes.hh:2640
crl::multisense::compressed_image::Header::timeSeconds
uint32_t timeSeconds
The time seconds value corresponding to when the image was captured.
Definition: MultiSenseTypes.hh:2459
crl::multisense::image::Config::m_wbDecay
uint32_t m_wbDecay
Definition: MultiSenseTypes.hh:1441
crl::multisense::DirectedStream::fpsDecimation
uint32_t fpsDecimation
Every Nth image to send.
Definition: MultiSenseTypes.hh:218
crl::multisense::imu::Info::rates
std::vector< RateEntry > rates
The various rates available for a specific IMU source.
Definition: MultiSenseTypes.hh:2322
crl::multisense::image::Config::setAutoExposureTargetIntensity
void setAutoExposureTargetIntensity(float d)
Set the desired auto-exposure target Intensity.
Definition: MultiSenseTypes.hh:919
crl::multisense::image::Config::setExposureSource
void setExposureSource(const DataSource &s)
Set the stream source which these exposure parameters should apply to.
Definition: MultiSenseTypes.hh:1027
crl::multisense::Source_Chroma_Rectified_Aux
static CRL_CONSTEXPR DataSource Source_Chroma_Rectified_Aux
Definition: MultiSenseTypes.hh:126
crl::multisense::imu::Sample::type
Type type
The type of data contained in the instance of imu::Sample.
Definition: MultiSenseTypes.hh:2178
crl::multisense::CameraProfile
uint32_t CameraProfile
Camera profile typedef representing the various stereo profiles available from newer S27/S30 MultiSen...
Definition: MultiSenseTypes.hh:165
crl::multisense::image::Config::setDisparities
void setDisparities(uint32_t d)
For stereo sensors, set the desired number of disparities used to search for matching features betwee...
Definition: MultiSenseTypes.hh:821
crl::multisense::compressed_image::Header::codec
ImageCompressionCodec codec
Compression codec.
Definition: MultiSenseTypes.hh:2451
crl::multisense::DirectedStream::udpPort
uint16_t udpPort
default=10001
Definition: MultiSenseTypes.hh:216
crl::multisense::system::DeviceInfo::lensName
std::string lensName
The name of the sensor's lens.
Definition: MultiSenseTypes.hh:2781
crl::multisense::lidar::RangeType
uint32_t RangeType
The type of a single laser range measurement
Definition: MultiSenseTypes.hh:1742
crl::multisense::Trigger_External_Inverted
static CRL_CONSTEXPR TriggerSource Trigger_External_Inverted
External OPTO_RX trigger input with Inverted Polarity.
Definition: MultiSenseTypes.hh:258
crl::multisense::system::ExternalCalibration::yaw
float yaw
The external yaw translation of the MultiSense in degrees.
Definition: MultiSenseTypes.hh:3147
crl::multisense::image::Header
Class containing image Header information common to all image types.
Definition: MultiSenseTypes.hh:441
crl::multisense::image::Config::setAutoWhiteBalance
void setAutoWhiteBalance(bool e)
Set the white-balance enable flag.
Definition: MultiSenseTypes.hh:948
crl::multisense::system::ExternalCalibration::z
float z
The external z translation of the MultiSense in meters.
Definition: MultiSenseTypes.hh:3138
crl::multisense::image::ExposureConfig::m_aeDecay
uint32_t m_aeDecay
Definition: MultiSenseTypes.hh:697
crl::multisense::Ground_Surface
static CRL_CONSTEXPR CameraProfile Ground_Surface
User would like to run spline-based ground surface algorithm on the camera.
Definition: MultiSenseTypes.hh:176
crl::multisense::image::Config::stereoPostFilterStrength
float stereoPostFilterStrength() const
Query the current image configuration's stereo post-filter strength.
Definition: MultiSenseTypes.hh:1221
crl::multisense::image::ExposureConfig::setAutoExposureDecay
void setAutoExposureDecay(uint32_t d)
Set the desired auto-exposure decay rate.
Definition: MultiSenseTypes.hh:538
crl::multisense::image::ExposureConfig::autoExposureThresh
float autoExposureThresh() const
Query the current image configuration's auto-exposure threshold.
Definition: MultiSenseTypes.hh:645
crl::multisense::system::ExternalCalibration::roll
float roll
The external roll translation of the MultiSense in degrees.
Definition: MultiSenseTypes.hh:3141
crl::multisense::image::Config::gamma
float gamma() const
Query the gamma correction factor.
Definition: MultiSenseTypes.hh:1305
crl::multisense::lidar::Header::timeStartSeconds
uint32_t timeStartSeconds
The seconds value of the time corresponding to the start of laser scan.
Definition: MultiSenseTypes.hh:1764
crl::multisense::lighting::SensorStatus
A external sensor status.
Definition: MultiSenseTypes.hh:2111
crl::multisense::image::Config::m_wbEnabled
bool m_wbEnabled
Definition: MultiSenseTypes.hh:1440
crl::multisense::image::Config
Class used to store a specific camera configuration.
Definition: MultiSenseTypes.hh:795
crl::multisense::imu::Info::RangeEntry::range
float range
The range of valid sample readings for a IMU source.
Definition: MultiSenseTypes.hh:2310
crl::multisense::imu::Sample::timeSeconds
uint32_t timeSeconds
The time seconds value corresponding to the specific sample.
Definition: MultiSenseTypes.hh:2180
crl::multisense::imu::Sample::time
double time() const
A convenience function used for getting the time of the specific sample.
Definition: MultiSenseTypes.hh:2214
crl::multisense::DirectedStream
Class used to request that MultiSense data be sent to a 3rd-party stream destination (UDP port),...
Definition: MultiSenseTypes.hh:205
crl::multisense::Active_Head_3
static CRL_CONSTEXPR CameraProfile Active_Head_3
User would like to set the active head to remote head 0.
Definition: MultiSenseTypes.hh:187
crl::multisense::image::Config::fy
float fy() const
Query the current camera calibrations rectified projection focal length in the y dimension.
Definition: MultiSenseTypes.hh:1332
crl::multisense::image::Config::m_primary_exposure
ExposureConfig m_primary_exposure
Definition: MultiSenseTypes.hh:1437
crl::multisense::imu::Info::units
std::string units
The units of for a specific IMU source.
Definition: MultiSenseTypes.hh:2320
crl::multisense::image::ExposureConfig::autoExposureRoiY
uint16_t autoExposureRoiY() const
Query the current image configuration's auto-exposure ROI Y value.
Definition: MultiSenseTypes.hh:659
crl::multisense::Source_Luma_Rectified_Left
static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Left
Definition: MultiSenseTypes.hh:122
crl::multisense::system::PcbInfo::revision
uint32_t revision
The revision number of a PCB.
Definition: MultiSenseTypes.hh:2681
crl::multisense::image::Config::autoExposureRoiWidth
uint16_t autoExposureRoiWidth() const
Query the current image configuration's auto-exposure ROI width value Will return crl::multisense::Ro...
Definition: MultiSenseTypes.hh:1258
crl::multisense::lidar::Header::rangesP
const RangeType * rangesP
Laser range data in millimeters.
Definition: MultiSenseTypes.hh:1784
crl::multisense::image::Config::width
uint32_t width() const
Query the current image configuration's width.
Definition: MultiSenseTypes.hh:1075
crl::multisense::imu::Sample::z
float z
z data for each sample
Definition: MultiSenseTypes.hh:2206
crl::multisense::Source_Luma_Rectified_Aux
static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Aux
Definition: MultiSenseTypes.hh:140