Skip to main content

LibMultiSense python package wrapped using pybind11

Project description

LibMultiSense

codecov

LibMultiSense is a C++ and Python library designed to simplify interaction with the MultiSense S family of stereo sensors developed by Carnegie Robotics. It provides a comprehensive, easy-to-use API for capturing and processing stereo sensor data an generating depth images, color images, and 3D point clouds.

Official product page: Carnegie Robotics MultiSense Products

Detailed documentation: LibMultiSense Documentation

LibMultiSense was recently refactored to have a new API. The following examples in the README all assume the user is using the new API. To build with the new API, the following CMake arguments should be set.

-DBUILD_LEGACY_API=0FF

The README for the Legacy API can be found here.

The LibMultiSense C++ and Python library has been tested with the following operating systems

  • Ubuntu
    • 20.04
    • 22.04
    • 24.04
  • MacOS Sequoia
  • Windows 11

Table of Contents

Client Networking Prerequisite

The MultiSense comes preconfigured with a static 10.66.171.21 IP address with a /24 subnet. To connect to the MultiSense, a client machine must be updated with an IP address on the 10.66.171 subnet.

Please see the host network configuration for details on how to set a client machine's IP address and MTU.

Quickstart Guide

Below are minimal examples demonstrating basic usage of LibMultiSense to capture rectified images from the camera.

Before running the examples make sure LibMultiSense is installed, and your machines network is properly configured.

For new users, it's recommended to start with the Python version of LibMultiSense. After installing the libmultisense package, several command-line utilities are automatically installed and can be run directly from your terminal:

  • multisense_device_info_utility: Display information about a connected MultiSense device.
  • multisense_save_image_utility: Save images (rectified, color, depth) from the camera to disk.
  • multisense_point_cloud_utility: Generate and save 3D point clouds in .ply format.
  • multisense_version_info_utility: Show firmware and hardware version information.
  • multisense_change_ip_utility: Update the network configuration of a MultiSense device.
  • multisense_image_cal_utility: Query or set the intrinsic and extrinsic calibration of the MultiSense device.
  • multisense_multi_channel_utility: Synchronize outputs from multiple MultiSense devices (requires PTP synchronization).
  • multisense_ptp_utility: Check the current PTP sync of the MultiSense device.
  • multisense_rectified_focal_length_utility: Update the focal length of the rectified image used to compute disparity.
  • multisense_feature_detector_utility: Display a live feed of detected features on the left rectified image.

Example usage:

multisense_device_info_utility --ip_address 10.66.171.21

Python

Install the LibMultiSenes python client and OpenCV dependency via

pip install libmultisense opencv-python
import libmultisense as lms
import cv2

channel_config = lms.ChannelConfig()
channel_config.ip_address = "10.66.171.21"
with lms.Channel.create(channel_config) as channel:
    channel.start_streams([lms.DataSource.LEFT_RECTIFIED_RAW, lms.DataSource.RIGHT_RECTIFIED_RAW])

    while True:
        frame = channel.get_next_image_frame()
        if frame:
            for source, image in frame.images.items():
                cv2.imwrite(str(source) + ".png", image.as_array)

C++

#include <MultiSense/MultiSenseChannel.hh>
#include <MultiSense/MultiSenseUtilities.hh>

namespace lms = multisense;

int main()
{
    const auto channel = lms::Channel::create(lms::Channel::Config{"10.66.171.21"});
    channel->start_streams({lms::DataSource::LEFT_RECTIFIED_RAW, lms::DataSource::RIGHT_RECTIFIED_RAW});

    while(true)
    {
        if (const auto image_frame = channel->get_next_image_frame(); image_frame)
        {
            for (const auto &[source, image]: image_frame->images)
            {
                const auto path = std::to_string(image_frame->frame_id) +  "_" +
                                  std::to_string(static_cast<int>(source)) + ".png";
                lms::write_image(image, path);
            }
        }
    }
    return 0;
}

Optional Dependencies When Building From Source

OpenCV

LibMultiSense optionally has OpenCV utility functions to make the LibMultiSense client API easier to integrate with existing systems. To build the OpenCV helpers the following CMake argument should be set

-DBUILD_OPENCV=ON

This will require a system installation of OpenCV, or an installation which can be pointed to with CMake's CMAKE_PREFIX_PATH argument

nlohmann json

LibMultiSense optionally uses nlohmann_json for serialization of base LibMultiSense types. To build the nlohmann_json serialization helpers the following CMake argument should be set

-DBUILD_JSON_SERIALIZATION=ON

This will require a system installation of nlohmann_json, or an installation which can be pointed to with CMake's CMAKE_PREFIX_PATH argument

pybind11

LibMultiSense optionally uses pybind11 to generate python bindings for the C++ API. To build the pybind11 python bindings the following CMake argument should be set

-DBUILD_PYTHON_BINDINGS=ON

This will require a system installation of pybind11, or an installation which can be pointed to with CMake's CMAKE_PREFIX_PATH argument

googletest

LibMultiSense optionally uses googletest for unit testing the C++ API. To build the googletest unit tests the following CMake argument should be set

-DBUILD_TESTS=ON

This will require a system installation of googletest, or an installation which can be pointed to with CMake's CMAKE_PREFIX_PATH argument

Code Coverage

LibMultiSense supports generating unit test coverage reports using lcov and genhtml. To enable coverage instrumentation, set the following CMake argument:

-DENABLE_COVERAGE=ON

Once enabled, you can generate the coverage report by running:

make coverage

The report will be generated in build/coverage_report/index.html. This requires lcov and genhtml to be installed on the system and is supported on Linux with GCC or Clang.


Installation

Linux

Python

PyPi (Recommended)

The following command installs/updates to the latest version of the LibMultisense Python API:

pip install --upgrade libmultisense

To avoid conflicts with other Python packages, it's recommended to utilize venv to isolate dependency installations.

From Source

LibMultiSense uses pybind11 to generate Python bindings for the base LibMultiSense API. These bindings can be installed via pip into a Python virtual environment or a local Python project.

To install the LibMultiSense Python bindings

> sudo apt install build-essential pybind11-dev nlohmann-json3-dev

> git clone https://github.com/carnegierobotics/LibMultiSense.git
> cd LibMultiSense
> pip install .

C++

LibMultiSense uses CMake for its build system.

To build the standalone LibMultiSense library and demonstration applications.

# Note this only needs to be run once before building
> sudo apt install build-essential nlohmann-json3-dev

> git clone https://github.com/carnegierobotics/LibMultiSense.git
> cd LibMultiSense
> mkdir build
> cd build && cmake -DBUILD_LEGACY_API=OFF -DBUILD_JSON_SERIALIZATION=ON -DCMAKE_INSTALL_PREFIX=../install ..
> make install
> cd ../install

