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.

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.7.0-cp313-cp313-win_amd64.whl (3.2 MB view details)

Uploaded CPython 3.13Windows x86-64

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

Uploaded CPython 3.13Windows x86

libmultisense-7.7.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.7.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.7.0-cp313-cp313-macosx_11_0_arm64.whl (2.2 MB view details)

Uploaded CPython 3.13macOS 11.0+ ARM64

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

Uploaded CPython 3.12Windows x86-64

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

Uploaded CPython 3.12Windows x86

libmultisense-7.7.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.7.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.7.0-cp312-cp312-macosx_11_0_arm64.whl (2.2 MB view details)

Uploaded CPython 3.12macOS 11.0+ ARM64

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

Uploaded CPython 3.11Windows x86-64

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

Uploaded CPython 3.11Windows x86

libmultisense-7.7.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.7.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.7.0-cp311-cp311-macosx_11_0_arm64.whl (2.2 MB view details)

Uploaded CPython 3.11macOS 11.0+ ARM64

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

Uploaded CPython 3.10Windows x86-64

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

Uploaded CPython 3.10Windows x86

libmultisense-7.7.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.7.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.7.0-cp310-cp310-macosx_11_0_arm64.whl (2.2 MB view details)

Uploaded CPython 3.10macOS 11.0+ ARM64

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

Uploaded CPython 3.9Windows x86-64

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

Uploaded CPython 3.9Windows x86

libmultisense-7.7.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.7.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.7.0-cp39-cp39-macosx_11_0_arm64.whl (2.2 MB view details)

Uploaded CPython 3.9macOS 11.0+ ARM64

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

Uploaded CPython 3.8Windows x86-64

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

Uploaded CPython 3.8Windows x86

libmultisense-7.7.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.7.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.7.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.7.0-cp313-cp313-win_amd64.whl.

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp313-cp313-win_amd64.whl
Algorithm Hash digest
SHA256 18ce0f0f7e44b172f62053b40d174a43c1c55a6c3355fad8a2a5d26822ad47f2
MD5 4e29de1c7d7f009b2f6d8f1c26399e3a
BLAKE2b-256 acf39520ffe53f2e80779ee0455a0a6a1732d66306e1ff7502bd23eb32dfa379

See more details on using hashes here.

File details

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

File metadata

  • Download URL: libmultisense-7.7.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.7.0-cp313-cp313-win32.whl
Algorithm Hash digest
SHA256 e8f17817092d1ea7959bdc11c123cc141d0b0cfa4e4bc60e09449df6984ba60e
MD5 4b70e94a1a22e1bbf4a24836299455c4
BLAKE2b-256 fee3125bd5a2d1d04b60f522650e738a71be3e6b8805f4cac6c40a93e194045b

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 b139417277d459a4c8c5373d01a1a077cbbf3424489b3ed3faa35f5e30b72702
MD5 c6ef28b33b6c38ec75546a5ad1f37740
BLAKE2b-256 54560cb7d8878dd20447f5a2811ae5f1766221f806d7c1393d0e86b8255a3331

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp313-cp313-manylinux_2_17_i686.manylinux2014_i686.whl
Algorithm Hash digest
SHA256 3246b96fd18e3ebf06d0b7212f4af72768f3b29f2c30bc50a5b8bb595b3f2cdd
MD5 dbdf64fc65df65d01d016749bbcc20e9
BLAKE2b-256 34b0ee875874d82b11aacd3c9f88a10faaa61bbf86e2525f3da02b207be4c6d1

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp313-cp313-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 8788a8586ad6043bdc85401d714615f20e51145f93a1157417def6c6b9258080
MD5 d1f32765f632d6dd3ec007c44aad1c27
BLAKE2b-256 5af708a585c3e4cef5f0ee0dd58ead067e04b34b0ac5395b66ce40411edaf30a

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp312-cp312-win_amd64.whl
Algorithm Hash digest
SHA256 6090e0f27a64270797d5454dbe8e2ff0b3a67f56d214e7e4dcca565705e5e6a9
MD5 0e8d67a4abedd218a78887b34e866166
BLAKE2b-256 6f15412dbdeb52686f95045f64fdba79b4f46435c8282eff6c2b127d3608f19b

See more details on using hashes here.

File details

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

File metadata

  • Download URL: libmultisense-7.7.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.7.0-cp312-cp312-win32.whl
