xvsdk  3.2.0
xv-types.h
1 #pragma once
2 #define NOMINMAX
3 
4 #include <array>
5 #include <vector>
6 #include <limits>
7 #include <string>
8 #include <memory>
9 
10 #if defined(__ANDROID__) && !defined(__x86_64__)
11 #define __XV_DRIVER_ONLY__
12 #endif
13 
14 namespace xv {
15 
19 enum class LogLevel {
20  debug = 1,
21  info,
22  warn,
23  err,
24  critical,
25  off
26 };
27 
28 enum class SlamStartMode {
29  Normal,
30  VisionOnly,
31  VisionWithGYRO
32 };
33 
34 enum DeviceSupport {
35  ONLYUSB,
36  ONLYDRIVER,
37  USBANDDRIVER,
38  ONLY_WIRELESS_CONTROLLER
39 };
40 
41 
45 enum class PlugEventType { Plugin, Unplug };
46 
51 #pragma pack(1)
52 
56 struct ExpSetting{
57  std::uint32_t iso_value;
58  std::uint32_t exp_abs;
59  std::uint8_t exp_mode;
60  std::int8_t exp_level;
61  std::uint8_t exp_anti; // ANTIBANDING_MODES
62  std::uint8_t iso_mode;
63 };
64 
68 struct AwbSetting
69 {
70  std::uint8_t awb_mode;
71  std::uint8_t awb_lock;
72 };
73 
77 struct AfSetting
78 {
79  std::uint8_t af_mode;
80  std::uint8_t af_dist;
81 };
82 
87 {
88  std::uint32_t cmd; //sensorId:8 + channel:8 + sensorCmd:16
89 
90  union {
91  std::uint8_t val[24];
92  AwbSetting awb;
93  ExpSetting exp;
94  AfSetting af;
95  std::int16_t val16;
96  std::int32_t val32;
97  }args;
98 };
99 
101 {
102  int32_t maxIsoGainValue;
103  int32_t minIsoGainValue;
104  int32_t maxExposureTimeUs;
105  int32_t minExposureTimeUs;
106  uint8_t targetMeanPixelValue;
107  int32_t ratioIso;
108  int32_t cpt_aec_no_modify_range;
109  float exposureTime_control_porprotion_value;
110  float exposureTime_control_integral_value;
111  float isoGain_control_porprotion_value;
112  float isoGain_control_integral_value;
113  uint32_t ISP_AEC_MODE;
114 };
115 
116 #pragma pack()
127 struct Version{
128  Version( int major = 0, int minor = 0, int patch = 0 );
129  Version( const std::string &s );
130 
131  int major = 0;
132  int minor = 0;
133  int patch = 0;
134 
135  int key() const;
136  std::string toString() const;
137 
138  static int (max)();
139 };
140 
141 bool operator<(const Version &a, const Version &b);
142 bool operator<=(const Version &a, const Version &b);
143 bool operator==(const Version &a, const Version &b);
144 bool operator!=(const Version &a, const Version &b);
145 bool operator>=(const Version &a, const Version &b);
146 bool operator>(const Version &a, const Version &b);
147 
148 std::ostream& operator<<(std::ostream& o, Version const& v);
152 template<class F> using Vector2 = std::array<F,2>;
153 template<class F> using Vector3 = std::array<F,3>;
154 template<class F> using Vector4 = std::array<F,4>;
155 template<class F> using Matrix3 = std::array<F,9>;
156 
157 typedef Vector2<bool> Vector2b;
158 typedef Vector3<bool> Vector3b;
159 typedef Vector4<bool> Vector4b;
160 typedef Vector2<double> Vector2d;
161 typedef Vector3<double> Vector3d;
162 typedef Vector4<double> Vector4d;
163 typedef Matrix3<double> Matrix3d;
164 typedef Vector2<float> Vector2f;
165 typedef Vector3<float> Vector3f;
166 typedef Vector4<float> Vector4f;
167 typedef Matrix3<float> Matrix3f;
168 
178 Vector4f rotationToQuaternion(Matrix3f const& rot);
184 Vector4d rotationToQuaternion(Matrix3d const& rot);
185 
191 Matrix3f quaternionToRotation(Vector4f const& q);
192 
198 Matrix3d quaternionToRotation(Vector4d const& q);
199 
203 Matrix3f quaternionsToRotation(Vector4f const& q);
204 
213 Vector3d rotationToPitchYawRoll(Matrix3d const& rot);
214 
223 Vector3f rotationToPitchYawRoll(Matrix3f const& rot);
224 
232 namespace details {
233 
237 template <class F=double>
238 class Transform_ {
239 
240 protected:
241  Vector3<F> m_translation;
242  Matrix3<F> m_rotation;
243 
244 public:
245 
246  static Transform_ Identity() {
247  return Transform_({0.,0,0},{1.,0,0,0,1,0,0,0,1});
248  }
249 
250  Transform_() {};
251  Transform_(Vector3<F> const& t, Matrix3<F> const& r={}) : m_translation(t), m_rotation(r) {};
252 
257 
262  Vector3<F> const& translation() const {return m_translation;}
266  void setTranslation(Vector3<F> const& v) {m_translation = v;}
270  void setTranslation(F const* v) {std::copy(v, v+3, m_translation.data());}
271 
276  Matrix3<F> const& rotation() const {return m_rotation;}
280  void setRotation(Matrix3<F> const& v) {m_rotation = v;}
284  void setRotation(F const* v) {std::copy(v, v+9, m_rotation.data());}
285 
289  F x() const { return m_translation[0]; }
293  F y() const { return m_translation[1]; }
297  F z() const { return m_translation[2]; }
303 };
304 
305 template <class F=double>
306 Transform_<F> operator*(Transform_<F> lhs, const Transform_<F>& rhs) {
307  lhs *= rhs;
308  return lhs;
309 }
310 
316 Vector3d operator*(const Transform_<double>& a, const Vector3d& p);
317 
323 Vector3f operator*(const Transform_<float>& a, const Vector3f& p);
324 
329 
334 
335 
336 template <class F=double>
338 
339 protected:
340  Vector3<F> m_translation;
341  Vector4<F> m_quaternions;
342 
343 public:
344 
345  static TransformQuat_ Identity() {
346  return TransformQuat_({0.,0,0},{0.,0,0,0,1});
347  }
348 
349  TransformQuat_() {}
350  TransformQuat_(Vector3<F> const& t, Vector4<F> const& q={}) : m_translation(t), m_quaternions(q) {}
351 
352  TransformQuat_& operator*=(TransformQuat_ const& q);
353 
354  Vector3<F> const& translation() const;
355  void setTranslation(Vector3<F> const& v);
356  void setTranslation(F const* v);
357 
361  Vector4<F> const& quaternion() const;
365  void setQuaternion(Vector4<F> const& v);
369  void setQuaternion(F const* v);
370 
374  F x() const { return m_translation[0]; }
378  F y() const { return m_translation[1]; }
382  F z() const { return m_translation[2]; }
383 
387  F qx() const { return m_quaternions[0]; }
391  F qy() const { return m_quaternions[1]; }
395  F qz() const { return m_quaternions[2]; }
399  F qw() const { return m_quaternions[3]; }
400 };
401 template <class F=double>
402 TransformQuat_<F> operator*(TransformQuat_<F> lhs, const TransformQuat_<F>& rhs) {
403  lhs *= rhs;
404  return lhs;
405 }
406 
407 template <class F=double>
408 class PoseQuat_ : public TransformQuat_<F> {
409  double m_hostTimestamp = std::numeric_limits<double>::infinity();
410  std::int64_t m_edgeTimestampUs = std::numeric_limits<std::int64_t>::min();
411 
412 public:
413 
414  PoseQuat_() {}
415  PoseQuat_(double t, TransformQuat_<F>const& tr={}) : m_hostTimestamp(t), TransformQuat_<F> (tr) {}
416  PoseQuat_(std::int64_t t, TransformQuat_<F>const& tr={}) : m_edgeTimestampUs(t), TransformQuat_<F> (tr) {}
417  PoseQuat_(double t, std::int64_t te, TransformQuat_<F>const& tr={}) : m_hostTimestamp(t), m_edgeTimestampUs(te), TransformQuat_<F> (tr) {}
418 
422  std::int64_t edgeTimestampUs() const {return m_edgeTimestampUs;};
426  void setEdgeTimestampUs(std::int64_t t) { m_edgeTimestampUs = t;};
430  double hostTimestamp() const {return m_hostTimestamp;};
434  void setHostTimestamp(double t) {m_hostTimestamp = t;};
435 };
436 
437 template <class F=double>
438 class PoseRot_ : public Transform_<F> {
439  double m_hostTimestamp = std::numeric_limits<double>::infinity();
440  std::int64_t m_edgeTimestampUs = std::numeric_limits<std::int64_t>::min();
441 
442 public:
443  PoseRot_() {}
444  PoseRot_(double t, Transform_<F>const& tr={}) : m_hostTimestamp(t), Transform_<F> (tr) {}
445  PoseRot_(std::int64_t t, Transform_<F>const& tr={}) : m_edgeTimestampUs(t), Transform_<F> (tr) {}
446  PoseRot_(double t, std::int64_t te, Transform_<F>const& tr={}) : m_hostTimestamp(t), m_edgeTimestampUs(te), Transform_<F> (tr) {}
447 
451  std::int64_t edgeTimestampUs() const {return m_edgeTimestampUs;};
455  void setEdgeTimestampUs(std::int64_t t) { m_edgeTimestampUs = t;};
459  double hostTimestamp() const {return m_hostTimestamp;};
463  void setHostTimestamp(double t) {m_hostTimestamp = t;};
464 };
465 
466 template <class F=double>
467 class Pose_ : public details::PoseRot_<F> {
468 
469 private:
470 
471  Vector4<F> m_quaternions;
472  double m_confidence = 0;
473 
474 public:
475 
476  static Pose_ Identity() {
477  return Pose_({0.,0,0},{1.,0,0,0,1,0,0,0,1});
478  }
479 
480  Pose_() {}
481 
485  Pose_(double c) : m_confidence(c) {}
486 
490  Pose_(Vector3<F> const& translation, Matrix3<F> const& rotation,
491  double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)(), double c=0.)
492  : m_confidence(c), PoseRot_<F>::PoseRot_(hostTimestamp, edgeTimestamp, {translation, rotation}), m_quaternions(rotationToQuaternion(rotation)) {}
493 
497  double confidence() const {return m_confidence;}
498 
502  void setConfidence(double c) { m_confidence = c;}
503 
507  Vector4<F> const& quaternion() const {return m_quaternions;}
511  void setQuaternion(Vector4<F> const& v) {
512  m_quaternions = v;
514  };
518  void setQuaternion(F const* v) {
519  std::copy(v, v+4, m_quaternions.data());
521  };
525  void setRotation(Matrix3<F> const& v) {
528  };
532  void setRotation(F const* v) {
533  std::copy(v, v+9, PoseRot_<F>::m_rotation.data());
535  };
536 
537 
538 
539 };
540 
541 template <class F>
542 class PosePred_ : public Pose_<F> {
543 
544 protected:
545  Vector3<F> m_linearVelocity = Vector3<F>{0.,0.,0.};
546  Vector3<F> m_angularVelocity = Vector3<F>{0.,0.,0.};
547  Vector3<F> m_linearAcceleration = Vector3<F>{0.,0.,0.};
548  Vector3<F> m_angularAcceleration = Vector3<F>{0.,0.,0.};
549 
550 public:
551 
552  static PosePred_ Identity() {
553  return PosePred_({0.,0,0},{1.,0,0,0,1,0,0,0,1});
554  }
555 
556  PosePred_() {}
557 
561  PosePred_(double c) : Pose_<F>::Pose_(c) {}
562 
566  PosePred_(Vector3<F> const& translation, Matrix3<F> const& rotation,
567  double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)(), double c=0.)
568  : Pose_<F>::Pose_(translation, rotation, hostTimestamp, edgeTimestamp, c) {}
569 
570  Transform_<F> const& transform() const { return *this; }
571 
575  Vector3<F> const& linearVelocity() const {return m_linearVelocity; }
579  Vector3<F> const& angularVelocity() const {return m_angularVelocity; }
583  void setLinearVelocity(Vector3<F> const& v) { m_linearVelocity=v; }
587  void setLinearVelocity(F const* v) {
588  std::copy(v, v+3, m_linearVelocity.data());
589  }
594  void setAngularVelocity(Vector3<F> const& v) { m_angularVelocity=v; }
599  void setAngularVelocity(F const* v) {
600  std::copy(v, v+3, m_angularVelocity.data());
601  }
602 
606  Vector3<F> const& linearAcceleration() const {return m_linearAcceleration; }
610  Vector3<F> const& angularAcceleration() const {return m_angularAcceleration; }
614  void setLinearAcceleration(Vector3<F> const& v) { m_linearAcceleration=v; }
618  void setLinearAcceleration(F const* v) {
619  std::copy(v, v+3, m_linearAcceleration.data());
620  }
625  void setAngularAcceleration(Vector3<F> const& v) { m_angularAcceleration=v; }
630  void setAngularAcceleration(F const* v) {
631  std::copy(v, v+3, m_angularAcceleration.data());
632  }
633 };
634 
635 }
636 
640 struct Transform : public details::Transform_<double> {
641  Transform();
643  Transform(Vector3d const& t, Matrix3d const& r);
644 };
648 struct TransformF : public details::Transform_<float> {
649  TransformF();
651  TransformF(Vector3f const& t, Matrix3f const& r);
652 };
653 
659 Vector3f operator*(const TransformF& a, const Vector3f& p);
665 Vector3d operator*(const Transform& lhs, const Vector3d& rhs);
669 TransformF inverse(const TransformF& t);
673 Transform inverse(const Transform& t);
674 
675 
679 struct TransformQuat : public details::TransformQuat_<double> {
680  TransformQuat();
681  TransformQuat(Vector3d const& t, Vector4d const& q);
682 };
686 struct TransformQuatF : public details::TransformQuat_<float> {
687  TransformQuatF();
688  TransformQuatF(Vector3f const& t, Vector4f const& q);
689 };
690 
706  int w;
710  int h;
714  double fx;
718  double fy;
722  double u0;
726  double v0;
737  std::array<double,5> distor;
739 };
740 
748  int w;
752  int h;
756  double fx;
760  double fy;
764  double u0;
768  double v0;
772  double xi;
773 };
774 
779  Transform pose;
780  UnifiedCameraModel intrinsics;
781 };
782 
787  Transform pose;
789 };
790 
797 struct Pose : public details::PosePred_<double> {
798  static Pose Identity() {
799  return Pose({0.,0,0},{1.,0,0,0,1,0,0,0,1});
800  }
801  Pose();
805  Pose(Vector3d const& translation, Matrix3d const& rotation,
806  double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)(), double c=0.);
812  Pose prediction(double dt) const;
813 };
814 
821 struct PoseF : public details::PosePred_<float> {
822  static Pose Identity() {
823  return Pose({0.,0,0},{1.,0,0,0,1,0,0,0,1});
824  }
825  PoseF();
829  PoseF(Vector3f const& translation, Matrix3f const& rotation,
830  double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)(), double c=0.);
831 
837  PoseF prediction(double dt) const;
838 };
839 
843 struct Event {
844  double hostTimestamp = std::numeric_limits<double>::infinity();
845  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
846  int type = 0;
847  int state = 0;
848 };
849 
853 class Orientation {
854 
855  Matrix3d m_rotation;
856  Vector4d m_quaternions;
857  Vector3d m_angularVelocity = Vector3d{0.,0.,0.};
858  Vector3d m_angularAcceleration = Vector3d{0.,0.,0.};
859 
860 public:
861  double hostTimestamp = std::numeric_limits<double>::infinity();
862  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
863 
864  Orientation();
865 
869  Orientation(Matrix3d const& rotation,
870  double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)());
871 
875  Orientation(Vector4d const& quaternion,
876  double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)());
877 
881  Vector4d const& quaternion() const;
885  void setQuaternion(Vector4d const& v);
889  void setQuaternion(double const* v);
890 
894  Matrix3d const& rotation() const {return m_rotation;}
895 
899  void setRotation(Matrix3d const& v);
903  void setRotation(double const* v);
908  Vector3d const& angularVelocity() const;
909 
914  void setAngularVelocity(Vector3d const& v);
915 
920  void setAngularVelocity(double const* v);
921 
926  void setAngularAcceleration(Vector3d const& v);
927 
932  void setAngularAcceleration(double const* v);
933 
939  Orientation prediction(double dt) const;
940 
941 };
942 
948 struct Plane {
950  std::string id;
951 
953  Vector3d normal;
954 
958  double d;
959 
963  std::vector<Vector3d> points;
964 
967  std::vector<Vector3d> vertices;
968  std::vector<std::array<uint32_t,3>> triangles;
969 };
970 
971 
975 struct SlamMap
976 {
977  std::vector<Vector3d> vertices;
978 };
979 
983 class CameraModel {
984 public:
985  virtual std::int32_t width() const {return 0; }
986  virtual std::int32_t height() const {return 0; }
987  virtual bool project(double const* /*p3d*/, double* /*p2d*/) const {return false;};
988  virtual bool raytrace(double const* /*p2d*/, double* /*p3d*/) const {return false;};
989 };
990 
994 struct Calibration {
995  Transform pose;
996  std::vector<UnifiedCameraModel> ucm;
997  std::vector<PolynomialDistortionCameraModel> pdcm;
998  std::vector<std::shared_ptr<CameraModel>> camerasModel;
999 };
1000 
1006 struct Imu {
1007  Vector3d gyro;
1008  Vector3d accel;
1009  Vector3b accelSaturation;
1010  Vector3d magneto;
1011  double temperature;
1012  double hostTimestamp = std::numeric_limits<double>::infinity();
1013  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1014 };
1015 
1020  std::size_t width;
1021  std::size_t height;
1022  std::shared_ptr<const std::uint8_t> data;
1023 };
1024 
1029  double hostTimestamp = std::numeric_limits<double>::infinity();
1030  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1031  std::vector<GrayScaleImage> images;
1032  std::int64_t id;
1033 };
1034 
1038 struct RgbImage {
1039  std::size_t width = 0;
1040  std::size_t height = 0;
1041  std::shared_ptr<const std::uint8_t> data = nullptr;
1042  RgbImage(std::size_t _width, std::size_t _height, std::shared_ptr<const std::uint8_t> _data) : width(_width), height(_height),data(_data) {}
1043 };
1044 
1048 struct ColorImage {
1049  enum class Codec { YUYV = 0, YUV420p, JPEG, NV12, BITSTREAM};
1050  Codec codec = Codec::YUYV;
1051  std::size_t width = 0;
1052  std::size_t height = 0;
1053  std::shared_ptr<const std::uint8_t> data = nullptr;
1054  unsigned int dataSize = 0;
1055  double hostTimestamp = std::numeric_limits<double>::infinity();
1056  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1060  RgbImage toRgb() const;
1061 };
1062 
1067  {
1068  int32_t enable_dewarp;
1069  float dewarp_zoom_factor;
1070  int32_t enable_disparity;
1071  int32_t enable_depth;
1072  int32_t enable_point_cloud;
1073  float baseline;
1074  float fov;
1075  uint8_t disparity_confidence_threshold;
1076  float homography[9];
1077  int32_t enable_gamma;
1078  float gamma_value;
1079  int32_t enable_gaussian;
1080  uint8_t mode;//standard 0 /Default:LRcheck 1 /Extended 2 /Subpixel 3
1081  uint16_t max_distance;//mm
1082  uint16_t min_distance;//mm
1083 
1084  inline bool operator==(const sgbm_config &cmp) const
1085  {
1086  return (enable_dewarp == cmp.enable_dewarp &&
1087  dewarp_zoom_factor == cmp.dewarp_zoom_factor &&
1088  enable_disparity == cmp.enable_disparity &&
1089  enable_depth == cmp.enable_depth &&
1090  enable_point_cloud == cmp.enable_point_cloud &&
1091  baseline == cmp.baseline &&
1092  fov == cmp.fov &&
1093  disparity_confidence_threshold == cmp.disparity_confidence_threshold);
1094  }
1095  inline bool operator!=(const sgbm_config &cmp) const
1096  {
1097  return !(*this == cmp);
1098  }
1099  };
1100 
1109 struct DepthImage {
1110  enum class Type { Depth_16 = 0, Depth_32, IR, Cloud, Raw, Eeprom, IQ };
1111  Type type = Type::Depth_32;
1112  std::size_t width = 0;
1113  std::size_t height = 0;
1114  double confidence = 0.0;
1115  std::shared_ptr<const std::uint8_t> data = nullptr;
1116  unsigned int dataSize = 0;
1117  double hostTimestamp = std::numeric_limits<double>::infinity();
1118  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1122  RgbImage toRgb() const;
1123 };
1124 
1126  std::size_t width = 0;
1127  std::size_t height = 0;
1128  std::shared_ptr<const std::uint8_t> data = nullptr;
1129  double hostTimestamp = std::numeric_limits<double>::infinity();
1130 };
1131 
1135 struct PointCloud {
1136  double hostTimestamp = std::numeric_limits<double>::infinity();
1137  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1138  std::vector<Vector3f> points;
1139 };
1140 
1142 {
1143  uint8_t data_ready_flag; // 0:invalid 1:valid
1144  double lat_data; //Latitude data
1145  uint8_t latdir; //latdir == 1(lat_data is north latitude) latdir == 2(lat_data is south latitude)
1146  double lon_data; //Longitude data
1147  uint8_t londir; //londir == 1(lon_data is east longitude) londir == 2(lon_data is west longitude)
1148  int satellite_num; //Number of satellites
1149  uint8_t mode; //mode == 1 (GPS + BDS) mode == 2(BDS)
1150 };
1151 
1152 enum class BeiDouGPSMode
1153 {
1154  BDS_SINGLE = 0,
1155  BDS_GPS_MIX = 1
1156 };
1157 
1161 struct Object {
1162  enum class Shape { BoundingBox = 0, Human, HandSkeleton };
1163  struct keypoint {
1164  double x = -1, y = -1, z = -1;
1165  };
1166 
1167  Shape shape = Shape::BoundingBox;
1168 
1169  int typeID = -1;
1170  std::string type = "";
1171  double x = 0;
1172  double y = 0;
1173  double width = 0;
1174  double height = 0;
1175  double confidence = 0.0f;
1176 
1177  std::vector<keypoint> keypoints;
1178 };
1179 
1184  struct keypoint {
1185  double x = -1, y = -1, z = -1;
1186  };
1187 
1188  int idx;
1189  std::string name;
1190  float score;
1191  float left, top, width, height;
1192  std::vector<keypoint> keypoints;
1193  Det2dObject(){};
1194  Det2dObject(int i, const std::string& n, float s, float l, float t, float w, float h) :
1195  idx(i), name(n), score(s), left(l), top(t), width(w), height(h) {}
1196  Det2dObject(int i, const std::string& n, float s, float l, float t, float w, float h, std::vector<keypoint> pts) :
1197  idx(i), name(n), score(s), left(l), top(t), width(w), height(h), keypoints(pts){}
1198 };
1199 
1201  std::shared_ptr<float> raw_data = nullptr;
1202  unsigned int raw_data_length;
1203  double hostTimestamp;
1204  uint64_t edgeTimestamp;
1205 };
1206 
1207 
1208 
1209 
1211  std::string type;
1212  std::vector<std::string> classes;
1213  double threshold = 0.5;
1214  bool flipStereo = false;
1215  bool flipRgb = false;
1216  bool flipTof = false;
1217  bool enable_3dbbox = false;
1218  std::vector<double> prior_bbox_z;
1219 };
1220 
1225 struct SgbmImage {
1226  enum class Type { Disparity = 0, Depth, PointCloud, None};
1227  Type type;
1228  SgbmImage() : type(Type::None) {}
1229  explicit SgbmImage(Type t) : type(t) {}
1230  std::size_t width = 0;
1231  std::size_t height = 0;
1232  std::shared_ptr<const std::uint8_t> data = nullptr;
1233  unsigned int dataSize = 0;
1234  double hostTimestamp = std::numeric_limits<double>::infinity();
1235  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1239  RgbImage toRgb() const;
1240 };
1241 
1246  enum class Codec {UYVY};
1247  const Codec codec;
1248  explicit ThermalImage(Codec t) : codec(t) {}
1249  std::size_t width = 0;
1250  std::size_t height = 0;
1251  std::shared_ptr<const std::uint8_t> data = nullptr;
1252  unsigned int dataSize = 0;
1253  double hostTimestamp = std::numeric_limits<double>::infinity();
1254  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1258  RgbImage toRgb() const;
1259 
1260  // InfraredImage(std::shared_ptr<const std::uint8_t> ptr) :
1261  // data(ptr)
1262  // {
1263 
1264  // }
1265  // std::size_t width = 0; //!< width of the image (in pixel)
1266  // std::size_t height = 0; //!< height of the image (in pixel)
1267  // std::shared_ptr<const std::uint8_t> data = nullptr; //! image of depth
1268  // unsigned int dataSize = 0;
1269  // double hostTimestamp = std::numeric_limits<double>::infinity(); //!< host timestamp of the physical measurement (in second based on the `std::chrono::steady_clock`).
1270  // std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)(); //!< timestamp of the physical measurement (in microsecond based on edge clock).
1271 };
1272 
1277  double hostTimestamp = std::numeric_limits<double>::infinity();
1278  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1279  std::vector<GrayScaleImage> images;
1280 };
1281 
1282 struct MicData {
1283  double hostTimestamp = std::numeric_limits<double>::infinity();
1284  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1285  std::shared_ptr<const std::uint8_t> data = nullptr;
1286  unsigned int dataSize = 0;
1287 };
1288 
1292 struct keypoint {
1293  float x = -1;
1294  float y = -1;
1295  float z = -1;
1296 };
1297 
1301 struct GestureData {
1302  int index[2] = {-1,-1};
1305  double hostTimestamp = std::numeric_limits<double>::infinity();
1306  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1307  float distance;
1308  float confidence;
1309 };
1310 
1311 enum class ResolutionMode{
1312  R_VGA,
1313  R_720P
1314 };
1315 
1319 typedef union XV_ET_POINT_2D
1320 {
1321  struct {
1322  float x, y;
1323  };
1324  float seq[2];
1325 }xv_ETPoint2D;
1326 
1330 typedef union XV_ET_POINT_3D
1331 {
1332  struct {
1333  float x, y, z;
1334  };
1335  float seq[3];
1336 }xv_ETPoint3D;
1337 
1341 enum XV_ET_EYE_TYPE {
1342  L_EYE = 1,
1343  R_EYE = 2
1344 };
1345 typedef XV_ET_EYE_TYPE xv_ETEyeType;
1346 
1350 enum XV_ET_MODE {
1351  track = 3,
1352  iris = 5
1353 };
1354 typedef XV_ET_MODE xv_ETMode;
1355 
1360  xv_ETMode mode;
1361  char configPath[260];
1362 };
1364 
1368 typedef struct XV_ET_COEFFICIENT {
1369  unsigned char buf[1024];
1371 
1372 
1373 enum XV_EyeGazeExDataValidity {
1374  EYE_GAZE_EXDATA_SCORE = 0,
1375 };
1376 
1382 {
1383  unsigned int gazeBitMask;
1389  float re;
1390  unsigned int exDataBitMask;
1391  float exData[32];
1392 };
1393 
1399 {
1400  unsigned int pupilBitMask;
1407 };
1408 
1414 {
1415  unsigned int eyeDataExBitMask;
1416  int blink;
1417  float openness;
1418  float eyelidUp;
1419  float eyelidDown;
1420 };
1421 
1427 {
1428  unsigned long long timestamp;
1433 
1436 
1439 
1442  float ipd;
1443 };
1444 
1446 typedef enum GazeStatus {
1448  GAZE_STATUS_OK,
1449 
1451  GAZE_STATUS_ERROR,
1452 
1454  GAZE_STATUS_INITIALIZE_FAILED,
1455 
1457  GAZE_STATUS_TERMINATE_FAILED,
1458 
1460  GAZE_STATUS_INVALID_PARAMETER,
1461 
1463  GAZE_STATUS_INVALID_OPERATION,
1464 
1466  GAZE_STATUS_DEVICE_NOT_AVAILABLE,
1467 
1469  GAZE_STATUS_TIMED_OUT,
1470 
1472  GAZE_STATUS_MEM_ALLOCATION_FAILED
1473 }
1474 GazeStatus;
1475 
1476 
1477 typedef enum CalibrationApiStatus {
1482  CALIBRATION_API_STATUS_COMPLETE_AUTOMATICALLY,
1483 
1485  CALIBRATION_API_STATUS_COMPLETE_MANUALLY,
1486 
1491  CALIBRATION_API_STATUS_ACCEPT_CALLING,
1492 
1494  CALIBRATION_API_STATUS_DO_NOT_CALL,
1495 
1497  CALIBRATION_API_STATUS_BUSY
1498 }
1499 CalibrationApiStatus;
1500 
1502 typedef struct CalibrationStatus {
1504  CalibrationApiStatus enter_status;
1505 
1507  CalibrationApiStatus collect_status;
1508 
1510  CalibrationApiStatus setup_status;
1511 
1513  CalibrationApiStatus compute_apply_status;
1514 
1516  CalibrationApiStatus leave_status;
1517 
1519  CalibrationApiStatus reset_status;
1520 }
1522 
1524 typedef struct GazeCalibrationData {
1526  void* data = nullptr;
1527 
1529  size_t size;
1530 
1533  {
1534  if (data != nullptr)
1535  {
1536  free(data);
1537  data = nullptr;
1538  }
1539  };
1540 }
1541 GazeCalibrationData;
1542 
1544 {
1545  std::vector<char> name;
1546  std::vector<unsigned char> feature;
1547  int size;
1548  int error;
1549 };
1550 
1555 struct DateTime {
1556  int Y, M, D;
1557  int h, m;
1558  int s;
1559 };
1560 
1567  int signal;
1568  unsigned char sum;
1569 };
1570 
1571 struct Triple
1572 {
1573  Vector2<unsigned short> p2d;
1574  size_t i3d;
1575  Triple(Vector2<unsigned short> const& p2, size_t i3): p2d(p2), i3d(i3) {}
1576 };
1578 {
1579  FisheyeImages fisheyeImages;
1580  std::vector<std::vector<Triple>> matches;
1581 };
1582 
1584 {
1585  float offset[3];
1586  float angles[3];
1587  float magnetic[3];
1588  int level;
1589 };
1590 
1594 struct HandPose{
1595  std::vector<Pose> pose; // 26 + 26
1596  float scale[2]; // 1 + 1
1597  int status[2] = {-1,-1};
1598  double timestamp[2];
1599  double fisheye_timestamp;
1600 };
1601 
1603  int tv_sec;
1604  int tv_msec;
1605  std::uint8_t state;
1606  float x;
1607  float y;
1608  float z;
1609  float pitch;
1610  float roll;
1611  float yaw;
1612  double hostTimestamp;
1613 };
1614 
1615 enum WirelessControllerDataType
1616 {
1617  UNKNOW = 0,
1618  LEFT = 0xC4,
1619  RIGHT = 0xC5,
1620  ALL = 0xC6
1621 };
1623 {
1624  WirelessControllerDataType type;
1625  Pose pose;
1626  uint8_t keyTrigger;
1627  uint8_t keySide;
1628  int16_t rocker_x;
1629  int16_t rocker_y;
1630  uint8_t key;
1631 };
1632 
1633 enum WirelessControllerSlamType
1634 {
1635  VIO = 1,
1636  CSLAM = 2,
1637  REAL_TIME_SHARED_MAP = 3
1638 };
1639 
1641 {
1642  std::string name;
1643  std::string mac;
1644  int state;
1645 };
1646 
1648 {
1649  uint8_t battery; // 1 bytes
1650  uint8_t temp; // 1 bytes
1651 };
1652 
1654 {
1655  int screenWidth;
1656  int screenHeight;
1657  float ipdDist;
1658  int srValue;
1659 };
1660 
1661 }
Generic camera model.
Definition: xv-types.h:983
Orientation only (3dof) of the pose.
Definition: xv-types.h:853
Orientation(Vector4d const &quaternion, double hostTimestamp=std::numeric_limits< double >::infinity(), std::int64_t edgeTimestamp=(std::numeric_limits< std::int64_t >::min)())
Construct an orientation (3dof) rotation and timestamps.
Matrix3d const & rotation() const
Get the rotation matrix part of the transformation.
Definition: xv-types.h:894
void setAngularAcceleration(Vector3d const &v)
Set an estimation of instantaneous angular acceleration of the pose.
void setQuaternion(Vector4d const &v)
Set the quaternion of the rotation [qx,qy,qz,qw].
void setQuaternion(double const *v)
Set the quaternion of the rotation using pointer of 4D array [qx,qy,qz,qw].
Vector3d const & angularVelocity() const
An estimation of instantaneous angular velocity of the pose.
double hostTimestamp
host timestamp of the plane (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:861
Vector4d const & quaternion() const
Get the quaternion of the rotation [qx,qy,qz,qw].
void setRotation(Matrix3d const &v)
Get the rotation matrix part of the transformation.
void setAngularVelocity(Vector3d const &v)
Set an estimation of instantaneous angular velocity of the pose.
void setAngularAcceleration(double const *v)
Set an estimation of instantaneous angular acceleration of the pose.
Orientation prediction(double dt) const
Prediction of the orientation based on angular velocity and acceleration.
std::int64_t edgeTimestampUs
timestamp of the plane (in microsecond based on edge clock).
Definition: xv-types.h:862
Orientation(Matrix3d const &rotation, double hostTimestamp=std::numeric_limits< double >::infinity(), std::int64_t edgeTimestamp=(std::numeric_limits< std::int64_t >::min)())
Construct an orientation (3dof) rotation and timestamps.
void setRotation(double const *v)
Set the quaternion of the rotation using pointer of 4D array.
void setAngularVelocity(double const *v)
Set an estimation of instantaneous angular velocity of the pose.
Definition: xv-types.h:542
void setAngularAcceleration(Vector3< F > const &v)
Set an estimation of instantaneous angular acceleration of the pose.
Definition: xv-types.h:625
void setAngularVelocity(F const *v)
Set an estimation of instantaneous angular velocity of the pose.
Definition: xv-types.h:599
void setAngularAcceleration(F const *v)
Set an estimation of instantaneous angular acceleration of the pose.
Definition: xv-types.h:630
void setLinearVelocity(Vector3< F > const &v)
Set the linear velocity (in m/s)
Definition: xv-types.h:583
Vector3< F > const & linearVelocity() const
Get the linear velocity (in m/s) of the pose.
Definition: xv-types.h:575
void setAngularVelocity(Vector3< F > const &v)
Set an estimation of instantaneous angular velocity of the pose.
Definition: xv-types.h:594
Vector3< F > const & angularVelocity() const
Get the angular velocity (x,y,z) in rad/s.
Definition: xv-types.h:579
void setLinearAcceleration(Vector3< F > const &v)
Set the linear acceleration (in m/s)
Definition: xv-types.h:614
Vector3< F > const & linearAcceleration() const
Get the linear acceleration (in m/s/s) of the pose.
Definition: xv-types.h:606
PosePred_(Vector3< F > const &translation, Matrix3< F > const &rotation, double hostTimestamp=std::numeric_limits< double >::infinity(), std::int64_t edgeTimestamp=(std::numeric_limits< std::int64_t >::min)(), double c=0.)
Construct a pose with a translation, rotation, timestamps and confidence.
Definition: xv-types.h:566
PosePred_(double c)
Construct a pose with a specified confidence.
Definition: xv-types.h:561
void setLinearVelocity(F const *v)
Set the angular velocity (x,y,z) in rad/s.
Definition: xv-types.h:587
Vector3< F > const & angularAcceleration() const
Get the angular acceleration (x,y,z) in rad/s/s.
Definition: xv-types.h:610
void setLinearAcceleration(F const *v)
Set the angular acceleration (x,y,z) in rad/s/s.
Definition: xv-types.h:618
Definition: xv-types.h:408
void setEdgeTimestampUs(std::int64_t t)
Set the edge timestamp of the pose (in microseconds).
Definition: xv-types.h:426
void setHostTimestamp(double t)
Set the host timestamp corresponding to the pose (in s).
Definition: xv-types.h:434
double hostTimestamp() const
Get the host timestamp corresponding to the pose (in s).
Definition: xv-types.h:430
std::int64_t edgeTimestampUs() const
Get the edge timestamp of the pose (in microseconds).
Definition: xv-types.h:422
Definition: xv-types.h:438
void setHostTimestamp(double t)
Set the host timestamp of the pose (in s).
Definition: xv-types.h:463
double hostTimestamp() const
Get the host timestamp of the pose (in s).
Definition: xv-types.h:459
void setEdgeTimestampUs(std::int64_t t)
Set the edge timestamp of the pose (in microseconds).
Definition: xv-types.h:455
std::int64_t edgeTimestampUs() const
Get the edge timestamp of the pose (in microseconds).
Definition: xv-types.h:451
Definition: xv-types.h:467
void setQuaternion(F const *v)
Set the quaternion of the rotation using pointer of 4D array.
Definition: xv-types.h:518
void setConfidence(double c)
Set the confidence of the pose. Value in [0,1], 0 means lost.
Definition: xv-types.h:502
Pose_(Vector3< F > const &translation, Matrix3< F > const &rotation, double hostTimestamp=std::numeric_limits< double >::infinity(), std::int64_t edgeTimestamp=(std::numeric_limits< std::int64_t >::min)(), double c=0.)
Construct a pose with a translation, rotation, timestamps and confidence.
Definition: xv-types.h:490
double confidence() const
Get the confidence of the pose. Value in [0,1], 0 means lost.
Definition: xv-types.h:497
void setRotation(F const *v)
Set the quaternion of the rotation using pointer of 4D array.
Definition: xv-types.h:532
Pose_(double c)
Construct a pose with a specified confidence.
Definition: xv-types.h:485
Vector4< F > const & quaternion() const
Get the quaternion of the rotation.
Definition: xv-types.h:507
void setRotation(Matrix3< F > const &v)
Get the rotation matrix part of the transformation.
Definition: xv-types.h:525
void setQuaternion(Vector4< F > const &v)
Set the quaternion of the rotation.
Definition: xv-types.h:511
Definition: xv-types.h:337
void setQuaternion(Vector4< F > const &v)
Set the quaternion [qx,qy,qz,qw] of the rotation.
F x() const
X coordinate of the translation.
Definition: xv-types.h:374
F qx() const
qx quaternion composant
Definition: xv-types.h:387
F qz() const
qx quaternion composant
Definition: xv-types.h:395
void setQuaternion(F const *v)
Set the quaternion [qx,qy,qz,qw] of the rotation using pointer to 4D array.
F z() const
Z coordinate of the translation.
Definition: xv-types.h:382
F y() const
Y coordinate of the translation.
Definition: xv-types.h:378
Vector4< F > const & quaternion() const
Get the quaternion [qx,qy,qz,qw] of the rotation.
F qw() const
qx quaternion composant
Definition: xv-types.h:399
F qy() const
qx quaternion composant
Definition: xv-types.h:391
Definition: xv-types.h:238
Vector3< F > const & translation() const
Get the translation part of the transformation.
Definition: xv-types.h:262
F z() const
Z coordinate of the translation.
Definition: xv-types.h:297
void setTranslation(Vector3< F > const &v)
Set the translation part of the transformation.
Definition: xv-types.h:266
Transform_< F > inverse() const
Compute the inverse transformation.
Transform_ & operator*=(Transform_ const &q)
Composition operator for transformations.
F x() const
X coordinate of the translation.
Definition: xv-types.h:289
F y() const
Y coordinate of the translation.
Definition: xv-types.h:293
void setTranslation(F const *v)
Set the translation part of the transformation using pointer to 3D array.
Definition: xv-types.h:270
void setRotation(Matrix3< F > const &v)
Get the rotation matrix part of the transformation.
Definition: xv-types.h:280
void setRotation(F const *v)
Set the rotation matrix (row major 3x3) part of the transformation using pointer to array of size 9.
Definition: xv-types.h:284
Matrix3< F > const & rotation() const
Get the rotation matrix part of the transformation.
Definition: xv-types.h:276
Vector4d rotationToQuaternion(Matrix3d const &rot)
Convert a rotation matrix to quaternion.
Matrix3d quaternionToRotation(Vector4d const &q)
Convert quaternion to rotation matrix.
Matrix3f quaternionsToRotation(Vector4f const &q)
Deprecated. Same to #quaternionToRotation.
Vector3f rotationToPitchYawRoll(Matrix3f const &rot)
Convert rotation Euler angles.
Transform_< float > inverse(const Transform_< float > &t)
Compute the inverse transformation.
AF settings.
Definition: xv-types.h:78
AWB settings.
Definition: xv-types.h:69
Definition: xv-types.h:1142
Definition: xv-types.h:1502
CalibrationApiStatus leave_status
Definition: xv-types.h:1516
CalibrationApiStatus reset_status
Definition: xv-types.h:1519
CalibrationApiStatus enter_status
Definition: xv-types.h:1504
CalibrationApiStatus setup_status
Definition: xv-types.h:1510
CalibrationApiStatus collect_status
Definition: xv-types.h:1507
CalibrationApiStatus compute_apply_status
Definition: xv-types.h:1513
Calibration (extrinsics and intrinsics).
Definition: xv-types.h:994
std::vector< UnifiedCameraModel > ucm
pose of the sensor(camera and display) in the IMU frame coordinates.
Definition: xv-types.h:996
std::vector< PolynomialDistortionCameraModel > pdcm
Deprecated, better to use camerasModel; List of Unified Camera Model parameters for differents camera...
Definition: xv-types.h:997
std::vector< std::shared_ptr< CameraModel > > camerasModel
Deprecated, better to use camerasModel; List of Polynomial Distortion Camera Model parameters for dif...
Definition: xv-types.h:998
Definition: xv-types.h:1200
A color image given by xv::ColorCamera.
Definition: xv-types.h:1048
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1056
unsigned int dataSize
image data
Definition: xv-types.h:1054
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1055
RgbImage toRgb() const
Convert to a xv::RgbImage.
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1051
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1052
Definition: xv-types.h:1555
int D
Year, month, and day.
Definition: xv-types.h:1556
int m
Hour and minutes.
Definition: xv-types.h:1557
int s
Seconds.
Definition: xv-types.h:1558
Definition: xv-types.h:1125
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1126
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1127
double hostTimestamp
image data of RGB-D pixels : RGB (3 bytes) D (float 4bytes)
Definition: xv-types.h:1129
An image provided by a TOF camera.
Definition: xv-types.h:1109
double confidence
confidence of depth [0.0,1.0]
Definition: xv-types.h:1114
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1113
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1112
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1118
RgbImage toRgb() const
Convert to a xv::RgbImage.
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1117
unsigned int dataSize
image of depth
Definition: xv-types.h:1116
Definition: xv-types.h:1184
Object detection bounding box. 2d.
Definition: xv-types.h:1183
Device setting.
Definition: xv-types.h:87
Event.
Definition: xv-types.h:843
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:844
int type
Type of event.
Definition: xv-types.h:846
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:845
int state
State of the event.
Definition: xv-types.h:847
Exposure settings.
Definition: xv-types.h:56
Definition: xv-types.h:1602
A color image given by xv::EyetrackingCamera.
Definition: xv-types.h:1276
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock),...
Definition: xv-types.h:1277
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1278
Images coming from xv::FisheyeCameras sensor system used for visual SLAM.
Definition: xv-types.h:1028
std::int64_t id
List of images (typically 2, first is left and second image is the right image)
Definition: xv-types.h:1032
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock),...
Definition: xv-types.h:1029
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1030
Definition: xv-types.h:1565
int distance
Distance.
Definition: xv-types.h:1566
int signal
Signal Intensity.
Definition: xv-types.h:1567
unsigned char sum
Check sum.
Definition: xv-types.h:1568
Definition: xv-types.h:1524
~GazeCalibrationData()
Definition: xv-types.h:1532
void * data
Definition: xv-types.h:1526
size_t size
Definition: xv-types.h:1529
Definition: xv-types.h:1654
Gesture data.
Definition: xv-types.h:1301
float distance
reserved, dynamic gesture movement distance.
Definition: xv-types.h:1307
float confidence
reserved, gesture confidence.
Definition: xv-types.h:1308
int index[2]
Index array for hands gesture, max size is two, default is -1 means invalid.
Definition: xv-types.h:1302
keypoint position[2]
Position array for hand gesture, max size is two, 2D points, z isn't used by default.
Definition: xv-types.h:1303
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1306
keypoint slamPosition[2]
Convert rgb points into slam points, Position array for hand gesture, max size is two.
Definition: xv-types.h:1304
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1305
A grayscale image that is usually an image from a camera used for visual SLAM.
Definition: xv-types.h:1019
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1021
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1020
new hand pose struct.
Definition: xv-types.h:1594
Data from IMU sensor of the XVisio device.
Definition: xv-types.h:1006
Vector3b accelSaturation
3-axis accel saturation status (true if saturating)
Definition: xv-types.h:1009
double temperature
sensor temperature (in K)
Definition: xv-types.h:1011
Vector3d accel
3-axis accelerometer values (in m/s²)
Definition: xv-types.h:1008
Vector3d gyro
3-axis gyrometer values (in rad/s)
Definition: xv-types.h:1007
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1012
Vector3d magneto
3-axis magnetometer values
Definition: xv-types.h:1010
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1013
Definition: xv-types.h:101
Definition: xv-types.h:1282
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1284
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1283
unsigned int dataSize
image data
Definition: xv-types.h:1286
Definition: xv-types.h:1210
Definition: xv-types.h:1163
Object detection bounding box.
Definition: xv-types.h:1161
Calibration parameters of a camera using Polynomial Distortion Model for camera intrinsics.
Definition: xv-types.h:786
A 3D plane definition.
Definition: xv-types.h:948
double d
Signed distance to origin. Signed distance between the plane and the origin of the world....
Definition: xv-types.h:958
Vector3d normal
Unit vector normal to the plane.
Definition: xv-types.h:953
std::string id
Plane unique identifier.
Definition: xv-types.h:950
std::vector< Vector3d > vertices
Flat, 3D, triangle mesh describing the detailed plane geometry extents. More convenient than the bord...
Definition: xv-types.h:967
std::vector< Vector3d > points
Points lying at the border of the plane. Array of 3D points lying on the plane that describes the pol...
Definition: xv-types.h:963
A point cloud of 3D points.
Definition: xv-types.h:1135
double hostTimestamp
host timestamp of ? (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1136
std::int64_t edgeTimestampUs
timestamp of ? (in microsecond based on edge clock).
Definition: xv-types.h:1137
Definition: xv-types.h:1578
Polynomial Distortion Model for camera intrisics.
Definition: xv-types.h:702
double fx
Focal length in width direction (in pixel)
Definition: xv-types.h:714
int w
Image width (in pixel)
Definition: xv-types.h:706
double fy
Focal length in height direction (in pixel)
Definition: xv-types.h:718
double u0
Optical axis intersection in width direction (in pixel)
Definition: xv-types.h:722
std::array< double, 5 > distor
Distortion parameters.
Definition: xv-types.h:737
int h
Image height (in pixel)
Definition: xv-types.h:710
double v0
Optical axis intersection in height direction (in pixel)
Definition: xv-types.h:726
Class representing a 6dof pose at a timestamp with a linear model for prediction.
Definition: xv-types.h:821
PoseF(Vector3f const &translation, Matrix3f const &rotation, double hostTimestamp=std::numeric_limits< double >::infinity(), std::int64_t edgeTimestamp=(std::numeric_limits< std::int64_t >::min)(), double c=0.)
Construct a pose with a translation, rotation, timestamps and confidence.
PoseF prediction(double dt) const
Prediction of the pose based on angular and linear velocity and acceleration.
Class representing a 6dof pose at a timestamp with a linear model for prediction.
Definition: xv-types.h:797
Pose(Vector3d const &translation, Matrix3d const &rotation, double hostTimestamp=std::numeric_limits< double >::infinity(), std::int64_t edgeTimestamp=(std::numeric_limits< std::int64_t >::min)(), double c=0.)
Construct a pose with a translation, rotation, timestamps and confidence.
Pose prediction(double dt) const
Prediction of the pose based on angular and linear velocity and acceleration.
A color image in RGB format.
Definition: xv-types.h:1038
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1039
RgbImage(std::size_t _width, std::size_t _height, std::shared_ptr< const std::uint8_t > _data)
image data (in row-major) : RGB RGB RGB .... Data size = width*height*3
Definition: xv-types.h:1042
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1040
SGBM data.
Definition: xv-types.h:1225
unsigned int dataSize
data of SGBM
Definition: xv-types.h:1233
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1234
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1235
RgbImage toRgb() const
Convert to a xv::RgbImage.
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1230
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1231
A sparse SLAM map with 3D points.
Definition: xv-types.h:976
Definition: xv-types.h:1584
A color image given by xv::ThermalCamera.
Definition: xv-types.h:1245
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1250
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1254
RgbImage toRgb() const
Convert to a xv::RgbImage.
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1253
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1249
unsigned int dataSize
image data
Definition: xv-types.h:1252
Represents atransformation (or pose) with translation and rotation matrix in float type.
Definition: xv-types.h:648
Represents a float typed transformation (or pose) with translation and quaternion for rotation in flo...
Definition: xv-types.h:686
Represents a float typed transformation (or pose) with translation and quaternion for rotation.
Definition: xv-types.h:679
Represents a transformation (or pose) with translation and rotation matrix.
Definition: xv-types.h:640
Definition: xv-types.h:1572
Calibration parameters of a camera using Unified Camera Model for camera intrinsics.
Definition: xv-types.h:778
Unified Camera Model.
Definition: xv-types.h:744
double u0
Optical axis intersection in width direction (in pixel)
Definition: xv-types.h:764
int w
Image width (in pixel)
Definition: xv-types.h:748
double xi
xi parameter of Unified Camera Model
Definition: xv-types.h:772
double fx
Focal length in width direction (in pixel)
Definition: xv-types.h:756
double fy
Focal length in height direction (in pixel)
Definition: xv-types.h:760
double v0
Optical axis intersection in height direction (in pixel)
Definition: xv-types.h:768
int h
Image height (in pixel)
Definition: xv-types.h:752
The Version struct.
Definition: xv-types.h:127
int minor
Minor number of the version.
Definition: xv-types.h:132
int major
Major number of the version.
Definition: xv-types.h:131
int patch
Patch number of the version.
Definition: xv-types.h:133
Definition: xv-types.h:1623
Definition: xv-types.h:1648
Definition: xv-types.h:1641
Definition: xv-types.h:1368
unsigned char buf[1024]
calibration factor.
Definition: xv-types.h:1369
Definition: xv-types.h:1427
XV_ET_PUPIL_INFO leftPupil
left eye pupil data
Definition: xv-types.h:1434
XV_ET_PUPIL_INFO rightPupil
right eye pupil data
Definition: xv-types.h:1435
XV_ET_GAZE_POINT recomGaze
recommend gaze data
Definition: xv-types.h:1430
XV_ET_EYE_EXDATA rightExData
right eye extend data(include blink and eyelid data)
Definition: xv-types.h:1438
XV_ET_GAZE_POINT rightGaze
right eye gaze data
Definition: xv-types.h:1432
unsigned long long timestamp
timestamp.
Definition: xv-types.h:1428
int recommend
whether if there has the recommend point. 0-no recommend point, 1-use left eye as recommend point,...
Definition: xv-types.h:1429
XV_ET_GAZE_POINT leftGaze
left eye gaze data
Definition: xv-types.h:1431
float ipd
The estimated interpupilary distance (IPD)
Definition: xv-types.h:1442
int leftEyeMove
0-Eye movement type is no-eye detected. 1-Eye movement type is blink. 2-Eye movement type is noraml.
Definition: xv-types.h:1440
XV_ET_EYE_EXDATA leftExData
left eye extend data(include blink and eyelid data)
Definition: xv-types.h:1437
int rightEyeMove
0-Eye movement type is no-eye detected. 1-Eye movement type is blink. 2-Eye movement type is noraml.
Definition: xv-types.h:1441
Definition: xv-types.h:1414
float eyelidDown
down eyelid data(0-1), down eyelid's vertical position in the image, normalization value,...
Definition: xv-types.h:1419
float openness
eye openness(0-100), 0-cloing, 100-opening normally, >100-opening on purpose.
Definition: xv-types.h:1417
unsigned int eyeDataExBitMask
eye extend data bit mask, identify the four data below are valid or invalid.
Definition: xv-types.h:1415
int blink
blink data, 0-no blink, 1-start blinking, 2-closing process, 3-close eyes, 4-opening process,...
Definition: xv-types.h:1416
float eyelidUp
up eyelid data(0-1), up eyelid's vertical position in the image, normalization value,...
Definition: xv-types.h:1418
Definition: xv-types.h:1382
xv_ETPoint3D rawPoint
gaze point before smooth, x and y are valid, z default value is 0, x and y scope are as above.
Definition: xv-types.h:1385
float re
gaze re value, confidence level.
Definition: xv-types.h:1389
xv_ETPoint3D gazeDirection
gaze direction.
Definition: xv-types.h:1388
float exData[32]
reserved data.
Definition: xv-types.h:1391
xv_ETPoint3D gazeOrigin
origin gaze center coordinate.
Definition: xv-types.h:1387
xv_ETPoint3D smoothPoint
gaze point after smooth, x and y are valid, z default value is 0, x and y scope are as above.
Definition: xv-types.h:1386
unsigned int exDataBitMask
reserved data.
Definition: xv-types.h:1390
xv_ETPoint3D gazePoint
gaze point, x and y are valid, z default value is 0, x and y scope are related to the input calibrati...
Definition: xv-types.h:1384
unsigned int gazeBitMask
gaze bit mask, identify the six data below are valid or invalid.
Definition: xv-types.h:1383
Definition: xv-types.h:1359
xv_ETMode mode
sdk mode, refer to xv_ETMode.
Definition: xv-types.h:1360
char configPath[260]
config file path.
Definition: xv-types.h:1361
Definition: xv-types.h:1399
unsigned int pupilBitMask
pupil bit mask, identify the six data below are valid or invalid.
Definition: xv-types.h:1400
float pupilMinorAxisMM
pupil diameter, pupil minor axis value(mm).
Definition: xv-types.h:1406
float pupilDiameter
pupil diameter, pupil long axis value(0-1), the ratio of the pixel value of the long axis size of the...
Definition: xv-types.h:1403
xv_ETPoint2D pupilCenter
pupil center(0-1), the coordinate value of pupil center in the image, normalization value,...
Definition: xv-types.h:1401
float pupilMinorAxis
pupil diameter, pupil minor axis value(0-1), the ratio of the pixel value of the minor axis size of t...
Definition: xv-types.h:1405
float pupilDistance
the distance between pupil and camera(mm)
Definition: xv-types.h:1402
float pupilDiameterMM
pupil diameter, pupil long axis value(mm).
Definition: xv-types.h:1404
Definition: xv-types.h:1544
Gesture key point.
Definition: xv-types.h:1292
SGBM CONFIG STRUCT.
Definition: xv-types.h:1067
Definition: xv-types.h:1320
Definition: xv-types.h:1331