To build the standalone LibMultiSense library without the demonstration applications, set the cmake variable -DMULTISENSE_BUILD_UTILITIES=OFF


MacOS

Python

PyPi (Recommended)

The following command installs/updates to the latest version of the LibMultisense Python API:

pip install --upgrade libmultisense

To avoid conflicts with other Python packages, it's recommended to utilize venv to isolate dependency installations.

From Source

LibMultiSense uses pybind11 to generate Python bindings for the base LibMultiSense API. These bindings can be installed via pip into a Python virtual environment or a local Python project.

To install the LibMultiSense Python bindings

> brew install pybind11 nlohmann-json

> git clone https://github.com/carnegierobotics/LibMultiSense.git
> cd LibMultiSense
> pip install .

C++

LibMultiSense uses CMake for its build system.

To build the standalone LibMultiSense library and demonstration applications.

# Note this only needs to be run once before building
> brew install nlohmann-json

> git clone https://github.com/carnegierobotics/LibMultiSense.git
> cd LibMultiSense
> mkdir build
> cd build && cmake -DBUILD_LEGACY_API=OFF -DBUILD_JSON_SERIALIZATION=ON -DCMAKE_INSTALL_PREFIX=../install ..
> make install
> cd ../install

To build the standalone LibMultiSense library without the demonstration applications, set the cmake variable -DMULTISENSE_BUILD_UTILITIES=OFF


Windows

Python

PyPi (Recommended)

The following command installs/updates to the latest version of the LibMultisense Python API.

After installing Python via the Microsoft Store execute the following command in a Powershell terminal

pip install --upgrade libmultisense

To avoid conflicts with other Python packages, it's recommended to utilize venv to isolate dependency installations.

From Source

LibMultiSense uses pybind11 to generate Python bindings for the base LibMultiSense API. These bindings can be installed via pip into a Python virtual environment or a local Python project. To ensure Windows has the proper build tools installed, please install Microsoft Visual Studio with the C++ and CMake extensions.

Note you will need to have a version of Python installed on your Windows system. This was tested with Python 3.9 installed via the Microsoft Store on Windows 11.

To install the LibMultiSense Python bindings open a powershell terminal and execute the following commands

> git clone https://github.com/carnegierobotics/LibMultiSense.git
> cd LibMultiSense
> git clone https://github.com/microsoft/vcpkg.git
> ./vcpkg/bootstrap-vcpkg.bat

> $Env:VCPKG_ROOT = ./vcpkg

> pip install .

C++

LibMultiSense uses CMake and vcpkg to build the LibMultiSense library. To ensure Windows has the proper build tools installed, please install Microsoft Visual Studio with the C++ and CMake extensions.

Open a powershell terminal and execute the following commands:

> git clone https://github.com/carnegierobotics/LibMultiSense.git
> cd LibMultiSense
> git clone https://github.com/microsoft/vcpkg.git
> ./vcpkg/bootstrap-vcpkg.bat

> $Env:VCPKG_ROOT = ./vcpkg

> cmake --build build --config Release --target install

CMake Project Integration

Integrating LibMultiSense into an existing CMake project is easy. There are two primary methods for integration: a local install on your system, or a submodule clone within your repository

Local Installation

LibMultiSense is installed on your system (i.e. in a location like /opt/multisense)

find_package(MultiSense)
target_link_libraries(<your-library-or-binary> MultiSense)

When running CMake, make sure to specify the location of the LibMultiSense install via -DCMAKE_PREFIX_PATH

Git Submodule

Clone the LibMultiSense repository into the existing project's source tree. In the main CMakeLists.txt file of the project, add the following lines:

 include_directories(LibMultiSense/source/LibMultiSense)
 add_subdirectory(LibMultiSense/source/LibMultiSense)

Documentation

Documentation of high-level LibMultiSense concepts can be found here

Doxygen documentation can be built for LibMultisense by running the Doxygen configuration file located in the docs directory

> cd LibMultiSense/docs
> doxygen Doxyfile

HTML and LaTex documentation will be generated in the docs directory.

Usage examples are included in the Doxygen documentation.


Support

To report an issue with this library or request a new feature, please use the GitHub issues system

For product support, please see the support section of our website Individual support requests can be created in our support portal

Wireshark Plugin

A Wireshark Lua dissector is provided in the wireshark directory to help analyze MultiSense network traffic on UDP port 9001.

Installation

To install the plugin:

Linux

Copy the plugin to your personal Wireshark plugins directory:

mkdir -p ~/.local/lib/wireshark/plugins
cp wireshark/multisense.lua ~/.local/lib/wireshark/plugins/

Windows

Copy wireshark/multisense.lua to %APPDATA%\Wireshark\plugins.

MacOS

Copy wireshark/multisense.lua to ~/.config/wireshark/plugins.

Manual Loading

Alternatively, you can load the plugin manually when starting Wireshark:

wireshark -X lua_script:wireshark/multisense.lua

Camera Configuration

Camera settings like resolution, exposure, FPS, gain, gamma, and white balance can be configured via the LibMultiSense image::Config

Python

import libmultisense as lms
import cv2

def main():
    channel_config = lms.ChannelConfig()
    channel_config.ip_address = "10.66.171.21"

    with lms.Channel.create(channel_config) as channel:
        if not channel:
            print("Invalid channel")
            exit(1)

        config = channel.get_config()
        config.frames_per_second = 10.0
        config.width = 960
        config.height = 600
        config.disparities = lms.MaxDisparities.D256
        config.image_config.auto_exposure_enabled = True
        config.image_config.gamma = 2.2
        if channel.set_config(config) != lms.Status.OK:
            print("Cannot set configuration")
            exit(1)

if __name__ == "__main__":
    main()

C++

#include <iostream>

#include <MultiSense/MultiSenseChannel.hh>
#include <MultiSense/MultiSenseUtilities.hh>

namespace lms = multisense;

int main(int argc, char** argv)
{
    const auto channel = lms::Channel::create(lms::Channel::Config{"10.66.171.21"});
    if (!channel)
    {
        std::cerr << "Failed to create channel" << std::endl;;
        return 1;
    }

    auto config = channel->get_config();
    config.frames_per_second = 10.0;
    config.width = 960;
    config.height = 600;
    config.disparities = lms::MultiSenseConfig::MaxDisparities::D256;
    config.image_config.auto_exposure_enabled = true;
    config.image_config.gamma = 2.2;
    if (const auto status = channel->set_config(config); status != lms::Status::OK)
    {
        std::cerr << "Cannot set config" << std::endl;
        return 1;
    }

    return 0;
}

Point Cloud Generation

Disparity images can be converted to 3D point cloud images using the client API.