Algorithm Hash digest
SHA256 34b1fcdbb19e5945838b436ef85850280c409b683fd4cbf90701d436d8ca0ec5
MD5 cdc22f9b96f650acc7619c864a6b7f52
BLAKE2b-256 7d9724bc5817f1f83cb3991374033bd1f4dae408175f5aaebc1227e85cfb6110

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 a5ce3c528989202a489458889f4334dc13e6c833933fada322571a92cf58684b
MD5 5ce7a17fc90af1ca62364a8ad9de8382
BLAKE2b-256 8645bfd2421e062e5ccfc247e7fbde48e1bda24c2da2d5165b08874e179335f1

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl
Algorithm Hash digest
SHA256 4d405b161422ace3fefa3d7b319b97f656a238e04db82cbde018bee363fb3bcd
MD5 9abf877fa4424c527a563ede6c70794b
BLAKE2b-256 9de7bfdbf868de3cc7f7019a47c8ce7357ad5acce4cf07c9ca8108ea3e029c63

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp312-cp312-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 77c9526fb991632b9e50e521277f86d328528bde66b65b57094f8cc5baa34bec
MD5 9f3828a8d69026f6e5971fd32d335760
BLAKE2b-256 26f54c60e33149352d8aa33b1d0e15455b98b5683f973916b89ae5b1223c0d65

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp311-cp311-win_amd64.whl
Algorithm Hash digest
SHA256 9c5c9176d4873317c07095fad1896af972cc80a5b6ed24d882fb062e0a1a129d
MD5 424a1497397242349dfb5354b3de3283
BLAKE2b-256 c554fe9b679a270eec8d3826e863a862a327d52884e011d5d04b0f25528f74a4

See more details on using hashes here.

File details

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

File metadata

  • Download URL: libmultisense-7.7.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.7.0-cp311-cp311-win32.whl
Algorithm Hash digest
SHA256 a812cebb299e1b669ea456528e42d9635c28b2f980dd4655599710aabb197031
MD5 9d652e7a10cdee2a98815424780340e3
BLAKE2b-256 378b0324e2f3f8bbfdc80d25a589e1703ab57a835db2723d74f25ae18292af0f

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 369df2231b783f676b83b8828f99744f997b7e7837db376e9da5b8a61717df90
MD5 22b3d875f015a274bea50e2dda0621d7
BLAKE2b-256 3b7062ef3c21a8bfa7e5a5d00b7f9386472964e58c7aab3650f2bcbfbb214e8f

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl
Algorithm Hash digest
SHA256 3392497215df7ddebbc1d16f4891544e734efb29f4410614366aa689fb5e9c60
MD5 e6beb83b6cef07f26168f1c72e877d8c
BLAKE2b-256 0153fdae8fc8dd729920f25bb2db059c60b21b75f1994a3ea12f2bb094e9271f

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp311-cp311-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 e5334c58bc8a5a4270ec9161b3173ba6517870af0c4c987a1a74846d3d811f2c
MD5 1be65245fa443667b1af599576531557
BLAKE2b-256 8d00ed8f883e9f9cd8ce8f81b0a578782f3d6b55c7000cac39dc4e596da9c0ac

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp310-cp310-win_amd64.whl
Algorithm Hash digest
SHA256 fe04f3ad14b7429fc7bcde178b92c08c6e2fb4b9987f95439d85e5b6890d6225
MD5 aa9de810acf109adfa87aea5cbeb83cc
BLAKE2b-256 f20fb627f9d080539e19472b4afa6695652a9b18c94b8343bbd14faccede6be3

See more details on using hashes here.

File details

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

File metadata

  • Download URL: libmultisense-7.7.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.7.0-cp310-cp310-win32.whl
