IMUData Class Reference

Contains inertial positional tracking data which gives the orientation of the ZED-M. More...

General Functions

 IMUData ()
 Default constructor which creates an empty IMUData (identity). More...
 
 IMUData (const IMUData &pose)
 IMUData constructor with deep copy. More...
 
 IMUData (const Transform &pose_data, unsigned long long timestamp=0, int confidence=0)
 IMUData constructor with deep copy. More...
 
 ~IMUData ()
 IMUData destructor. More...
 
Translation getTranslation ()
 Returns the translation from the pose. More...
 
Orientation getOrientation ()
 Returns the orientation from the pose. More...
 
Rotation getRotationMatrix ()
 Returns the rotation (3x3) from the pose. More...
 
Rotation getRotation ()
 Returns the rotation (3x3) from the pose. More...
 
float3 getRotationVector ()
 Returns the rotation (3x1 rotation vector obtained from 3x3 rotation matrix using Rodrigues formula) from the pose. More...
 
float3 getEulerAngles (bool radian=true)
 Convert the Rotation of the Transform as Euler angles. More...
 

Attributes

sl::Matrix3f orientation_covariance
 
sl::float3 angular_velocity
 
sl::float3 linear_acceleration
 
sl::Matrix3f angular_velocity_convariance
 
sl::Matrix3f linear_acceleration_convariance
 
int image_sync_trigger
 
Transform pose_data
 
sl::timeStamp timestamp
 
int pose_confidence
 
float pose_covariance [36]
 6x6 Pose covariance of translation (the first 3 values) and rotation in so3 (the last 3 values) More...
 
bool valid
 
float twist [6]
 
float twist_covariance [36]
 

Detailed Description

Contains inertial positional tracking data which gives the orientation of the ZED-M.

Note
This data will not be filled if you are using a ZED camera

Different representations of orientation can be retrieved, along with timestamp and pose confidence. Raw data (linear acceleration and angular velocity) are also given along with the calculated orientation.

Constructor and Destructor

◆ IMUData() [1/3]

IMUData ( )

Default constructor which creates an empty IMUData (identity).

◆ IMUData() [2/3]

IMUData ( const IMUData pose)

IMUData constructor with deep copy.

◆ IMUData() [3/3]

IMUData ( const Transform pose_data,
unsigned long long  timestamp = 0,
int  confidence = 0 
)

IMUData constructor with deep copy.

◆ ~IMUData()

~IMUData ( )

IMUData destructor.

Functions

◆ getTranslation()

Translation getTranslation ( )
inherited

Returns the translation from the pose.

Returns
The (3x1) translation vector.

◆ getOrientation()

Orientation getOrientation ( )
inherited

Returns the orientation from the pose.

Returns
The (4x1) orientation vector.

◆ getRotationMatrix()

Rotation getRotationMatrix ( )
inherited

Returns the rotation (3x3) from the pose.

Returns
The (3x3) rotation matrix.

◆ getRotation()

Rotation getRotation ( )
inlineinherited

Returns the rotation (3x3) from the pose.

Returns
The (3x3) rotation matrix.
Deprecated:
See getRotationMatrix

◆ getRotationVector()

float3 getRotationVector ( )
inherited

Returns the rotation (3x1 rotation vector obtained from 3x3 rotation matrix using Rodrigues formula) from the pose.

Returns
The (3x1) rotation vector.

◆ getEulerAngles()

float3 getEulerAngles ( bool  radian = true)
inherited

Convert the Rotation of the Transform as Euler angles.

Parameters
radian: Define if the angle in is radian or degree. default : true.
Returns
The Euler angles, as a float3 representing the rotations around the X, Y and Z axes. (YZX convention)

Variables

◆ orientation_covariance

sl::Matrix3f orientation_covariance

(3x3) 3x3 Covariance matrix for orientation (x,y,z axes)

◆ angular_velocity

sl::float3 angular_velocity

(3x1) Vector for angular velocity of the IMU, given in deg/s. In other words, the current velocity at which the sensor is rotating around the x, y, and z axes.

◆ linear_acceleration

sl::float3 linear_acceleration

(3x1) Vector for linear acceleration of the IMU, given in m/s^2. In other words, the current acceleration of the sensor, along with the x, y, and z axes.

◆ angular_velocity_convariance

sl::Matrix3f angular_velocity_convariance

(3x3) 3x3 Covariance matrix for the angular velocity

◆ linear_acceleration_convariance

sl::Matrix3f linear_acceleration_convariance

(3x3) 3x3 Covariance matrix for the linear acceleration

◆ image_sync_trigger

int image_sync_trigger

Indicates if the IMUData has been taken during a frame capture on sensor. If value is 1, IMUData has been taken during the same time than a frame has been acquired by the left sensor (the time precision is linked to the IMU rate, therefore 800Hz == 1.3ms) If value is 0, the data has not been taken during a frame acquisition.

◆ pose_data

Transform pose_data
inherited

4x4 Matrix which contains the rotation (3x3) and the translation. Orientation is extracted from this transform as well.

◆ timestamp

sl::timeStamp timestamp
inherited

Timestamp of the pose. This timestamp should be compared with the camera timestamp for synchronization.

◆ pose_confidence

int pose_confidence
inherited

Confidence/Quality of the pose estimation for the target frame.
A confidence metric of the tracking [0-100], 0 means that the tracking is lost, 100 means that the tracking can be fully trusted.

◆ pose_covariance

float pose_covariance[36]
inherited

6x6 Pose covariance of translation (the first 3 values) and rotation in so3 (the last 3 values)

Note
Computed only if sl::TrackingParameters::enable_spatial_memory is disabled.

◆ valid

bool valid
inherited

boolean that indicates if tracking is activated or not. You should check that first if something wrong.

◆ twist

float twist[6]
inherited

twist and twist covariance of the camera available in reference camera

◆ twist_covariance

float twist_covariance[36]
inherited