The following modified version of the Quickstart example, converts disparity images to 3D point clouds colorized using the left rectified image.

Python

import libmultisense as lms
import cv2

def main():
    channel_config = lms.ChannelConfig()
    channel_config.ip_address = "10.66.171.21"

    with lms.Channel.create(channel_config) as channel:
        if not channel:
            print("Invalid channel")
            exit(1)

        if channel.start_streams([lms.DataSource.LEFT_RECTIFIED_RAW, lms.DataSource.LEFT_DISPARITY_RAW]) != lms.Status.OK:
            print("Unable to start streams")
            exit(1)

        while True:
            frame = channel.get_next_image_frame()
            if frame:
                point_cloud = lms.create_gray8_pointcloud(frame,
                                                         args.max_range,
                                                         lms.DataSource.LEFT_RECTIFIED_RAW,
                                                         lms.DataSource.LEFT_DISPARITY_RAW)

                print("Saving pointcloud for frame id: ", frame.frame_id)
                lms.write_pointcloud_ply(point_cloud, str(frame.frame_id) + ".ply")

if __name__ == "__main__":
    main()

C++

#include <iostream>

#include <MultiSense/MultiSenseChannel.hh>
#include <MultiSense/MultiSenseUtilities.hh>

namespace lms = multisense;

volatile bool done = false;

int main(int argc, char** argv)
{
    const auto channel = lms::Channel::create(lms::Channel::Config{"10.66.171.21"});
    if (!channel)
    {
        std::cerr << "Failed to create channel" << std::endl;;
        return 1;
    }

    if (const auto status = channel->start_streams({lms::DataSource::LEFT_RECTIFIED_RAW,
                                                    lms::DataSource::LEFT_DISPARITY_RAW}); status != lms::Status::OK)
    {
        std::cerr << "Cannot start streams: " << lms::to_string(status) << std::endl;
        return 1;
    }

    const double max_range_m = 20.0;

    while(!done)
    {
        if (const auto image_frame = channel->get_next_image_frame(); image_frame)
        {
            if (const auto point_cloud = lms::create_color_pointcloud<uint8_t>(image_frame.value(),
                                                                               max_range_m,
                                                                               lms::DataSource::LEFT_RECTIFIED_RAW,
                                                                               lms::DataSource::LEFT_DISPARITY_RAW); point_cloud)
            {
                std::cout << "Saving pointcloud for frame id: " << image_frame->frame_id << std::endl;
                lms::write_pointcloud_ply(point_cloud.value(), std::to_string(image_frame->frame_id) + ".ply");
            }
        }
    }

    return 0;
}

Depth Image Generation

Disparity images can be converted to depth images using the client API

The following modified version of the Quickstart example, converts disparity images to openni depth images and saves them to disk using OpenCV.

Python

import libmultisense as lms
import cv2

def main():
    channel_config = lms.ChannelConfig()
    channel_config.ip_address = "10.66.171.21"

    with lms.Channel.create(channel_config) as channel:
        if not channel:
            print("Invalid channel")
            exit(1)

        if channel.start_streams([lms.DataSource.LEFT_DISPARITY_RAW]) != lms.Status.OK:
            print("Unable to start streams")
            exit(1)

        # Set to true to save the depth image in the frame of the aux color camera
        in_aux_frame = False

        while True:
            frame = channel.get_next_image_frame()
            if frame:
                # MONO16 depth images are quantized to 1 mm per 1 pixel value to match the OpenNI standard.
                # For example, a depth image pixel with a value of 10 would correspond to a depth of 10mm
                depth_image = lms.create_depth_image(frame, lms.PixelFormat.MONO16, lms.DataSource.LEFT_DISPARITY_RAW, in_aux_frame, 65535)
                if depth_image:
                    print("Saving depth image for frame id: ", frame.frame_id)
                    cv2.imwrite(str(frame.frame_id) + ".png", depth_image.as_array)

if __name__ == "__main__":
    main()

C++

#include <iostream>

#include <opencv2/opencv.hpp>

#define HAVE_OPENCV 1
#include <MultiSense/MultiSenseChannel.hh>
#include <MultiSense/MultiSenseUtilities.hh>

namespace lms = multisense;

volatile bool done = false;

int main(int argc, char** argv)
{
    const auto channel = lms::Channel::create(lms::Channel::Config{"10.66.171.21"});
    if (!channel)
    {
        std::cerr << "Failed to create channel" << std::endl;;
        return 1;
    }

    if (const auto status = channel->start_streams({lms::DataSource::LEFT_DISPARITY_RAW}); status != lms::Status::OK)
    {
        std::cerr << "Cannot start streams: " << lms::to_string(status) << std::endl;
        return 1;
    }

    // Set to true to save the depth image in the frame of the aux color camera
    const bool in_aux_frame = false;

    while(!done)
    {
        if (const auto image_frame = channel->get_next_image_frame(); image_frame)
        {
            //
            // MONO16 depth will be quantized to mm to match OpenNI's depth format
            //
            if (const auto depth_image = lms::create_depth_image(image_frame.value(),
                                                                 lms::Image::PixelFormat::MONO16,
                                                                 lms::DataSource::LEFT_DISPARITY_RAW,
                                                                 in_aux_frame,
                                                                 65535); depth_image)
            {
                std::cout << "Saving depth image for frame id: " << image_frame->frame_id << std::endl;
                cv::imwrite(std::to_string(image_frame->frame_id) + ".png", depth_image->cv_mat());
            }
        }
    }

    return 0;
}

Color Image Generation

Luma and Chroma Aux images can be converted to BGR color images using the client API

The following modified version of the Quickstart example, converts luma and chroma aux images to BGR images and saves them to disk using OpenCV.

Python

import libmultisense as lms
import cv2

def main():
    channel_config = lms.ChannelConfig()
    channel_config.ip_address = "10.66.171.21"

    with lms.Channel.create(channel_config) as channel:
        if not channel:
            print("Invalid channel")
            exit(1)

        if channel.start_streams([lms.DataSource.AUX_RAW]) != lms.Status.OK:
            print("Unable to start streams")
            exit(1)

        while True:
            frame = channel.get_next_image_frame()
            if frame:
                bgr = lms.create_bgr_image(frame, lms.DataSource.AUX_RAW)
                if bgr:
                    cv2.imwrite(str(frame.frame_id) + ".png", bgr.as_array)

if __name__ == "__main__":
    main()

C++

#include <iostream>

#include <opencv2/opencv.hpp>

#define HAVE_OPENCV 1
#include <MultiSense/MultiSenseChannel.hh>
#include <MultiSense/MultiSenseUtilities.hh>

namespace lms = multisense;

volatile bool done = false;

