Skip to content

Latest commit

 

History

History
159 lines (123 loc) · 8.05 KB

t265.md

File metadata and controls

159 lines (123 loc) · 8.05 KB

T265 Tracking Camera

The Intel® RealSense™ Tracking Camera T265 includes two fisheye lens sensors, an IMU and an Intel® Movidius™ Myriad™ 2 VPU. All of the V‑SLAM algorithms run directly on the VPU, allowing for very low latency and extremely efficient power consumption (1.5W).

Realsense SDK currently supports T265 on Windows and Linux as well as via our ROS wrapper.

Notes / known issues

  • For wheeled robots, odometer input is a requirement for robust and accurate tracking. The relevant APIs will be added to librealsense and ROS/realsense in upcoming releases. Currently, the API is available in the underlying device driver.
  • The relocalization API should be considered unstable, and is planned to be updated in a future release
  • macOS and Android support will come in a future release, as well as OpenVR integration.

To aid AR/VR integration, the T265 tracking device uses the defacto VR framework standard coordinate system instead of the SDK standard:

T265 Pose orientation

  1. Positive X direction is towards right imager
  2. Positive Y direction is upwards toward the top of the device
  3. Positive Z direction is inwards toward the back of the device

The center of tracking corresponds to the center location between the right and left monochrome imagers on the PCB

Calibration

The T265's sensors (including the IMU) are calibrated in the production line, so no further calibration process is required (unlike the D435i).

Integration with the SDK

The following librealsense tools and demos are IMU and tracking-ready:

  • rs-pose - A basic pose retrieval example
  • rs-pose-predict - Demonstrates pose prediction using current system time and the callback API
  • rs-capture - 2D Visualization.
  • rs-enumerate-devices - list the IMU and tracking profiles (FPS rates and formats).
  • rs-data-collect - Store and serialize IMU and Tracking (pose) data in Excel-friendly csv format. The tool uses low-level sensor API to minimize software-imposed latencies. Useful for performance profiling.
  • realsense-viewer - Provides 2D visualization of IMU and Tracking data. 3D visualization is available for Pose samples:

T265 2D Sensors
T265 3D Pose Tracking

The IMU and Tracking data streams are fully compatible with SDK's embedded recorder utility.

API

The pose and IMU data are treated by the SDK like any other supported sensor. Therefore the sensor access and invocation API calls are similar to those of the depth/rgb sensors of D400 and SR300:

rs2::pipeline pipe;

rs2::config cfg;
cfg.enable_stream(RS2_STREAM_GYRO);
cfg.enable_stream(RS2_STREAM_ACCEL);
cfg.enable_stream(RS2_STREAM_POSE);

pipe.start(cfg);

while (app) // Application still alive?
{
    rs2::frameset frameset = pipe.wait_for_frames();

    // Find and retrieve IMU and/or tracking data
    if (rs2::motion_frame accel_frame = frameset.first_or_default(RS2_STREAM_ACCEL))
    {
        rs2_vector accel_sample = accel_frame.get_motion_data();
        //std::cout << "Accel:" << accel_sample.x << ", " << accel_sample.y << ", " << accel_sample.z << std::endl;
        //...
    }

    if (rs2::motion_frame gyro_frame = frameset.first_or_default(RS2_STREAM_GYRO))
    {
        rs2_vector gyro_sample = gyro_frame.get_motion_data();
        //std::cout << "Gyro:" << gyro_sample.x << ", " << gyro_sample.y << ", " << gyro_sample.z << std::endl;
        //...
    }

    if (rs2::pose_frame pose_frame = frameset.first_or_default(RS2_STREAM_POSE))
    {
        rs2_pose pose_sample = pose_frame.get_pose_data();
        //std::cout << "Pose:" << pose_sample.translation.x << ", " << pose_sample.translation.y << ", " << pose_sample.translation.z << std::endl;
        //...
    }
}

FAQ

Is this a depth camera?

No, the T265 does not offer any Depth information. It can provide position and orientation (6-DOF), IMU (accelerometer and gyroscope), and two monochrome fisheye streams.

Can I use it together with a depth camera?

Yes, this device can be used with RealSense (and most likely any 3rd-party) depth cameras. It is passive and comes with an IR-cut filter.

How can I use the camera intrinsics and extrinsics?

The T265 uses the Kanalla-Brandt distortion model. This model is supported in OpenCV as part of the fisheye model. There is a python example which uses the camera intrinsics and extrinsics to compute depth from T265 images on the host using OpenCV.

What platforms are supported?

At launch the T265 will be supported via librealsense on Windows and Linux, and via ros-realsense. Mac-OS and Android support are planned but not scheduled yet, as well as OpenVR integration.

What are the system requirements?

Any board with USB2 capable of receiving pose data at 260 times a second should be sufficient. The device was validated on Intel NUC platform. To access the fisheye streams, USB3 is required.

Will the same SLAM be available for the D435i as a software package?

We are still looking into it, please stay tuned.

What is wheel odometry and how does it help T265 navigate?

Wheel odometry is the use of sensors to measure how much a wheel turns, it can be used to estimate changes in a wheeled robots position. T265 has wheel odometry support built in, allowing it to use the data from these sensors to refine the position data of the robot. Providing robotic wheel odometer or velocimeter data over USB to TM2 and the corresponding calibration data will make the tracking much more robust on wheeled robots, which otherwise can experience many tracking failures. The calibration file format is described in the section below. We consider odometer input to be a requirement for robust tracking on wheeled robots.

Can T265 work indoors and outdoors?

Yes, T265 can work both indoors and outdoors. Just like a person, it can be blinded by light that shines straight into its eyes, and it can’t see in absolute darkness.

Do multiple T265 devices interfere with each other?

No, you can use as many T265 devices in a space as you like.

Appendix

Wheel odometry calibration file format

Below is a sample calibration file with inline comments (not a valid file format!) that explain each field. Please note that this is an intermediate solution and a more unified interface will be coming.

{
    "velocimeters": [ // array of velocity sensors (currently max. 2 supported)
        {
            "scale_and_alignment": [ // 3-by-3 matrix, row-major (multiplies measurement)
                1.0,
                0.0000000000000000,
                0.0000000000000000,
                0.0000000000000000,
                1.0,
                0.0000000000000000,
                0.0000000000000000,
                0.0000000000000000,
                1.0
            ],
            "noise_variance": 0.004445126050420168, // measurement covariance (to be determined/tuned)
            "extrinsics": { // relative transformation of sensor frame w.r.t. T265 body frame
                "T": [ // translation (in meters)
                    -0.5059,
                    -0.6294,
                    -0.6873
                ],
                "T_variance": [ // currently not used, please ignore
                    9.999999974752427e-7, 
                    9.999999974752427e-7, 
                    9.999999974752427e-7
                ],
                "W": [ // orientation in axis-angle representation, axis x angle (in rad)
                    -1.1155,
                    -1.1690,
                    -1.2115
                ],
                "W_variance": [ // currently not used, please ignore
                    9.999999974752427e-5, 
                    9.999999974752427e-5, 
                    9.999999974752427e-5
                ]
            }
        }
    ]
}