Algorithm Hash digest
SHA256 449202f42002f2c06fe17baffa4e9724d7f6adb853bc9cea4b87aad22d04d452
MD5 566ea3ad41bb42d855458f2928c80cd2
BLAKE2b-256 9b2f6025d1d3a99b83704136e015cf4f18226b558e3ce94a818ff70181e783fb

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 5fa8b2d903c5f05c4671a39591b8deffe8e52a1a9f387e830172d259a7cd4d3e
MD5 d373dc909020da0a3cf835a29b2938a4
BLAKE2b-256 410ba412a016fc0f813574508d44d072142bfb4779ac6ed3482a66aa678c1432

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl
Algorithm Hash digest
SHA256 078b5e0a1cdb69ff8bc79badf49d0890ffb747ad88945e51dd99dc692c8d2161
MD5 5ef962ab169199e2451a1c84b3a067f2
BLAKE2b-256 f8b2708c1186dc790bbafb69924b0a888551f77783b46835638b38b473d6a499

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp310-cp310-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 5c79b826338a73dd0fea7250de6f5e670ccc6c60427292340aa5d73dd35a2bd6
MD5 04e63d9b655b0bce84454c908e6c6816
BLAKE2b-256 b3cdfec731f29b6f3316d33a744ab9434337fa2a8f5b4b1330d95fd9acb59996

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp39-cp39-win_amd64.whl
Algorithm Hash digest
SHA256 7f4c7c7e03dd11eed9db417a7449eeed00982c31f8b5ab9a5d1760dd1ac99089
MD5 f3f82f07e72774c7ba6340a14bc2b96b
BLAKE2b-256 dc172e58af2fa85abcf496feb1032cbf9a9d4e14766991c9ca5d5973b49168ef

See more details on using hashes here.

File details

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

File metadata

  • Download URL: libmultisense-7.7.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.7.0-cp39-cp39-win32.whl
Algorithm Hash digest
SHA256 54199fb57474c2ae027ee1942c89c161625ba4dea4fef120e971cf960b9d95b3
MD5 066399e3c7247aa6f4926eae7c4807f6
BLAKE2b-256 ab65d0d91171aec74b96b84e9c04e815d03e9b4e48d1cb4e1e40d2d7f3ce290f

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 82d7d1c001c6efb39418141e216bc5932c271289d6768d22ce8bb216fe5e0f5e
MD5 40604d1c0d4ad8fb1c795f41794d5b8f
BLAKE2b-256 c944f1ad2fab7a56e86675d0e7fd52e9bb60f1b67e3b4000914d189f7760eea2

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl
Algorithm Hash digest
SHA256 aa362f79d0c2bf2e4b574845014850bda8b21718f91b9c0f6ee5105227cc2069
MD5 7fb83d75e7fd0295631215713db95e56
BLAKE2b-256 3664610cc4a0a61e923127e4f40b33830eafef3b6bc7f16e3712c87b97368f88

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp39-cp39-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 4eca7fb6846df45ed1627a5257e2507d7a9e7400db59cff1644d345cf6fcaba2
MD5 1f99fdbd0961a914f3f9f7a7e2e17248
BLAKE2b-256 6fb33c17f4fc005562d29a6dd4e37610115fdc4bb30904da6bbbc476e9282090

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp38-cp38-win_amd64.whl
Algorithm Hash digest
SHA256 504b3e9320ba721aa48653673e87f7f9e3974f0d52f329712612bd77137862e2
MD5 258780ca421430775f769acb41d2244c
BLAKE2b-256 be71df788b3cbd3b76182ac1545f4bded030854b1304c69db4d56025149d9692

See more details on using hashes here.

File details

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

File metadata

  • Download URL: libmultisense-7.7.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.7.0-cp38-cp38-win32.whl
Algorithm Hash digest
SHA256 ab0d6256223b5e28fb31fdee12622b1c33355afb47988e07968cddf5fdc5435b
MD5 0c943503daf859bec74c3c965ee5bb32
BLAKE2b-256 dc91bae9ed07db7907684943a7bf9928dbc3417f3c884e6027b3e8a361d506f4

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl
Algorithm Hash digest
SHA256 f09d6b53249a93c7cd460a75c2b1a6a64b91cdff923b084d8b4f3173c11e066b
MD5 36a70b4dfc03e61782c24c2362c59b9c
BLAKE2b-256 59c810a238defb65374e39f7f48629d5d623472e7b28be9ba8cc0d2b969ddc34

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl
Algorithm Hash digest
SHA256 1cd4c48f4ecd7cf7f8e13d3609fb39f826065b8d2a1cb04ba9e0c0d47dd29ac8
MD5 3d23b882cb5836646fb4a1efddb24cef
BLAKE2b-256 bb496c0e08fa336aa508f898ecfbe214389dc322e01d4a90de710f4ce597815d

See more details on using hashes here.

File details

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

File metadata

File hashes

Hashes for libmultisense-7.7.0-cp38-cp38-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 6f1c77e94dbadf275aacca9c29ed9b078fccb9689106d7437813f3990e2c7d87
MD5 18ae490e3aaa47fca0fb3349bd0fff95
BLAKE2b-256 8c8194ff9254eed01297d60f6bcb7553d31d01e0b9fbc9121530182f8ca429a7

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