int main(int argc, char** argv)
{
    const auto channel = lms::Channel::create(lms::Channel::Config{"10.66.171.21"});
    if (!channel)
    {
        std::cerr << "Failed to create channel" << std::endl;;
        return 1;
    }

    if (const auto status = channel->start_streams({lms::DataSource::AUX_RAW}); status != lms::Status::OK)
    {
        std::cerr << "Cannot start streams: " << lms::to_string(status) << std::endl;
        return 1;
    }

    while(!done)
    {
        if (const auto image_frame = channel->get_next_image_frame(); image_frame)
        {
            if (const auto bgr = create_bgr_image(image_frame.value(), lms::DataSource::AUX_RAW); bgr)
            {
                cv::imwrite(std::to_string(image_frame->frame_id) + ".png", bgr->cv_mat());
            }
        }
    }

    return 0;
}

Lighting Control

MultiSense units like the KS21 contain integrated lighting which can be controlled via the lighting_config. Some units also support driving external LEDs via GPIO.

Python

import libmultisense as lms

def main():
    channel_config = lms.ChannelConfig()
    channel_config.ip_address = "10.66.171.21"

    with lms.Channel.create(channel_config) as channel:
        if not channel:
            print("Invalid channel")
            exit(1)

        config = channel.get_config()

        # Check if the camera supports lighting
        if config.lighting_config is not None:
            # Internal LEDs (Integrated into the camera)
            if config.lighting_config.internal is not None:
                # Set the lighting intensity to 50%
                config.lighting_config.internal.intensity = 50.0
                # Enable flashing. When enabled the lights will only be on while the camera is exposing
                config.lighting_config.internal.flash = True

            # External LEDs (Driven via external GPIO)
            if config.lighting_config.external is not None:
                # Set the external lighting intensity to 100%
                config.lighting_config.external.intensity = 100.0
                # Sync external flash with the main stereo pair
                config.lighting_config.external.flash = lms.FlashMode.SYNC_WITH_MAIN_STEREO
                # Number of pulses per exposure (useful for human persistence of vision)
                config.lighting_config.external.pulses_per_exposure = 1

            if channel.set_config(config) != lms.Status.OK:
                print("Cannot set configuration")
                exit(1)

if __name__ == "__main__":
    main()

C++

#include <iostream>
#include <MultiSense/MultiSenseChannel.hh>

namespace lms = multisense;

int main(int argc, char** argv)
{
    const auto channel = lms::Channel::create(lms::Channel::Config{"10.66.171.21"});
    if (!channel)
    {
        std::cerr << "Failed to create channel" << std::endl;
        return 1;
    }

    auto config = channel->get_config();

    // Check if the camera supports lighting
    if (config.lighting_config)
    {
        // Internal LEDs (Integrated into the camera)
        if (config.lighting_config->internal)
        {
            // Set the lighting intensity to 50%
            config.lighting_config->internal->intensity = 50.0f;
            // Enable flashing. When enabled the lights will only be on while the camera is exposing
            config.lighting_config->internal->flash = true;
        }

        // External LEDs (Driven via external GPIO)
        if (config.lighting_config->external)
        {
            // Set the external lighting intensity to 100%
            config.lighting_config->external->intensity = 100.0f;
            // Sync external flash with the main stereo pair
            config.lighting_config->external->flash = lms::MultiSenseConfig::LightingConfig::ExternalConfig::FlashMode::SYNC_WITH_MAIN_STEREO;
            // Number of pulses per exposure (useful for human persistence of vision)
            config.lighting_config->external->pulses_per_exposure = 1;
        }

        if (const auto status = channel->set_config(config); status != lms::Status::OK)
        {
            std::cerr << "Cannot set configuration" << std::endl;
            return 1;
        }
    }

    return 0;
}

IMU Data Streaming

LibMultiSense supports streaming IMU data from the camera. The IMU must first be configured to enable the desired sensors (accelerometer, gyroscope) and set their sample rates and ranges.

Python

import libmultisense as lms

def main():
    channel_config = lms.ChannelConfig()
    channel_config.ip_address = "10.66.171.21"

    with lms.Channel.create(channel_config) as channel:
        if not channel:
            print("Invalid channel")
            exit(1)

        #
        # Get the current configuration
        #
        config = channel.get_config()

        #
        # Configure the IMU. We first need to get the IMU info to find supported rates and ranges
        #
        info = channel.get_info()
        if not info.imu:
            print("Sensor does not have an IMU")
            exit(1)

        imu_config = lms.ImuConfig()
        imu_config.samples_per_frame = 10 # Number of samples per ImuFrame

        # Enable Accelerometer. Select appropriate rate/range
        if info.imu.accelerometer:
            accel_mode = lms.ImuOperatingMode()
            accel_mode.enabled = True
            accel_mode.rate = info.imu.accelerometer.rates[0]
            accel_mode.range = info.imu.accelerometer.ranges[0]
            imu_config.accelerometer = accel_mode

        # Enable Gyroscope. Select appropriate rate/range
        if info.imu.gyroscope:
            gyro_mode = lms.ImuOperatingMode()
            gyro_mode.enabled = True
            gyro_mode.rate = info.imu.gyroscope.rates[0]
            gyro_mode.range = info.imu.gyroscope.ranges[0]
            imu_config.gyroscope = gyro_mode

        config.imu_config = imu_config
        if channel.set_config(config) != lms.Status.OK:
            print("Failed to set IMU configuration")
            exit(1)

        #
        # Start the IMU stream
        #
        if channel.start_streams([lms.DataSource.IMU]) != lms.Status.OK:
            print("Unable to start IMU stream")
            exit(1)

        while True:
            imu_frame = channel.get_next_imu_frame()
            if imu_frame:
                for sample in imu_frame.samples:
                    if sample.accelerometer:
                        print(f"Accel: x={sample.accelerometer.x}, y={sample.accelerometer.y}, z={sample.accelerometer.z}")
                    if sample.gyroscope:
                        print(f"Gyro: x={sample.gyroscope.x}, y={sample.gyroscope.y}, z={sample.gyroscope.z}")

if __name__ == "__main__":
    main()

C++

#include <iostream>
#include <MultiSense/MultiSenseChannel.hh>

namespace lms = multisense;

