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 #include <climits>
42 #include <string>
43 #include <vector>
44 #include <iostream>
45 
46 #if defined (CRL_HAVE_CONSTEXPR)
47 #define CRL_CONSTEXPR constexpr
48 #else
49 #define CRL_CONSTEXPR const
50 #endif
51 
52 // Define MULTISENSE_API appropriately. This is needed to correctly link with
53 // LibMultiSense when it is built as a DLL on Windows.
54 #if !defined(MULTISENSE_API)
55 #if defined (_MSC_VER)
56 #if defined (MultiSense_STATIC)
57 #define MULTISENSE_API __declspec(dllexport)
58 #elif defined (MultiSense_EXPORTS)
59 #define MULTISENSE_API __declspec(dllexport)
60 #else
61 #define MULTISENSE_API __declspec(dllimport)
62 #endif
63 
64 #else
65 #define MULTISENSE_API
66 #endif
67 
68 #endif
69 
70 #if defined (_MSC_VER)
71 /*
72  * C4251 warns about exporting classes with members not marked as __declspec(export).
73  * It is not easy to work around this without breaking the MultiSense API, but it
74  * is safe to ignore this warning as long as the MultiSense DLL is compiled with the
75  * same compiler version and STL version.
76  */
77 #pragma warning (push)
78 #pragma warning (disable: 4251)
79 #endif
80 
81 namespace crl {
82 namespace multisense {
83 
87 typedef uint32_t VersionType;
88 
93 typedef int32_t Status;
94 
95 //
96 // General status codes
97 
105 
114 typedef uint64_t DataSource;
115 
117 static CRL_CONSTEXPR DataSource Source_All = 0xffffffffffffffff;
128 static CRL_CONSTEXPR DataSource Source_Disparity_Left = (1ull<<10); // same as Source_Disparity
140 static CRL_CONSTEXPR DataSource Source_Imu = (1ull<<25);
141 static CRL_CONSTEXPR DataSource Source_Pps = (1ull<<26);
153 
162 
169 typedef uint32_t CameraProfile;
170 
186 
191 typedef uint32_t ImageCompressionCodec;
192 
195 
206 typedef int16_t RemoteHeadChannel;
219 
235 
240 
250  const std::vector<RemoteHeadChannel> &r) :
251  controller(c),
252  responders(r) {};
253 
257  std::vector<RemoteHeadChannel> responders;
258 
259 };
260 
261 /*
262  * Trigger sources used to determine which input should be used to trigger
263  * a frame capture on a device
264  */
265 typedef uint32_t TriggerSource;
266 
275 
280 public:
285  virtual bool inMask(DataSource mask) { (void) mask; return true; };
286  virtual ~HeaderBase() {};
287 };
288 
289 namespace image {
290 
454 public:
455 
459  uint32_t bitsPerPixel;
461  uint32_t width;
463  uint32_t height;
465  int64_t frameId;
467  uint32_t timeSeconds;
470 
472  uint32_t exposure;
474  float gain;
478  uint32_t imageLength;
480  const void *imageDataP;
481 
486  : source(Source_Unknown) {};
487 
492  virtual bool inMask(DataSource mask) { return (mask & source) != 0;};
493 };
494 
506 typedef void (*Callback)(const Header& header,
507  void *userDataP);
508 
510 public:
512  m_exposure(10000), m_aeEnabled(true), m_aeMax(5000000), m_aeDecay(7), m_aeThresh(0.9f),
513  m_autoExposureRoiX(0), m_autoExposureRoiY(0),
514  m_autoExposureRoiWidth(Roi_Full_Image), m_autoExposureRoiHeight(Roi_Full_Image),
515  m_aeTargetIntensity(Exposure_Default_Target_Intensity),
516  m_gain(Exposure_Default_Gain) {};
517 
525  void setExposure (uint32_t e) { m_exposure = e; };
526 
533  void setAutoExposure (bool e) { m_aeEnabled = e; };
534 
541  void setAutoExposureMax (uint32_t m) { m_aeMax = m; };
542 
549  void setAutoExposureDecay (uint32_t d) { m_aeDecay = d; };
550 
557  void setAutoExposureTargetIntensity (float d) { m_aeTargetIntensity = d; };
558 
566  void setAutoExposureThresh(float t) { m_aeThresh = t; };
567 
583  void setAutoExposureRoi(uint16_t start_x, uint16_t start_y, uint16_t width, uint16_t height)
584  {
585  m_autoExposureRoiX = start_x;
586  m_autoExposureRoiY = start_y;
587  m_autoExposureRoiWidth = width;
588  m_autoExposureRoiHeight = height;
589  }
590 
597  void setGain(const float &g) { m_gain = g; };
598 
599  //
600  // Query
601 
608  uint32_t exposure () const { return m_exposure; };
609 
616  bool autoExposure () const { return m_aeEnabled; };
617 
624  uint32_t autoExposureMax () const { return m_aeMax; };
625 
632  uint32_t autoExposureDecay () const { return m_aeDecay; };
633 
640  float autoExposureTargetIntensity () const { return m_aeTargetIntensity; };
641 
648  float autoExposureThresh() const { return m_aeThresh; };
649 
655  uint16_t autoExposureRoiX () const { return m_autoExposureRoiX; };
656 
662  uint16_t autoExposureRoiY () const { return m_autoExposureRoiY; };
663 
671  uint16_t autoExposureRoiWidth () const { return m_autoExposureRoiWidth; };
672 
680  uint16_t autoExposureRoiHeight () const { return m_autoExposureRoiHeight; };
681 
687  float gain() const { return m_gain; };
688 
689  private:
690  uint32_t m_exposure;
692  uint32_t m_aeMax;
693  uint32_t m_aeDecay;
694  float m_aeThresh;
695 
700 
702  float m_gain;
703 };
704 
791 public:
792 
793  //
794  // User configurable member functions
795 
804  void setResolution (uint32_t w,
805  uint32_t h) { m_width=w;m_height=h; };
806 
816  void setDisparities (uint32_t d) { m_disparities=d; };
817 
825  void setWidth (uint32_t w) { m_width = w; };
826 
834  void setHeight (uint32_t h) { m_height = h; };
835 
845  void setFps (float f) { m_fps = f; };
846 
853  void setGain (float g) { m_gain = g; };
854 
862  void setExposure (uint32_t e) { m_exposure.setExposure(e); };
863 
870  void setAutoExposure (bool e) { m_exposure.setAutoExposure(e); };
871 
878  void setAutoExposureMax (uint32_t m) { m_exposure.setAutoExposureMax(m); };
879 
886  void setAutoExposureDecay (uint32_t d) { m_exposure.setAutoExposureDecay(d); };
887 
894  void setAutoExposureTargetIntensity (float d) { m_exposure.setAutoExposureTargetIntensity(d); };
895 
903  void setAutoExposureThresh(float t) { m_exposure.setAutoExposureThresh(t); };
904 
914  void setWhiteBalance (float r,
915  float b) { m_wbRed=r;m_wbBlue=b; };
916 
923  void setAutoWhiteBalance (bool e) { m_wbEnabled = e; };
924 
931  void setAutoWhiteBalanceDecay (uint32_t d) { m_wbDecay = d; };
932 
939  void setAutoWhiteBalanceThresh (float t) { m_wbThresh = t; };
940 
951  void setStereoPostFilterStrength(float s) { m_spfStrength = s; };
952 
963  void setHdr (bool e) { m_hdrEnabled = e; };
964 
980  void setAutoExposureRoi(uint16_t start_x, uint16_t start_y, uint16_t width, uint16_t height)
981  {
982  m_exposure.setAutoExposureRoi(start_x, start_y, width, height);
983  }
984 
990  void setCameraProfile(const CameraProfile &profile)
991  {
992  m_profile = profile;
993  }
994 
1003  void setGamma(const float g) { m_gamma = g; };
1004 
1005 
1006  //
1007  // Query
1008 
1014  uint32_t width () const { return m_width; };
1015 
1022  uint32_t height () const { return m_height; };
1023 
1031  uint32_t disparities () const { return m_disparities; };
1032 
1039  float fps () const { return m_fps; };
1040 
1046  float gain () const { return m_gain; };
1047 
1048 
1055  uint32_t exposure () const { return m_exposure.exposure(); };
1056 
1063  bool autoExposure () const { return m_exposure.autoExposure(); };
1064 
1071  uint32_t autoExposureMax () const { return m_exposure.autoExposureMax(); };
1072 
1079  uint32_t autoExposureDecay () const { return m_exposure.autoExposureDecay(); };
1080 
1087  float autoExposureTargetIntensity () const { return m_exposure.autoExposureTargetIntensity(); };
1088 
1095  float autoExposureThresh() const { return m_exposure.autoExposureThresh(); };
1096 
1103  float whiteBalanceRed () const { return m_wbRed; };
1104 
1111  float whiteBalanceBlue () const { return m_wbBlue; };
1112 
1119  bool autoWhiteBalance () const { return m_wbEnabled; };
1120 
1127  uint32_t autoWhiteBalanceDecay () const { return m_wbDecay; };
1128 
1135  float autoWhiteBalanceThresh () const { return m_wbThresh; };
1136 
1143  float stereoPostFilterStrength() const { return m_spfStrength; };
1144 
1150  bool hdrEnabled () const { return m_hdrEnabled; };
1151 
1157  uint16_t autoExposureRoiX () const { return m_exposure.autoExposureRoiX(); };
1158 
1164  uint16_t autoExposureRoiY () const { return m_exposure.autoExposureRoiY(); };
1165 
1173  uint16_t autoExposureRoiWidth () const { return m_exposure.autoExposureRoiWidth(); };
1174 
1182  uint16_t autoExposureRoiHeight () const { return m_exposure.autoExposureRoiHeight(); };
1183 
1189  CameraProfile cameraProfile () const { return m_profile; };
1190 
1197  float gamma() const { return m_gamma; };
1198 
1199  //
1200  // Query camera calibration (read-only)
1201  //
1202  // These parameters are adjusted for the current operating resolution of the device.
1203 
1213  float fx() const { return m_fx; };
1214 
1224  float fy() const { return m_fy; };
1225 
1236  float cx() const { return m_cx; };
1237 
1248  float cy() const { return m_cy; };
1249 
1258  float tx() const { return m_tx; };
1259 
1269  float ty() const { return m_ty; };
1270 
1280  float tz() const { return m_tz; };
1281 
1290  float roll() const { return m_roll; };
1291 
1300  float pitch() const { return m_pitch; };
1301 
1310  float yaw() const { return m_yaw; };
1311 
1316  Config() : m_fps(5.0f), m_gain(1.0f),
1317  m_exposure(),
1318  m_wbBlue(1.0f), m_wbRed(1.0f), m_wbEnabled(true), m_wbDecay(3), m_wbThresh(0.5f),
1319  m_width(1024), m_height(544), m_disparities(128), m_spfStrength(0.5f),
1320  m_hdrEnabled(false),
1321  m_profile(User_Control),
1322  m_gamma(2.0),
1323  m_fx(0), m_fy(0), m_cx(0), m_cy(0),
1324  m_tx(0), m_ty(0), m_tz(0), m_roll(0), m_pitch(0), m_yaw(0) {};
1325 private:
1326 
1327  float m_fps, m_gain;
1329  float m_wbBlue;
1330  float m_wbRed;
1332  uint32_t m_wbDecay;
1333  float m_wbThresh;
1334  uint32_t m_width, m_height;
1335  uint32_t m_disparities;
1339  float m_gamma;
1340 
1341 protected:
1342 
1343  float m_fx, m_fy, m_cx, m_cy;
1344  float m_tx, m_ty, m_tz;
1345  float m_roll, m_pitch, m_yaw;
1346 };
1347 
1349 public:
1350 
1351  //
1352  // User configurable member functions
1353 
1354 
1361  void setGain (float g) { m_gain = g; };
1362 
1370  void setExposure (uint32_t e) { m_exposure.setExposure(e); };
1371 
1378  void setAutoExposure (bool e) { m_exposure.setAutoExposure(e); };
1379 
1386  void setAutoExposureMax (uint32_t m) { m_exposure.setAutoExposureMax(m); };
1387 
1394  void setAutoExposureDecay (uint32_t d) { m_exposure.setAutoExposureDecay(d); };
1395 
1402  void setAutoExposureTargetIntensity (float d) { m_exposure.setAutoExposureTargetIntensity(d); };
1403 
1411  void setAutoExposureThresh(float t) { m_exposure.setAutoExposureThresh(t); };
1412 
1422  void setWhiteBalance (float r,
1423  float b) { m_wbRed=r;m_wbBlue=b; };
1424 
1431  void setAutoWhiteBalance (bool e) { m_wbEnabled = e; };
1432 
1439  void setAutoWhiteBalanceDecay (uint32_t d) { m_wbDecay = d; };
1440 
1447  void setAutoWhiteBalanceThresh (float t) { m_wbThresh = t; };
1448 
1459  void setHdr (bool e) { m_hdrEnabled = e; };
1460 
1476  void setAutoExposureRoi(uint16_t start_x, uint16_t start_y, uint16_t width, uint16_t height)
1477  {
1478  m_exposure.setAutoExposureRoi(start_x, start_y, width, height);
1479  }
1480 
1486  void setCameraProfile(const CameraProfile &profile)
1487  {
1488  m_profile = profile;
1489  }
1490 
1499  void setGamma(const float g) { m_gamma = g; };
1500 
1501 
1508  void enableSharpening(const bool &s) { m_sharpeningEnable = s; };
1509 
1516  void setSharpeningPercentage(const float &s) { m_sharpeningPercentage = s; };
1517 
1526  void setSharpeningLimit(const uint8_t &s) { m_sharpeningLimit = s; };
1527 
1528  //
1529  // Query
1530  //
1531  //
1532  // Query camera calibration (read-only)
1533  //
1534  // These parameters are adjusted for the current operating resolution of the device.
1535 
1545  float fx() const { return m_fx; };
1546 
1556  float fy() const { return m_fy; };
1557 
1568  float cx() const { return m_cx; };
1569 
1580  float cy() const { return m_cy; };
1581 
1587  float gain () const { return m_gain; };
1588 
1595  uint32_t exposure () const { return m_exposure.exposure(); };
1596 
1603  bool autoExposure () const { return m_exposure.autoExposure(); };
1604 
1611  uint32_t autoExposureMax () const { return m_exposure.autoExposureMax(); };
1612 
1619  uint32_t autoExposureDecay () const { return m_exposure.autoExposureDecay(); };
1620 
1627  float autoExposureTargetIntensity () const { return m_exposure.autoExposureTargetIntensity(); };
1628 
1635  float autoExposureThresh() const { return m_exposure.autoExposureThresh(); };
1636 
1643  float whiteBalanceRed () const { return m_wbRed; };
1644 
1651  float whiteBalanceBlue () const { return m_wbBlue; };
1652 
1659  bool autoWhiteBalance () const { return m_wbEnabled; };
1660 
1667  uint32_t autoWhiteBalanceDecay () const { return m_wbDecay; };
1668 
1675  float autoWhiteBalanceThresh () const { return m_wbThresh; };
1676 
1682  bool hdrEnabled () const { return m_hdrEnabled; };
1683 
1689  uint16_t autoExposureRoiX () const { return m_exposure.autoExposureRoiX(); };
1690 
1696  uint16_t autoExposureRoiY () const { return m_exposure.autoExposureRoiY(); };
1697 
1705  uint16_t autoExposureRoiWidth () const { return m_exposure.autoExposureRoiWidth(); };
1706 
1714  uint16_t autoExposureRoiHeight () const { return m_exposure.autoExposureRoiHeight(); };
1715 
1721  CameraProfile cameraProfile () const { return m_profile; };
1722 
1729  float gamma() const { return m_gamma; };
1730 
1736  bool enableSharpening() const { return m_sharpeningEnable; };
1737 
1743  float sharpeningPercentage() const { return m_sharpeningPercentage; };
1744 
1750  uint8_t sharpeningLimit() const { return m_sharpeningLimit; };
1751 
1756  AuxConfig() : m_gain(1.0f),
1757  m_exposure(),
1758  m_wbBlue(1.0f), m_wbRed(1.0f), m_wbEnabled(true), m_wbDecay(3), m_wbThresh(0.5f),
1759  m_hdrEnabled(false),
1760  m_profile(User_Control),
1761  m_gamma(2.0),
1762  m_sharpeningEnable(false), m_sharpeningPercentage(0.0f), m_sharpeningLimit(0),
1763  m_fx(0), m_fy(0), m_cx(0), m_cy(0) {};
1764 private:
1765 
1766  float m_gain;
1768  float m_wbBlue;
1769  float m_wbRed;
1771  uint32_t m_wbDecay;
1772  float m_wbThresh;
1775  float m_gamma;
1779 
1780 protected:
1781 
1782  float m_fx, m_fy, m_cx, m_cy;
1783 };
1784 
1868 public:
1869 
1874  public:
1875 
1877  float M[3][3];
1880  float D[8];
1882  float R[3][3];
1884  float P[3][4];
1885  };
1886 
1893 };
1894 
1896 public:
1897 
1899  int delay;
1900 
1901 };
1902 
1904 public:
1905 
1907  bool enable;
1908 
1909 };
1910 
1950 public:
1951 
1955  Histogram() : channels(0),
1956  bins(0),
1957  data() {};
1960  uint32_t channels;
1962  uint32_t bins;
1965  std::vector<uint32_t> data;
1966 };
1967 
1969 public:
1970 
1974  RemoteHeadConfig() : m_syncGroups()
1975  {};
1976 
1982  RemoteHeadConfig(const std::vector<RemoteHeadSyncGroup> &sync_groups) :
1983  m_syncGroups(sync_groups)
1984  {}
1985 
1991  void setSyncGroups(const std::vector<RemoteHeadSyncGroup> &sync_groups) { m_syncGroups = sync_groups; }
1992 
1998  std::vector<RemoteHeadSyncGroup> syncGroups() const { return m_syncGroups; }
1999 
2000 private:
2001 
2003  std::vector<RemoteHeadSyncGroup> m_syncGroups;
2004 };
2005 
2006 
2007 } // namespace image
2008 
2009 namespace lidar {
2010 
2012 typedef uint32_t RangeType;
2014 typedef uint32_t IntensityType;
2015 
2023 public:
2024 
2029  : pointCount(0) {};
2030 
2032  uint32_t scanId;
2038  uint32_t timeEndSeconds;
2046  int32_t scanArc;
2048  uint32_t maxRange;
2050  uint32_t pointCount;
2051 
2057  const IntensityType *intensitiesP; // device units
2058 };
2059 
2069 typedef void (*Callback)(const Header& header,
2070  void *userDataP);
2071 
2153 public:
2154 
2157  float laserToSpindle[4][4];
2160  float cameraToSpindleFixed[4][4];
2161 };
2162 
2163 } // namespace lidar
2164 
2165 namespace lighting {
2166 
2168 static CRL_CONSTEXPR uint32_t MAX_LIGHTS = 8;
2170 static CRL_CONSTEXPR float MAX_DUTY_CYCLE = 100.0;
2171 
2258 public:
2259 
2268  void setFlash(bool onOff) { m_flashEnabled = onOff; };
2269 
2276  bool getFlash() const { return m_flashEnabled; };
2277 
2286  bool setDutyCycle(float percent) {
2287  if (percent < 0.0f || percent > MAX_DUTY_CYCLE)
2288  return false;
2289 
2290  std::fill(m_dutyCycle.begin(),
2291  m_dutyCycle.end(),
2292  percent);
2293  return true;
2294  };
2295 
2307  bool setDutyCycle(uint32_t i,
2308  float percent) {
2309  if (i >= MAX_LIGHTS ||
2310  percent < 0.0f || percent > MAX_DUTY_CYCLE)
2311  return false;
2312 
2313  m_dutyCycle[i] = percent;
2314  return true;
2315  };
2316 
2326  float getDutyCycle(uint32_t i) const {
2327  if (i >= MAX_LIGHTS)
2328  return 0.0f;
2329  return m_dutyCycle[i];
2330  };
2331 
2341  uint32_t getNumberOfPulses( ) const {
2342  return m_numberPulses;
2343  }
2344 
2354  bool setNumberOfPulses(const uint32_t numPulses) {
2355 
2356  m_numberPulses = numPulses;
2357  return true;
2358  }
2359 
2367  uint32_t getStartupTime( ) const {
2368  return m_lightStartupOffset_us;
2369  }
2370 
2380  bool setStartupTime(uint32_t ledTransientResponse_us) {
2381 
2382  m_lightStartupOffset_us = ledTransientResponse_us;
2383  return true;
2384  }
2385 
2393  bool getInvertPulse( ) const {
2394  return m_invertPulse;
2395  }
2396 
2406  bool setInvertPulse(const bool invert) {
2407  m_invertPulse = invert;
2408  return true;
2409  }
2410  /*
2411  * Enable a rolling shutter camera flash synchronization, this will Allow
2412  * an LED to flash with in sync with a rolling shutter imager, to reduce
2413  * the possibility of, seeing inconsistent lighting artifacts with rolling
2414  * shutter imagers.
2415  * Note: This feature is only available for Next Gen Stereo Cameras, with a
2416  * rolling shutter aux imager.
2417  *
2418  * @param enabled enable/disable the rolling shutter synchronization feature.
2419  *
2420  * @return True on success, False on failure
2421  */
2422  bool enableRollingShutterLedSynchronization(const bool enabled) {
2423  m_rollingShutterLedEnabled = enabled;
2424  return true;
2425  }
2426 
2435  return m_rollingShutterLedEnabled;
2436  }
2437 
2441  Config() : m_flashEnabled(false), m_dutyCycle(MAX_LIGHTS, -1.0f),
2442  m_numberPulses(1), m_lightStartupOffset_us(0), m_invertPulse(false),
2443  m_rollingShutterLedEnabled(false) {};
2444 
2445 private:
2446 
2447  bool m_flashEnabled;
2448  std::vector<float> m_dutyCycle;
2449  uint32_t m_numberPulses;
2453 };
2454 
2492 public:
2493 
2500 
2501  SensorStatus() : ambientLightPercentage(100.0f) {};
2502 };
2503 
2504 } // namespace lighting
2505 
2506 namespace pps {
2507 
2518 public:
2519 
2521  int64_t sensorTime;
2522 
2524  uint32_t timeSeconds;
2527 };
2528 
2532 typedef void (*Callback)(const Header& header,
2533  void *userDataP);
2534 
2535 } // namespace pps
2536 
2537 namespace imu {
2538 
2544 public:
2545 
2547  typedef uint16_t Type;
2548 
2549  static CRL_CONSTEXPR Type Type_Accelerometer = 1;
2550  static CRL_CONSTEXPR Type Type_Gyroscope = 2;
2551  static CRL_CONSTEXPR Type Type_Magnetometer = 3;
2552 
2556  uint32_t timeSeconds;
2559 
2566  float x;
2567 
2574  float y;
2575 
2582  float z;
2583 
2590  double time() const {
2591  return (static_cast<double>(timeSeconds) +
2592  1e-6 * static_cast<double>(timeMicroSeconds));
2593  };
2594 };
2595 
2605 public:
2606 
2609  uint32_t sequence;
2613  std::vector<Sample> samples;
2614 };
2615 
2619 typedef void (*Callback)(const Header& header,
2620  void *userDataP);
2621 
2668 public:
2669 
2673  typedef struct {
2675  float sampleRate;
2678  } RateEntry;
2679 
2683  typedef struct {
2686  float range;
2688  float resolution;
2689  } RangeEntry;
2690 
2692  std::string name;
2694  std::string device;
2696  std::string units;
2698  std::vector<RateEntry> rates;
2700  std::vector<RangeEntry> ranges;
2701 };
2702 
2800 public:
2801 
2804  std::string name;
2806  bool enabled;
2809  uint32_t rateTableIndex;
2813 };
2814 
2815 } // namespace imu
2816 
2817 namespace compressed_image {
2818 
2820 public:
2821 
2825  uint32_t bitsPerPixel;
2829  uint32_t width;
2831  uint32_t height;
2833  int64_t frameId;
2835  uint32_t timeSeconds;
2838 
2840  uint32_t exposure;
2842  float gain;
2846  uint32_t imageLength;
2848  const void *imageDataP;
2849 
2854  : source(Source_Unknown) {};
2855 
2860  virtual bool inMask(DataSource mask) { return (mask & source) != 0;};
2861 };
2862 
2866 typedef void (*Callback)(const Header& header,
2867  void *userDataP);
2868 
2869 } // namespace compressed_image
2870 
2871 namespace ground_surface {
2872 
2879 public:
2881  int64_t frameId;
2883  int64_t timestamp;
2885  uint8_t success;
2886 
2895 
2897  float xzCellOrigin[2];
2899  float xzCellSize[2];
2901  float xzLimit[2];
2903  float minMaxAzimuthAngle[2];
2904 
2907  float extrinsics[6];
2908 
2911  float quadraticParams[6];
2912 };
2913 
2917 typedef void (*Callback)(const Header& header,
2918  void *userDataP);
2919 
2920 } // namespace ground_surface
2921 
2922 namespace apriltag {
2923 
2930 public:
2933  std::string family;
2935  uint32_t id;
2937  uint8_t hamming;
2945  double tagToImageHomography[3][3];
2947  double center[2];
2953  double corners[4][2];
2954  };
2955 
2957  int64_t frameId;
2959  int64_t timestamp;
2961  std::string imageSource;
2963  uint8_t success;
2965  uint32_t numDetections;
2967  std::vector<ApriltagDetection> detections;
2968 };
2969 
2973 typedef void (*Callback)(const Header& header,
2974  void *userDataP);
2975 
2976 } // namespace apriltag
2977 
2978 namespace feature_detector {
2979 
2980 
2985 
2986 
2987  struct Feature {
2988  uint16_t x;
2989  uint16_t y;
2990  uint8_t angle;
2991  uint8_t resp;
2992  uint8_t octave;
2993  uint8_t descriptor;
2994  };
2995 
2996  struct Descriptor {
2997  uint32_t d[8]; //Descriptor is 32 bytes
2998  };
2999 
3001  public:
3002 
3004  int64_t frameId;
3005  uint32_t timeSeconds;
3008  uint16_t octaveWidth;
3009  uint16_t octaveHeight;
3010  uint16_t numOctaves;
3011  uint16_t scaleFactor;
3012  uint16_t motionStatus;
3013  uint16_t averageXMotion;
3014  uint16_t averageYMotion;
3015  uint16_t numFeatures;
3016  uint16_t numDescriptors;
3017  std::vector<Feature> features;
3018  std::vector<Descriptor> descriptors;
3019  };
3020 
3024  typedef void (*Callback)(const Header& header,
3025  void *userDataP);
3026 
3027 } // namespace feature_detector
3028 
3029 
3030 namespace system {
3031 
3057 public:
3058 
3060  uint32_t width;
3062  uint32_t height;
3066  int32_t disparities;
3067 
3079  DeviceMode(uint32_t w=0,
3080  uint32_t h=0,
3081  DataSource d=0,
3082  int32_t s=-1) :
3083  width(w),
3084  height(h),
3085  supportedDataSources(d),
3086  disparities(s) {};
3087 };
3088 
3126 public:
3127 
3129  std::string apiBuildDate;
3132 
3137 
3143  uint64_t sensorFpgaDna;
3144 
3149  apiVersion(0),
3150  sensorFirmwareVersion(0),
3151  sensorHardwareVersion(0),
3152  sensorHardwareMagic(0),
3153  sensorFpgaDna(0) {};
3154 };
3155 
3161 public:
3162 
3164  std::string name;
3166  uint32_t revision;
3167 
3171  PcbInfo() : revision(0) {};
3172 };
3173 
3212 public:
3213 
3215  static CRL_CONSTEXPR uint8_t MAX_PCBS = 8;
3216 
3217  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_SL = 1;
3218  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7 = 2;
3219  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S = HARDWARE_REV_MULTISENSE_S7; // alias for backward source compatibility
3220  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_M = 3;
3221  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7S = 4;
3222  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S21 = 5;
3223  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_ST21 = 6;
3224  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_C6S2_S27 = 7;
3225  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S30 = 8;
3226  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7AR = 9;
3227  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_KS21 = 10;
3228  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_MONOCAM = 11;
3229  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_REMOTE_HEAD_VPB = 12;
3230  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_REMOTE_HEAD_STEREO = 13;
3231  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_REMOTE_HEAD_MONOCAM = 14;
3232  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_KS21_SILVER = 15;
3233  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_ST25 = 16;
3234  static CRL_CONSTEXPR uint32_t HARDWARE_REV_BCAM = 100;
3235  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MONO = 101;
3236 
3237  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_NONE = 0;
3238  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_GREY = 1;
3239  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_COLOR = 2;
3240  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_GREY = 3;
3241  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_COLOR = 4;
3242  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_FLIR_TAU2 = 7;
3243  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_IMX104_COLOR = 100;
3244  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_AR0234_GREY = 200;
3245  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_AR0239_COLOR = 202;
3246 
3247  static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_NONE = 0;
3248  static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_INTERNAL = 1;
3249  static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_EXTERNAL = 2;
3250  static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_PATTERN_PROJECTOR = 3;
3251  static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_OUTPUT_TRIGGER = 4;
3252  static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_PATTERN_PROJECTOR_AND_OUTPUT_TRIGGER = 5;
3253 
3255  std::string name;
3257  std::string buildDate;
3259  std::string serialNumber;
3262 
3264  std::vector<PcbInfo> pcbs;
3265 
3267  std::string imagerName;
3269  uint32_t imagerType;
3271  uint32_t imagerWidth;
3273  uint32_t imagerHeight;
3274 
3276  std::string lensName;
3278  uint32_t lensType;
3285 
3287  uint32_t lightingType;
3289  uint32_t numberOfLights;
3290 
3292  std::string laserName;
3294  uint32_t laserType;
3295 
3297  std::string motorName;
3299  uint32_t motorType;
3302 
3307  hardwareRevision(0),
3308  imagerType(0),
3309  imagerWidth(0),
3310  imagerHeight(0),
3311  lensType(0),
3312  nominalBaseline(0.0),
3313  nominalFocalLength(0.0),
3314  nominalRelativeAperture(0.0),
3315  lightingType(0),
3316  numberOfLights(0),
3317  laserType(0),
3318  motorType(0),
3319  motorGearReduction(0.0) {};
3320 };
3321 
3390 public:
3391 
3393  std::string ipv4Address;
3395  std::string ipv4Gateway;
3397  std::string ipv4Netmask;
3398 
3403  ipv4Address("10.66.171.21"),
3404  ipv4Gateway("10.66.171.1"),
3405  ipv4Netmask("255.255.240.0") {};
3406 
3416  NetworkConfig(const std::string& a,
3417  const std::string& g,
3418  const std::string& n) :
3419  ipv4Address(a),
3420  ipv4Gateway(g),
3421  ipv4Netmask(n) {};
3422 };
3423 
3461  public:
3462 
3465  double uptime;
3466 
3469  bool systemOk;
3470 
3473  bool laserOk;
3474 
3478 
3482 
3485  bool imuOk;
3486 
3490 
3493 
3497 
3500 
3503 
3506 
3509 
3513 
3515  float fpgaPower;
3516 
3518  float logicPower;
3519 
3522 
3525  uptime(0.),
3526  systemOk(false),
3527  laserOk(false),
3528  laserMotorOk(false),
3529  camerasOk(false),
3530  imuOk(false),
3531  externalLedsOk(false),
3532  processingPipelineOk(false),
3533  powerSupplyTemperature(0.),
3534  fpgaTemperature(0.),
3535  leftImagerTemperature(0.),
3536  rightImagerTemperature(0.),
3537  inputVoltage(0.),
3538  inputCurrent(0.),
3539  fpgaPower(0.),
3540  logicPower(0.),
3541  imagerPower(0.) {};
3542 };
3543 
3624  public:
3625 
3627  float x;
3628 
3630  float y;
3631 
3633  float z;
3634 
3636  float roll;
3637 
3639  float pitch;
3640 
3642  float yaw;
3643 
3646  x(0.),
3647  y(0.),
3648  z(0.),
3649  roll(0.),
3650  pitch(0.),
3651  yaw(0.) {};
3652 };
3653 
3707  public:
3708 
3714 
3720 
3728 
3733 
3738 
3741 
3745 
3749 
3752 
3755 
3759 
3763 
3767 
3772 
3776 
3780 
3783  ground_surface_number_of_levels_x(4),
3784  ground_surface_number_of_levels_z(4),
3785  ground_surface_base_model(1),
3786  ground_surface_pointcloud_grid_size(0.5),
3787  ground_surface_min_points_per_grid(10),
3788  ground_surface_pointcloud_decimation(1),
3789  ground_surface_pointcloud_max_range_m(30.0),
3790  ground_surface_pointcloud_min_range_m(0.5),
3791  ground_surface_pointcloud_max_width_m(25.0),
3792  ground_surface_pointcloud_min_width_m(-25.0),
3793  ground_surface_pointcloud_max_height_m(10.0),
3794  ground_surface_pointcloud_min_height_m(-10.0),
3795  ground_surface_obstacle_height_thresh_m(2.0),
3796  ground_surface_obstacle_percentage_thresh(0.5),
3797  ground_surface_max_fitting_iterations(10),
3798  ground_surface_adjacent_cell_search_size_m(1.5) {};
3799 };
3800 
3845  public:
3847  std::string family;
3848 
3850  uint8_t max_hamming;
3851 
3856 
3860 
3879 
3882 
3888 
3891  family("tagStandard52h13"),
3892  max_hamming(0),
3893  quad_detection_blur_sigma(0.75),
3894  quad_detection_decimate(1.0),
3895  min_border_width(5),
3896  refine_quad_edges(false),
3897  decode_sharpening(0.25) {};
3898 };
3899 
3960 
3961  private:
3962 
3972 
3987 
3996  uint32_t m_motion;
3997 
3998  public:
4004  uint32_t numberOfFeatures() const { return m_numberOfFeatures; };
4005 
4011  bool grouping() const { return m_grouping; };
4012 
4018  bool motion() const { return m_motion; };
4019 
4029  void setNumberOfFeatures(const uint32_t &numberOfFeatures) {
4030 
4032  {
4033  std::cout << "WARNING: The number of features requested is above recommended level!" << '\n';
4034  std::cout << "If a performance impact is noticed reduce number of features and/or framerate of camera" << '\n';
4035  std::cout << "The recommended maximum camera settings when using the feature detector is:" << '\n';
4036  std::cout << "Quarter Res: 15FPS and 1500 Features" << '\n';
4037  std::cout << "Full Res: 5FPS and 5000 Features" << '\n';
4038  }
4039 
4040  m_numberOfFeatures = numberOfFeatures;
4041 
4042  };
4043 
4049  void setGrouping(const bool &g) {
4050  m_grouping = g;
4051  }
4052 
4060  void setMotion(const uint32_t &m) {
4061  m_motion = m;
4062  }
4063 
4066  m_numberOfFeatures(feature_detector::RECOMMENDED_MAX_FEATURES_QUARTER_RES),
4067  m_grouping(true),
4068  m_motion(1)
4069  {};
4070 };
4071 
4076  public:
4079  uint8_t gm_present;
4080 
4082  uint8_t gm_id[8] = {0};
4083 
4085  int64_t gm_offset;
4086 
4088  int64_t path_delay;
4089 
4091  uint16_t steps_removed;
4092 
4095  gm_present(0),
4096  gm_offset(0),
4097  path_delay(0),
4098  steps_removed(0) {};
4099 };
4100 
4105 {
4107  numMissedHeaders(0),
4109  numImageMetaData(0),
4110  numDispatchedImage(0),
4111  numDispatchedLidar(0),
4112  numDispatchedPps(0),
4113  numDispatchedImu(0),
4117  {
4118  };
4119 
4121  {
4122  };
4123 
4124  //
4125  // The total number of sequence ids observed where headers appeared to have
4126  // been missed
4127  std::size_t numMissedHeaders;
4128 
4129  //
4130  // The number of UDP assemblers that were dropped from the depth cache
4131  // while awaiting assembly
4133 
4134  //
4135  // The number of image metadata messages that were received
4136  std::size_t numImageMetaData;
4137 
4138  //
4139  // The number of images that were dispatched
4140  std::size_t numDispatchedImage;
4141 
4142  //
4143  // The number of lidar scans that were dispatched
4144  std::size_t numDispatchedLidar;
4145 
4146  //
4147  // The number of dispatched PPS messages
4148  std::size_t numDispatchedPps;
4149 
4150  //
4151  // The number of dispatched IMU messages
4152  std::size_t numDispatchedImu;
4153 
4154  //
4155  // The number of dispatched compressed images
4157 
4158  //
4159  // The number of dispatched ground surface spline events
4161 
4162  //
4163  // The number of dispatched AprilTag detection events
4165 
4166  //
4167  // The number of dispatached feature detections
4169 };
4170 
4171 } // namespace system
4172 } // namespace multisense
4173 } // namespace crl
4174 
4175 #if defined (_MSC_VER)
4176 #pragma warning (pop)
4177 #endif
4178 
4179 #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:274
crl::multisense::image::AuxConfig::m_fy
float m_fy
Definition: MultiSenseTypes.hh:1782
crl::multisense::image::Config::ty
float ty() const
Query the current camera calibrations stereo baseline.
Definition: MultiSenseTypes.hh:1269
crl::multisense::image::AuxConfig::enableSharpening
bool enableSharpening() const
Query whether sharpening is enabled or not on the aux camera.
Definition: MultiSenseTypes.hh:1736
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:2840
crl::multisense::system::GroundSurfaceParams::ground_surface_base_model
int ground_surface_base_model
The model to apply to the raw pointcloud data before modeling with a B-Spline.
Definition: MultiSenseTypes.hh:3727
crl::multisense::system::GroundSurfaceParams::ground_surface_pointcloud_max_range_m
float ground_surface_pointcloud_max_range_m
The max pointcloud range (along the z dimension / optical axis) after applying external transform,...
Definition: MultiSenseTypes.hh:3744
crl::multisense::imu::Config
Class used to store a specific IMU configuration.
Definition: MultiSenseTypes.hh:2799
crl::multisense::imu::Config::enabled
bool enabled
A boolean flag indicating whether the given IMU source is currently enabled.
Definition: MultiSenseTypes.hh:2806
crl::multisense::feature_detector::Feature::y
uint16_t y
Definition: MultiSenseTypes.hh:2989
crl::multisense::image::ExposureConfig::m_autoExposureRoiY
uint16_t m_autoExposureRoiY
Definition: MultiSenseTypes.hh:697
crl::multisense::image::AuxConfig::gain
float gain() const
Query the current image configuration's gain setting.
Definition: MultiSenseTypes.hh:1587
crl::multisense::system::DeviceInfo::DeviceInfo
DeviceInfo()
Default constructor.
Definition: MultiSenseTypes.hh:3306
crl::multisense::image::Header::exposure
uint32_t exposure
The image exposure time in microseconds.
Definition: MultiSenseTypes.hh:472
crl::multisense::feature_detector::RECOMMENDED_MAX_FEATURES_QUARTER_RES
static CRL_CONSTEXPR int RECOMMENDED_MAX_FEATURES_QUARTER_RES
The recommended maximum number of features for quarter resolution camera operation.
Definition: MultiSenseTypes.hh:2984
crl::multisense::ground_surface::Header
Class containing Header information for a Ground Surface Spline callback.
Definition: MultiSenseTypes.hh:2878
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:980
crl::multisense::system::ExternalCalibration::y
float y
The external y translation of the MultiSense in meters.
Definition: MultiSenseTypes.hh:3630
crl::multisense::Status_Ok
static CRL_CONSTEXPR Status Status_Ok
Definition: MultiSenseTypes.hh:98
crl::multisense::lighting::Config::getInvertPulse
bool getInvertPulse() const
Get whether or not the LED pulse is inverted.
Definition: MultiSenseTypes.hh:2393
crl::multisense::Source_Compressed_Aux
static CRL_CONSTEXPR DataSource Source_Compressed_Aux
Definition: MultiSenseTypes.hh:149
crl::multisense::image::AuxConfig::m_profile
CameraProfile m_profile
Definition: MultiSenseTypes.hh:1774
crl::multisense::image::Config::autoWhiteBalanceDecay
uint32_t autoWhiteBalanceDecay() const
Query the current image configuration's white-balance decay rate.
Definition: MultiSenseTypes.hh:1127
crl::multisense::image::Config::whiteBalanceBlue
float whiteBalanceBlue() const
Query the current image configuration's blue white-balance setting.
Definition: MultiSenseTypes.hh:1111
crl::multisense::image::Config::m_wbBlue
float m_wbBlue
Definition: MultiSenseTypes.hh:1329
crl::multisense::system::PtpStatus
PTP status data associated with a specific stamped MultiSense message.
Definition: MultiSenseTypes.hh:4075
crl::multisense::system::DeviceInfo::motorType
uint32_t motorType
The type of the sensor's motor.
Definition: MultiSenseTypes.hh:3299
crl::multisense::system::StatusMessage::inputCurrent
float inputCurrent
The current drawn from the input power supply by the MultiSense.
Definition: MultiSenseTypes.hh:3512
crl::multisense::RemoteHeadSyncGroup::RemoteHeadSyncGroup
RemoteHeadSyncGroup()
Default constructor.
Definition: MultiSenseTypes.hh:239
crl::multisense::Source_Compressed_Rectified_Aux
static CRL_CONSTEXPR DataSource Source_Compressed_Rectified_Aux
Definition: MultiSenseTypes.hh:152
crl::multisense::image::ExposureConfig::autoExposureTargetIntensity
float autoExposureTargetIntensity() const
Query the current image configuration's auto-exposure target Intensity.
Definition: MultiSenseTypes.hh:640
crl::multisense::system::DeviceInfo::buildDate
std::string buildDate
The date the device was manufactured.
Definition: MultiSenseTypes.hh:3257
crl::multisense::system::GroundSurfaceParams::ground_surface_pointcloud_max_height_m
float ground_surface_pointcloud_max_height_m
The max pointcloud height (along the y dimension) after applying external transform,...
Definition: MultiSenseTypes.hh:3758
crl::multisense::image::AuxConfig::setAutoExposure
void setAutoExposure(bool e)
Set auto-exposure enable flag.
Definition: MultiSenseTypes.hh:1378
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:474
crl::multisense::image::TransmitDelay::delay
int delay
Delay between completing a frame and actually sending it over the network (in ms)
Definition: MultiSenseTypes.hh:1899
crl::multisense::image::Header::bitsPerPixel
uint32_t bitsPerPixel
Bits per pixel in the image.
Definition: MultiSenseTypes.hh:459
crl::multisense::system::ChannelStatistics::numImageMetaData
std::size_t numImageMetaData
Definition: MultiSenseTypes.hh:4136
crl::multisense::system::GroundSurfaceParams::GroundSurfaceParams
GroundSurfaceParams()
Default constructor.
Definition: MultiSenseTypes.hh:3782
crl::multisense::image::ExposureConfig
Definition: MultiSenseTypes.hh:509
crl::multisense::feature_detector::Feature::angle
uint8_t angle
Definition: MultiSenseTypes.hh:2990
crl::multisense::image::Config::roll
float roll() const
Query the current camera calibrations roll value.
Definition: MultiSenseTypes.hh:1290
crl::multisense::image::Calibration
Class used For querying/setting camera calibration.
Definition: MultiSenseTypes.hh:1867
crl::multisense::Source_Luma_Rectified_Right
static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Right
Definition: MultiSenseTypes.hh:123
crl::multisense::Source_AprilTag_Detections
static CRL_CONSTEXPR DataSource Source_AprilTag_Detections
Definition: MultiSenseTypes.hh:138
crl::multisense::lighting::Config::setInvertPulse
bool setInvertPulse(const bool invert)
Invert the output signal that drives lighting.
Definition: MultiSenseTypes.hh:2406
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:583
crl::multisense::feature_detector::Header::timeNanoSeconds
uint32_t timeNanoSeconds
Definition: MultiSenseTypes.hh:3006
crl::multisense::lighting::Config::getStartupTime
uint32_t getStartupTime() const
Get the startup time offset of the led in microseconds The LED or output trigger is triggered this ma...
Definition: MultiSenseTypes.hh:2367
crl::multisense::image::Config::pitch
float pitch() const
Query the current camera calibrations pitch value.
Definition: MultiSenseTypes.hh:1300
crl::multisense::Source_Disparity_Aux
static CRL_CONSTEXPR DataSource Source_Disparity_Aux
Definition: MultiSenseTypes.hh:146
crl::multisense::image::AuxConfig::setGain
void setGain(float g)
Set the desired output image's gain.
Definition: MultiSenseTypes.hh:1361
crl::multisense::image::AuxConfig::setAutoExposureDecay
void setAutoExposureDecay(uint32_t d)
Set the desired auto-exposure decay rate.
Definition: MultiSenseTypes.hh:1394
crl::multisense::image::Calibration::right
Data right
Full resolution camera calibration corresponding to the right camera.
Definition: MultiSenseTypes.hh:1890
crl::multisense::lighting::Config::m_invertPulse
bool m_invertPulse
Definition: MultiSenseTypes.hh:2451
crl::multisense::system::GroundSurfaceParams::ground_surface_obstacle_height_thresh_m
float ground_surface_obstacle_height_thresh_m
This is the height threshold, in meters, that a cluster of points must be above the initial ground su...
Definition: MultiSenseTypes.hh:3766
crl::multisense::image::ExposureConfig::autoExposureDecay
uint32_t autoExposureDecay() const
Query the current image configuration's auto-exposure decay rate.
Definition: MultiSenseTypes.hh:632
crl::multisense::system::DeviceInfo::name
std::string name
The name of a given device.
Definition: MultiSenseTypes.hh:3255
crl::multisense::image::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks of image data.
Definition: MultiSenseTypes.hh:506
crl::multisense::compressed_image::Header::height
uint32_t height
Height of the image.
Definition: MultiSenseTypes.hh:2831
crl::multisense::image::ExposureConfig::m_gain
float m_gain
Definition: MultiSenseTypes.hh:702
crl::multisense::imu::Header::samples
std::vector< Sample > samples
A vector of samples from the sensor.
Definition: MultiSenseTypes.hh:2613
crl::multisense::image::AuxConfig::fx
float fx() const
Query the current aux camera calibration rectified projection focal length in the x dimension.
Definition: MultiSenseTypes.hh:1545
crl::multisense::image::AuxConfig::setAutoWhiteBalance
void setAutoWhiteBalance(bool e)
Set the white-balance enable flag.
Definition: MultiSenseTypes.hh:1431
crl::multisense::image::AuxConfig::autoExposureDecay
uint32_t autoExposureDecay() const
Query the current image configuration's auto-exposure decay rate.
Definition: MultiSenseTypes.hh:1619
crl::multisense::image::Config::m_profile
CameraProfile m_profile
Definition: MultiSenseTypes.hh:1338
crl::multisense::Source_Raw_Aux
static CRL_CONSTEXPR DataSource Source_Raw_Aux
Definition: MultiSenseTypes.hh:142
crl::multisense::Remote_Head_0
static CRL_CONSTEXPR RemoteHeadChannel Remote_Head_0
The Remote Head Camera at position 0.
Definition: MultiSenseTypes.hh:210
crl::multisense::system::StatusMessage::StatusMessage
StatusMessage()
Default constructor for a single StatusMessage object.
Definition: MultiSenseTypes.hh:3524
crl::multisense::image::Config::setAutoWhiteBalanceDecay
void setAutoWhiteBalanceDecay(uint32_t d)
Set the white-balance decay rate.
Definition: MultiSenseTypes.hh:931
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:2819
crl::multisense::apriltag::Header::timestamp
int64_t timestamp
The frame timestamp (nanoseconds) of the image that the apriltags were detected on.
Definition: MultiSenseTypes.hh:2959
crl::multisense::lidar::Header::spindleAngleEnd
int32_t spindleAngleEnd
The spindle angle in microradians corresponding to the end of a laser scan.
Definition: MultiSenseTypes.hh:2044
crl::multisense::Source_Compressed_Left
static CRL_CONSTEXPR DataSource Source_Compressed_Left
Definition: MultiSenseTypes.hh:147
crl::multisense::image::Config::autoExposureDecay
uint32_t autoExposureDecay() const
Query the current image configuration's auto-exposure decay rate.
Definition: MultiSenseTypes.hh:1079
crl::multisense::image::Config::autoWhiteBalance
bool autoWhiteBalance() const
Query the current image configuration's white-balance enable setting.
Definition: MultiSenseTypes.hh:1119
crl::multisense::image::AuxConfig::autoExposure
bool autoExposure() const
Query the current image configuration's auto-exposure enable setting.
Definition: MultiSenseTypes.hh:1603
crl::multisense::imu::Info::ranges
std::vector< RangeEntry > ranges
The various ranges and resolutions available for a specific IMU source.
Definition: MultiSenseTypes.hh:2700
crl::multisense::image::AuxConfig::setAutoExposureTargetIntensity
void setAutoExposureTargetIntensity(float d)
Set the desired auto-exposure target Intensity.
Definition: MultiSenseTypes.hh:1402
crl::multisense::ground_surface::Header::controlPointsBitsPerPixel
uint32_t controlPointsBitsPerPixel
Bits per pixel in the dynamically-sized control points array.
Definition: MultiSenseTypes.hh:2888
crl::multisense::apriltag::Header::ApriltagDetection
Definition: MultiSenseTypes.hh:2931
crl::multisense::image::Config::exposure
uint32_t exposure() const
Query the current image configuration's exposure setting.
Definition: MultiSenseTypes.hh:1055
crl::multisense::image::Config::cameraProfile
CameraProfile cameraProfile() const
Query the current image configurations camera profile.
Definition: MultiSenseTypes.hh:1189
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:285
crl::multisense::image::AuxConfig::autoExposureMax
uint32_t autoExposureMax() const
Query the current image configuration's maximum auto-exposure value.
Definition: MultiSenseTypes.hh:1611
MULTISENSE_API
#define MULTISENSE_API
Definition: MultiSenseTypes.hh:65
crl::multisense::image::AuxConfig::autoExposureTargetIntensity
float autoExposureTargetIntensity() const
Query the current image configuration's auto-exposure target intensity.
Definition: MultiSenseTypes.hh:1627
crl::multisense::ImageCompressionCodec
uint32_t ImageCompressionCodec
Image compression codec typedef indicating the compression scheme which was used on the compressed ou...
Definition: MultiSenseTypes.hh:191
crl::multisense::lidar::Header
Class which stores Header information for a lidar scan.
Definition: MultiSenseTypes.hh:2022
crl::multisense::image::Config::autoExposureRoiX
uint16_t autoExposureRoiX() const
Query the current image configuration's auto-exposure ROI X value.
Definition: MultiSenseTypes.hh:1157
crl::multisense::imu::Info::device
std::string device
The device name for a specific IMU source.
Definition: MultiSenseTypes.hh:2694
crl::multisense::Source_Compressed_Rectified_Right
static CRL_CONSTEXPR DataSource Source_Compressed_Rectified_Right
Definition: MultiSenseTypes.hh:151
crl::multisense::feature_detector::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for feature_detector data.
Definition: MultiSenseTypes.hh:3024
crl::multisense::imu::Info::RangeEntry::resolution
float resolution
The resolution setting for a given IMU source.
Definition: MultiSenseTypes.hh:2688
crl::multisense::system::DeviceInfo::laserType
uint32_t laserType
The type of the sensor's laser.
Definition: MultiSenseTypes.hh:3294
crl::multisense::ground_surface::Header::success
uint8_t success
Success flag for B-Spline fitting process — no control points will be available if this is false.
Definition: MultiSenseTypes.hh:2885
crl::multisense::image::AuxConfig::m_hdrEnabled
bool m_hdrEnabled
Definition: MultiSenseTypes.hh:1773
crl::multisense::system::ExternalCalibration::pitch
float pitch
The external pitch translation of the MultiSense in degrees.
Definition: MultiSenseTypes.hh:3639
crl::multisense::image::Config::autoExposureRoiY
uint16_t autoExposureRoiY() const
Query the current image configuration's auto-exposure ROI Y value.
Definition: MultiSenseTypes.hh:1164
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:2825
crl::multisense::image::Header::height
uint32_t height
Height of the image.
Definition: MultiSenseTypes.hh:463
crl::multisense::system::ApriltagParams::quad_detection_decimate
double quad_detection_decimate
Amount to decimate image before detecting quads.
Definition: MultiSenseTypes.hh:3859
crl::multisense::system::DeviceInfo::imagerHeight
uint32_t imagerHeight
The maximum height of the sensor's imager.
Definition: MultiSenseTypes.hh:3273
crl::multisense::image::AuxConfig::setGamma
void setGamma(const float g)
Set the gamma correction factor.
Definition: MultiSenseTypes.hh:1499
crl::multisense::image::AuxConfig::setHdr
void setHdr(bool e)
Set the HDR enable flag.
Definition: MultiSenseTypes.hh:1459
crl::multisense::system::FeatureDetectorConfig::grouping
bool grouping() const
Query the status of the feature detector feature grouping.
Definition: MultiSenseTypes.hh:4011
crl::multisense::feature_detector::Header::features
std::vector< Feature > features
Definition: MultiSenseTypes.hh:3017
crl::multisense::image::Config::setAutoExposure
void setAutoExposure(bool e)
Set auto-exposure enable flag.
Definition: MultiSenseTypes.hh:870
crl::multisense::system::GroundSurfaceParams::ground_surface_pointcloud_decimation
int ground_surface_pointcloud_decimation
The decimation factor for the disparity image when generating the pointcloud.
Definition: MultiSenseTypes.hh:3740
crl::multisense::lidar::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks of lidar data.
Definition: MultiSenseTypes.hh:2069
crl::multisense::image::PacketDelay
Definition: MultiSenseTypes.hh:1903
crl::multisense::Source_Imu
static CRL_CONSTEXPR DataSource Source_Imu
Definition: MultiSenseTypes.hh:140
crl::multisense::image::Config::Config
Config()
Default constructor for a image configuration.
Definition: MultiSenseTypes.hh:1316
crl::multisense::image::ExposureConfig::setAutoExposureMax
void setAutoExposureMax(uint32_t m)
Set the desired maximum auto-exposure value.
Definition: MultiSenseTypes.hh:541
crl::multisense::image::Config::m_fy
float m_fy
Definition: MultiSenseTypes.hh:1343
crl::multisense::image::Histogram::Histogram
Histogram()
Default constructor.
Definition: MultiSenseTypes.hh:1955
crl::multisense::system::DeviceInfo::pcbs
std::vector< PcbInfo > pcbs
The information for all the PCBs in the device.
Definition: MultiSenseTypes.hh:3264
crl::multisense::image::ExposureConfig::m_aeThresh
float m_aeThresh
Definition: MultiSenseTypes.hh:694
crl::multisense::system::NetworkConfig::ipv4Address
std::string ipv4Address
An Ipv4 address corresponding to a sensor.
Definition: MultiSenseTypes.hh:3393
crl::multisense::image::Calibration::aux
Data aux
Full resolution camera calibration corresponding to aux color camera.
Definition: MultiSenseTypes.hh:1892
crl::multisense::image::Config::setResolution
void setResolution(uint32_t w, uint32_t h)
Set a desired output resolution.
Definition: MultiSenseTypes.hh:804
crl::multisense::system::ChannelStatistics
A struct for storing statistics for a channel object.
Definition: MultiSenseTypes.hh:4104
crl::multisense::Source_Disparity
static CRL_CONSTEXPR DataSource Source_Disparity
Definition: MultiSenseTypes.hh:127
crl::multisense::lighting::Config::setStartupTime
bool setStartupTime(uint32_t ledTransientResponse_us)
Set the transient startup time of the led, for better synchronization.
Definition: MultiSenseTypes.hh:2380
crl::multisense::image::Header::source
DataSource source
DataSource corresponding to imageDataP.
Definition: MultiSenseTypes.hh:457
crl::multisense::imu::Info::name
std::string name
The name of a specific IMU source.
Definition: MultiSenseTypes.hh:2692
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:2809
crl::multisense::feature_detector::RECOMMENDED_MAX_FEATURES_FULL_RES
static CRL_CONSTEXPR int RECOMMENDED_MAX_FEATURES_FULL_RES
The recommended maximum number of features for full resolution camera operation.
Definition: MultiSenseTypes.hh:2982
crl::multisense::image::PacketDelay::enable
bool enable
Enable interpacket delay, should be used when client network cannot handle inbound messages.
Definition: MultiSenseTypes.hh:1907
crl::multisense::Remote_Head_VPB
static CRL_CONSTEXPR RemoteHeadChannel Remote_Head_VPB
The Remote Head Vision Processor Board.
Definition: MultiSenseTypes.hh:208
crl::multisense::image::AuxConfig::m_wbEnabled
bool m_wbEnabled
Definition: MultiSenseTypes.hh:1770
crl::multisense::system::DeviceInfo::lensType
uint32_t lensType
The type of the sensor's lens.
Definition: MultiSenseTypes.hh:3278
crl::multisense::Source_Feature_Right
static CRL_CONSTEXPR DataSource Source_Feature_Right
Definition: MultiSenseTypes.hh:134
crl::multisense::lidar::Header::intensitiesP
const IntensityType * intensitiesP
Laser intensity values corresponding to each laser range point.
Definition: MultiSenseTypes.hh:2057
crl::multisense::compressed_image::Header::framesPerSecond
float framesPerSecond
The number of frames per second currently streaming from the device.
Definition: MultiSenseTypes.hh:2844
crl::multisense::system::FeatureDetectorConfig
Example code showing usage of the onboard feature detector.
Definition: MultiSenseTypes.hh:3959
crl::multisense::Remote_Head_Invalid
static CRL_CONSTEXPR RemoteHeadChannel Remote_Head_Invalid
Invalid Remote Head position.
Definition: MultiSenseTypes.hh:218
crl::multisense::system::GroundSurfaceParams::ground_surface_pointcloud_grid_size
float ground_surface_pointcloud_grid_size
This is the size of grid dimension that the poiontcloud is binned into along the X/Z plane.
Definition: MultiSenseTypes.hh:3732
crl::multisense::system::DeviceInfo::nominalFocalLength
float nominalFocalLength
The nominal focal length for the lens in meters.
Definition: MultiSenseTypes.hh:3282
crl::multisense::feature_detector::Header::numDescriptors
uint16_t numDescriptors
Definition: MultiSenseTypes.hh:3016
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:183
crl::multisense::image::Config::setAutoWhiteBalanceThresh
void setAutoWhiteBalanceThresh(float t)
Set the white-balance threshold.
Definition: MultiSenseTypes.hh:939
crl::multisense::apriltag::Header
Class containing Header information for a apriltag callback.
Definition: MultiSenseTypes.hh:2929
crl::multisense::image::Config::m_gain
float m_gain
Definition: MultiSenseTypes.hh:1327
crl::multisense::Detail_Disparity
static CRL_CONSTEXPR CameraProfile Detail_Disparity
User would like more detail in the disparity image.
Definition: MultiSenseTypes.hh:174
crl::multisense::feature_detector::Feature::resp
uint8_t resp
Definition: MultiSenseTypes.hh:2991
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:2286
crl::multisense::system::DeviceInfo::laserName
std::string laserName
The name of the sensor's laser.
Definition: MultiSenseTypes.hh:3292
crl::multisense::feature_detector::Header::numOctaves
uint16_t numOctaves
Definition: MultiSenseTypes.hh:3010
crl::multisense::system::VersionInfo::apiBuildDate
std::string apiBuildDate
The build date of libMultiSense.
Definition: MultiSenseTypes.hh:3129
crl::multisense::image::ExposureConfig::setAutoExposureTargetIntensity
void setAutoExposureTargetIntensity(float d)
Set the desired auto-exposure target Intensity .
Definition: MultiSenseTypes.hh:557
crl::multisense::lighting::Config::setNumberOfPulses
bool setNumberOfPulses(const uint32_t numPulses)
Set the number of pulses of the light within a single exposure This is used to trigger the light or o...
Definition: MultiSenseTypes.hh:2354
crl::multisense::system::DeviceInfo
Class used to store device information specific to a sensor.
Definition: MultiSenseTypes.hh:3211
crl::multisense::system::FeatureDetectorConfig::motion
bool motion() const
Query the status of the feature detector motion detection.
Definition: MultiSenseTypes.hh:4018
crl::multisense::image::AuxConfig::whiteBalanceBlue
float whiteBalanceBlue() const
Query the current image configuration's blue white-balance setting.
Definition: MultiSenseTypes.hh:1651
crl::multisense::apriltag::Header::numDetections
uint32_t numDetections
The number of apriltags that were detected.
Definition: MultiSenseTypes.hh:2965
crl::multisense::image::AuxConfig::exposure
uint32_t exposure() const
Query the current image configuration's exposure setting.
Definition: MultiSenseTypes.hh:1595
crl::multisense::lighting::Config::setFlash
void setFlash(bool onOff)
Turn on/off light flashing.
Definition: MultiSenseTypes.hh:2268
crl::multisense::system::ChannelStatistics::numDispatchedGroundSurfaceSpline
std::size_t numDispatchedGroundSurfaceSpline
Definition: MultiSenseTypes.hh:4160
crl::multisense::compressed_image::Header::gain
float gain
The imager gain the image was captured with.
Definition: MultiSenseTypes.hh:2842
crl::multisense::system::PtpStatus::gm_offset
int64_t gm_offset
Offset of camera PHC to PTP grandmaster clock in nanosec.
Definition: MultiSenseTypes.hh:4085
crl::multisense::Source_Ground_Surface_Spline_Data
static CRL_CONSTEXPR DataSource Source_Ground_Surface_Spline_Data
Definition: MultiSenseTypes.hh:136
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:3416
crl::multisense::system::ApriltagParams::family
std::string family
Apriltag family to detect.
Definition: MultiSenseTypes.hh:3847
crl::multisense::system::ChannelStatistics::~ChannelStatistics
~ChannelStatistics()
Definition: MultiSenseTypes.hh:4120
crl::multisense::system::DeviceMode
Class used query the device modes for a given sensor.
Definition: MultiSenseTypes.hh:3056
crl::multisense::image::Histogram
Class which stores a image histogram from a camera image.
Definition: MultiSenseTypes.hh:1949
crl::multisense::image::RemoteHeadConfig
Definition: MultiSenseTypes.hh:1968
crl::multisense::image::Config::cy
float cy() const
Query the current camera calibrations left rectified image center in the y dimension.
Definition: MultiSenseTypes.hh:1248
crl::multisense::feature_detector::Header::timeSeconds
uint32_t timeSeconds
Definition: MultiSenseTypes.hh:3005
crl::multisense::image::AuxConfig::setWhiteBalance
void setWhiteBalance(float r, float b)
Set the desired image white-balance.
Definition: MultiSenseTypes.hh:1422
crl::multisense::system::StatusMessage::fpgaTemperature
float fpgaTemperature
The temperature of the FPGA.
Definition: MultiSenseTypes.hh:3499
crl::multisense::feature_detector::Header::source
DataSource source
Definition: MultiSenseTypes.hh:3003
crl::multisense::system::PtpStatus::path_delay
int64_t path_delay
Estimated delay of syncronization messages from master in nanosec.
Definition: MultiSenseTypes.hh:4088
crl::multisense::image::RemoteHeadConfig::m_syncGroups
std::vector< RemoteHeadSyncGroup > m_syncGroups
The groups of remote head cameras to be synchronized.
Definition: MultiSenseTypes.hh:2003
crl::multisense::image::Config::fps
float fps() const
Query the current image configuration's frames-per-second setting.
Definition: MultiSenseTypes.hh:1039
crl::multisense::Source_Chroma_Aux
static CRL_CONSTEXPR DataSource Source_Chroma_Aux
Definition: MultiSenseTypes.hh:145
crl::multisense::image::AuxConfig::cx
float cx() const
Query the current aux camera calibration aux rectified image center in the x dimension.
Definition: MultiSenseTypes.hh:1568
crl::multisense::lidar::Header::Header
Header()
Default constructor.
Definition: MultiSenseTypes.hh:2028
crl::multisense::imu::Info::RateEntry::sampleRate
float sampleRate
The sample rate of a given IMU source in Hz.
Definition: MultiSenseTypes.hh:2675
crl::multisense::system::StatusMessage::camerasOk
bool camerasOk
A boolean flag indicating if the imagers are functioning.
Definition: MultiSenseTypes.hh:3481
crl::multisense::image::AuxConfig::hdrEnabled
bool hdrEnabled() const
Query the current image configuration's HDR enable flag.
Definition: MultiSenseTypes.hh:1682
crl::multisense::apriltag::Header::imageSource
std::string imageSource
The image source that the apriltags were detected on.
Definition: MultiSenseTypes.hh:2961
crl::multisense::imu::Sample::y
float y
y data for each sample
Definition: MultiSenseTypes.hh:2574
crl::multisense::system::ExternalCalibration::ExternalCalibration
ExternalCalibration()
Default constructor.
Definition: MultiSenseTypes.hh:3645
crl::multisense::system::VersionInfo::sensorFirmwareVersion
VersionType sensorFirmwareVersion
The version type of the sensor firmware.
Definition: MultiSenseTypes.hh:3136
crl::multisense::apriltag::Header::ApriltagDetection::id
uint32_t id
The ID of the tag.
Definition: MultiSenseTypes.hh:2935
crl::multisense::image::ExposureConfig::m_autoExposureRoiHeight
uint16_t m_autoExposureRoiHeight
Definition: MultiSenseTypes.hh:699
crl::multisense::Remote_Head_3
static CRL_CONSTEXPR RemoteHeadChannel Remote_Head_3
The Remote Head Camera at position 3.
Definition: MultiSenseTypes.hh:216
crl::multisense::image::Config::setAutoExposureMax
void setAutoExposureMax(uint32_t m)
Set the desired maximum auto-exposure value.
Definition: MultiSenseTypes.hh:878
crl::multisense::image::Config::autoExposureThresh
float autoExposureThresh() const
Query the current image configuration's auto-exposure threshold.
Definition: MultiSenseTypes.hh:1095
crl::multisense::feature_detector::Header::averageXMotion
uint16_t averageXMotion
Definition: MultiSenseTypes.hh:3013
crl::multisense::lighting::Config::m_numberPulses
uint32_t m_numberPulses
Definition: MultiSenseTypes.hh:2449
crl::multisense::apriltag::Header::ApriltagDetection::decisionMargin
float decisionMargin
The quality/confidence of the binary decoding process average difference between intensity of data bi...
Definition: MultiSenseTypes.hh:2941
crl::multisense::system::FeatureDetectorConfig::m_numberOfFeatures
uint32_t m_numberOfFeatures
numberOfFeatures The maximum features to be searched for in one image.
Definition: MultiSenseTypes.hh:3971
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:1150
crl::multisense::image::Config::setWidth
void setWidth(uint32_t w)
Set the width of the desired output resolution.
Definition: MultiSenseTypes.hh:825
crl::multisense::Source_Chroma_Left
static CRL_CONSTEXPR DataSource Source_Chroma_Left
Definition: MultiSenseTypes.hh:124
crl::multisense::feature_detector::Header::octaveHeight
uint16_t octaveHeight
Definition: MultiSenseTypes.hh:3009
crl::multisense::image::Config::setAutoExposureThresh
void setAutoExposureThresh(float t)
Set the desired auto-exposure threshold.
Definition: MultiSenseTypes.hh:903
crl::multisense::lighting::MAX_DUTY_CYCLE
static CRL_CONSTEXPR float MAX_DUTY_CYCLE
The maximum duty cycle for adjusting light intensity.
Definition: MultiSenseTypes.hh:2170
crl::multisense::image::Header::imageLength
uint32_t imageLength
The length of the image data stored in imageDataP.
Definition: MultiSenseTypes.hh:478
crl::multisense::Remote_Head_1
static CRL_CONSTEXPR RemoteHeadChannel Remote_Head_1
The Remote Head Camera at position 1.
Definition: MultiSenseTypes.hh:212
crl::multisense::system::StatusMessage::laserMotorOk
bool laserMotorOk
A boolean flag indicating if the laser motor controller is functioning.
Definition: MultiSenseTypes.hh:3477
crl::multisense::system::StatusMessage::powerSupplyTemperature
float powerSupplyTemperature
The temperature of the internal switching mode power supply.
Definition: MultiSenseTypes.hh:3496
crl::multisense::pps::Header
Class containing Header information for a PPS event.
Definition: MultiSenseTypes.hh:2517
crl::multisense::lidar::Calibration
Class used to store a laser calibration.
Definition: MultiSenseTypes.hh:2152
crl::multisense::ground_surface::Header::frameId
int64_t frameId
Unique ID used to describe an image.
Definition: MultiSenseTypes.hh:2881
crl::multisense::feature_detector::Header::ptpNanoSeconds
int64_t ptpNanoSeconds
Definition: MultiSenseTypes.hh:3007
crl::multisense::system::FeatureDetectorConfig::FeatureDetectorConfig
FeatureDetectorConfig()
Default constructor.
Definition: MultiSenseTypes.hh:4065
crl::multisense::feature_detector::Header::octaveWidth
uint16_t octaveWidth
Definition: MultiSenseTypes.hh:3008
crl::multisense::lighting::Config::m_lightStartupOffset_us
uint32_t m_lightStartupOffset_us
Definition: MultiSenseTypes.hh:2450
crl::multisense::image::ExposureConfig::setGain
void setGain(const float &g)
Set the gain applied to the camera.
Definition: MultiSenseTypes.hh:597
crl::multisense::system::GroundSurfaceParams::ground_surface_min_points_per_grid
int ground_surface_min_points_per_grid
This is the minimum number of pointcloud points which ust be within a binned grid cell in oder for th...
Definition: MultiSenseTypes.hh:3737
crl::multisense::system::DeviceInfo::imagerType
uint32_t imagerType
The type of the sensor's imager.
Definition: MultiSenseTypes.hh:3269
crl::multisense::Source_Compressed_Right
static CRL_CONSTEXPR DataSource Source_Compressed_Right
Definition: MultiSenseTypes.hh:148
crl::multisense::imu::Sample::x
float x
x data for each sample
Definition: MultiSenseTypes.hh:2566
crl::multisense::apriltag::Header::frameId
int64_t frameId
The frame ID of the image that the apriltags were detected on.
Definition: MultiSenseTypes.hh:2957
crl::multisense::Exposure_Default_Source
static CRL_CONSTEXPR DataSource Exposure_Default_Source
Definition: MultiSenseTypes.hh:159
crl::multisense::Source_Compressed_Rectified_Left
static CRL_CONSTEXPR DataSource Source_Compressed_Rectified_Left
Definition: MultiSenseTypes.hh:150
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:492
crl::multisense::system::VersionInfo::sensorFirmwareBuildDate
std::string sensorFirmwareBuildDate
The build date of the sensor firmware.
Definition: MultiSenseTypes.hh:3134
crl::multisense::image::AuxConfig::autoWhiteBalanceThresh
float autoWhiteBalanceThresh() const
Query the current image configuration's white-balance threshold.
Definition: MultiSenseTypes.hh:1675
crl::multisense::system::StatusMessage::laserOk
bool laserOk
A boolean flag indicating if the laser is functioning.
Definition: MultiSenseTypes.hh:3473
crl::multisense::image::AuxConfig::cameraProfile
CameraProfile cameraProfile() const
Query the current image configurations camera profile.
Definition: MultiSenseTypes.hh:1721
crl::multisense::User_Control
static CRL_CONSTEXPR CameraProfile User_Control
User has direct control over all settings in the image configuration.
Definition: MultiSenseTypes.hh:172
crl::multisense::system::PcbInfo::PcbInfo
PcbInfo()
Default constructor.
Definition: MultiSenseTypes.hh:3171
crl::multisense::compressed_image::Header::width
uint32_t width
Width of the image.
Definition: MultiSenseTypes.hh:2829
crl::multisense::imu::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for IMU data.
Definition: MultiSenseTypes.hh:2619
crl::multisense::system::PtpStatus::steps_removed
uint16_t steps_removed
Number of network hops from GM to local clock.
Definition: MultiSenseTypes.hh:4091
crl::multisense::system::NetworkConfig::ipv4Netmask
std::string ipv4Netmask
An Ipv4 netmask corresponding to a sensor.
Definition: MultiSenseTypes.hh:3397
crl::multisense::feature_detector::Descriptor::d
uint32_t d[8]
Definition: MultiSenseTypes.hh:2997
crl::multisense::ground_surface::Header::controlPointsHeight
uint32_t controlPointsHeight
Height of the dynamically-sized control points array.
Definition: MultiSenseTypes.hh:2892
crl::multisense::image::Config::height
uint32_t height() const
Query the current image configuration's height.
Definition: MultiSenseTypes.hh:1022
crl::multisense::lighting::SensorStatus::ambientLightPercentage
float ambientLightPercentage
This represents the percentage of light the ambient sensor currently sees.
Definition: MultiSenseTypes.hh:2499
crl::multisense::HeaderBase::~HeaderBase
virtual ~HeaderBase()
Definition: MultiSenseTypes.hh:286
crl::multisense::image::Config::gain
float gain() const
Query the current image configuration's gain setting.
Definition: MultiSenseTypes.hh:1046
crl::multisense::image::AuxConfig::cy
float cy() const
Query the current aux camera calibration aux rectified image center in the y dimension.
Definition: MultiSenseTypes.hh:1580
crl::multisense::system::StatusMessage::rightImagerTemperature
float rightImagerTemperature
The temperature of the right imager.
Definition: MultiSenseTypes.hh:3505
crl::multisense::image::AuxConfig::m_wbDecay
uint32_t m_wbDecay
Definition: MultiSenseTypes.hh:1771
crl::multisense::system::DeviceInfo::hardwareRevision
uint32_t hardwareRevision
The hardware revision of the given sensor.
Definition: MultiSenseTypes.hh:3261
crl::multisense::system::NetworkConfig::ipv4Gateway
std::string ipv4Gateway
An Ipv4 gateway corresponding to a sensor.
Definition: MultiSenseTypes.hh:3395
crl::multisense::Source_Pps
static CRL_CONSTEXPR DataSource Source_Pps
Definition: MultiSenseTypes.hh:141
crl::multisense::feature_detector::Feature
Definition: MultiSenseTypes.hh:2987
crl::multisense::image::AuxConfig::setAutoExposureThresh
void setAutoExposureThresh(float t)
Set the desired auto-exposure threshold.
Definition: MultiSenseTypes.hh:1411
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:2307
crl::multisense::image::AuxConfig::autoExposureRoiWidth
uint16_t autoExposureRoiWidth() const
Query the current image configuration's auto-exposure ROI width value Will return crl::multisense::Ro...
Definition: MultiSenseTypes.hh:1705
crl::multisense::system::PtpStatus::PtpStatus
PtpStatus()
Default constructor for a single PtpStatus object.
Definition: MultiSenseTypes.hh:4094
crl::multisense::system::StatusMessage
Class containing status information for a particular device.
Definition: MultiSenseTypes.hh:3460
crl::multisense::imu::Header
Class containing Header information for an IMU callback.
Definition: MultiSenseTypes.hh:2604
crl::multisense::image::Config::cx
float cx() const
Query the current camera calibrations left rectified image center in the x dimension.
Definition: MultiSenseTypes.hh:1236
crl::multisense::HeaderBase
Base Header class for sensor callbacks.
Definition: MultiSenseTypes.hh:279
crl::multisense::image::AuxConfig::m_gamma
float m_gamma
Definition: MultiSenseTypes.hh:1775
crl::multisense::system::ExternalCalibration::x
float x
The external x translation of the MultiSense in meters.
Definition: MultiSenseTypes.hh:3627
crl::multisense::image::AuxConfig::m_sharpeningLimit
uint8_t m_sharpeningLimit
Definition: MultiSenseTypes.hh:1778
crl::multisense::image::AuxConfig::gamma
float gamma() const
Query the gamma correction factor.
Definition: MultiSenseTypes.hh:1729
crl::multisense::image::AuxConfig::setAutoWhiteBalanceThresh
void setAutoWhiteBalanceThresh(float t)
Set the white-balance threshold.
Definition: MultiSenseTypes.hh:1447
crl::multisense::lidar::IntensityType
uint32_t IntensityType
The type of a single laser intensity measurement
Definition: MultiSenseTypes.hh:2014
crl::multisense::image::Config::autoExposureMax
uint32_t autoExposureMax() const
Query the current image configuration's maximum auto-exposure value.
Definition: MultiSenseTypes.hh:1071
crl::multisense::feature_detector::Feature::octave
uint8_t octave
Definition: MultiSenseTypes.hh:2992
crl::multisense::system::DeviceInfo::motorName
std::string motorName
The name of the sensor's motor.
Definition: MultiSenseTypes.hh:3297
crl::multisense::image::ExposureConfig::autoExposureMax
uint32_t autoExposureMax() const
Query the current image configuration's maximum auto-exposure value.
Definition: MultiSenseTypes.hh:624
crl::multisense::DataSource
uint64_t DataSource
Data sources typedef representing the various data sources available from sensors in the MultiSense-S...
Definition: MultiSenseTypes.hh:114
crl::multisense::system::DeviceInfo::imagerWidth
uint32_t imagerWidth
The maximum width of the sensor's imager.
Definition: MultiSenseTypes.hh:3271
crl::multisense::system::GroundSurfaceParams::ground_surface_obstacle_percentage_thresh
float ground_surface_obstacle_percentage_thresh
The percentage of points in a cell cluster that must be above the height threshold in order to classi...
Definition: MultiSenseTypes.hh:3771
crl::multisense::image::AuxConfig
Definition: MultiSenseTypes.hh:1348
crl::multisense::AprilTag
static CRL_CONSTEXPR CameraProfile AprilTag
User would like to run apriltag detector on the camera.
Definition: MultiSenseTypes.hh:185
crl::multisense::system::PcbInfo
Class used to store PCB information for the various circuit boards in a sensor.
Definition: MultiSenseTypes.hh:3160
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:1182
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:178
crl::multisense::system::ChannelStatistics::numDispatchedAprilTagDetections
std::size_t numDispatchedAprilTagDetections
Definition: MultiSenseTypes.hh:4164
crl::multisense::image::AuxConfig::setCameraProfile
void setCameraProfile(const CameraProfile &profile)
Set the operation profile for the camera to use.
Definition: MultiSenseTypes.hh:1486
crl::multisense::compressed_image::Header::Header
Header()
Default Constructor.
Definition: MultiSenseTypes.hh:2853
crl::multisense::image::ExposureConfig::m_aeMax
uint32_t m_aeMax
Definition: MultiSenseTypes.hh:692
crl::multisense::H264
static CRL_CONSTEXPR ImageCompressionCodec H264
Image data is compressed with the H.264 Codec.
Definition: MultiSenseTypes.hh:194
crl::multisense::image::AuxConfig::setSharpeningPercentage
void setSharpeningPercentage(const float &s)
Set the sharpening percentage for the aux luma channel.
Definition: MultiSenseTypes.hh:1516
crl::multisense::image::RemoteHeadConfig::syncGroups
std::vector< RemoteHeadSyncGroup > syncGroups() const
Query the groups of remote head cameras to be synchronized.
Definition: MultiSenseTypes.hh:1998
crl::multisense::apriltag::Header::success
uint8_t success
Success flag to indicate whether for the apriltag algorithm ran successfully.
Definition: MultiSenseTypes.hh:2963
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:533
crl::multisense::image::ExposureConfig::m_autoExposureRoiX
uint16_t m_autoExposureRoiX
Definition: MultiSenseTypes.hh:696
crl::multisense::image::Config::setExposure
void setExposure(uint32_t e)
Set the exposure time used to capture images.
Definition: MultiSenseTypes.hh:862
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:1336
crl::multisense::compressed_image::Header::imageDataP
const void * imageDataP
A pointer to the compressed image data.
Definition: MultiSenseTypes.hh:2848
crl::multisense::system::StatusMessage::processingPipelineOk
bool processingPipelineOk
A boolean indicating if the processing pipeline is ok.
Definition: MultiSenseTypes.hh:3492
crl::multisense::system::GroundSurfaceParams::ground_surface_pointcloud_min_width_m
float ground_surface_pointcloud_min_width_m
The min pointcloud width (along the x dimension) after applying external transform.
Definition: MultiSenseTypes.hh:3754
crl::multisense::Source_Ground_Surface_Class_Image
static CRL_CONSTEXPR DataSource Source_Ground_Surface_Class_Image
Definition: MultiSenseTypes.hh:137
crl::multisense::lighting::SensorStatus::SensorStatus
SensorStatus()
Definition: MultiSenseTypes.hh:2501
crl::multisense::image::AuxConfig::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:1476
crl::multisense::imu::Sample::Type
uint16_t Type
Typedef used to determine which data source a sample came from.
Definition: MultiSenseTypes.hh:2547
crl::multisense::feature_detector::Header::descriptors
std::vector< Descriptor > descriptors
Definition: MultiSenseTypes.hh:3018
crl::multisense::image::Config::autoWhiteBalanceThresh
float autoWhiteBalanceThresh() const
Query the current image configuration's white-balance threshold.
Definition: MultiSenseTypes.hh:1135
crl::multisense::system::VersionInfo::VersionInfo
VersionInfo()
Default constructor which initialize all values to 0.
Definition: MultiSenseTypes.hh:3148
crl::multisense::system::FeatureDetectorConfig::m_grouping
bool m_grouping
grouping Enable/Disable the grouping feature in feaure detection.
Definition: MultiSenseTypes.hh:3986
crl::multisense::image::ExposureConfig::m_autoExposureRoiWidth
uint16_t m_autoExposureRoiWidth
Definition: MultiSenseTypes.hh:698
crl::multisense::Source_Lidar_Scan
static CRL_CONSTEXPR DataSource Source_Lidar_Scan
Definition: MultiSenseTypes.hh:139
crl::multisense::image::Config::setAutoExposureDecay
void setAutoExposureDecay(uint32_t d)
Set the desired auto-exposure decay rate.
Definition: MultiSenseTypes.hh:886
crl::multisense::image::Config::yaw
float yaw() const
Query the current camera calibrations yaw value.
Definition: MultiSenseTypes.hh:1310
crl::multisense::lidar::Header::maxRange
uint32_t maxRange
The maximum range of the laser scanner in millimeters.
Definition: MultiSenseTypes.hh:2048
crl::multisense::system::DeviceInfo::lightingType
uint32_t lightingType
The lighting type supported by the sensor.
Definition: MultiSenseTypes.hh:3287
crl::multisense::image::Header::Header
Header()
Default Constructor.
Definition: MultiSenseTypes.hh:485
crl::multisense::apriltag::Header::detections
std::vector< ApriltagDetection > detections
Apriltag detections.
Definition: MultiSenseTypes.hh:2967
crl::multisense::image::Histogram::bins
uint32_t bins
The number of possible pixel values for each color channel.
Definition: MultiSenseTypes.hh:1962
crl::multisense::image::AuxConfig::setSharpeningLimit
void setSharpeningLimit(const uint8_t &s)
Set the sharpening limit.
Definition: MultiSenseTypes.hh:1526
crl::multisense::image::Calibration::left
Data left
Full resolution camera calibration corresponding to the left camera.
Definition: MultiSenseTypes.hh:1888
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:3064
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:3079
crl::multisense::Source_Luma_Aux
static CRL_CONSTEXPR DataSource Source_Luma_Aux
Definition: MultiSenseTypes.hh:143
crl::multisense::system::DeviceMode::disparities
int32_t disparities
The number of valid disparities for a given device mode.
Definition: MultiSenseTypes.hh:3066
crl::multisense::image::RemoteHeadConfig::RemoteHeadConfig
RemoteHeadConfig()
Default constructor with no sync groups.
Definition: MultiSenseTypes.hh:1974
crl::multisense::image::Config::m_gamma
float m_gamma
Definition: MultiSenseTypes.hh:1339
crl::multisense::image::Config::m_width
uint32_t m_width
Definition: MultiSenseTypes.hh:1334
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:2890
crl::multisense::lidar::Header::scanArc
int32_t scanArc
The total angular range of a individual laser scan in microradians.
Definition: MultiSenseTypes.hh:2046
crl::multisense::feature_detector::Header::averageYMotion
uint16_t averageYMotion
Definition: MultiSenseTypes.hh:3014
crl::multisense::image::AuxConfig::m_wbThresh
float m_wbThresh
Definition: MultiSenseTypes.hh:1772
crl::multisense::system::ChannelStatistics::numDispatchedFeatureDetections
std::size_t numDispatchedFeatureDetections
Definition: MultiSenseTypes.hh:4168
crl::multisense::Trigger_Internal
static CRL_CONSTEXPR TriggerSource Trigger_Internal
Default internal trigger source.
Definition: MultiSenseTypes.hh:268
crl::multisense::system::PtpStatus::gm_present
uint8_t gm_present
Status of grandmaster clock; 1 if synchronized to nonlocal GM OR if nonlocal GM was present any time ...
Definition: MultiSenseTypes.hh:4079
crl::multisense::image::Config::disparities
uint32_t disparities() const
Query the current image configuration's number of disparities.
Definition: MultiSenseTypes.hh:1031
crl::multisense::imu::Info::RangeEntry
Class containing a one valid IMU range configuration.
Definition: MultiSenseTypes.hh:2683
crl::multisense::system::DeviceInfo::serialNumber
std::string serialNumber
The serial number of the device.
Definition: MultiSenseTypes.hh:3259
crl::multisense::system::ChannelStatistics::numDispatchedLidar
std::size_t numDispatchedLidar
Definition: MultiSenseTypes.hh:4144
crl::multisense::system::ChannelStatistics::numDispatchedCompressedImage
std::size_t numDispatchedCompressedImage
Definition: MultiSenseTypes.hh:4156
crl::multisense::lighting::Config
Class used to store a specific lighting configuration.
Definition: MultiSenseTypes.hh:2257
crl::multisense::image::ExposureConfig::m_aeTargetIntensity
float m_aeTargetIntensity
Definition: MultiSenseTypes.hh:701
crl::multisense::system::DeviceInfo::nominalBaseline
float nominalBaseline
The nominal sensor baseline in meters.
Definition: MultiSenseTypes.hh:3280
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:2917
crl::multisense::image::Header::width
uint32_t width
Width of the image.
Definition: MultiSenseTypes.hh:461
crl::multisense::feature_detector::Header::scaleFactor
uint16_t scaleFactor
Definition: MultiSenseTypes.hh:3011
crl::multisense::image::Config::m_disparities
uint32_t m_disparities
Definition: MultiSenseTypes.hh:1335
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:2812
crl::multisense::imu::Info::RateEntry
Class containing a one valid IMU rate configuration.
Definition: MultiSenseTypes.hh:2673
crl::multisense::image::Config::setWhiteBalance
void setWhiteBalance(float r, float b)
Set the desired image white-balance.
Definition: MultiSenseTypes.hh:914
crl::multisense::system::GroundSurfaceParams
Class containing parameters for the ground surface modeling and obstacle detection application which ...
Definition: MultiSenseTypes.hh:3706
crl::multisense::image::Config::fx
float fx() const
Query the current camera calibrations rectified projection focal length in the x dimension.
Definition: MultiSenseTypes.hh:1213
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:476
crl::multisense::lidar::Header::spindleAngleStart
int32_t spindleAngleStart
The spindle angle in microradians corresponding to the start of a laser scan.
Definition: MultiSenseTypes.hh:2042
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:616
crl::multisense::image::ExposureConfig::exposure
uint32_t exposure() const
Query the current image configuration's exposure setting.
Definition: MultiSenseTypes.hh:608
crl::multisense::system::ExternalCalibration
A external calibration associated with the MultiSense.
Definition: MultiSenseTypes.hh:3623
crl::multisense::imu::Sample::timeMicroSeconds
uint32_t timeMicroSeconds
The time microseconds value corresponding to the specific sample.
Definition: MultiSenseTypes.hh:2558
crl::multisense::system::VersionInfo::sensorHardwareMagic
uint64_t sensorHardwareMagic
The hardware magic number.
Definition: MultiSenseTypes.hh:3141
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:2883
crl::multisense::TriggerSource
uint32_t TriggerSource
Definition: MultiSenseTypes.hh:265
crl::multisense::image::AuxConfig::sharpeningLimit
uint8_t sharpeningLimit() const
Query the limit of sharpening applied to the aux luma image.
Definition: MultiSenseTypes.hh:1750
crl::multisense::image::Header::imageDataP
const void * imageDataP
A pointer to the image data.
Definition: MultiSenseTypes.hh:480
crl::multisense::lighting::Config::enableRollingShutterLedSynchronization
bool enableRollingShutterLedSynchronization(const bool enabled)
Definition: MultiSenseTypes.hh:2422
crl::multisense::image::Config::autoExposure
bool autoExposure() const
Query the current image configuration's auto-exposure enable setting.
Definition: MultiSenseTypes.hh:1063
crl::multisense::system::FeatureDetectorConfig::m_motion
uint32_t m_motion
motion Enable / disable motion detection in the feature detector.
Definition: MultiSenseTypes.hh:3996
crl::multisense::image::AuxConfig::m_exposure
ExposureConfig m_exposure
Definition: MultiSenseTypes.hh:1767
crl::multisense::Remote_Head_2
static CRL_CONSTEXPR RemoteHeadChannel Remote_Head_2
The Remote Head Camera at position 2.
Definition: MultiSenseTypes.hh:214
crl::multisense::system::VersionInfo::apiVersion
VersionType apiVersion
The version of libMultiSense.
Definition: MultiSenseTypes.hh:3131
crl::multisense::system::StatusMessage::uptime
double uptime
The system uptime of the MultiSense in seconds.
Definition: MultiSenseTypes.hh:3465
crl::multisense::system::FeatureDetectorConfig::setGrouping
void setGrouping(const bool &g)
Set the feature grouping capability the feature detector.
Definition: MultiSenseTypes.hh:4049
crl::multisense::apriltag::Header::ApriltagDetection::hamming
uint8_t hamming
The hamming distance between the detection and the real code.
Definition: MultiSenseTypes.hh:2937
crl::multisense::compressed_image::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for compressed image data.
Definition: MultiSenseTypes.hh:2866
crl::multisense::image::Config::m_wbRed
float m_wbRed
Definition: MultiSenseTypes.hh:1330
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::feature_detector::Descriptor
Definition: MultiSenseTypes.hh:2996
crl::multisense::feature_detector::Header::motionStatus
uint16_t motionStatus
Definition: MultiSenseTypes.hh:3012
crl::multisense::system::StatusMessage::inputVoltage
float inputVoltage
The input voltage supplied to the MultiSense.
Definition: MultiSenseTypes.hh:3508
crl::multisense::image::Config::m_exposure
ExposureConfig m_exposure
Definition: MultiSenseTypes.hh:1328
crl::multisense::lidar::Header::pointCount
uint32_t pointCount
The number of points in the laser scan.
Definition: MultiSenseTypes.hh:2050
crl::multisense::image::ExposureConfig::autoExposureRoiX
uint16_t autoExposureRoiX() const
Query the current image configuration's auto-exposure ROI X value.
Definition: MultiSenseTypes.hh:655
crl::multisense::system::ApriltagParams::min_border_width
size_t min_border_width
Minimum border width that can be considered a valid tag.
Definition: MultiSenseTypes.hh:3878
crl::multisense::apriltag::Header::ApriltagDetection::family
std::string family
The family of the tag.
Definition: MultiSenseTypes.hh:2933
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:3469
crl::multisense::Exposure_Default_Target_Intensity
static CRL_CONSTEXPR float Exposure_Default_Target_Intensity
Definition: MultiSenseTypes.hh:160
crl::multisense::image::Config::setStereoPostFilterStrength
void setStereoPostFilterStrength(float s)
Set the desired stereo post-filter strength.
Definition: MultiSenseTypes.hh:951
crl::multisense::system::StatusMessage::logicPower
float logicPower
The power consumed by the MicroBlaze CPU.
Definition: MultiSenseTypes.hh:3518
CRL_CONSTEXPR
#define CRL_CONSTEXPR
Definition: MultiSenseTypes.hh:49
crl::multisense::pps::Header::timeSeconds
uint32_t timeSeconds
The local time's seconds value.
Definition: MultiSenseTypes.hh:2524
crl::multisense::ground_surface::Header::controlPointsImageDataP
const void * controlPointsImageDataP
A pointer to the dynamically-sized control points array data.
Definition: MultiSenseTypes.hh:2894
crl::multisense::image::Config::m_hdrEnabled
bool m_hdrEnabled
Definition: MultiSenseTypes.hh:1337
crl::multisense::system::ApriltagParams::ApriltagParams
ApriltagParams()
Default constructor.
Definition: MultiSenseTypes.hh:3890
crl::multisense::lighting::Config::getNumberOfPulses
uint32_t getNumberOfPulses() const
Get the number of pulses of the light per a single exposure This is used to trigger the light or outp...
Definition: MultiSenseTypes.hh:2341
crl::multisense::image::AuxConfig::autoWhiteBalance
bool autoWhiteBalance() const
Query the current image configuration's white-balance enable setting.
Definition: MultiSenseTypes.hh:1659
crl::multisense::system::DeviceMode::height
uint32_t height
The image height configuration for a given device mode.
Definition: MultiSenseTypes.hh:3062
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:2860
crl::multisense::imu::Header::sequence
uint32_t sequence
The sequence number for each header containing IMU samples.
Definition: MultiSenseTypes.hh:2609
crl::multisense::pps::Header::sensorTime
int64_t sensorTime
The sensor time in nanoseconds when a given PPS event occurred
Definition: MultiSenseTypes.hh:2521
crl::multisense::system::DeviceInfo::numberOfLights
uint32_t numberOfLights
The number of lights supported by the sensor.
Definition: MultiSenseTypes.hh:3289
crl::multisense::image::Config::whiteBalanceRed
float whiteBalanceRed() const
Query the current image configuration's red white-balance setting.
Definition: MultiSenseTypes.hh:1103
crl::multisense::Status_Exception
static CRL_CONSTEXPR Status Status_Exception
Definition: MultiSenseTypes.hh:104
crl::multisense::system::GroundSurfaceParams::ground_surface_pointcloud_min_height_m
float ground_surface_pointcloud_min_height_m
The min pointcloud height (along the y dimension) after applying external transform,...
Definition: MultiSenseTypes.hh:3762
crl::multisense::image::Header::timeMicroSeconds
uint32_t timeMicroSeconds
The time microseconds value corresponding to when the image was captured.
Definition: MultiSenseTypes.hh:469
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:2804
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:671
crl::multisense::system::PcbInfo::name
std::string name
The name of a PCB.
Definition: MultiSenseTypes.hh:3164
crl::multisense::image::Header::timeSeconds
uint32_t timeSeconds
The time seconds value corresponding to when the image was captured.
Definition: MultiSenseTypes.hh:467
crl::multisense::compressed_image::Header::timeMicroSeconds
uint32_t timeMicroSeconds
The time microseconds value corresponding to when the image was captured.
Definition: MultiSenseTypes.hh:2837
crl::multisense::system::StatusMessage::imuOk
bool imuOk
A boolean flag indicating if the imu is functioning.
Definition: MultiSenseTypes.hh:3485
crl::multisense::image::Header::frameId
int64_t frameId
Unique ID used to describe an image.
Definition: MultiSenseTypes.hh:465
crl::multisense::image::Config::setCameraProfile
void setCameraProfile(const CameraProfile &profile)
Set the operation profile for the camera to use.
Definition: MultiSenseTypes.hh:990
crl::multisense::image::ExposureConfig::ExposureConfig
ExposureConfig()
Definition: MultiSenseTypes.hh:511
crl::multisense::image::AuxConfig::m_wbRed
float m_wbRed
Definition: MultiSenseTypes.hh:1769
crl::multisense::image::ExposureConfig::setAutoExposureThresh
void setAutoExposureThresh(float t)
Set the desired auto-exposure threshold.
Definition: MultiSenseTypes.hh:566
crl::multisense::pps::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for PPS events.
Definition: MultiSenseTypes.hh:2532
crl::multisense::system::NetworkConfig::NetworkConfig
NetworkConfig()
Default constructor with the sensor factory default IP configuration.
Definition: MultiSenseTypes.hh:3402
crl::multisense::system::ChannelStatistics::numMissedHeaders
std::size_t numMissedHeaders
Definition: MultiSenseTypes.hh:4122
crl::multisense::compressed_image::Header::source
DataSource source
DataSource corresponding to imageDataP.
Definition: MultiSenseTypes.hh:2823
crl::multisense::image::Config::tz
float tz() const
Query the current camera calibrations stereo baseline.
Definition: MultiSenseTypes.hh:1280
crl::multisense::system::DeviceMode::width
uint32_t width
The image width configuration for a given device mode.
Definition: MultiSenseTypes.hh:3060
crl::multisense::image::RemoteHeadConfig::RemoteHeadConfig
RemoteHeadConfig(const std::vector< RemoteHeadSyncGroup > &sync_groups)
Constructor allowing definition of sync groups.
Definition: MultiSenseTypes.hh:1982
crl::multisense::RemoteHeadSyncGroup
Remote head sync group defines a group of remote heads which will have their image captures synchroni...
Definition: MultiSenseTypes.hh:234
crl::multisense::system::VersionInfo::sensorHardwareVersion
uint64_t sensorHardwareVersion
The hardware version of the sensor.
Definition: MultiSenseTypes.hh:3139
crl::multisense::Source_Chroma_Right
static CRL_CONSTEXPR DataSource Source_Chroma_Right
Definition: MultiSenseTypes.hh:125
crl::multisense::system::GroundSurfaceParams::ground_surface_pointcloud_max_width_m
float ground_surface_pointcloud_max_width_m
The max pointcloud width (along the x dimension) after applying external transform.
Definition: MultiSenseTypes.hh:3751
crl::multisense::image::RemoteHeadConfig::setSyncGroups
void setSyncGroups(const std::vector< RemoteHeadSyncGroup > &sync_groups)
Set the groups of remote head cameras to be synchronized.
Definition: MultiSenseTypes.hh:1991
crl::multisense::system::ApriltagParams::quad_detection_blur_sigma
double quad_detection_blur_sigma
Sigma of the Gaussian blur applied to the image before quad_detection Specified in full resolution pi...
Definition: MultiSenseTypes.hh:3855
crl::multisense::system::ChannelStatistics::numDroppedAssemblers
std::size_t numDroppedAssemblers
Definition: MultiSenseTypes.hh:4132
crl::multisense::Source_Feature_Aux
static CRL_CONSTEXPR DataSource Source_Feature_Aux
Definition: MultiSenseTypes.hh:135
crl::multisense::system::StatusMessage::externalLedsOk
bool externalLedsOk
A boolean flag indicating if the external LEDs are OK.
Definition: MultiSenseTypes.hh:3489
crl::multisense::system::NetworkConfig
Class containing the network configuration for a specific sensor.
Definition: MultiSenseTypes.hh:3389
crl::multisense::Source_Rgb_Left
static CRL_CONSTEXPR DataSource Source_Rgb_Left
Definition: MultiSenseTypes.hh:132
crl::multisense::image::AuxConfig::setAutoExposureMax
void setAutoExposureMax(uint32_t m)
Set the desired maximum auto-exposure value.
Definition: MultiSenseTypes.hh:1386
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:680
crl::multisense::feature_detector::Feature::x
uint16_t x
Definition: MultiSenseTypes.hh:2988
crl::multisense::image::Histogram::data
std::vector< uint32_t > data
The histogram data concatinated serially in GRBG order.
Definition: MultiSenseTypes.hh:1965
crl::multisense::image::ExposureConfig::m_aeEnabled
bool m_aeEnabled
Definition: MultiSenseTypes.hh:691
crl::multisense::system::VersionInfo::sensorFpgaDna
uint64_t sensorFpgaDna
The FPGA DNA.
Definition: MultiSenseTypes.hh:3143
crl::multisense::pps::Header::timeMicroSeconds
uint32_t timeMicroSeconds
The local time's microseconds value.
Definition: MultiSenseTypes.hh:2526
crl::multisense::feature_detector::Header::frameId
int64_t frameId
Definition: MultiSenseTypes.hh:3004
crl::multisense::image::AuxConfig::setExposure
void setExposure(uint32_t e)
Set the exposure time used to capture images.
Definition: MultiSenseTypes.hh:1370
crl::multisense::system::DeviceInfo::motorGearReduction
float motorGearReduction
The gear reduction for the sensor's laser assembly.
Definition: MultiSenseTypes.hh:3301
crl::multisense::lidar::Header::timeEndMicroSeconds
uint32_t timeEndMicroSeconds
The microseconds value of the time corresponding to the end of laser scan.
Definition: MultiSenseTypes.hh:2040
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:158
crl::multisense::image::Config::setHdr
void setHdr(bool e)
Set the HDR enable flag.
Definition: MultiSenseTypes.hh:963
crl::multisense::lidar::Header::timeStartMicroSeconds
uint32_t timeStartMicroSeconds
The microseconds value of the time corresponding to the start of laser scan.
Definition: MultiSenseTypes.hh:2036
crl::multisense::system::ApriltagParams::refine_quad_edges
bool refine_quad_edges
Whether or not to refine the edges before attempting to decode.
Definition: MultiSenseTypes.hh:3881
crl::multisense::Status_TimedOut
static CRL_CONSTEXPR Status Status_TimedOut
Definition: MultiSenseTypes.hh:99
crl::multisense::image::Config::m_wbThresh
float m_wbThresh
Definition: MultiSenseTypes.hh:1333
crl::multisense::image::Config::tx
float tx() const
Query the current camera calibrations stereo baseline.
Definition: MultiSenseTypes.hh:1258
crl::multisense::system::ChannelStatistics::numDispatchedImage
std::size_t numDispatchedImage
Definition: MultiSenseTypes.hh:4140
crl::multisense::imu::Sample
Class containing a single IMU sample.
Definition: MultiSenseTypes.hh:2543
crl::multisense::system::DeviceInfo::nominalRelativeAperture
float nominalRelativeAperture
The nominal relative aperature for the sensor.
Definition: MultiSenseTypes.hh:3284
crl::multisense::imu::Info::RateEntry::bandwidthCutoff
float bandwidthCutoff
The bandwith cutoff for a given IMU source in Hz.
Definition: MultiSenseTypes.hh:2677
crl::multisense::lighting::MAX_LIGHTS
static CRL_CONSTEXPR uint32_t MAX_LIGHTS
The maximum number of lights for a given sensor.
Definition: MultiSenseTypes.hh:2168
crl::multisense::system::FeatureDetectorConfig::setMotion
void setMotion(const uint32_t &m)
Set the feature motion detection capability of the feature detector Functions to enable motion detect...
Definition: MultiSenseTypes.hh:4060
crl::multisense::image::AuxConfig::m_sharpeningEnable
bool m_sharpeningEnable
Definition: MultiSenseTypes.hh:1776
crl::multisense::system::StatusMessage::imagerPower
float imagerPower
The power consumed by the imager chips.
Definition: MultiSenseTypes.hh:3521
crl::multisense::image::AuxConfig::autoExposureThresh
float autoExposureThresh() const
Query the current image configuration's auto-exposure threshold.
Definition: MultiSenseTypes.hh:1635
crl::multisense::image::Config::setGain
void setGain(float g)
Set the desired output image's gain.
Definition: MultiSenseTypes.hh:853
crl::multisense::lidar::Header::timeEndSeconds
uint32_t timeEndSeconds
The seconds value of the time corresponding to the end of laser scan.
Definition: MultiSenseTypes.hh:2038
crl::multisense::system::GroundSurfaceParams::ground_surface_adjacent_cell_search_size_m
float ground_surface_adjacent_cell_search_size_m
The size of the neighborhood to search around an obstacle cell for the lowest/minimum cell centroid h...
Definition: MultiSenseTypes.hh:3779
crl::multisense::image::Config::setGamma
void setGamma(const float g)
Set the gamma correction factor.
Definition: MultiSenseTypes.hh:1003
crl::multisense::lighting::Config::getRollingShutterLedSynchronizationStatus
bool getRollingShutterLedSynchronizationStatus(void) const
Get the setting of the rollingShutterSynchronization.
Definition: MultiSenseTypes.hh:2434
crl::multisense::Trigger_External
static CRL_CONSTEXPR TriggerSource Trigger_External
External OPTO_RX trigger input.
Definition: MultiSenseTypes.hh:270
crl::multisense::image::TransmitDelay
Definition: MultiSenseTypes.hh:1895
crl::multisense::Exposure_Default_Gain
static CRL_CONSTEXPR float Exposure_Default_Gain
Definition: MultiSenseTypes.hh:161
crl::multisense::feature_detector::Feature::descriptor
uint8_t descriptor
Definition: MultiSenseTypes.hh:2993
crl::multisense::system::StatusMessage::fpgaPower
float fpgaPower
The power consumed by the FPGA.
Definition: MultiSenseTypes.hh:3515
crl::multisense::image::Config::setFps
void setFps(float f)
Set the desired output frames per second.
Definition: MultiSenseTypes.hh:845
crl::multisense::image::Config::m_yaw
float m_yaw
Definition: MultiSenseTypes.hh:1345
crl::multisense::Source_Feature_Left
static CRL_CONSTEXPR DataSource Source_Feature_Left
Definition: MultiSenseTypes.hh:133
crl::multisense::imu::Info
Class containing detailed information for the IMU.
Definition: MultiSenseTypes.hh:2667
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:2326
crl::multisense::compressed_image::Header::imageLength
uint32_t imageLength
The length of the image data stored in imageDataP.
Definition: MultiSenseTypes.hh:2846
crl::multisense::image::ExposureConfig::setExposure
void setExposure(uint32_t e)
Set the exposure time used to capture images.
Definition: MultiSenseTypes.hh:525
crl::multisense::image::AuxConfig::autoExposureRoiX
uint16_t autoExposureRoiX() const
Query the current image configuration's auto-exposure ROI X value.
Definition: MultiSenseTypes.hh:1689
crl::multisense::image::Config::setHeight
void setHeight(uint32_t h)
Set the height of the desired output resolution.
Definition: MultiSenseTypes.hh:834
crl::multisense::system::GroundSurfaceParams::ground_surface_number_of_levels_z
int ground_surface_number_of_levels_z
This argument specifies how many levels of spline interpolation are to be performed in the z dimensio...
Definition: MultiSenseTypes.hh:3719
crl::multisense::feature_detector::Header::numFeatures
uint16_t numFeatures
Definition: MultiSenseTypes.hh:3015
crl::multisense::image::Config::m_tz
float m_tz
Definition: MultiSenseTypes.hh:1344
crl::multisense::lighting::Config::getFlash
bool getFlash() const
Get the current lighting flash setting.
Definition: MultiSenseTypes.hh:2276
crl::multisense::system::StatusMessage::leftImagerTemperature
float leftImagerTemperature
The temperature of the left imager.
Definition: MultiSenseTypes.hh:3502
crl::multisense::system::FeatureDetectorConfig::numberOfFeatures
uint32_t numberOfFeatures() const
Query the maximum number of features applied to the camera feature detector.
Definition: MultiSenseTypes.hh:4004
crl::multisense::system::DeviceInfo::imagerName
std::string imagerName
The name of the sensor's imager.
Definition: MultiSenseTypes.hh:3267
crl::multisense::High_Contrast
static CRL_CONSTEXPR CameraProfile High_Contrast
User would like more contrast in images.
Definition: MultiSenseTypes.hh:176
crl::multisense::lighting::Config::m_dutyCycle
std::vector< float > m_dutyCycle
Definition: MultiSenseTypes.hh:2448
crl::multisense::image::AuxConfig::setAutoWhiteBalanceDecay
void setAutoWhiteBalanceDecay(uint32_t d)
Set the white-balance decay rate.
Definition: MultiSenseTypes.hh:1439
crl::multisense::image::Config::autoExposureTargetIntensity
float autoExposureTargetIntensity() const
Query the current image configuration's auto-exposure target intensity.
Definition: MultiSenseTypes.hh:1087
crl::multisense::image::Calibration::Data
Class to store camera calibration matrices.
Definition: MultiSenseTypes.hh:1873
crl::multisense::image::AuxConfig::AuxConfig
AuxConfig()
Default constructor for a image configuration.
Definition: MultiSenseTypes.hh:1756
crl::multisense::compressed_image::Header::frameId
int64_t frameId
Unique ID used to describe an image.
Definition: MultiSenseTypes.hh:2833
crl::multisense::system::VersionInfo
Class containing version info for a specific sensor.
Definition: MultiSenseTypes.hh:3125
crl::multisense::compressed_image::Header::timeSeconds
uint32_t timeSeconds
The time seconds value corresponding to when the image was captured.
Definition: MultiSenseTypes.hh:2835
crl::multisense::image::Config::m_wbDecay
uint32_t m_wbDecay
Definition: MultiSenseTypes.hh:1332
crl::multisense::lighting::Config::Config
Config()
Default constructor.
Definition: MultiSenseTypes.hh:2441
crl::multisense::imu::Info::rates
std::vector< RateEntry > rates
The various rates available for a specific IMU source.
Definition: MultiSenseTypes.hh:2698
crl::multisense::system::ApriltagParams::max_hamming
uint8_t max_hamming
The maximum hamming correction that will be applied while detecting codes.
Definition: MultiSenseTypes.hh:3850
crl::multisense::system::ChannelStatistics::numDispatchedPps
std::size_t numDispatchedPps
Definition: MultiSenseTypes.hh:4148
crl::multisense::image::Config::setAutoExposureTargetIntensity
void setAutoExposureTargetIntensity(float d)
Set the desired auto-exposure target Intensity.
Definition: MultiSenseTypes.hh:894
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:2554
crl::multisense::CameraProfile
uint32_t CameraProfile
Camera profile typedef representing the various stereo profiles available from newer S27/S30 MultiSen...
Definition: MultiSenseTypes.hh:169
crl::multisense::system::FeatureDetectorConfig::setNumberOfFeatures
void setNumberOfFeatures(const uint32_t &numberOfFeatures)
Set the maximum number of features applied to the camera feature detector.
Definition: MultiSenseTypes.hh:4029
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:816
crl::multisense::system::ChannelStatistics::ChannelStatistics
ChannelStatistics()
Definition: MultiSenseTypes.hh:4106
crl::multisense::compressed_image::Header::codec
ImageCompressionCodec codec
Compression codec.
Definition: MultiSenseTypes.hh:2827
crl::multisense::system::DeviceInfo::lensName
std::string lensName
The name of the sensor's lens.
Definition: MultiSenseTypes.hh:3276
crl::multisense::image::AuxConfig::m_sharpeningPercentage
float m_sharpeningPercentage
Definition: MultiSenseTypes.hh:1777
crl::multisense::RemoteHeadSyncGroup::RemoteHeadSyncGroup
RemoteHeadSyncGroup(const RemoteHeadChannel c, const std::vector< RemoteHeadChannel > &r)
Constructor to initialize a remote head sync pair.
Definition: MultiSenseTypes.hh:249
crl::multisense::lidar::RangeType
uint32_t RangeType
The type of a single laser range measurement
Definition: MultiSenseTypes.hh:2012
crl::multisense::Trigger_External_Inverted
static CRL_CONSTEXPR TriggerSource Trigger_External_Inverted
External OPTO_RX trigger input with Inverted Polarity.
Definition: MultiSenseTypes.hh:272
crl::multisense::image::AuxConfig::autoExposureRoiY
uint16_t autoExposureRoiY() const
Query the current image configuration's auto-exposure ROI Y value.
Definition: MultiSenseTypes.hh:1696
crl::multisense::system::ExternalCalibration::yaw
float yaw
The external yaw translation of the MultiSense in degrees.
Definition: MultiSenseTypes.hh:3642
crl::multisense::image::Header
Class containing image Header information common to all image types.
Definition: MultiSenseTypes.hh:453
crl::multisense::image::Config::setAutoWhiteBalance
void setAutoWhiteBalance(bool e)
Set the white-balance enable flag.
Definition: MultiSenseTypes.hh:923
crl::multisense::image::AuxConfig::enableSharpening
void enableSharpening(const bool &s)
Enable sharpening for the aux luma channel.
Definition: MultiSenseTypes.hh:1508
crl::multisense::system::ExternalCalibration::z
float z
The external z translation of the MultiSense in meters.
Definition: MultiSenseTypes.hh:3633
crl::multisense::image::AuxConfig::m_wbBlue
float m_wbBlue
Definition: MultiSenseTypes.hh:1768
crl::multisense::image::ExposureConfig::m_aeDecay
uint32_t m_aeDecay
Definition: MultiSenseTypes.hh:693
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:180
crl::multisense::image::Config::stereoPostFilterStrength
float stereoPostFilterStrength() const
Query the current image configuration's stereo post-filter strength.
Definition: MultiSenseTypes.hh:1143
crl::multisense::image::AuxConfig::autoExposureRoiHeight
uint16_t autoExposureRoiHeight() const
Query the current image configuration's auto-exposure ROI height value Will return crl::multisense::R...
Definition: MultiSenseTypes.hh:1714
crl::multisense::image::ExposureConfig::setAutoExposureDecay
void setAutoExposureDecay(uint32_t d)
Set the desired auto-exposure decay rate.
Definition: MultiSenseTypes.hh:549
crl::multisense::image::ExposureConfig::autoExposureThresh
float autoExposureThresh() const
Query the current image configuration's auto-exposure threshold.
Definition: MultiSenseTypes.hh:648
crl::multisense::system::ExternalCalibration::roll
float roll
The external roll translation of the MultiSense in degrees.
Definition: MultiSenseTypes.hh:3636
crl::multisense::system::ApriltagParams::decode_sharpening
double decode_sharpening
How much to sharpen the quad before sampling the pixels.
Definition: MultiSenseTypes.hh:3887
crl::multisense::image::Config::gamma
float gamma() const
Query the gamma correction factor.
Definition: MultiSenseTypes.hh:1197
crl::multisense::lidar::Header::timeStartSeconds
uint32_t timeStartSeconds
The seconds value of the time corresponding to the start of laser scan.
Definition: MultiSenseTypes.hh:2034
crl::multisense::system::ApriltagParams
Class containing parameters for the apriltag fiduciual detection algorithm application which may be r...
Definition: MultiSenseTypes.hh:3844
crl::multisense::lighting::SensorStatus
A external sensor status.
Definition: MultiSenseTypes.hh:2491
crl::multisense::lighting::Config::m_rollingShutterLedEnabled
bool m_rollingShutterLedEnabled
Definition: MultiSenseTypes.hh:2452
crl::multisense::system::GroundSurfaceParams::ground_surface_pointcloud_min_range_m
float ground_surface_pointcloud_min_range_m
The min pointcloud range (along the z dimension / optical axis) after applying external transform,...
Definition: MultiSenseTypes.hh:3748
crl::multisense::image::Config::m_wbEnabled
bool m_wbEnabled
Definition: MultiSenseTypes.hh:1331
crl::multisense::image::Config
Class used to store a specific camera configuration.
Definition: MultiSenseTypes.hh:790
crl::multisense::imu::Info::RangeEntry::range
float range
The range of valid sample readings for a IMU source.
Definition: MultiSenseTypes.hh:2686
crl::multisense::RemoteHeadChannel
int16_t RemoteHeadChannel
Remote head channel defines which channel is used to communicate to a specific component in the Remot...
Definition: MultiSenseTypes.hh:206
crl::multisense::imu::Sample::timeSeconds
uint32_t timeSeconds
The time seconds value corresponding to the specific sample.
Definition: MultiSenseTypes.hh:2556
crl::multisense::imu::Sample::time
double time() const
A convenience function used for getting the time of the specific sample.
Definition: MultiSenseTypes.hh:2590
crl::multisense::system::GroundSurfaceParams::ground_surface_max_fitting_iterations
int ground_surface_max_fitting_iterations
The maximum number of iterations to undertake in the spline fit and obstacle detection loop.
Definition: MultiSenseTypes.hh:3775
crl::multisense::system::GroundSurfaceParams::ground_surface_number_of_levels_x
int ground_surface_number_of_levels_x
This argument specifies how many levels of spline interpolation are to be performed in the x dimensio...
Definition: MultiSenseTypes.hh:3713
crl::multisense::image::AuxConfig::autoWhiteBalanceDecay
uint32_t autoWhiteBalanceDecay() const
Query the current image configuration's white-balance decay rate.
Definition: MultiSenseTypes.hh:1667
crl::multisense::image::AuxConfig::fy
float fy() const
Query the current aux camera calibration rectified projection focal length in the y dimension.
Definition: MultiSenseTypes.hh:1556
crl::multisense::image::AuxConfig::whiteBalanceRed
float whiteBalanceRed() const
Query the current image configuration's red white-balance setting.
Definition: MultiSenseTypes.hh:1643
crl::multisense::feature_detector::Header
Definition: MultiSenseTypes.hh:3000
crl::multisense::RemoteHeadSyncGroup::responders
std::vector< RemoteHeadChannel > responders
The synchronization responders.
Definition: MultiSenseTypes.hh:257
crl::multisense::system::ChannelStatistics::numDispatchedImu
std::size_t numDispatchedImu
Definition: MultiSenseTypes.hh:4152
crl::multisense::image::Config::fy
float fy() const
Query the current camera calibrations rectified projection focal length in the y dimension.
Definition: MultiSenseTypes.hh:1224
crl::multisense::imu::Info::units
std::string units
The units of for a specific IMU source.
Definition: MultiSenseTypes.hh:2696
crl::multisense::image::ExposureConfig::autoExposureRoiY
uint16_t autoExposureRoiY() const
Query the current image configuration's auto-exposure ROI Y value.
Definition: MultiSenseTypes.hh:662
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:3166
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:1173
crl::multisense::apriltag::Callback
void(* Callback)(const Header &header, void *userDataP)
Function pointer for receiving callbacks for apriltag data.
Definition: MultiSenseTypes.hh:2973
crl::multisense::image::AuxConfig::sharpeningPercentage
float sharpeningPercentage() const
Query the percentage of sharpening applied to the aux luma image.
Definition: MultiSenseTypes.hh:1743
crl::multisense::lidar::Header::rangesP
const RangeType * rangesP
Laser range data in millimeters.
Definition: MultiSenseTypes.hh:2054
crl::multisense::image::Config::width
uint32_t width() const
Query the current image configuration's width.
Definition: MultiSenseTypes.hh:1014
crl::multisense::imu::Sample::z
float z
z data for each sample
Definition: MultiSenseTypes.hh:2582
crl::multisense::RemoteHeadSyncGroup::controller
RemoteHeadChannel controller
The synchronization controller.
Definition: MultiSenseTypes.hh:252
crl::multisense::Source_Luma_Rectified_Aux
static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Aux
Definition: MultiSenseTypes.hh:144