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 };
39 
40 
44 enum class PlugEventType { Plugin, Unplug };
45 
50 #pragma pack(1)
51 
55 struct ExpSetting{
56  std::uint32_t iso_value;
57  std::uint32_t exp_abs;
58  std::uint8_t exp_mode;
59  std::int8_t exp_level;
60  std::uint8_t exp_anti; // ANTIBANDING_MODES
61  std::uint8_t iso_mode;
62 };
63 
67 struct AwbSetting
68 {
69  std::uint8_t awb_mode;
70  std::uint8_t awb_lock;
71 };
72 
76 struct AfSetting
77 {
78  std::uint8_t af_mode;
79  std::uint8_t af_dist;
80 };
81 
86 {
87  std::uint32_t cmd; //sensorId:8 + channel:8 + sensorCmd:16
88 
89  union {
90  std::uint8_t val[24];
91  AwbSetting awb;
92  ExpSetting exp;
93  AfSetting af;
94  std::int16_t val16;
95  std::int32_t val32;
96  }args;
97 };
98 
100 {
101  int32_t maxIsoGainValue;
102  int32_t minIsoGainValue;
103  int32_t maxExposureTimeUs;
104  int32_t minExposureTimeUs;
105  uint8_t targetMeanPixelValue;
106  int32_t ratioIso;
107  int32_t cpt_aec_no_modify_range;
108  float exposureTime_control_porprotion_value;
109  float exposureTime_control_integral_value;
110  float isoGain_control_porprotion_value;
111  float isoGain_control_integral_value;
112  uint32_t ISP_AEC_MODE;
113 };
114 
115 #pragma pack()
116 
126 struct Version{
127  Version( int major = 0, int minor = 0, int patch = 0 );
128  Version( const std::string &s );
129 
130  int major = 0;
131  int minor = 0;
132  int patch = 0;
133 
134  int key() const;
135  std::string toString() const;
136 
137  static int (max)();
138 };
139 
140 bool operator<(const Version &a, const Version &b);
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 
147 std::ostream& operator<<(std::ostream& o, Version const& v);
151 template<class F> using Vector2 = std::array<F,2>;
152 template<class F> using Vector3 = std::array<F,3>;
153 template<class F> using Vector4 = std::array<F,4>;
154 template<class F> using Matrix3 = std::array<F,9>;
155 
156 typedef Vector2<bool> Vector2b;
157 typedef Vector3<bool> Vector3b;
158 typedef Vector4<bool> Vector4b;
159 typedef Vector2<double> Vector2d;
160 typedef Vector3<double> Vector3d;
161 typedef Vector4<double> Vector4d;
162 typedef Matrix3<double> Matrix3d;
163 typedef Vector2<float> Vector2f;
164 typedef Vector3<float> Vector3f;
165 typedef Vector4<float> Vector4f;
166 typedef Matrix3<float> Matrix3f;
167 
177 Vector4f rotationToQuaternion(Matrix3f const& rot);
183 Vector4d rotationToQuaternion(Matrix3d const& rot);
184 
190 Matrix3f quaternionToRotation(Vector4f const& q);
191 
197 Matrix3d quaternionToRotation(Vector4d const& q);
198 
202 Matrix3f quaternionsToRotation(Vector4f const& q);
203 
212 Vector3d rotationToPitchYawRoll(Matrix3d const& rot);
213 
222 Vector3f rotationToPitchYawRoll(Matrix3f const& rot);
223 
231 namespace details {
232 
236 template <class F=double>
237 class Transform_ {
238 
239 protected:
240  Vector3<F> m_translation;
241  Matrix3<F> m_rotation;
242 
243 public:
244 
245  static Transform_ Identity() {
246  return Transform_({0.,0,0},{1.,0,0,0,1,0,0,0,1});
247  }
248 
249  Transform_() {};
250  Transform_(Vector3<F> const& t, Matrix3<F> const& r={}) : m_translation(t), m_rotation(r) {};
251 
255  Transform_& operator*=(Transform_ const& q);
256 
261  Vector3<F> const& translation() const {return m_translation;}
265  void setTranslation(Vector3<F> const& v) {m_translation = v;}
269  void setTranslation(F const* v) {std::copy(v, v+3, m_translation.data());}
270 
275  Matrix3<F> const& rotation() const {return m_rotation;}
279  void setRotation(Matrix3<F> const& v) {m_rotation = v;}
283  void setRotation(F const* v) {std::copy(v, v+9, m_rotation.data());}
284 
288  F x() const { return m_translation[0]; }
292  F y() const { return m_translation[1]; }
296  F z() const { return m_translation[2]; }
301  Transform_<F> inverse() const;
302 };
303 
304 template <class F=double>
305 Transform_<F> operator*(Transform_<F> lhs, const Transform_<F>& rhs) {
306  lhs *= rhs;
307  return lhs;
308 }
309 
315 Vector3d operator*(const Transform_<double>& a, const Vector3d& p);
316 
322 Vector3f operator*(const Transform_<float>& a, const Vector3f& p);
323 
328 
332 Transform_<double> inverse(const Transform_<double>& t);
333 
334 
335 template <class F=double>
337 
338 protected:
339  Vector3<F> m_translation;
340  Vector4<F> m_quaternions;
341 
342 public:
343 
344  static TransformQuat_ Identity() {
345  return TransformQuat_({0.,0,0},{0.,0,0,0,1});
346  }
347 
348  TransformQuat_() {}
349  TransformQuat_(Vector3<F> const& t, Vector4<F> const& q={}) : m_translation(t), m_quaternions(q) {}
350 
351  TransformQuat_& operator*=(TransformQuat_ const& q);
352 
353  Vector3<F> const& translation() const;
354  void setTranslation(Vector3<F> const& v);
355  void setTranslation(F const* v);
356 
360  Vector4<F> const& quaternion() const;
364  void setQuaternion(Vector4<F> const& v);
368  void setQuaternion(F const* v);
369 
373  F x() const { return m_translation[0]; }
377  F y() const { return m_translation[1]; }
381  F z() const { return m_translation[2]; }
382 
386  F qx() const { return m_quaternions[0]; }
390  F qy() const { return m_quaternions[1]; }
394  F qz() const { return m_quaternions[2]; }
398  F qw() const { return m_quaternions[3]; }
399 };
400 template <class F=double>
401 TransformQuat_<F> operator*(TransformQuat_<F> lhs, const TransformQuat_<F>& rhs) {
402  lhs *= rhs;
403  return lhs;
404 }
405 
406 template <class F=double>
407 class PoseQuat_ : public TransformQuat_<F> {
408  double m_hostTimestamp = std::numeric_limits<double>::infinity();
409  std::int64_t m_edgeTimestampUs = std::numeric_limits<std::int64_t>::min();
410 
411 public:
412 
413  PoseQuat_() {}
414  PoseQuat_(double t, TransformQuat_<F>const& tr={}) : m_hostTimestamp(t), TransformQuat_<F> (tr) {}
415  PoseQuat_(std::int64_t t, TransformQuat_<F>const& tr={}) : m_edgeTimestampUs(t), TransformQuat_<F> (tr) {}
416  PoseQuat_(double t, std::int64_t te, TransformQuat_<F>const& tr={}) : m_hostTimestamp(t), m_edgeTimestampUs(te), TransformQuat_<F> (tr) {}
417 
421  std::int64_t edgeTimestampUs() const {return m_edgeTimestampUs;};
425  void setEdgeTimestampUs(std::int64_t t) { m_edgeTimestampUs = t;};
429  double hostTimestamp() const {return m_hostTimestamp;};
433  void setHostTimestamp(double t) {m_hostTimestamp = t;};
434 };
435 
436 template <class F=double>
437 class PoseRot_ : public Transform_<F> {
438  double m_hostTimestamp = std::numeric_limits<double>::infinity();
439  std::int64_t m_edgeTimestampUs = std::numeric_limits<std::int64_t>::min();
440 
441 public:
442  PoseRot_() {}
443  PoseRot_(double t, Transform_<F>const& tr={}) : m_hostTimestamp(t), Transform_<F> (tr) {}
444  PoseRot_(std::int64_t t, Transform_<F>const& tr={}) : m_edgeTimestampUs(t), Transform_<F> (tr) {}
445  PoseRot_(double t, std::int64_t te, Transform_<F>const& tr={}) : m_hostTimestamp(t), m_edgeTimestampUs(te), Transform_<F> (tr) {}
446 
450  std::int64_t edgeTimestampUs() const {return m_edgeTimestampUs;};
454  void setEdgeTimestampUs(std::int64_t t) { m_edgeTimestampUs = t;};
458  double hostTimestamp() const {return m_hostTimestamp;};
462  void setHostTimestamp(double t) {m_hostTimestamp = t;};
463 };
464 
465 template <class F=double>
466 class Pose_ : public details::PoseRot_<F> {
467 
468 private:
469 
470  Vector4<F> m_quaternions;
471  double m_confidence = 0;
472 
473 public:
474 
475  static Pose_ Identity() {
476  return Pose_({0.,0,0},{1.,0,0,0,1,0,0,0,1});
477  }
478 
479  Pose_() {}
480 
484  Pose_(double c) : m_confidence(c) {}
485 
489  Pose_(Vector3<F> const& translation, Matrix3<F> const& rotation,
490  double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)(), double c=0.)
491  : m_confidence(c), PoseRot_<F>::PoseRot_(hostTimestamp, edgeTimestamp, {translation, rotation}), m_quaternions(rotationToQuaternion(rotation)) {}
492 
496  double confidence() const {return m_confidence;}
497 
501  void setConfidence(double c) { m_confidence = c;}
502 
506  Vector4<F> const& quaternion() const {return m_quaternions;}
510  void setQuaternion(Vector4<F> const& v) {
511  m_quaternions = v;
513  };
517  void setQuaternion(F const* v) {
518  std::copy(v, v+4, m_quaternions.data());
520  };
524  void setRotation(Matrix3<F> const& v) {
527  };
531  void setRotation(F const* v) {
532  std::copy(v, v+9, PoseRot_<F>::m_rotation.data());
534  };
535 
536 
537 
538 };
539 
540 template <class F>
541 class PosePred_ : public Pose_<F> {
542 
543 protected:
544  Vector3<F> m_linearVelocity = Vector3<F>{0.,0.,0.};
545  Vector3<F> m_angularVelocity = Vector3<F>{0.,0.,0.};
546  Vector3<F> m_linearAcceleration = Vector3<F>{0.,0.,0.};
547  Vector3<F> m_angularAcceleration = Vector3<F>{0.,0.,0.};
548 
549 public:
550 
551  static PosePred_ Identity() {
552  return PosePred_({0.,0,0},{1.,0,0,0,1,0,0,0,1});
553  }
554 
555  PosePred_() {}
556 
560  PosePred_(double c) : Pose_<F>::Pose_(c) {}
561 
565  PosePred_(Vector3<F> const& translation, Matrix3<F> const& rotation,
566  double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)(), double c=0.)
567  : Pose_<F>::Pose_(translation, rotation, hostTimestamp, edgeTimestamp, c) {}
568 
569  Transform_<F> const& transform() const { return *this; }
570 
574  Vector3<F> const& linearVelocity() const {return m_linearVelocity; }
578  Vector3<F> const& angularVelocity() const {return m_angularVelocity; }
582  void setLinearVelocity(Vector3<F> const& v) { m_linearVelocity=v; }
586  void setLinearVelocity(F const* v) {
587  std::copy(v, v+3, m_linearVelocity.data());
588  }
593  void setAngularVelocity(Vector3<F> const& v) { m_angularVelocity=v; }
598  void setAngularVelocity(F const* v) {
599  std::copy(v, v+3, m_angularVelocity.data());
600  }
601 
605  Vector3<F> const& linearAcceleration() const {return m_linearAcceleration; }
609  Vector3<F> const& angularAcceleration() const {return m_angularAcceleration; }
613  void setLinearAcceleration(Vector3<F> const& v) { m_linearAcceleration=v; }
617  void setLinearAcceleration(F const* v) {
618  std::copy(v, v+3, m_linearAcceleration.data());
619  }
624  void setAngularAcceleration(Vector3<F> const& v) { m_angularAcceleration=v; }
629  void setAngularAcceleration(F const* v) {
630  std::copy(v, v+3, m_angularAcceleration.data());
631  }
632 };
633 
634 }
635 
639 struct Transform : public details::Transform_<double> {
640  Transform();
642  Transform(Vector3d const& t, Matrix3d const& r);
643 };
647 struct TransformF : public details::Transform_<float> {
648  TransformF();
650  TransformF(Vector3f const& t, Matrix3f const& r);
651 };
652 
658 Vector3f operator*(const TransformF& a, const Vector3f& p);
664 Vector3d operator*(const Transform& lhs, const Vector3d& rhs);
668 TransformF inverse(const TransformF& t);
672 Transform inverse(const Transform& t);
673 
674 
678 struct TransformQuat : public details::TransformQuat_<double> {
679  TransformQuat();
680  TransformQuat(Vector3d const& t, Vector4d const& q);
681 };
685 struct TransformQuatF : public details::TransformQuat_<float> {
686  TransformQuatF();
687  TransformQuatF(Vector3f const& t, Vector4f const& q);
688 };
689 
705  int w;
709  int h;
713  double fx;
717  double fy;
721  double u0;
725  double v0;
736  std::array<double,5> distor;
738 };
739 
747  int w;
751  int h;
755  double fx;
759  double fy;
763  double u0;
767  double v0;
771  double xi;
772 };
773 
778  Transform pose;
779  UnifiedCameraModel intrinsics;
780 };
781 
786  Transform pose;
788 };
789 
796 struct Pose : public details::PosePred_<double> {
797  static Pose Identity() {
798  return Pose({0.,0,0},{1.,0,0,0,1,0,0,0,1});
799  }
800  Pose();
804  Pose(Vector3d const& translation, Matrix3d const& rotation,
805  double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)(), double c=0.);
811  Pose prediction(double dt) const;
812 };
813 
820 struct PoseF : public details::PosePred_<float> {
821  static Pose Identity() {
822  return Pose({0.,0,0},{1.,0,0,0,1,0,0,0,1});
823  }
824  PoseF();
828  PoseF(Vector3f const& translation, Matrix3f const& rotation,
829  double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)(), double c=0.);
830 
836  PoseF prediction(double dt) const;
837 };
838 
842 struct Event {
843  double hostTimestamp = std::numeric_limits<double>::infinity();
844  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
845  int type = 0;
846  int state = 0;
847 };
848 
852 class Orientation {
853 
854  Matrix3d m_rotation;
855  Vector4d m_quaternions;
856  Vector3d m_angularVelocity = Vector3d{0.,0.,0.};
857  Vector3d m_angularAcceleration = Vector3d{0.,0.,0.};
858 
859 public:
860  double hostTimestamp = std::numeric_limits<double>::infinity();
861  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
862 
863  Orientation();
864 
868  Orientation(Matrix3d const& rotation,
869  double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)());
870 
874  Orientation(Vector4d const& quaternion,
875  double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)());
876 
880  Vector4d const& quaternion() const;
884  void setQuaternion(Vector4d const& v);
888  void setQuaternion(double const* v);
889 
893  Matrix3d const& rotation() const {return m_rotation;}
894 
898  void setRotation(Matrix3d const& v);
902  void setRotation(double const* v);
907  Vector3d const& angularVelocity() const;
908 
913  void setAngularVelocity(Vector3d const& v);
914 
919  void setAngularVelocity(double const* v);
920 
925  void setAngularAcceleration(Vector3d const& v);
926 
931  void setAngularAcceleration(double const* v);
932 
938  Orientation prediction(double dt) const;
939 
940 };
941 
947 struct Plane {
949  std::string id;
950 
952  Vector3d normal;
953 
957  double d;
958 
962  std::vector<Vector3d> points;
963 
966  std::vector<Vector3d> vertices;
967  std::vector<std::array<uint32_t,3>> triangles;
968 };
969 
970 
974 struct SlamMap
975 {
976  std::vector<Vector3d> vertices;
977 };
978 
982 class CameraModel {
983 public:
984  virtual std::int32_t width() const {return 0; }
985  virtual std::int32_t height() const {return 0; }
986  virtual bool project(double const* /*p3d*/, double* /*p2d*/) const {return false;};
987  virtual bool raytrace(double const* /*p2d*/, double* /*p3d*/) const {return false;};
988 };
989 
993 struct Calibration {
994  Transform pose;
995  std::vector<UnifiedCameraModel> ucm;
996  std::vector<PolynomialDistortionCameraModel> pdcm;
997  std::vector<std::shared_ptr<CameraModel>> camerasModel;
998 };
999 
1005 struct Imu {
1006  Vector3d gyro;
1007  Vector3d accel;
1008  Vector3b accelSaturation;
1009  Vector3d magneto;
1010  double temperature;
1011  double hostTimestamp = std::numeric_limits<double>::infinity();
1012  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1013 };
1014 
1019  std::size_t width;
1020  std::size_t height;
1021  std::shared_ptr<const std::uint8_t> data;
1022 };
1023 
1028  double hostTimestamp = std::numeric_limits<double>::infinity();
1029  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1030  std::vector<GrayScaleImage> images;
1031  std::int64_t id;
1032 };
1033 
1037 struct RgbImage {
1038  std::size_t width = 0;
1039  std::size_t height = 0;
1040  std::shared_ptr<const std::uint8_t> data = nullptr;
1041  RgbImage(std::size_t _width, std::size_t _height, std::shared_ptr<const std::uint8_t> _data) : width(_width), height(_height),data(_data) {}
1042 };
1043 
1047 struct ColorImage {
1048  enum class Codec { YUYV = 0, YUV420p, JPEG, NV12, BITSTREAM};
1049  Codec codec = Codec::YUYV;
1050  std::size_t width = 0;
1051  std::size_t height = 0;
1052  std::shared_ptr<const std::uint8_t> data = nullptr;
1053  unsigned int dataSize = 0;
1054  double hostTimestamp = std::numeric_limits<double>::infinity();
1055  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1056 
1059  RgbImage toRgb() const;
1060 };
1061 
1066  {
1067  int32_t enable_dewarp;
1068  float dewarp_zoom_factor;
1069  int32_t enable_disparity;
1070  int32_t enable_depth;
1071  int32_t enable_point_cloud;
1072  float baseline;
1073  float fov;
1074  uint8_t disparity_confidence_threshold;
1075  float homography[9];
1076  int32_t enable_gamma;
1077  float gamma_value;
1078  int32_t enable_gaussian;
1079  uint8_t mode;//standard 0 /Default:LRcheck 1 /Extended 2 /Subpixel 3
1080  uint16_t max_distance;//mm
1081  uint16_t min_distance;//mm
1082 
1083  inline bool operator==(const sgbm_config &cmp) const
1084  {
1085  return (enable_dewarp == cmp.enable_dewarp &&
1086  dewarp_zoom_factor == cmp.dewarp_zoom_factor &&
1087  enable_disparity == cmp.enable_disparity &&
1088  enable_depth == cmp.enable_depth &&
1089  enable_point_cloud == cmp.enable_point_cloud &&
1090  baseline == cmp.baseline &&
1091  fov == cmp.fov &&
1092  disparity_confidence_threshold == cmp.disparity_confidence_threshold);
1093  }
1094  inline bool operator!=(const sgbm_config &cmp) const
1095  {
1096  return !(*this == cmp);
1097  }
1098  };
1099 
1108 struct DepthImage {
1109  enum class Type { Depth_16 = 0, Depth_32, IR, Cloud, Raw, Eeprom, IQ };
1110  Type type = Type::Depth_32;
1111  std::size_t width = 0;
1112  std::size_t height = 0;
1113  double confidence = 0.0;
1114  std::shared_ptr<const std::uint8_t> data = nullptr;
1115  unsigned int dataSize = 0;
1116  double hostTimestamp = std::numeric_limits<double>::infinity();
1117  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1118 
1121  RgbImage toRgb() const;
1122 };
1123 
1125  std::size_t width = 0;
1126  std::size_t height = 0;
1127  std::shared_ptr<const std::uint8_t> data = nullptr;
1128  double hostTimestamp = std::numeric_limits<double>::infinity();
1129 };
1130 
1134 struct PointCloud {
1135  double hostTimestamp = std::numeric_limits<double>::infinity();
1136  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1137  std::vector<Vector3f> points;
1138 };
1139 
1143 struct Object {
1144  enum class Shape { BoundingBox = 0, Human, HandSkeleton };
1145  struct keypoint {
1146  double x = -1, y = -1, z = -1;
1147  };
1148 
1149  Shape shape = Shape::BoundingBox;
1150 
1151  int typeID = -1;
1152  std::string type = "";
1153  double x = 0;
1154  double y = 0;
1155  double width = 0;
1156  double height = 0;
1157  double confidence = 0.0f;
1158 
1159  std::vector<keypoint> keypoints;
1160 };
1161 
1162 
1164  std::shared_ptr<float> raw_data = nullptr;
1165  unsigned int raw_data_length;
1166 };
1167 
1168 
1169 
1170 
1172  std::string type;
1173  std::vector<std::string> classes;
1174  double threshold = 0.5;
1175  bool flipStereo = false;
1176  bool flipRgb = false;
1177  bool flipTof = false;
1178  bool enable_3dbbox = false;
1179  std::vector<double> prior_bbox_z;
1180 };
1181 
1186 struct SgbmImage {
1187  enum class Type { Disparity = 0, Depth, PointCloud};
1188  const Type type;
1189  explicit SgbmImage(Type t) : type(t) {}
1190  std::size_t width = 0;
1191  std::size_t height = 0;
1192  std::shared_ptr<const std::uint8_t> data = nullptr;
1193  unsigned int dataSize = 0;
1194  double hostTimestamp = std::numeric_limits<double>::infinity();
1195  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1196 
1199  RgbImage toRgb() const;
1200 };
1201 
1206  enum class Codec {UYVY};
1207  const Codec codec;
1208  explicit ThermalImage(Codec t) : codec(t) {}
1209  std::size_t width = 0;
1210  std::size_t height = 0;
1211  std::shared_ptr<const std::uint8_t> data = nullptr;
1212  unsigned int dataSize = 0;
1213  double hostTimestamp = std::numeric_limits<double>::infinity();
1214  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1215 
1218  RgbImage toRgb() const;
1219 };
1220 
1225  double hostTimestamp = std::numeric_limits<double>::infinity();
1226  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1227  std::vector<GrayScaleImage> images;
1228 };
1229 
1230 struct MicData {
1231  double hostTimestamp = std::numeric_limits<double>::infinity();
1232  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1233  std::shared_ptr<const std::uint8_t> data = nullptr;
1234  unsigned int dataSize = 0;
1235 };
1236 
1240 struct keypoint {
1241  float x = -1;
1242  float y = -1;
1243  float z = -1;
1244 };
1245 
1249 struct GestureData {
1250  int index[2] = {-1,-1};
1251  keypoint position[2];
1252  keypoint slamPosition[2];
1253  double hostTimestamp = std::numeric_limits<double>::infinity();
1254  std::int64_t edgeTimestampUs = (std::numeric_limits<std::int64_t>::min)();
1255  float distance;
1256  float confidence;
1257 };
1258 
1259 enum class ResolutionMode{
1260  R_VGA,
1261  R_720P
1262 };
1263 
1267 typedef union XV_ET_POINT_2D
1268 {
1269  struct {
1270  float x, y;
1271  };
1272  float seq[2];
1273 }xv_ETPoint2D;
1274 
1278 typedef union XV_ET_POINT_3D
1279 {
1280  struct {
1281  float x, y, z;
1282  };
1283  float seq[3];
1284 }xv_ETPoint3D;
1285 
1289 enum XV_ET_EYE_TYPE {
1290  L_EYE = 1,
1291  R_EYE = 2
1292 };
1293 typedef XV_ET_EYE_TYPE xv_ETEyeType;
1294 
1298 enum XV_ET_MODE {
1299  track = 3,
1300  iris = 5
1301 };
1302 typedef XV_ET_MODE xv_ETMode;
1303 
1308  xv_ETMode mode;
1309  char configPath[260];
1310 };
1312 
1316 typedef struct XV_ET_COEFFICIENT {
1317  unsigned char buf[1024];
1319 
1320 
1321 enum XV_EyeGazeExDataValidity {
1322  EYE_GAZE_EXDATA_SCORE = 0,
1323 };
1324 
1330 {
1331  unsigned int gazeBitMask;
1337  float re;
1338  unsigned int exDataBitMask;
1339  float exData[32];
1340 };
1341 
1347 {
1348  unsigned int pupilBitMask;
1355 };
1356 
1362 {
1363  unsigned int eyeDataExBitMask;
1364  int blink;
1365  float openness;
1366  float eyelidUp;
1367  float eyelidDown;
1368 };
1369 
1375 {
1376  unsigned long long timestamp;
1381 
1384 
1387 
1388  float ipd;
1389 };
1390 
1392 typedef enum GazeStatus {
1394  GAZE_STATUS_OK,
1395 
1397  GAZE_STATUS_ERROR,
1398 
1400  GAZE_STATUS_INITIALIZE_FAILED,
1401 
1403  GAZE_STATUS_TERMINATE_FAILED,
1404 
1406  GAZE_STATUS_INVALID_PARAMETER,
1407 
1409  GAZE_STATUS_INVALID_OPERATION,
1410 
1412  GAZE_STATUS_DEVICE_NOT_AVAILABLE,
1413 
1415  GAZE_STATUS_TIMED_OUT,
1416 
1418  GAZE_STATUS_MEM_ALLOCATION_FAILED
1419 }
1420 GazeStatus;
1421 
1422 
1423 typedef enum CalibrationApiStatus {
1428  CALIBRATION_API_STATUS_COMPLETE_AUTOMATICALLY,
1429 
1431  CALIBRATION_API_STATUS_COMPLETE_MANUALLY,
1432 
1437  CALIBRATION_API_STATUS_ACCEPT_CALLING,
1438 
1440  CALIBRATION_API_STATUS_DO_NOT_CALL,
1441 
1443  CALIBRATION_API_STATUS_BUSY
1444 }
1445 CalibrationApiStatus;
1446 
1448 typedef struct CalibrationStatus {
1450  CalibrationApiStatus enter_status;
1451 
1453  CalibrationApiStatus collect_status;
1454 
1456  CalibrationApiStatus setup_status;
1457 
1459  CalibrationApiStatus compute_apply_status;
1460 
1462  CalibrationApiStatus leave_status;
1463 
1465  CalibrationApiStatus reset_status;
1466 }
1468 
1470 typedef struct GazeCalibrationData {
1472  void* data = nullptr;
1473 
1475  size_t size;
1476 
1479  {
1480  if (data != nullptr)
1481  {
1482  free(data);
1483  data = nullptr;
1484  }
1485  };
1486 }
1488 
1490 {
1491  std::vector<char> name;
1492  std::vector<unsigned char> feature;
1493  int size;
1494  int error;
1495 };
1496 
1501 struct DateTime {
1502  int Y, M, D;
1503  int h, m;
1504  int s;
1505 };
1506 
1513  int signal;
1514  unsigned char sum;
1515 };
1516 
1517 struct Triple
1518 {
1519  Vector2<unsigned short> p2d;
1520  size_t i3d;
1521  Triple(Vector2<unsigned short> const& p2, size_t i3): p2d(p2), i3d(i3) {}
1522 };
1524 {
1525  FisheyeImages fisheyeImages;
1526  std::vector<std::vector<Triple>> matches;
1527 };
1528 
1529 }
Calibration (extrinsics and intrinsics).
Definition: xv-types.h:993
double hostTimestamp() const
Get the host timestamp corresponding to the pose (in s).
Definition: xv-types.h:429
F qw() const
qx quaternion composant
Definition: xv-types.h:398
double u0
Optical axis intersection in width direction (in pixel)
Definition: xv-types.h:721
int D
Year, month, and day.
Definition: xv-types.h:1502
Exposure settings.
Definition: xv-types.h:55
Matrix3d quaternionToRotation(Vector4d const &q)
Convert quaternion to rotation matrix.
int w
Image width (in pixel)
Definition: xv-types.h:747
void setHostTimestamp(double t)
Set the host timestamp of the pose (in s).
Definition: xv-types.h:462
AWB settings.
Definition: xv-types.h:67
void setRotation(Matrix3< F > const &v)
Get the rotation matrix part of the transformation.
Definition: xv-types.h:279
void setAngularAcceleration(Vector3< F > const &v)
Set an estimation of instantaneous angular acceleration of the pose.
Definition: xv-types.h:624
SGBM CONFIG STRUCT.
Definition: xv-types.h:1065
F x() const
X coordinate of the translation.
Definition: xv-types.h:288
Vector3d magneto
3-axis magnetometer values
Definition: xv-types.h:1009
Class representing a 6dof pose at a timestamp with a linear model for prediction. ...
Definition: xv-types.h:820
Vector3f rotationToPitchYawRoll(Matrix3f const &rot)
Convert rotation Euler angles.
void setAngularAcceleration(F const *v)
Set an estimation of instantaneous angular acceleration of the pose.
Definition: xv-types.h:629
XV_ET_GAZE_POINT leftGaze
left eye gaze data
Definition: xv-types.h:1379
Object detection bounding box.
Definition: xv-types.h:1143
Definition: xv-types.h:1448
float eyelidDown
down eyelid data(0-1), down eyelid&#39;s vertical position in the image, normalization value...
Definition: xv-types.h:1367
Vector3< F > const & translation() const
Get the translation part of the transformation.
Definition: xv-types.h:261
float pupilDiameterMM
pupil diameter, pupil long axis value(mm).
Definition: xv-types.h:1352
int h
Image height (in pixel)
Definition: xv-types.h:751
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:283
CalibrationApiStatus enter_status
Definition: xv-types.h:1450
XV_ET_EYE_EXDATA rightExData
right eye extend data(include blink and eyelid data)
Definition: xv-types.h:1386
Calibration parameters of a camera using Unified Camera Model for camera intrinsics.
Definition: xv-types.h:777
A sparse SLAM map with 3D points.
Definition: xv-types.h:974
double v0
Optical axis intersection in height direction (in pixel)
Definition: xv-types.h:725
float openness
eye openness(0-100), 0-cloing, 100-opening normally, >100-opening on purpose.
Definition: xv-types.h:1365
double fx
Focal length in width direction (in pixel)
Definition: xv-types.h:713
unsigned char sum
Check sum.
Definition: xv-types.h:1514
double u0
Optical axis intersection in width direction (in pixel)
Definition: xv-types.h:763
int h
Image height (in pixel)
Definition: xv-types.h:709
Gesture key point.
Definition: xv-types.h:1240
F qy() const
qx quaternion composant
Definition: xv-types.h:390
void setAngularVelocity(F const *v)
Set an estimation of instantaneous angular velocity of the pose.
Definition: xv-types.h:598
float re
gaze re value, confidence level.
Definition: xv-types.h:1337
Definition: xv-types.h:1124
Definition: xv-types.h:1511
Definition: xv-types.h:1523
CalibrationApiStatus collect_status
Definition: xv-types.h:1453
CalibrationApiStatus reset_status
Definition: xv-types.h:1465
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1019
A color image in RGB format.
Definition: xv-types.h:1037
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:489
Represents a float typed transformation (or pose) with translation and quaternion for rotation in flo...
Definition: xv-types.h:685
Definition: xv-types.h:1267
int distance
Distance.
Definition: xv-types.h:1512
XV_ET_GAZE_POINT rightGaze
right eye gaze data
Definition: xv-types.h:1380
Matrix3f quaternionsToRotation(Vector4f const &q)
Deprecated. Same to #quaternionToRotation.
Vector3< F > const & angularAcceleration() const
Get the angular acceleration (x,y,z) in rad/s/s.
Definition: xv-types.h:609
Vector4< F > const & quaternion() const
Get the quaternion of the rotation.
Definition: xv-types.h:506
Data from IMU sensor of the XVisio device.
Definition: xv-types.h:1005
std::int64_t edgeTimestampUs() const
Get the edge timestamp of the pose (in microseconds).
Definition: xv-types.h:421
An image provided by a TOF camera.
Definition: xv-types.h:1108
Vector3d normal
Unit vector normal to the plane.
Definition: xv-types.h:952
CalibrationApiStatus compute_apply_status
Definition: xv-types.h:1459
Definition: xv-types.h:1145
int s
Seconds.
Definition: xv-types.h:1504
double temperature
sensor temperature (in K)
Definition: xv-types.h:1010
Definition: xv-types.h:1163
Definition: xv-types.h:1489
void setLinearVelocity(Vector3< F > const &v)
Set the linear velocity (in m/s)
Definition: xv-types.h:582
size_t size
Definition: xv-types.h:1475
float confidence
reserved, gesture confidence.
Definition: xv-types.h:1256
unsigned int pupilBitMask
pupil bit mask, identify the six data below are valid or invalid.
Definition: xv-types.h:1348
float pupilMinorAxisMM
pupil diameter, pupil minor axis value(mm).
Definition: xv-types.h:1354
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:1353
F qz() const
qx quaternion composant
Definition: xv-types.h:394
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:1332
Definition: xv-types.h:1517
F y() const
Y coordinate of the translation.
Definition: xv-types.h:292
Represents a transformation (or pose) with translation and rotation matrix.
Definition: xv-types.h:639
xv_ETPoint3D gazeDirection
gaze direction.
Definition: xv-types.h:1336
Definition: xv-types.h:1230
F x() const
X coordinate of the translation.
Definition: xv-types.h:373
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:962
AF settings.
Definition: xv-types.h:76
CalibrationApiStatus setup_status
Definition: xv-types.h:1456
double v0
Optical axis intersection in height direction (in pixel)
Definition: xv-types.h:767
CalibrationApiStatus leave_status
Definition: xv-types.h:1462
Definition: xv-types.h:1307
Definition: xv-types.h:1171
Images coming from xv::FisheyeCameras sensor system used for visual SLAM.
Definition: xv-types.h:1027
Definition: xv-types.h:407
void setConfidence(double c)
Set the confidence of the pose. Value in [0,1], 0 means lost.
Definition: xv-types.h:501
float pupilDistance
the distance between pupil and camera(mm)
Definition: xv-types.h:1350
float distance
reserved, dynamic gesture movement distance.
Definition: xv-types.h:1255
void setRotation(Matrix3< F > const &v)
Get the rotation matrix part of the transformation.
Definition: xv-types.h:524
Definition: xv-types.h:1346
int signal
Signal Intensity.
Definition: xv-types.h:1513
void setQuaternion(F const *v)
Set the quaternion of the rotation using pointer of 4D array.
Definition: xv-types.h:517
xv_ETMode mode
sdk mode, refer to xv_ETMode.
Definition: xv-types.h:1308
Definition: xv-types.h:541
double confidence() const
Get the confidence of the pose. Value in [0,1], 0 means lost.
Definition: xv-types.h:496
~GazeCalibrationData()
Definition: xv-types.h:1478
double xi
xi parameter of Unified Camera Model
Definition: xv-types.h:771
double fy
Focal length in height direction (in pixel)
Definition: xv-types.h:759
Transform_< float > inverse(const Transform_< float > &t)
Compute the inverse transformation.
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:1333
F qx() const
qx quaternion composant
Definition: xv-types.h:386
Vector3d gyro
3-axis gyrometer values (in rad/s)
Definition: xv-types.h:1006
Class representing a 6dof pose at a timestamp with a linear model for prediction. ...
Definition: xv-types.h:796
PosePred_(double c)
Construct a pose with a specified confidence.
Definition: xv-types.h:560
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:997
xv_ETPoint3D gazeOrigin
origin gaze center coordinate.
Definition: xv-types.h:1335
Vector3b accelSaturation
3-axis accel saturation status (true if saturating)
Definition: xv-types.h:1008
F y() const
Y coordinate of the translation.
Definition: xv-types.h:377
void setTranslation(F const *v)
Set the translation part of the transformation using pointer to 3D array.
Definition: xv-types.h:269
Unified Camera Model.
Definition: xv-types.h:743
unsigned int gazeBitMask
gaze bit mask, identify the six data below are valid or invalid.
Definition: xv-types.h:1331
Pose_(double c)
Construct a pose with a specified confidence.
Definition: xv-types.h:484
Vector3< F > const & linearVelocity() const
Get the linear velocity (in m/s) of the pose.
Definition: xv-types.h:574
std::array< double, 5 > distor
Distortion parameters.
Definition: xv-types.h:736
A grayscale image that is usually an image from a camera used for visual SLAM.
Definition: xv-types.h:1018
A color image given by xv::ColorCamera.
Definition: xv-types.h:1047
A point cloud of 3D points.
Definition: xv-types.h:1134
F z() const
Z coordinate of the translation.
Definition: xv-types.h:381
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:1351
Definition: xv-sdk.h:10
Definition: xv-types.h:1501
void setEdgeTimestampUs(std::int64_t t)
Set the edge timestamp of the pose (in microseconds).
Definition: xv-types.h:454
Vector3d accel
3-axis accelerometer values (in m/s²)
Definition: xv-types.h:1007
XV_ET_PUPIL_INFO leftPupil
left eye pupil data
Definition: xv-types.h:1382
int m
Hour and minutes.
Definition: xv-types.h:1503
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:565
double fx
Focal length in width direction (in pixel)
Definition: xv-types.h:755
void setEdgeTimestampUs(std::int64_t t)
Set the edge timestamp of the pose (in microseconds).
Definition: xv-types.h:425
void setLinearAcceleration(F const *v)
Set the angular acceleration (x,y,z) in rad/s/s.
Definition: xv-types.h:617
The Version struct.
Definition: xv-types.h:126
XV_ET_GAZE_POINT recomGaze
recommend gaze data
Definition: xv-types.h:1378
void setTranslation(Vector3< F > const &v)
Set the translation part of the transformation.
Definition: xv-types.h:265
std::vector< Vector3d > vertices
Flat, 3D, triangle mesh describing the detailed plane geometry extents. More convenient than the bord...
Definition: xv-types.h:966
void setLinearVelocity(F const *v)
Set the angular velocity (x,y,z) in rad/s.
Definition: xv-types.h:586
Vector3< F > const & linearAcceleration() const
Get the linear acceleration (in m/s/s) of the pose.
Definition: xv-types.h:605
float ipd
The estimated interpupilary distance (IPD)
Definition: xv-types.h:1388
std::vector< PolynomialDistortionCameraModel > pdcm
Deprecated, better to use camerasModel; List of Unified Camera Model parameters for differents camera...
Definition: xv-types.h:996
int blink
blink data, 0-no blink, 1-start blinking, 2-closing process, 3-close eyes, 4-opening process...
Definition: xv-types.h:1364
Polynomial Distortion Model for camera intrisics.
Definition: xv-types.h:701
Definition: xv-types.h:1470
Definition: xv-types.h:1278
unsigned int eyeDataExBitMask
eye extend data bit mask, identify the four data below are valid or invalid.
Definition: xv-types.h:1363
std::int64_t id
List of images (typically 2, first is left and second image is the right image)
Definition: xv-types.h:1031
Definition: xv-types.h:1361
std::vector< UnifiedCameraModel > ucm
pose of the sensor(camera and display) in the IMU frame coordinates.
Definition: xv-types.h:995
Definition: xv-types.h:1374
Definition: xv-types.h:336
SGBM data.
Definition: xv-types.h:1186
float eyelidUp
up eyelid data(0-1), up eyelid&#39;s vertical position in the image, normalization value, image height is 1.
Definition: xv-types.h:1366
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:1041
std::int64_t edgeTimestampUs() const
Get the edge timestamp of the pose (in microseconds).
Definition: xv-types.h:450
int recommend
whether if there has the recommend point. 0-no recommend point, 1-use left eye as recommend point...
Definition: xv-types.h:1377
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:1334
double d
Signed distance to origin. Signed distance between the plane and the origin of the world...
Definition: xv-types.h:957
void setRotation(F const *v)
Set the quaternion of the rotation using pointer of 4D array.
Definition: xv-types.h:531
double hostTimestamp() const
Get the host timestamp of the pose (in s).
Definition: xv-types.h:458
unsigned int exDataBitMask
reserved data.
Definition: xv-types.h:1338
A color image given by xv::ThermalCamera.
Definition: xv-types.h:1205
Matrix3< F > const & rotation() const
Get the rotation matrix part of the transformation.
Definition: xv-types.h:275
double fy
Focal length in height direction (in pixel)
Definition: xv-types.h:717
Definition: xv-types.h:237
void setLinearAcceleration(Vector3< F > const &v)
Set the linear acceleration (in m/s)
Definition: xv-types.h:613
Calibration parameters of a camera using Polynomial Distortion Model for camera intrinsics.
Definition: xv-types.h:785
Event.
Definition: xv-types.h:842
A 3D plane definition.
Definition: xv-types.h:947
void setAngularVelocity(Vector3< F > const &v)
Set an estimation of instantaneous angular velocity of the pose.
Definition: xv-types.h:593
Matrix3d const & rotation() const
Get the rotation matrix part of the transformation.
Definition: xv-types.h:893
A color image given by xv::EyetrackingCamera.
Definition: xv-types.h:1224
XV_ET_EYE_EXDATA leftExData
left eye extend data(include blink and eyelid data)
Definition: xv-types.h:1385
Definition: xv-types.h:1329
Gesture data.
Definition: xv-types.h:1249
Vector3< F > const & angularVelocity() const
Get the angular velocity (x,y,z) in rad/s.
Definition: xv-types.h:578
Definition: xv-types.h:437
XV_ET_PUPIL_INFO rightPupil
right eye pupil data
Definition: xv-types.h:1383
Orientation only (3dof) of the pose.
Definition: xv-types.h:852
xv_ETPoint2D pupilCenter
pupil center(0-1), the coordinate value of pupil center in the image, normalization value...
Definition: xv-types.h:1349
Represents a float typed transformation (or pose) with translation and quaternion for rotation...
Definition: xv-types.h:678
Definition: xv-types.h:466
Represents atransformation (or pose) with translation and rotation matrix in float type...
Definition: xv-types.h:647
F z() const
Z coordinate of the translation.
Definition: xv-types.h:296
std::string id
Plane unique identifier.
Definition: xv-types.h:949
Definition: xv-types.h:99
Device setting.
Definition: xv-types.h:85
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1020
Generic camera model.
Definition: xv-types.h:982
unsigned long long timestamp
timestamp.
Definition: xv-types.h:1376
void setHostTimestamp(double t)
Set the host timestamp corresponding to the pose (in s).
Definition: xv-types.h:433
void setQuaternion(Vector4< F > const &v)
Set the quaternion of the rotation.
Definition: xv-types.h:510
int w
Image width (in pixel)
Definition: xv-types.h:705
Definition: xv-types.h:1316
Vector4d rotationToQuaternion(Matrix3d const &rot)
Convert a rotation matrix to quaternion.