int main(int argc, char** argv)
{
    const auto channel = lms::Channel::create(lms::Channel::Config{"10.66.171.21"});
    if (!channel)
    {
        std::cerr << "Failed to create channel" << std::endl;
        return 1;
    }

    //
    // Get the current configuration
    //
    auto config = channel->get_config();

    //
    // Configure the IMU. We first need to get the IMU info to find supported rates and ranges
    //
    const auto info = channel->get_info();
    if (!info.imu)
    {
        std::cerr << "Sensor does not have an IMU" << std::endl;
        return 1;
    }

    lms::MultiSenseConfig::ImuConfig imu_config;
    imu_config.samples_per_frame = 10;

    // Enable Accelerometer
    if (info.imu->accelerometer)
    {
        lms::MultiSenseConfig::ImuConfig::OperatingMode accel_mode;
        accel_mode.enabled = true;
        accel_mode.rate = info.imu->accelerometer->rates[0];
        accel_mode.range = info.imu->accelerometer->ranges[0];
        imu_config.accelerometer = accel_mode;
    }

    // Enable Gyroscope
    if (info.imu->gyroscope)
    {
        lms::MultiSenseConfig::ImuConfig::OperatingMode gyro_mode;
        gyro_mode.enabled = true;
        gyro_mode.rate = info.imu->gyroscope->rates[0];
        gyro_mode.range = info.imu->gyroscope->ranges[0];
        imu_config.gyroscope = gyro_mode;
    }

    config.imu_config = imu_config;
    if (const auto status = channel->set_config(config); status != lms::Status::OK)
    {
        std::cerr << "Failed to set IMU configuration: " << lms::to_string(status) << std::endl;
        return 1;
    }

    //
    // Start the IMU stream
    //
    if (const auto status = channel->start_streams({lms::DataSource::IMU}); status != lms::Status::OK)
    {
        std::cerr << "Cannot start IMU stream: " << lms::to_string(status) << std::endl;
        return 1;
    }

    while(true)
    {
        if (const auto imu_frame = channel->get_next_imu_frame(); imu_frame)
        {
            for (const auto& sample : imu_frame->samples)
            {
                if (sample.accelerometer)
                {
                    std::cout << "Accel: x=" << sample.accelerometer->x
                              << ", y=" << sample.accelerometer->y
                              << ", z=" << sample.accelerometer->z << std::endl;
                }
                if (sample.gyroscope)
                {
                    std::cout << "Gyro: x=" << sample.gyroscope->x
                              << ", y=" << sample.gyroscope->y
                              << ", z=" << sample.gyroscope->z << std::endl;
                }
            }
        }
    }

    return 0;
}

Query Camera Calibration

The camera's internal stereo calibration can be queried from the MultiSense. This calibration corresponds to the full-resolution operating mode of the camera and can be used to rectify raw images or project 3D points.

Python

import libmultisense as lms

def main():
    channel_config = lms.ChannelConfig()
    channel_config.ip_address = "10.66.171.21"

    with lms.Channel.create(channel_config) as channel:
        if not channel:
            print("Invalid channel")
            exit(1)

        # Query the camera calibration. NOTE this is for the full resolution operating mode. Each frame
        # also contains a scaled calibration which can be easier to handle depending on the application
        calibration = channel.get_calibration()

        # Print the intrinsic matrix (K) for the left camera
        print("Left Camera Intrinsic Matrix (K):")
        print(calibration.left.K)

        # Print the rectified projection matrix (P) for the left camera
        print("Left Camera Rectified Projection Matrix (P):")
        print(calibration.left.P)

        # Print the distortion coefficients (D) for the left camera
        print("Left Camera Distortion Coefficients (D):")
        print(calibration.left.D)

        # Access aux camera calibration if present
        if calibration.aux is not None:
             print("Aux Camera Intrinsic Matrix (K):")
             print(calibration.aux.K)

        # Create a Q matrix to convert disparity pixels to 3D point clouds
        Q = lms.QMatrix(calibration.left, calibration.right);
        print(Q.matrix())

if __name__ == "__main__":
    main()

C++

#include <iostream>
#include <MultiSense/MultiSenseChannel.hh>
#include <MultiSense/MultiSenseUtilities.hh>

namespace lms = multisense;

int main(int argc, char** argv)
{
    const auto channel = lms::Channel::create(lms::Channel::Config{"10.66.171.21"});
    if (!channel)
    {
        std::cerr << "Failed to create channel" << std::endl;
        return 1;
    }

    // Query the camera calibration. NOTE this is for the full resolution operating mode. Each frame also contains
    // a scaled calibration which can be easier to handle depending on the application
    const auto calibration = channel->get_calibration();

    // Access intrinsic matrix (K) for the left camera
    std::cout << "Left Camera Intrinsic Matrix (K):" << std::endl;
    for (const auto& row : calibration.left.K)
    {
        for (float val : row)
        {
            std::cout << val << " ";
        }
        std::cout << std::endl;
    }

    // Access rectified projection matrix (P) for the left camera
    std::cout << "Left Camera Rectified Projection Matrix (P):" << std::endl;
    for (const auto& row : calibration.left.P)
    {
        for (float val : row)
        {
            std::cout << val << " ";
        }
        std::cout << std::endl;
    }

    // Generate a Q matrix to convert disparity points to 3D point clouds
    const auto Q = QMatrix(calibration.left, calibration.right);

    return 0;
}

Feature Rendering

LibMultiSense supports retrieving image features computed on-camera. These are synchronized with the corresponding image frames.

The following example demonstrates how to retrieve and render features on a rectified image.

[!NOTE] MultiSense firmware version v7.36 or newer is required to use the onboard feature detector

Python

import libmultisense as lms
import cv2

def main():
    channel_config = lms.ChannelConfig()
    channel_config.ip_address = "10.66.171.21"

    with lms.Channel.create(channel_config) as channel:
        if not channel:
            print("Invalid channel")
            exit(1)

        # Set the feature detector config to enable the feature detector
        config = channel.get_config()
        config.feature_detector_config = lms.FeatureDetectorConfig()
        config.feature_detector_config.number_of_features = 1500
        config.feature_detector_config.grouping_enabled = True
        channel.set_config(config)

        # Start both the rectified image and the corresponding feature stream
        sources = [lms.DataSource.LEFT_MONO_RAW, lms.DataSource.LEFT_ORB_FEATURES]
        if channel.start_streams(sources) != lms.Status.OK:
            print("Unable to start streams")
            exit(1)

        while True:
            frame = channel.get_next_image_frame()
            if frame and frame.has_image(lms.DataSource.LEFT_MONO_RAW):
                img = frame.get_image(lms.DataSource.LEFT_MONO_RAW).as_array

                # Convert grayscale to BGR for color rendering
                display_img = cv2.cvtColor(img, cv2.COLOR_GRAY2BGR)

                if frame.has_feature(lms.DataSource.LEFT_ORB_FEATURES):
                    features = frame.get_feature(lms.DataSource.LEFT_ORB_FEATURES)
                    print(f"Frame {frame.frame_id}: Received {len(features.keypoints)} features")

                    for kp in features.keypoints:
                        cv2.circle(display_img, (int(kp.x), int(kp.y)), 3, (0, 255, 0), -1)

                cv2.imshow("MultiSense Features", display_img)
                if cv2.waitKey(1) & 0xFF == ord('q'):
                    break

