Coordinate Frames

Motion is relative to an observing position. For example, if a user is holding and walking with a ZED, the camera will not be in motion relative to the user, but it will be in motion relative to the floor. In the same way, the ZED needs to express its motion information relative to a reference frame. This reference frame can either be the World Frame or the previous Camera Frame.

Camera Frame

The Camera Frame is the frame attached to the camera. Located at the back of the left eye of the device, it represents the viewport of the camera and allows to express relative pose. To get the movement between the current camera position and the one corresponding to the previous image, use getPosition(zed_pose, REFERENCE_FRAME::CAMERA).

World Frame

Describing the position of the camera in absolute real-world space requires a reference point that remains stationary as the device moves. This global reference frame is called World Frame. If no initial parameters are set, the World Frame is located at the place where the ZED first started motion tracking, and is oriented in the direction where the device was looking. To get the position of the camera in real-world space, use getPosition(zed_pose, REFERENCE_FRAME::WORLD).

World Frame Transform

You can change the initial location of the Camera Frame relative to the World Frame:

  • By setting an initial world transform in PositionalTrackingParameters, the Camera Frame will start at the given position and orientation in world space. This is useful when using the ZED with an IMU, so that the two sensors provide pose data relative to a common reference frame.
  • If Spatial Memory is enabled and an Area file is loaded, the World Frame will be the one stored in the Area file.
sl::Transform initial_position;
// Set the initial position of the Camera Frame at 1m80 above the World Frame
initial_position.setTranslation(sl::Translation(0,180,0));
tracking_parameters.initial_world_transform = initial_position;
initial_position = sl.Transform()
# Set the initial position of the Camera Frame at 1m80 above the World Frame
initial_translation = sl.Translation()
initial_translation.init_vector(0,180,0)
initial_position.set_translation(initial_translation)
tracking_parameters.set_initial_world_transform(initial_position)
PositionalTrackingParameters trackingParams = new PositionalTrackingParameters();
// Set the initial position of the Camera Frame at 1m80 above the World Frame
trackingParams.initialWorldPosition = new Vector3(0, 180, 0);
zed.EnablePositionalTracking(ref trackingParams);

Frame Transforms

When the ZED is moved, the motion of the left eye and the center of the camera is not the same. To describe the actual motion of the center of the camera, you need to use a frame transform. A frame transform expresses the rotational and translational offsets between coordinate frames.

The function getPosition() returns the pose of the Camera Frame located on the left eye. To get the movement of the center of the camera, you need to add a rigid transform.

How to transform pose data

To get pose data in a user-specified coordinate frame:

  • Measure the spatial transformation (translation and/or rotation) between the left eye of the camera and the local frame you want to get the pose data into.
  • Get pose updates using getPosition().
  • Transform each pose into the new coordinate frame using the translation and orientation offsets measured initially.
  • Use the transformed pose in your application.
void transformPose(sl::Transform &pose, float tx) {
    Transform transform_;
    transform_.setIdentity();
    // Translate the tracking frame by tx along the X axis  
    transform_.tx = tx;  
    // Pose(new reference frame) = M.inverse() * Pose (camera frame) * M, where M is the transform between two frames
    pose = Transform::inverse(transform_) * pose * transform_;  
}

// Get the distance between the center of the camera and the left eye
float translation_left_to_center = zed.getCameraInformation().calibration_parameters.T.x * 0.5f;
// Retrieve and transform the pose data into a new frame located at the center of the camera
POSITIONAL_TRACKING_STATE tracking_state = zed.getPosition(camera_pose, REFERENCE_FRAME::WORLD);
transformPose(camera_pose.pose_data, translation_left_to_center);
def transform_pose(pose, tx) :
    transform_ = sl.Transform()
    transform_.set_identity()
    # Translate the tracking frame by tx along the X axis
    transform_[0][3] = tx
    # Pose(new reference frame) = M.inverse() * pose (camera frame) * M, where M is the transform between the two frames
    transform_inv = sl.Transform()
    transform_inv.init_matrix(transform_)
    transform_inv.inverse()
    pose = transform_inv * pose * transform_

# Get the distance between the center of the camera and the left eye
translation_left_to_center = zed.get_camera_information().calibration_parameters.T[0]
# Retrieve and transform the pose data into a new frame located at the center of the camera
tracking_state = zed.get_position(camera_pose, sl.REFERENCE_FRAME.WORLD)
transform_pose(camera_pose.pose_data(sl.Transform()), translation_left_to_center)
public void transformPose(ref Matrix4x4 pose, float tx)
{
    Quaternion rotation_ = Quaternion.Identity;
    Vector3 position_ = Vector3.Zero;
    // Translate the tracking frame by tx along the X axis  
    position_.X = tx;
    Matrix4x4 transform_ = Matrix4x4.CreateFromQuaternion(rotation_);
    transform_.Translation = position_;
    transform_ = Matrix4x4.Transpose(transform_);

    Matrix4x4 transform_inv = Matrix4x4.Identity;
    Matrix4x4.Invert(transform_, out transform_inv);
    // Pose(new reference frame) = M.inverse() * Pose (camera frame) * M, where M is the transform between two frames
    pose = transform_inv * pose * transform_;
}

// Get the distance between the center of the camera and the left eye
float translation_left_to_center = zed.GetCalibrationParameters().Trans.X * 0.5f;
// Retrieve and transform the pose data into a new frame located at the center of the camera
Quaternion rotation = Quaternion.Identity;
Vector3 position = Vector3.Zero;
POSITIONAL_TRACKING_STATE tracking_state = zed.GetPosition(ref rotation, ref position, REFERENCE_FRAME.WORLD);
Matrix4x4 pose = Matrix4x4.CreateFromQuaternion(rotation);
pose.Translation = position;
pose = Matrix4x4.Transpose(pose);
transformPose(ref pose, translation_left_to_center);

Frame transforms can be used to track the movement of different local components of a rigid body. For example, when using an HMD in VR applications, it is important to transform pose data at the pivot point of the user’s head and neck to accurately describe head movements. On a robot, a rigid spatial transformation between auxiliary sensors (IMU frame for example) and the Camera coordinate frame is necessary for sensor fusion, although this is usually handled with ROS.

See Positional Tracking sample for code example of spatial transformation.

Selecting a Coordinate System

The ZED uses a three-dimensional Cartesian coordinate system (X, Y, Z) to specify positions and orientations. The coordinate system can be either right-handed or left-handed. By default, the ZED uses an image coordinate system which is right-handed with the positive Y-axis pointing down, X-axis pointing right and Z-axis pointing away from the camera.

Different coordinate systems can be selected using InitParameters:

  • Right handed, y-down (image - default)
  • Left handed, y-up (Unity)
  • Right handed, y-up (OpenGL)
  • Left handed, z-up (Unreal Engine)
  • Right handed, z-up
  • Right handed, z-up, x-forward (ROS)

init_params.coordinate_system = COORDINATE_SYSTEM::RIGHT_HANDED_Y_UP;
init_params.coordinate_system = sl.COORDINATE_SYSTEM.RIGHT_HANDED_Y_UP
init_params.coordinateSystem = COORDINATE_SYSTEM.RIGHT_HANDED_Y_UP;

Note: Camera Frame and World Frame always share the same coordinate system.

Coordinate Units

By default, coordinate values are in millimeters. It is possible to change coordinate units to meters, centimeters, feet and inches using:

init_params.coordinate_units = UNIT::METER; // Set units in meters
init_params.coordinate_units = sl.UNIT.METER # Set units in meters
init_params.coordinateUnits = UNIT.METER; // Set units in meters