MultiSenseTypes.hh
Go to the documentation of this file.
1 
37 #ifndef LibMultiSense_MultiSenseTypes_hh
38 #define LibMultiSense_MultiSenseTypes_hh
39 
40 #include <stdint.h>
41 
42 #include <string>
43 #include <vector>
44 
45 //
46 // Add compatibility for C++ 11
47 #if __cplusplus > 199711L
48 // This compiler supports C++11.
49 #define CRL_CONSTEXPR constexpr
50 #else
51 // This compiler does not support C++11.
52 #define CRL_CONSTEXPR const
53 #endif
54 
55 // Define MULTISENSE_API appropriately. This is needed to correctly link with
56 // LibMultiSense when it is built as a DLL on Windows.
57 #if !defined(MULTISENSE_API)
58 #if defined (_MSC_VER)
59 #if defined (MultiSense_EXPORTS)
60 #define MULTISENSE_API __declspec(dllexport)
61 #else
62 #define MULTISENSE_API __declspec(dllimport)
63 #endif
64 #else
65 #define MULTISENSE_API
66 #endif
67 #endif
68 
69 #if defined (_MSC_VER)
70 /*
71  * C4251 warns about exporting classes with members not marked as __declspec(export).
72  * It is not easy to work around this without breaking the MultiSense API, but it
73  * is safe to ignore this warning as long as the MultiSense DLL is compiled with the
74  * same compiler version and STL version.
75  */
76 #pragma warning (push)
77 #pragma warning (disable: 4251)
78 #endif
79 
80 namespace crl {
81 namespace multisense {
82 
83 
87 typedef uint32_t VersionType;
88 
93 typedef int32_t Status;
94 
95 //
96 // General status codes
97 
98 static CRL_CONSTEXPR Status Status_Ok = 0;
99 static CRL_CONSTEXPR Status Status_TimedOut = -1;
100 static CRL_CONSTEXPR Status Status_Error = -2;
101 static CRL_CONSTEXPR Status Status_Failed = -3;
103 static CRL_CONSTEXPR Status Status_Unknown = -5;
104 static CRL_CONSTEXPR Status Status_Exception = -6;
105 
114 typedef uint32_t DataSource;
115 
116 static CRL_CONSTEXPR DataSource Source_Unknown = 0;
117 static CRL_CONSTEXPR DataSource Source_All = 0xffffffff;
118 static CRL_CONSTEXPR DataSource Source_Raw_Left = (1<<0);
119 static CRL_CONSTEXPR DataSource Source_Raw_Right = (1<<1);
120 static CRL_CONSTEXPR DataSource Source_Luma_Left = (1<<2);
121 static CRL_CONSTEXPR DataSource Source_Luma_Right = (1<<3);
122 static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Left = (1<<4);
123 static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Right = (1<<5);
124 static CRL_CONSTEXPR DataSource Source_Chroma_Left = (1<<6);
125 static CRL_CONSTEXPR DataSource Source_Chroma_Right = (1<<7);
126 static CRL_CONSTEXPR DataSource Source_Disparity = (1<<10);
127 static CRL_CONSTEXPR DataSource Source_Disparity_Left = (1<<10); // same as Source_Disparity
128 static CRL_CONSTEXPR DataSource Source_Disparity_Right = (1<<11);
129 static CRL_CONSTEXPR DataSource Source_Disparity_Cost = (1<<12);
130 static CRL_CONSTEXPR DataSource Source_Jpeg_Left = (1<<16);
131 static CRL_CONSTEXPR DataSource Source_Rgb_Left = (1<<17);
132 static CRL_CONSTEXPR DataSource Source_Lidar_Scan = (1<<24);
133 static CRL_CONSTEXPR DataSource Source_Imu = (1<<25);
134 static CRL_CONSTEXPR DataSource Source_Pps = (1<<26);
135 
143 public:
144 
146  static CRL_CONSTEXPR uint16_t DFL_UDP_PORT = 10001;
147 
149  DataSource mask;
151  std::string address;
153  uint16_t udpPort;
155  uint32_t fpsDecimation;
156 
161 
174  DirectedStream(DataSource m,
175  const std::string& addr,
176  uint16_t p=DFL_UDP_PORT,
177  uint32_t dec=1) :
178  mask(m),
179  address(addr),
180  udpPort(p),
181  fpsDecimation(dec) {};
182 };
183 
184 /*
185  * Trigger sources used to determine which input should be used to trigger
186  * a frame capture on a device
187  */
188 typedef uint32_t TriggerSource;
189 
191 static CRL_CONSTEXPR TriggerSource Trigger_Internal = 0;
193 static CRL_CONSTEXPR TriggerSource Trigger_External = 1;
194 
195 
196 
201 public:
206  virtual bool inMask(DataSource mask) { return true; };
207  virtual ~HeaderBase() {};
208 };
209 
210 namespace image {
211 
375 public:
376 
378  DataSource source;
380  uint32_t bitsPerPixel;
382  uint32_t width;
384  uint32_t height;
386  int64_t frameId;
388  uint32_t timeSeconds;
391 
393  uint32_t exposure;
395  float gain;
399  uint32_t imageLength;
401  const void *imageDataP;
402 
407  : source(Source_Unknown) {};
408 
413  virtual bool inMask(DataSource mask) { return (mask & source) != 0;};
414 };
415 
427 typedef void (*Callback)(const Header& header,
428  void *userDataP);
429 
516 public:
517 
518  //
519  // User configurable member functions
520 
529  void setResolution (uint32_t w,
530  uint32_t h) { m_width=w;m_height=h; };
531 
541  void setDisparities (uint32_t d) { m_disparities=d; };
542 
551  void setCamMode (int m) { m_cam_mode=m; };
552 
561  void setOffset (int o) { m_offset=o; };
562 
570  void setWidth (uint32_t w) { m_width = w; };
571 
579  void setHeight (uint32_t h) { m_height = h; };
580 
590  void setFps (float f) { m_fps = f; };
591 
598  void setGain (float g) { m_gain = g; };
599 
607  void setExposure (uint32_t e) { m_exposure = e; };
608 
615  void setAutoExposure (bool e) { m_aeEnabled = e; };
616 
623  void setAutoExposureMax (uint32_t m) { m_aeMax = m; };
624 
631  void setAutoExposureDecay (uint32_t d) { m_aeDecay = d; };
632 
640  void setAutoExposureThresh(float t) { m_aeThresh = t; };
641 
651  void setWhiteBalance (float r,
652  float b) { m_wbRed=r;m_wbBlue=b; };
653 
660  void setAutoWhiteBalance (bool e) { m_wbEnabled = e; };
661 
668  void setAutoWhiteBalanceDecay (uint32_t d) { m_wbDecay = d; };
669 
676  void setAutoWhiteBalanceThresh (float t) { m_wbThresh = t; };
677 
688  void setStereoPostFilterStrength(float s) { m_spfStrength = s; };
689 
700  void setHdr (bool e) { m_hdrEnabled = e; };
701 
702 
703  //
704  // Query
705 
711  uint32_t width () const { return m_width; };
712 
719  uint32_t height () const { return m_height; };
720 
728  uint32_t disparities () const { return m_disparities; };
729 
736  int camMode () const { return m_cam_mode; };
737 
744  int offset () const { return m_offset; };
745 
752  float fps () const { return m_fps; };
753 
760  float gain () const { return m_gain; };
761 
762 
769  uint32_t exposure () const { return m_exposure; };
770 
777  bool autoExposure () const { return m_aeEnabled; };
778 
785  uint32_t autoExposureMax () const { return m_aeMax; };
786 
793  uint32_t autoExposureDecay () const { return m_aeDecay; };
794 
801  float autoExposureThresh() const { return m_aeThresh; };
802 
809  float whiteBalanceRed () const { return m_wbRed; };
810 
817  float whiteBalanceBlue () const { return m_wbBlue; };
818 
825  bool autoWhiteBalance () const { return m_wbEnabled; };
826 
833  uint32_t autoWhiteBalanceDecay () const { return m_wbDecay; };
834 
841  float autoWhiteBalanceThresh () const { return m_wbThresh; };
842 
849  float stereoPostFilterStrength() const { return m_spfStrength; };
850 
856  bool hdrEnabled () const { return m_hdrEnabled; };
857 
858 
859 
860  //
861  // Query camera calibration (read-only)
862  //
863  // These parameters are adjusted for the current operating resolution of the device.
864 
874  float fx() const { return m_fx; };
875 
885  float fy() const { return m_fy; };
886 
897  float cx() const { return m_cx; };
898 
909  float cy() const { return m_cy; };
910 
919  float tx() const { return m_tx; };
920 
930  float ty() const { return m_ty; };
931 
941  float tz() const { return m_tz; };
942 
951  float roll() const { return m_roll; };
952 
961  float pitch() const { return m_pitch; };
962 
971  float yaw() const { return m_yaw; };
972 
977  Config() : m_fps(5.0f), m_gain(1.0f),
978  m_exposure(10000), m_aeEnabled(true), m_aeMax(5000000), m_aeDecay(7), m_aeThresh(0.75f),
979  m_wbBlue(1.0f), m_wbRed(1.0f), m_wbEnabled(true), m_wbDecay(3), m_wbThresh(0.5f),
980  m_width(1024), m_height(544), m_disparities(128), m_cam_mode(0), m_offset(-1), m_spfStrength(0.5f), m_hdrEnabled(false),
981  m_fx(0), m_fy(0), m_cx(0), m_cy(0),
982  m_tx(0), m_ty(0), m_tz(0), m_roll(0), m_pitch(0), m_yaw(0) {};
983 private:
984 
985  float m_fps, m_gain;
986  uint32_t m_exposure;
988  uint32_t m_aeMax;
989  uint32_t m_aeDecay;
990  float m_aeThresh;
991  float m_wbBlue;
992  float m_wbRed;
994  uint32_t m_wbDecay;
995  float m_wbThresh;
996  uint32_t m_width, m_height;
997  uint32_t m_disparities;
999  int m_offset;
1002 
1003 protected:
1004 
1005  float m_fx, m_fy, m_cx, m_cy;
1006  float m_tx, m_ty, m_tz;
1007  float m_roll, m_pitch, m_yaw;
1008 };
1009 
1093 public:
1094 
1099  public:
1100 
1102  float M[3][3];
1105  float D[8];
1107  float R[3][3];
1109  float P[3][4];
1110  };
1111 
1116 };
1117 
1200 public:
1201 
1204  uint8_t adc_gain[2];
1205 
1208  int16_t bl_offset[2];
1209 
1210 };
1211 
1213 public:
1214 
1216  int delay;
1217 
1218 };
1219 
1259 public:
1260 
1264  Histogram() : channels(0),
1265  bins(0),
1266  data() {};
1269  uint32_t channels;
1271  uint32_t bins;
1274  std::vector<uint32_t> data;
1275 };
1276 
1277 }; // namespace image
1278 
1279 
1280 
1281 
1282 namespace lidar {
1283 
1285 typedef uint32_t RangeType;
1287 typedef uint32_t IntensityType;
1288 
1296 public:
1297 
1302  : pointCount(0) {};
1303 
1305  uint32_t scanId;
1311  uint32_t timeEndSeconds;
1319  int32_t scanArc;
1321  uint32_t maxRange;
1323  uint32_t pointCount;
1324 
1327  const RangeType *rangesP;
1330  const IntensityType *intensitiesP; // device units
1331 };
1332 
1342 typedef void (*Callback)(const Header& header,
1343  void *userDataP);
1344 
1426 public:
1427 
1430  float laserToSpindle[4][4];
1433  float cameraToSpindleFixed[4][4];
1434 };
1435 
1436 }; // namespace lidar
1437 
1438 
1439 
1440 namespace lighting {
1441 
1442 
1444 static CRL_CONSTEXPR uint32_t MAX_LIGHTS = 8;
1446 static CRL_CONSTEXPR float MAX_DUTY_CYCLE = 100.0;
1449 
1536 public:
1537 
1546  void setFlash(bool onOff) { m_flashEnabled = onOff; };
1547 
1554  bool getFlash() const { return m_flashEnabled; };
1555 
1564  bool setDutyCycle(float percent) {
1565  if (percent < 0.0 || percent > MAX_DUTY_CYCLE)
1566  return false;
1567 
1568  std::fill(m_dutyCycle.begin(),
1569  m_dutyCycle.end(),
1570  percent);
1571  return true;
1572  };
1573 
1585  bool setDutyCycle(uint32_t i,
1586  float percent) {
1587  if (i >= MAX_LIGHTS ||
1588  percent < 0.0 || percent > MAX_DUTY_CYCLE)
1589  return false;
1590 
1591  m_dutyCycle[i] = percent;
1592  return true;
1593  };
1594 
1604  float getDutyCycle(uint32_t i) const {
1605  if (i >= MAX_LIGHTS)
1606  return 0.0f;
1607  return m_dutyCycle[i];
1608  };
1609 
1614  Config() : m_flashEnabled(false), m_dutyCycle(MAX_LIGHTS, -1.0f) {};
1615 
1616 private:
1617 
1618  bool m_flashEnabled;
1619  std::vector<float> m_dutyCycle;
1620 };
1621 
1659 public:
1660 
1667 
1668  SensorStatus() : ambientLightPercentage(100.0f) {};
1669 };
1670 
1671 }; // namespace lighting
1672 
1673 
1674 
1675 
1676 namespace pps {
1677 
1688 public:
1689 
1691  int64_t sensorTime;
1692 
1694  uint32_t timeSeconds;
1697 };
1698 
1702 typedef void (*Callback)(const Header& header,
1703  void *userDataP);
1704 
1705 }; // namespace pps
1706 
1707 
1708 
1709 namespace imu {
1710 
1716 public:
1717 
1719  typedef uint16_t Type;
1720 
1721  static CRL_CONSTEXPR Type Type_Accelerometer = 1;
1722  static CRL_CONSTEXPR Type Type_Gyroscope = 2;
1723  static CRL_CONSTEXPR Type Type_Magnetometer = 3;
1724 
1726  Type type;
1728  uint32_t timeSeconds;
1731 
1738  float x;
1739 
1746  float y;
1747 
1754  float z;
1755 
1762  double time() const {
1763  return (static_cast<double>(timeSeconds) +
1764  1e-6 * static_cast<double>(timeMicroSeconds));
1765  };
1766 };
1767 
1777 public:
1778 
1781  uint32_t sequence;
1785  std::vector<Sample> samples;
1786 };
1787 
1791 typedef void (*Callback)(const Header& header,
1792  void *userDataP);
1793 
1840 public:
1841 
1845  typedef struct {
1847  float sampleRate;
1850  } RateEntry;
1851 
1855  typedef struct {
1858  float range;
1860  float resolution;
1861  } RangeEntry;
1862 
1864  std::string name;
1866  std::string device;
1868  std::string units;
1870  std::vector<RateEntry> rates;
1872  std::vector<RangeEntry> ranges;
1873 };
1874 
1972 public:
1973 
1976  std::string name;
1978  bool enabled;
1981  uint32_t rateTableIndex;
1985 };
1986 
1987 }; // namespace imu
1988 
1989 
1990 
1991 
1992 namespace system {
1993 
2019 public:
2020 
2022  uint32_t width;
2024  uint32_t height;
2028  int32_t disparities;
2029 
2041  DeviceMode(uint32_t w=0,
2042  uint32_t h=0,
2043  DataSource d=0,
2044  int32_t s=-1) :
2045  width(w),
2046  height(h),
2047  supportedDataSources(d),
2048  disparities(s) {};
2049 };
2050 
2088 public:
2089 
2091  std::string apiBuildDate;
2093  VersionType apiVersion;
2094 
2099 
2105  uint64_t sensorFpgaDna;
2106 
2111  apiVersion(0),
2112  sensorFirmwareVersion(0),
2113  sensorHardwareVersion(0),
2114  sensorHardwareMagic(0),
2115  sensorFpgaDna(0) {};
2116 };
2117 
2123 public:
2124 
2126  std::string name;
2128  uint32_t revision;
2129 
2133  PcbInfo() : revision(0) {};
2134 };
2135 
2174 public:
2175 
2177  static CRL_CONSTEXPR uint32_t MAX_PCBS = 8;
2178 
2179  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_SL = 1;
2180  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7 = 2;
2181  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S = HARDWARE_REV_MULTISENSE_S7; // alias for backward source compatibility
2182  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_M = 3;
2183  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S7S = 4;
2184  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_S21 = 5;
2185  static CRL_CONSTEXPR uint32_t HARDWARE_REV_MULTISENSE_ST21 = 6;
2186  static CRL_CONSTEXPR uint32_t HARDWARE_REV_BCAM = 100;
2187 
2188  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_GREY = 1;
2189  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_COLOR = 2;
2190  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_GREY = 3;
2191  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_COLOR = 4;
2192  static CRL_CONSTEXPR uint32_t IMAGER_TYPE_IMX104_COLOR = 100;
2193 
2194  static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_NONE = 0;
2195  static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_SL_INTERNAL = 1;
2196  static CRL_CONSTEXPR uint32_t LIGHTING_TYPE_S21_EXTERNAL = 2;
2197 
2199  std::string name;
2201  std::string buildDate;
2203  std::string serialNumber;
2206 
2208  std::vector<PcbInfo> pcbs;
2209 
2211  std::string imagerName;
2213  uint32_t imagerType;
2215  uint32_t imagerWidth;
2217  uint32_t imagerHeight;
2218 
2220  std::string lensName;
2222  uint32_t lensType;
2229 
2231  uint32_t lightingType;
2233  uint32_t numberOfLights;
2234 
2236  std::string laserName;
2238  uint32_t laserType;
2239 
2241  std::string motorName;
2243  uint32_t motorType;
2246 
2251  hardwareRevision(0),
2252  imagerType(0),
2253  imagerWidth(0),
2254  imagerHeight(0),
2255  lensType(0),
2256  nominalBaseline(0.0),
2257  nominalFocalLength(0.0),
2258  nominalRelativeAperture(0.0),
2259  lightingType(0),
2260  numberOfLights(0),
2261  laserType(0),
2262  motorType(0),
2263  motorGearReduction(0.0) {};
2264 };
2265 
2334 public:
2335 
2337  std::string ipv4Address;
2339  std::string ipv4Gateway;
2341  std::string ipv4Netmask;
2342 
2347  ipv4Address("10.66.171.21"),
2348  ipv4Gateway("10.66.171.1"),
2349  ipv4Netmask("255.255.240.0") {};
2350 
2360  NetworkConfig(const std::string& a,
2361  const std::string& g,
2362  const std::string& n) :
2363  ipv4Address(a),
2364  ipv4Gateway(g),
2365  ipv4Netmask(n) {};
2366 };
2367 
2405  public:
2406 
2409  double uptime;
2410 
2413  bool systemOk;
2414 
2417  bool laserOk;
2418 
2422 
2426 
2429  bool imuOk;
2430 
2434 
2437 
2441 
2444 
2447 
2450 
2453 
2457 
2459  float fpgaPower;
2460 
2462  float logicPower;
2463 
2466 
2469  uptime(0.),
2470  systemOk(false),
2471  laserOk(false),
2472  laserMotorOk(false),
2473  camerasOk(false),
2474  imuOk(false),
2475  externalLedsOk(false),
2476  processingPipelineOk(false),
2477  powerSupplyTemperature(0.),
2478  fpgaTemperature(0.),
2479  leftImagerTemperature(0.),
2480  rightImagerTemperature(0.),
2481  inputVoltage(0.),
2482  inputCurrent(0.),
2483  fpgaPower(0.),
2484  logicPower(0.),
2485  imagerPower(0.) {};
2486 };
2487 
2568  public:
2569 
2571  float x;
2572 
2574  float y;
2575 
2577  float z;
2578 
2580  float roll;
2581 
2583  float pitch;
2584 
2586  float yaw;
2587 
2590  x(0.),
2591  y(0.),
2592  z(0.),
2593  roll(0.),
2594  pitch(0.),
2595  yaw(0.) {};
2596 };
2597 
2598 }; // namespace system
2599 }; // namespace multisense
2600 }; // namespace crl
2601 
2602 #if defined (_MSC_VER)
2603 #pragma warning (pop)
2604 #endif
2605 
2606 #endif // LibMultiSense_MultiSenseTypes_hh
#define CRL_CONSTEXPR
d
static CRL_CONSTEXPR DataSource Source_Disparity_Cost
virtual bool inMask(DataSource mask)
std::vector< RangeEntry > ranges
NetworkConfig(const std::string &a, const std::string &g, const std::string &n)
static CRL_CONSTEXPR DataSource Source_Disparity_Right
static CRL_CONSTEXPR DataSource Source_Disparity_Left
DirectedStream(DataSource m, const std::string &addr, uint16_t p=DFL_UDP_PORT, uint32_t dec=1)
static CRL_CONSTEXPR DataSource Source_Jpeg_Left
void setAutoWhiteBalanceDecay(uint32_t d)
static CRL_CONSTEXPR DataSource Source_Disparity
f
static CRL_CONSTEXPR TriggerSource Trigger_Internal
std::vector< Sample > samples
static CRL_CONSTEXPR DataSource Source_Chroma_Left
#define MULTISENSE_API
static CRL_CONSTEXPR Status Status_Unsupported
float getDutyCycle(uint32_t i) const
static CRL_CONSTEXPR TriggerSource Trigger_External
static CRL_CONSTEXPR DataSource Source_Luma_Left
void setResolution(uint32_t w, uint32_t h)
bool setDutyCycle(uint32_t i, float percent)
std_msgs::Header * header(M &m)
static CRL_CONSTEXPR Status Status_Failed
static CRL_CONSTEXPR float MAX_AMBIENT_LIGHTING
uint32_t autoWhiteBalanceDecay() const
static CRL_CONSTEXPR DataSource Source_Lidar_Scan
static CRL_CONSTEXPR DataSource Source_Luma_Right
const IntensityType * intensitiesP
static CRL_CONSTEXPR DataSource Source_Imu
std::vector< RateEntry > rates
Definition: channel.cc:56
virtual bool inMask(DataSource mask)
static CRL_CONSTEXPR Status Status_TimedOut
static CRL_CONSTEXPR float MAX_DUTY_CYCLE
static CRL_CONSTEXPR Status Status_Ok
static CRL_CONSTEXPR DataSource Source_Pps
static CRL_CONSTEXPR DataSource Source_Rgb_Left
DeviceMode(uint32_t w=0, uint32_t h=0, DataSource d=0, int32_t s=-1)
void setWhiteBalance(float r, float b)
static CRL_CONSTEXPR DataSource Source_Unknown
static CRL_CONSTEXPR DataSource Source_Raw_Right
static CRL_CONSTEXPR DataSource Source_Raw_Left
static CRL_CONSTEXPR uint32_t MAX_LIGHTS
static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Right
void(* Callback)(const Header &header, void *userDataP)
static CRL_CONSTEXPR Status Status_Exception
static CRL_CONSTEXPR Status Status_Error
static CRL_CONSTEXPR DataSource Source_Chroma_Right
static CRL_CONSTEXPR DataSource Source_All
static CRL_CONSTEXPR Status Status_Unknown
static CRL_CONSTEXPR DataSource Source_Luma_Rectified_Left


multisense_lib
Author(s):
autogenerated on Sat Apr 6 2019 02:16:46