if __name__ == "__main__":
    main()

C++

#include <iostream>
#include <opencv2/opencv.hpp>

#define HAVE_OPENCV 1
#include <MultiSense/MultiSenseChannel.hh>
#include <MultiSense/MultiSenseUtilities.hh>

namespace lms = multisense;

int main(int argc, char** argv)
{
    const auto channel = lms::Channel::create(lms::Channel::Config{"10.66.171.21"});
    if (!channel)
    {
        std::cerr << "Failed to create channel" << std::endl;
        return 1;
    }

    //
    // Set the feature detector config to enable the feature detector
    //
    auto config = channel->get_config();
    config.feature_detector_config = lms::MultiSenseConfig::FeatureDetectorConfig{number_of_features, true, 1};
    channel->set_config(config);

    // Start both the rectified image and the corresponding feature stream
    const std::vector<lms::DataSource> sources = {
        lms::DataSource::LEFT_MONO_RAW,
        lms::DataSource::LEFT_ORB_FEATURES
    };

    if (const auto status = channel->start_streams(sources); status != lms::Status::OK)
    {
        std::cerr << "Cannot start streams: " << lms::to_string(status) << std::endl;
        return 1;
    }

    while(true)
    {
        if (const auto frame = channel->get_next_image_frame(); frame)
        {
            if (frame->has_image(lms::DataSource::LEFT_MONO_RAW))
            {
                cv::Mat img = frame->get_image(lms::DataSource::LEFT_MONO_RAW).cv_mat();
                cv::Mat display_img;
                cv::cvtColor(img, display_img, cv::COLOR_GRAY2BGR);

                if (frame->has_feature(lms::DataSource::LEFT_ORB_FEATURES))
                {
                    const auto& features = frame->get_feature(lms::DataSource::LEFT_ORB_FEATURES);

                    // Use the native OpenCV utility to convert keypoints and draw them
                    cv::drawKeypoints(display_img, features.cv_keypoints(), display_img, cv::Scalar(0, 255, 0));
                }

                cv::imshow("MultiSense Features", display_img);
                if (cv::waitKey(1) == 'q') break;
            }
        }
    }

    return 0;
}

Project details


Download files

Download the file for your platform. If you're not sure which to choose, learn more about installing packages.

Source Distributions

No source distribution files available for this release.See tutorial on generating distribution archives.

Built Distributions

If you're not sure about the file name format, learn more about wheel file names.

libmultisense-7.8.0-cp313-cp313-win_amd64.whl (3.2 MB view details)

Uploaded CPython 3.13Windows x86-64

libmultisense-7.8.0-cp313-cp313-win32.whl (2.7 MB view details)

Uploaded CPython 3.13Windows x86

libmultisense-7.8.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl (3.1 MB view details)

Uploaded CPython 3.13manylinux: glibc 2.17+ x86-64

libmultisense-7.8.0-cp313-cp313-manylinux_2_17_i686.manylinux2014_i686.whl (3.4 MB view details)

Uploaded CPython 3.13manylinux: glibc 2.17+ i686

libmultisense-7.8.0-cp313-cp313-macosx_11_0_arm64.whl (2.2 MB view details)

Uploaded CPython 3.13macOS 11.0+ ARM64

libmultisense-7.8.0-cp312-cp312-win_amd64.whl (3.2 MB view details)

Uploaded CPython 3.12Windows x86-64

libmultisense-7.8.0-cp312-cp312-win32.whl (2.7 MB view details)

Uploaded CPython 3.12Windows x86

libmultisense-7.8.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl (3.1 MB view details)

Uploaded CPython 3.12manylinux: glibc 2.17+ x86-64

libmultisense-7.8.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl (3.4 MB view details)

Uploaded CPython 3.12manylinux: glibc 2.17+ i686

libmultisense-7.8.0-cp312-cp312-macosx_11_0_arm64.whl (2.2 MB view details)

Uploaded CPython 3.12macOS 11.0+ ARM64

libmultisense-7.8.0-cp311-cp311-win_amd64.whl (3.2 MB view details)

Uploaded CPython 3.11Windows x86-64

libmultisense-7.8.0-cp311-cp311-win32.whl (2.7 MB view details)

Uploaded CPython 3.11Windows x86

libmultisense-7.8.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl (3.1 MB view details)

Uploaded CPython 3.11manylinux: glibc 2.17+ x86-64

libmultisense-7.8.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl (3.4 MB view details)

Uploaded CPython 3.11manylinux: glibc 2.17+ i686

libmultisense-7.8.0-cp311-cp311-macosx_11_0_arm64.whl (2.2 MB view details)

Uploaded CPython 3.11macOS 11.0+ ARM64

libmultisense-7.8.0-cp310-cp310-win_amd64.whl (3.2 MB view details)

Uploaded CPython 3.10Windows x86-64

libmultisense-7.8.0-cp310-cp310-win32.whl (2.7 MB view details)

Uploaded CPython 3.10Windows x86

libmultisense-7.8.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl (3.1 MB view details)

Uploaded CPython 3.10manylinux: glibc 2.17+ x86-64

libmultisense-7.8.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl (3.4 MB view details)

Uploaded CPython 3.10manylinux: glibc 2.17+ i686

libmultisense-7.8.0-cp310-cp310-macosx_11_0_arm64.whl (2.2 MB view details)

Uploaded CPython 3.10macOS 11.0+ ARM64

libmultisense-7.8.0-cp39-cp39-win_amd64.whl (3.3 MB view details)

Uploaded CPython 3.9Windows x86-64

libmultisense-7.8.0-cp39-cp39-win32.whl (2.7 MB view details)

Uploaded CPython 3.9Windows x86

libmultisense-7.8.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl (3.1 MB view details)

Uploaded CPython 3.9manylinux: glibc 2.17+ x86-64

libmultisense-7.8.0-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl (3.4 MB view details)

Uploaded CPython 3.9manylinux: glibc 2.17+ i686

libmultisense-7.8.0-cp39-cp39-macosx_11_0_arm64.whl (2.2 MB view details)

Uploaded CPython 3.9macOS 11.0+ ARM64

libmultisense-7.8.0-cp38-cp38-win_amd64.whl (3.2 MB view details)

Uploaded CPython 3.8Windows x86-64

libmultisense-7.8.0-cp38-cp38-win32.whl (2.7 MB view details)

Uploaded CPython 3.8Windows x86

libmultisense-7.8.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl (3.1 MB view details)

Uploaded CPython 3.8manylinux: glibc 2.17+ x86-64

libmultisense-7.8.0-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl (3.4 MB view details)

Uploaded CPython 3.8manylinux: glibc 2.17+ i686

