10 #if defined(__ANDROID__) && !defined(__x86_64__)
11 #define __XV_DRIVER_ONLY__
28 enum class SlamStartMode {
44 enum class PlugEventType { Plugin, Unplug };
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;
61 std::uint8_t iso_mode;
69 std::uint8_t awb_mode;
70 std::uint8_t awb_lock;
101 int32_t maxIsoGainValue;
102 int32_t minIsoGainValue;
103 int32_t maxExposureTimeUs;
104 int32_t minExposureTimeUs;
105 uint8_t targetMeanPixelValue;
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;
128 Version(
const std::string &s );
135 std::string toString()
const;
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>;
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;
236 template <
class F=
double>
240 Vector3<F> m_translation;
241 Matrix3<F> m_rotation;
246 return Transform_({0.,0,0},{1.,0,0,0,1,0,0,0,1});
250 Transform_(Vector3<F>
const& t, Matrix3<F>
const& r={}) : m_translation(t), m_rotation(r) {};
275 Matrix3<F>
const&
rotation()
const {
return m_rotation;}
283 void setRotation(F
const* v) {std::copy(v, v+9, m_rotation.data());}
288 F
x()
const {
return m_translation[0]; }
292 F
y()
const {
return m_translation[1]; }
296 F
z()
const {
return m_translation[2]; }
304 template <
class F=
double>
335 template <
class F=
double>
339 Vector3<F> m_translation;
340 Vector4<F> m_quaternions;
349 TransformQuat_(Vector3<F>
const& t, Vector4<F>
const& q={}) : m_translation(t), m_quaternions(q) {}
353 Vector3<F>
const& translation()
const;
354 void setTranslation(Vector3<F>
const& v);
355 void setTranslation(F
const* v);
373 F
x()
const {
return m_translation[0]; }
377 F
y()
const {
return m_translation[1]; }
381 F
z()
const {
return m_translation[2]; }
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]; }
400 template <
class F=
double>
401 TransformQuat_<F> operator*(TransformQuat_<F> lhs,
const TransformQuat_<F>& rhs) {
406 template <
class F=
double>
408 double m_hostTimestamp = std::numeric_limits<double>::infinity();
409 std::int64_t m_edgeTimestampUs = std::numeric_limits<std::int64_t>::min();
436 template <
class F=
double>
438 double m_hostTimestamp = std::numeric_limits<double>::infinity();
439 std::int64_t m_edgeTimestampUs = std::numeric_limits<std::int64_t>::min();
465 template <
class F=
double>
470 Vector4<F> m_quaternions;
471 double m_confidence = 0;
475 static Pose_ Identity() {
476 return Pose_({0.,0,0},{1.,0,0,0,1,0,0,0,1});
484 Pose_(
double c) : m_confidence(c) {}
490 double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)(),
double c=0.)
518 std::copy(v, v+4, m_quaternions.data());
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.};
552 return PosePred_({0.,0,0},{1.,0,0,0,1,0,0,0,1});
566 double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)(),
double c=0.)
587 std::copy(v, v+3, m_linearVelocity.data());
599 std::copy(v, v+3, m_angularVelocity.data());
618 std::copy(v, v+3, m_linearAcceleration.data());
630 std::copy(v, v+3, m_angularAcceleration.data());
642 Transform(Vector3d
const& t, Matrix3d
const& r);
650 TransformF(Vector3f
const& t, Matrix3f
const& r);
658 Vector3f operator*(
const TransformF& a,
const Vector3f& p);
664 Vector3d operator*(
const Transform& lhs,
const Vector3d& rhs);
797 static Pose Identity() {
798 return Pose({0.,0,0},{1.,0,0,0,1,0,0,0,1});
805 double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)(),
double c=0.);
821 static Pose Identity() {
822 return Pose({0.,0,0},{1.,0,0,0,1,0,0,0,1});
829 double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)(),
double c=0.);
855 Vector4d m_quaternions;
856 Vector3d m_angularVelocity = Vector3d{0.,0.,0.};
857 Vector3d m_angularAcceleration = Vector3d{0.,0.,0.};
869 double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)());
875 double hostTimestamp = std::numeric_limits<double>::infinity(), std::int64_t edgeTimestamp = (std::numeric_limits<std::int64_t>::min)());
893 Matrix3d
const&
rotation()
const {
return m_rotation;}
967 std::vector<std::array<uint32_t,3>> triangles;
976 std::vector<Vector3d> vertices;
984 virtual std::int32_t width()
const {
return 0; }
985 virtual std::int32_t height()
const {
return 0; }
986 virtual bool project(
double const* ,
double* )
const {
return false;};
987 virtual bool raytrace(
double const* ,
double* )
const {
return false;};
995 std::vector<UnifiedCameraModel>
ucm;
996 std::vector<PolynomialDistortionCameraModel>
pdcm;
1021 std::shared_ptr<const std::uint8_t> data;
1030 std::vector<GrayScaleImage> images;
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) {}
1048 enum class Codec { YUYV = 0, YUV420p, JPEG, NV12, BITSTREAM};
1049 Codec codec = Codec::YUYV;
1052 std::shared_ptr<const std::uint8_t> data =
nullptr;
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;
1074 uint8_t disparity_confidence_threshold;
1075 float homography[9];
1076 int32_t enable_gamma;
1078 int32_t enable_gaussian;
1080 uint16_t max_distance;
1081 uint16_t min_distance;
1083 inline bool operator==(
const sgbm_config &cmp)
const
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 &&
1092 disparity_confidence_threshold == cmp.disparity_confidence_threshold);
1094 inline bool operator!=(
const sgbm_config &cmp)
const
1096 return !(*
this == cmp);
1109 enum class Type { Depth_16 = 0, Depth_32, IR, Cloud, Raw, Eeprom, IQ };
1110 Type type = Type::Depth_32;
1114 std::shared_ptr<const std::uint8_t> data =
nullptr;
1127 std::shared_ptr<const std::uint8_t> data =
nullptr;
1137 std::vector<Vector3f> points;
1144 enum class Shape { BoundingBox = 0, Human, HandSkeleton };
1146 double x = -1, y = -1, z = -1;
1149 Shape shape = Shape::BoundingBox;
1152 std::string type =
"";
1157 double confidence = 0.0f;
1159 std::vector<keypoint> keypoints;
1167 double x = -1, y = -1, z = -1;
1173 float left, top, width, height;
1174 std::vector<keypoint> keypoints;
1176 Det2dObject(
int i,
const std::string& n,
float s,
float l,
float t,
float w,
float h) :
1177 idx(i), name(n), score(s), left(l), top(t), width(w), height(h) {}
1178 Det2dObject(
int i,
const std::string& n,
float s,
float l,
float t,
float w,
float h, std::vector<keypoint> pts) :
1179 idx(i), name(n), score(s), left(l), top(t), width(w), height(h), keypoints(pts){}
1183 std::shared_ptr<float> raw_data =
nullptr;
1184 unsigned int raw_data_length;
1185 double hostTimestamp;
1186 uint64_t edgeTimestamp;
1194 std::vector<std::string> classes;
1195 double threshold = 0.5;
1196 bool flipStereo =
false;
1197 bool flipRgb =
false;
1198 bool flipTof =
false;
1199 bool enable_3dbbox =
false;
1200 std::vector<double> prior_bbox_z;
1208 enum class Type { Disparity = 0, Depth,
PointCloud, None};
1214 std::shared_ptr<const std::uint8_t> data =
nullptr;
1228 enum class Codec {UYVY};
1233 std::shared_ptr<const std::uint8_t> data =
nullptr;
1249 std::vector<GrayScaleImage> images;
1255 std::shared_ptr<const std::uint8_t> data =
nullptr;
1281 enum class ResolutionMode{
1311 enum XV_ET_EYE_TYPE {
1315 typedef XV_ET_EYE_TYPE xv_ETEyeType;
1324 typedef XV_ET_MODE xv_ETMode;
1343 enum XV_EyeGazeExDataValidity {
1344 EYE_GAZE_EXDATA_SCORE = 0,
1416 typedef enum GazeStatus {
1424 GAZE_STATUS_INITIALIZE_FAILED,
1427 GAZE_STATUS_TERMINATE_FAILED,
1430 GAZE_STATUS_INVALID_PARAMETER,
1433 GAZE_STATUS_INVALID_OPERATION,
1436 GAZE_STATUS_DEVICE_NOT_AVAILABLE,
1439 GAZE_STATUS_TIMED_OUT,
1442 GAZE_STATUS_MEM_ALLOCATION_FAILED
1447 typedef enum CalibrationApiStatus {
1452 CALIBRATION_API_STATUS_COMPLETE_AUTOMATICALLY,
1455 CALIBRATION_API_STATUS_COMPLETE_MANUALLY,
1461 CALIBRATION_API_STATUS_ACCEPT_CALLING,
1464 CALIBRATION_API_STATUS_DO_NOT_CALL,
1467 CALIBRATION_API_STATUS_BUSY
1469 CalibrationApiStatus;
1504 if (
data !=
nullptr)
1511 GazeCalibrationData;
1515 std::vector<char> name;
1516 std::vector<unsigned char> feature;
1543 Vector2<unsigned short> p2d;
1545 Triple(Vector2<unsigned short>
const& p2,
size_t i3): p2d(p2), i3d(i3) {}
1550 std::vector<std::vector<Triple>> matches;
1565 std::vector<Pose> pose;
1567 int status[2] = {-1,-1};
1568 double timestamp[2];
1569 double fisheye_timestamp;
1582 double hostTimestamp;
Generic camera model.
Definition: xv-types.h:982
Orientation only (3dof) of the pose.
Definition: xv-types.h:852
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:893
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:860
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:861
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:541
void setAngularAcceleration(Vector3< F > const &v)
Set an estimation of instantaneous angular acceleration of the pose.
Definition: xv-types.h:624
void setAngularVelocity(F const *v)
Set an estimation of instantaneous angular velocity of the pose.
Definition: xv-types.h:598
void setAngularAcceleration(F const *v)
Set an estimation of instantaneous angular acceleration of the pose.
Definition: xv-types.h:629
void setLinearVelocity(Vector3< F > const &v)
Set the linear velocity (in m/s)
Definition: xv-types.h:582
Vector3< F > const & linearVelocity() const
Get the linear velocity (in m/s) of the pose.
Definition: xv-types.h:574
void setAngularVelocity(Vector3< F > const &v)
Set an estimation of instantaneous angular velocity of the pose.
Definition: xv-types.h:593
Vector3< F > const & angularVelocity() const
Get the angular velocity (x,y,z) in rad/s.
Definition: xv-types.h:578
void setLinearAcceleration(Vector3< F > const &v)
Set the linear acceleration (in m/s)
Definition: xv-types.h:613
Vector3< F > const & linearAcceleration() const
Get the linear acceleration (in m/s/s) of the pose.
Definition: xv-types.h:605
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
PosePred_(double c)
Construct a pose with a specified confidence.
Definition: xv-types.h:560
void setLinearVelocity(F const *v)
Set the angular velocity (x,y,z) in rad/s.
Definition: xv-types.h:586
Vector3< F > const & angularAcceleration() const
Get the angular acceleration (x,y,z) in rad/s/s.
Definition: xv-types.h:609
void setLinearAcceleration(F const *v)
Set the angular acceleration (x,y,z) in rad/s/s.
Definition: xv-types.h:617
Definition: xv-types.h:407
void setEdgeTimestampUs(std::int64_t t)
Set the edge timestamp of the pose (in microseconds).
Definition: xv-types.h:425
void setHostTimestamp(double t)
Set the host timestamp corresponding to the pose (in s).
Definition: xv-types.h:433
double hostTimestamp() const
Get the host timestamp corresponding to the pose (in s).
Definition: xv-types.h:429
std::int64_t edgeTimestampUs() const
Get the edge timestamp of the pose (in microseconds).
Definition: xv-types.h:421
Definition: xv-types.h:437
void setHostTimestamp(double t)
Set the host timestamp of the pose (in s).
Definition: xv-types.h:462
double hostTimestamp() const
Get the host timestamp of the pose (in s).
Definition: xv-types.h:458
void setEdgeTimestampUs(std::int64_t t)
Set the edge timestamp of the pose (in microseconds).
Definition: xv-types.h:454
std::int64_t edgeTimestampUs() const
Get the edge timestamp of the pose (in microseconds).
Definition: xv-types.h:450
Definition: xv-types.h:466
void setQuaternion(F const *v)
Set the quaternion of the rotation using pointer of 4D array.
Definition: xv-types.h:517
void setConfidence(double c)
Set the confidence of the pose. Value in [0,1], 0 means lost.
Definition: xv-types.h:501
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
double confidence() const
Get the confidence of the pose. Value in [0,1], 0 means lost.
Definition: xv-types.h:496
void setRotation(F const *v)
Set the quaternion of the rotation using pointer of 4D array.
Definition: xv-types.h:531
Pose_(double c)
Construct a pose with a specified confidence.
Definition: xv-types.h:484
Vector4< F > const & quaternion() const
Get the quaternion of the rotation.
Definition: xv-types.h:506
void setRotation(Matrix3< F > const &v)
Get the rotation matrix part of the transformation.
Definition: xv-types.h:524
void setQuaternion(Vector4< F > const &v)
Set the quaternion of the rotation.
Definition: xv-types.h:510
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:77
AWB settings.
Definition: xv-types.h:68
Definition: xv-types.h:1472
CalibrationApiStatus leave_status
Definition: xv-types.h:1486
CalibrationApiStatus reset_status
Definition: xv-types.h:1489
CalibrationApiStatus enter_status
Definition: xv-types.h:1474
CalibrationApiStatus setup_status
Definition: xv-types.h:1480
CalibrationApiStatus collect_status
Definition: xv-types.h:1477
CalibrationApiStatus compute_apply_status
Definition: xv-types.h:1483
Calibration (extrinsics and intrinsics).
Definition: xv-types.h:993
std::vector< UnifiedCameraModel > ucm
pose of the sensor(camera and display) in the IMU frame coordinates.
Definition: xv-types.h:995
std::vector< PolynomialDistortionCameraModel > pdcm
Deprecated, better to use camerasModel; List of Unified Camera Model parameters for differents camera...
Definition: xv-types.h:996
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
Definition: xv-types.h:1182
A color image given by xv::ColorCamera.
Definition: xv-types.h:1047
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1055
unsigned int dataSize
image data
Definition: xv-types.h:1053
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1054
RgbImage toRgb() const
Convert to a xv::RgbImage.
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1050
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1051
Definition: xv-types.h:1525
int D
Year, month, and day.
Definition: xv-types.h:1526
int m
Hour and minutes.
Definition: xv-types.h:1527
int s
Seconds.
Definition: xv-types.h:1528
Definition: xv-types.h:1124
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1125
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1126
double hostTimestamp
image data of RGB-D pixels : RGB (3 bytes) D (float 4bytes)
Definition: xv-types.h:1128
An image provided by a TOF camera.
Definition: xv-types.h:1108
double confidence
confidence of depth [0.0,1.0]
Definition: xv-types.h:1113
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1112
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1111
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1117
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:1116
unsigned int dataSize
image of depth
Definition: xv-types.h:1115
Definition: xv-types.h:1166
Object detection bounding box. 2d.
Definition: xv-types.h:1165
Device setting.
Definition: xv-types.h:86
Event.
Definition: xv-types.h:842
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:843
int type
Type of event.
Definition: xv-types.h:845
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:844
int state
State of the event.
Definition: xv-types.h:846
Exposure settings.
Definition: xv-types.h:55
Definition: xv-types.h:1572
A color image given by xv::EyetrackingCamera.
Definition: xv-types.h:1246
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock),...
Definition: xv-types.h:1247
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1248
Images coming from xv::FisheyeCameras sensor system used for visual SLAM.
Definition: xv-types.h:1027
std::int64_t id
List of images (typically 2, first is left and second image is the right image)
Definition: xv-types.h:1031
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock),...
Definition: xv-types.h:1028
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1029
Definition: xv-types.h:1535
int distance
Distance.
Definition: xv-types.h:1536
int signal
Signal Intensity.
Definition: xv-types.h:1537
unsigned char sum
Check sum.
Definition: xv-types.h:1538
Definition: xv-types.h:1494
~GazeCalibrationData()
Definition: xv-types.h:1502
void * data
Definition: xv-types.h:1496
size_t size
Definition: xv-types.h:1499
Gesture data.
Definition: xv-types.h:1271
float distance
reserved, dynamic gesture movement distance.
Definition: xv-types.h:1277
float confidence
reserved, gesture confidence.
Definition: xv-types.h:1278
int index[2]
Index array for hands gesture, max size is two, default is -1 means invalid.
Definition: xv-types.h:1272
keypoint position[2]
Position array for hand gesture, max size is two, 2D points, z isn't used by default.
Definition: xv-types.h:1273
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1276
keypoint slamPosition[2]
Convert rgb points into slam points, Position array for hand gesture, max size is two.
Definition: xv-types.h:1274
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1275
A grayscale image that is usually an image from a camera used for visual SLAM.
Definition: xv-types.h:1018
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1020
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1019
new hand pose struct.
Definition: xv-types.h:1564
Data from IMU sensor of the XVisio device.
Definition: xv-types.h:1005
Vector3b accelSaturation
3-axis accel saturation status (true if saturating)
Definition: xv-types.h:1008
double temperature
sensor temperature (in K)
Definition: xv-types.h:1010
Vector3d accel
3-axis accelerometer values (in m/s²)
Definition: xv-types.h:1007
Vector3d gyro
3-axis gyrometer values (in rad/s)
Definition: xv-types.h:1006
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1011
Vector3d magneto
3-axis magnetometer values
Definition: xv-types.h:1009
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1012
Definition: xv-types.h:100
Definition: xv-types.h:1252
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1254
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1253
unsigned int dataSize
image data
Definition: xv-types.h:1256
Definition: xv-types.h:1192
Definition: xv-types.h:1145
Object detection bounding box.
Definition: xv-types.h:1143
Calibration parameters of a camera using Polynomial Distortion Model for camera intrinsics.
Definition: xv-types.h:785
A 3D plane definition.
Definition: xv-types.h:947
double d
Signed distance to origin. Signed distance between the plane and the origin of the world....
Definition: xv-types.h:957
Vector3d normal
Unit vector normal to the plane.
Definition: xv-types.h:952
std::string id
Plane unique identifier.
Definition: xv-types.h:949
std::vector< Vector3d > vertices
Flat, 3D, triangle mesh describing the detailed plane geometry extents. More convenient than the bord...
Definition: xv-types.h:966
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
A point cloud of 3D points.
Definition: xv-types.h:1134
double hostTimestamp
host timestamp of ? (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1135
std::int64_t edgeTimestampUs
timestamp of ? (in microsecond based on edge clock).
Definition: xv-types.h:1136
Definition: xv-types.h:1548
Polynomial Distortion Model for camera intrisics.
Definition: xv-types.h:701
double fx
Focal length in width direction (in pixel)
Definition: xv-types.h:713
int w
Image width (in pixel)
Definition: xv-types.h:705
double fy
Focal length in height direction (in pixel)
Definition: xv-types.h:717
double u0
Optical axis intersection in width direction (in pixel)
Definition: xv-types.h:721
std::array< double, 5 > distor
Distortion parameters.
Definition: xv-types.h:736
int h
Image height (in pixel)
Definition: xv-types.h:709
double v0
Optical axis intersection in height direction (in pixel)
Definition: xv-types.h:725
Class representing a 6dof pose at a timestamp with a linear model for prediction.
Definition: xv-types.h:820
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:796
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:1037
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1038
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::size_t height
height of the image (in pixel)
Definition: xv-types.h:1039
SGBM data.
Definition: xv-types.h:1207
unsigned int dataSize
data of SGBM
Definition: xv-types.h:1215
double hostTimestamp
host timestamp of the physical measurement (in second based on the std::chrono::steady_clock).
Definition: xv-types.h:1216
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1217
RgbImage toRgb() const
Convert to a xv::RgbImage.
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1212
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1213
A sparse SLAM map with 3D points.
Definition: xv-types.h:975
Definition: xv-types.h:1554
A color image given by xv::ThermalCamera.
Definition: xv-types.h:1227
std::size_t height
height of the image (in pixel)
Definition: xv-types.h:1232
std::int64_t edgeTimestampUs
timestamp of the physical measurement (in microsecond based on edge clock).
Definition: xv-types.h:1236
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:1235
std::size_t width
width of the image (in pixel)
Definition: xv-types.h:1231
unsigned int dataSize
image data
Definition: xv-types.h:1234
Definition: xv-types.h:1542
Calibration parameters of a camera using Unified Camera Model for camera intrinsics.
Definition: xv-types.h:777
Unified Camera Model.
Definition: xv-types.h:743
double u0
Optical axis intersection in width direction (in pixel)
Definition: xv-types.h:763
int w
Image width (in pixel)
Definition: xv-types.h:747
double xi
xi parameter of Unified Camera Model
Definition: xv-types.h:771
double fx
Focal length in width direction (in pixel)
Definition: xv-types.h:755
double fy
Focal length in height direction (in pixel)
Definition: xv-types.h:759
double v0
Optical axis intersection in height direction (in pixel)
Definition: xv-types.h:767
int h
Image height (in pixel)
Definition: xv-types.h:751
The Version struct.
Definition: xv-types.h:126
int minor
Minor number of the version.
Definition: xv-types.h:131
int major
Major number of the version.
Definition: xv-types.h:130
int patch
Patch number of the version.
Definition: xv-types.h:132
Definition: xv-types.h:1338
unsigned char buf[1024]
calibration factor.
Definition: xv-types.h:1339
Definition: xv-types.h:1397
XV_ET_PUPIL_INFO leftPupil
left eye pupil data
Definition: xv-types.h:1404
XV_ET_PUPIL_INFO rightPupil
right eye pupil data
Definition: xv-types.h:1405
XV_ET_GAZE_POINT recomGaze
recommend gaze data
Definition: xv-types.h:1400
XV_ET_EYE_EXDATA rightExData
right eye extend data(include blink and eyelid data)
Definition: xv-types.h:1408
XV_ET_GAZE_POINT rightGaze
right eye gaze data
Definition: xv-types.h:1402
unsigned long long timestamp
timestamp.
Definition: xv-types.h:1398
int recommend
whether if there has the recommend point. 0-no recommend point, 1-use left eye as recommend point,...
Definition: xv-types.h:1399
XV_ET_GAZE_POINT leftGaze
left eye gaze data
Definition: xv-types.h:1401
float ipd
The estimated interpupilary distance (IPD)
Definition: xv-types.h:1412
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:1410
XV_ET_EYE_EXDATA leftExData
left eye extend data(include blink and eyelid data)
Definition: xv-types.h:1407
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:1411
Definition: xv-types.h:1384
float eyelidDown
down eyelid data(0-1), down eyelid's vertical position in the image, normalization value,...
Definition: xv-types.h:1389
float openness
eye openness(0-100), 0-cloing, 100-opening normally, >100-opening on purpose.
Definition: xv-types.h:1387
unsigned int eyeDataExBitMask
eye extend data bit mask, identify the four data below are valid or invalid.
Definition: xv-types.h:1385
int blink
blink data, 0-no blink, 1-start blinking, 2-closing process, 3-close eyes, 4-opening process,...
Definition: xv-types.h:1386
float eyelidUp
up eyelid data(0-1), up eyelid's vertical position in the image, normalization value,...
Definition: xv-types.h:1388
Definition: xv-types.h:1352
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:1355
float re
gaze re value, confidence level.
Definition: xv-types.h:1359
xv_ETPoint3D gazeDirection
gaze direction.
Definition: xv-types.h:1358
float exData[32]
reserved data.
Definition: xv-types.h:1361
xv_ETPoint3D gazeOrigin
origin gaze center coordinate.
Definition: xv-types.h:1357
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:1356
unsigned int exDataBitMask
reserved data.
Definition: xv-types.h:1360
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:1354
unsigned int gazeBitMask
gaze bit mask, identify the six data below are valid or invalid.
Definition: xv-types.h:1353
Definition: xv-types.h:1329
xv_ETMode mode
sdk mode, refer to xv_ETMode.
Definition: xv-types.h:1330
char configPath[260]
config file path.
Definition: xv-types.h:1331
Definition: xv-types.h:1369
unsigned int pupilBitMask
pupil bit mask, identify the six data below are valid or invalid.
Definition: xv-types.h:1370
float pupilMinorAxisMM
pupil diameter, pupil minor axis value(mm).
Definition: xv-types.h:1376
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:1373
xv_ETPoint2D pupilCenter
pupil center(0-1), the coordinate value of pupil center in the image, normalization value,...
Definition: xv-types.h:1371
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:1375
float pupilDistance
the distance between pupil and camera(mm)
Definition: xv-types.h:1372
float pupilDiameterMM
pupil diameter, pupil long axis value(mm).
Definition: xv-types.h:1374
Definition: xv-types.h:1514
Gesture key point.
Definition: xv-types.h:1262
SGBM CONFIG STRUCT.
Definition: xv-types.h:1066
Definition: xv-types.h:1290
Definition: xv-types.h:1301