libmultisense-7.8.0-cp38-cp38-macosx_11_0_arm64.whl (2.2 MB view details)

Uploaded CPython 3.8macOS 11.0+ ARM64

File details

Details for the file libmultisense-7.8.0-cp313-cp313-win_amd64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp313-cp313-win_amd64.whl
Algorithm Hash digest
SHA256 7121e66a4c4b952097734da34bcba7bd98526cef51196b435f2d14c04dcf05c5
MD5 04761af42c3e5bea38f6020781ff1f2e
BLAKE2b-256 4622f3fc58bfdf9c9e380b95c35464ac349d7f525fec0711cf097856b5743022

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp313-cp313-win32.whl.

File metadata

  • Download URL: libmultisense-7.8.0-cp313-cp313-win32.whl
  • Upload date:
  • Size: 2.7 MB
  • Tags: CPython 3.13, Windows x86
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.2.0 CPython/3.12.3

File hashes

Hashes for libmultisense-7.8.0-cp313-cp313-win32.whl
Algorithm Hash digest
SHA256 d338225642c7083f2a097b48301fcfe606ccb191c8d933e4c08630262aacd5b5
MD5 b8d003120846b869bc39463187005048
BLAKE2b-256 b8d4c77936b78cd82b584bf20b1e30764a7111a686342258f6ce27cc36b5bb4d

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 6e6a0ae6d39284962ca4b3a2a285c33d95dadb3b742633ff26f3220228466da8
MD5 1245ab946e5dc3047aff88cba371e14d
BLAKE2b-256 a76a1b51740013faa54c4c0bb7a2d75e9234b4c4b704382a6ac48647c562fb6f

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp313-cp313-manylinux_2_17_i686.manylinux2014_i686.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp313-cp313-manylinux_2_17_i686.manylinux2014_i686.whl
Algorithm Hash digest
SHA256 0f111a46de9390baf57ee68a2c4b9dfd75bc5139cbed4ae8ba1300ab091244cc
MD5 793beeda040a66cfacf0aafdea1273be
BLAKE2b-256 7e075d5360d453320f65ce19a13e71b1fd1dca6e25a6a93184f80f1030dc5f5f

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp313-cp313-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp313-cp313-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 09fbe1ef0b0b0c964e4e5f8af514d7224bf663df31b473bfd6700283ba0d003b
MD5 c35203889e2b15ef28ddab0a31efbbce
BLAKE2b-256 4c7b0817d2f672a27f5250c1136ad2ca1712f4dcfe8f8f7457dd15f24e3a86cd

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp312-cp312-win_amd64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp312-cp312-win_amd64.whl
Algorithm Hash digest
SHA256 7b53c5f82079e87ada653f8850234dc9d5498fc39bb78c6dca880a0cdb41ca5f
MD5 2b71fe44600da28b85674e00d83f9f3d
BLAKE2b-256 b8d51bb16ab0ccbc5dbe2fa03dac2d1045ce74379bc55de78188ce997e5906fc

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp312-cp312-win32.whl.

File metadata

  • Download URL: libmultisense-7.8.0-cp312-cp312-win32.whl
  • Upload date:
  • Size: 2.7 MB
  • Tags: CPython 3.12, Windows x86
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.2.0 CPython/3.12.3

File hashes

Hashes for libmultisense-7.8.0-cp312-cp312-win32.whl
Algorithm Hash digest
SHA256 1d1428eea38e9cad8a3937daf68769e16eef1fa881e4293a5e43a5f5e458ca1a
MD5 a2b5707e94b6f987bb795f30f9cb3541
BLAKE2b-256 748a5f2b0809a1b94c0f5bbb109c7d3bd2f202cce45484a4442157cc12f8a89f

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 20c55360f9005343dd80bc4b4e0db30b335b826ba71525a9dedae6cc3f741289
MD5 59525af92a0c7ed9b417ad3fcbcb7e59
BLAKE2b-256 a284ad5e5c6855856f1875a22b4c18d4572fc5dd93447622c7a854762e0ce847

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl
Algorithm Hash digest
SHA256 7474471951dbf7d586caad940eb2c0aba6ffa53c5bc6844a482062a033eea44a
MD5 0b0e77aa4cc54a60a08f90ad1d8b5935
BLAKE2b-256 b8bb1805a535eddc86ef09ccf0a60985c835fbfc2a193ecd7e75c6d440cec69d

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp312-cp312-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp312-cp312-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 3ef7bcbd4709364c4f806ffe2dfad12bd5ba47db7fb544a1a6b865cd720bd8ed
MD5 5665e8b427bb7275c2a587839a5a3a20
BLAKE2b-256 5056c1913027405f5f88931080d0ebc3d64193d2ffb79dd76b95f7e81d69f673

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp311-cp311-win_amd64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp311-cp311-win_amd64.whl
Algorithm Hash digest
SHA256 3fa07bba248a5932cac3f8e19bc4aa115c76a26a26490974b3d1984d03d2962a
MD5 5492b918a44f041bdd1b8227b66afa82
BLAKE2b-256 afc6fe4a24e53484321a64bb658d4ad528719625807727572a0029f83279c5a7

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp311-cp311-win32.whl.

File metadata

  • Download URL: libmultisense-7.8.0-cp311-cp311-win32.whl
  • Upload date:
  • Size: 2.7 MB
  • Tags: CPython 3.11, Windows x86
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.2.0 CPython/3.12.3

File hashes

Hashes for libmultisense-7.8.0-cp311-cp311-win32.whl
Algorithm Hash digest
SHA256 96b99b1c789bec9271a9020ced397fdabd7bba802479ca44fc0da491580ccbe6
MD5 ba9c618fd4345afee74500946079d690
BLAKE2b-256 6606e367acd4590a26fee2fc7f7cfa6f73d8c558ffe7c34a6287bf63e61ac518

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 b65814d8138e16a10113fec18b4202e9655768f2943adfc42acef6f3ff96460a
MD5 8d28bb02e2cfb9468fca8af0a7844682
BLAKE2b-256 2cd32c58c2b9d0551e32916e400905ba3c65b6ffc87b13e2fe5966320647c326

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl
Algorithm Hash digest
SHA256 446bfcff93b781f2fed048dddc85f73f7f07849c9a1d82d14ac310958392937a
MD5 7525a5f84ff91a7dbc380a8caae9b146
BLAKE2b-256 764d3d84e574fcd450e1f28da78e35322fd089df7ad7b273f6cc5d1c63d45ef0

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp311-cp311-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp311-cp311-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 6e7a3ed4cf98bc69f868795217d10dfe6030340acaa7ac0439a20a53a35f0373
MD5 3417bd293d65eafa501125126ce12270
BLAKE2b-256 f4278f4cb197a491c30701e64af8df222ea2001c25337c710061095c59c1e637

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp310-cp310-win_amd64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp310-cp310-win_amd64.whl
Algorithm Hash digest
SHA256 6479b77ee9c5ed91275807a4cfde54d6d2f2cec47891b5354d3cd7f855e8d693
MD5 101fa8ccbacb6827e5e2ed1960d48238
BLAKE2b-256 dd56aa0683e483c1f41c7c112ada4861e396e3f633a9b72cebcdb15edad73c12

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp310-cp310-win32.whl.

File metadata

  • Download URL: libmultisense-7.8.0-cp310-cp310-win32.whl
  • Upload date:
  • Size: 2.7 MB
  • Tags: CPython 3.10, Windows x86
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.2.0 CPython/3.12.3

File hashes

Hashes for libmultisense-7.8.0-cp310-cp310-win32.whl
Algorithm Hash digest
SHA256 bd40e8a12634e0bf42549b02aaea519fdc5941a7a119df2043d070e46b2856a8
MD5 b985f7b1b42b7c06611c31e354397687
BLAKE2b-256 55f2bccb46c3f69603e4c1e11968bd26e5239ea62d1721a5478e7fd1a1b7a2de

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 36802d7193d39f1e77843734731362dc8e893400612b12e51a8bab92bf21b322
MD5 2d6d84dd3b2e8adefe3403d7765f842c
BLAKE2b-256 50fef798dae13a1d11ff75c09645b189e0f6072fce25087192731ed0eca68db2

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl
Algorithm Hash digest
SHA256 4cd3eb86864fd1b3adbe90f08d28ccac5a5b5c316cc51b981bb0433b7f53b1e8
MD5 ddaefe98360df30e4324f7d7a63fa173
BLAKE2b-256 8b25ae5ca816651b17d6389596f0505f82a286996910777171c83e8990cce2f1

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp310-cp310-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp310-cp310-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 003aa995100832c6197e08b899d25d7b2ffb71d17f0a28ca29360b394470539c
MD5 b6a79df470e11adf5c69c143901a3c45
BLAKE2b-256 754249c988390d4629270306cbd3d6117d371a217ce2d186999ed61c86a99200

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp39-cp39-win_amd64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp39-cp39-win_amd64.whl
Algorithm Hash digest
SHA256 3d567b60af98d176b05648de64dd016ed1dbec3658dcd21a56ae5030b0b170b2
MD5 5fe4cb4a601e02afc16d0e45ccdc8438
BLAKE2b-256 3aad431676f11cc4e802d8e7b528a72a91b34420ec2d5574cc66c84abe667f68

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp39-cp39-win32.whl.

File metadata

  • Download URL: libmultisense-7.8.0-cp39-cp39-win32.whl
  • Upload date:
  • Size: 2.7 MB
  • Tags: CPython 3.9, Windows x86
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.2.0 CPython/3.12.3

File hashes

Hashes for libmultisense-7.8.0-cp39-cp39-win32.whl
Algorithm Hash digest
SHA256 8ccd67fa3753ab4d1add007f5ce9d59c5b31ddf8da2b0313bddafd66585a193a
MD5 bc9942c7d0f03ca6c86935dc73fe334d
BLAKE2b-256 b176ec645c1ff9c603a259719430a677b11ef2eb441b5b504c4f861f58b45eeb

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 7564a9cd6426d485e19f27d61bcfff81fc1c980dcbeadd45025c492b684dc847
MD5 9b1665314513331e43469b5988f96f6d
BLAKE2b-256 35cbf9dbae92de9bca002d814f70e47224f2870bf8a0e084816cd093a362ba8e

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl
Algorithm Hash digest
SHA256 74a423551914726d97f3f2873274a7915a17a23e3aa357b56d44a9e7325cf109
MD5 27f284df4fe5edfba00dbbc57aa073eb
BLAKE2b-256 8941b346537b4f9b63f11803db6d264a003e435e9c062195d0fb06b1fb4fa205

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp39-cp39-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp39-cp39-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 d02c64d33e103050521331f10ffe81513cde3d5dc08a5d072fa2b5812bf3aeb1
MD5 478f6585a3a427a0935530c01949433b
BLAKE2b-256 54dd84790a0cad3f044728bfd408be3d222bd75949eeeb190eb170310af234f3

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp38-cp38-win_amd64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp38-cp38-win_amd64.whl
Algorithm Hash digest
SHA256 64145de19a7d76bb9bddd85cbe6c7e32eee3f2fc4dc506c8be619e12982e700e
MD5 c2ffa70b2d31c768184e0f18e7e274b8
BLAKE2b-256 5812ad187b9be2c10586224bac7093c831bea7c02ab3841d89ed2af71033e5ec

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp38-cp38-win32.whl.

File metadata

  • Download URL: libmultisense-7.8.0-cp38-cp38-win32.whl
  • Upload date:
  • Size: 2.7 MB
  • Tags: CPython 3.8, Windows x86
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.2.0 CPython/3.12.3

File hashes

Hashes for libmultisense-7.8.0-cp38-cp38-win32.whl
Algorithm Hash digest
SHA256 975fecb4a9aece8d68f35f2ca5e903cef44720c5e082f1a2125046b666ff7f83
MD5 e91a3b202ede6b0fb0ab369ec376a07c
BLAKE2b-256 898136ce315649904e332ee706112fe2d85486ebf8374bd5dfefe756ec6ee44d

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 253a036013ed1f3b0efb800c76ba516bcc88ec03f234a3e7bf4d6ce656036243
MD5 dc296c67e01233c2c0f85b2312a65fe6
BLAKE2b-256 29dff69cefee78d9aeb66557b969126c5bb0d7291817703d95fab229eb3c84e8

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl
Algorithm Hash digest
SHA256 06564d31f04f52ee8b48852249a962e1d8db3eb9a6b5bd1d084f9e4994c04bf5
MD5 c614aba59ac110a3e1559438efc384d1
BLAKE2b-256 2426ca0cb2553ab92a257849813996e86771f2b939637c2ca7f2c8640fb78853

See more details on using hashes here.

File details

Details for the file libmultisense-7.8.0-cp38-cp38-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for libmultisense-7.8.0-cp38-cp38-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 f56767d0274cca1fbe016d349219b074405e1a0e29ce330daf12c7cb7f947af6
MD5 8f9fa8e2058c9b4cc17e591ab32df676
BLAKE2b-256 e44292d250ad51e150319ac743aa91d5249cd286aa15284cda4e3b981c786814

See more details on using hashes here.

Supported by

AWS Cloud computing and Security Sponsor Datadog Monitoring Depot Continuous Integration Fastly CDN Google Download Analytics Pingdom Monitoring Sentry Error logging StatusPage Status page