Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
179 changes: 179 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,9 @@ The LibMultiSense C++ and Python library has been tested with the following oper
- [Color Image Generation](#color-image-generation)
- [Python](#python-7)
- [C++](#c-7)
- [IMU Data Streaming](#imu-data-streaming)
- [Python](#python-8)
- [C++](#c-8)

## Client Networking Prerequisite

Expand Down Expand Up @@ -734,3 +737,179 @@ int main(int argc, char** argv)
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

```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++

```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;
}
```
28 changes: 27 additions & 1 deletion python/bindings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,8 @@ PYBIND11_MODULE(_libmultisense, m) {
.value("AUX_CHROMA_RECTIFIED_RAW", multisense::DataSource::AUX_CHROMA_RECTIFIED_RAW)
.value("AUX_RAW", multisense::DataSource::AUX_RAW)
.value("AUX_RECTIFIED_RAW", multisense::DataSource::AUX_RECTIFIED_RAW)
.value("COST_RAW", multisense::DataSource::COST_RAW);
.value("COST_RAW", multisense::DataSource::COST_RAW)
.value("IMU", multisense::DataSource::IMU);

// ColorImageEncoding
py::enum_<multisense::ColorImageEncoding>(m, "ColorImageEncoding")
Expand Down Expand Up @@ -279,6 +280,30 @@ PYBIND11_MODULE(_libmultisense, m) {
.def_readonly("capture_exposure_time", &multisense::ImageFrame::capture_exposure_time)
.def_readonly("capture_gain", &multisense::ImageFrame::capture_gain);

// ImuSample::Measurement
py::class_<multisense::ImuSample::Measurement>(m, "ImuMeasurement")
.def(py::init<>())
PYBIND11_JSON_SUPPORT(multisense::ImuSample::Measurement)
.def_readwrite("x", &multisense::ImuSample::Measurement::x)
.def_readwrite("y", &multisense::ImuSample::Measurement::y)
.def_readwrite("z", &multisense::ImuSample::Measurement::z);

// ImuSample
py::class_<multisense::ImuSample>(m, "ImuSample")
.def(py::init<>())
PYBIND11_JSON_SUPPORT(multisense::ImuSample)
.def_readwrite("accelerometer", &multisense::ImuSample::accelerometer)
.def_readwrite("gyroscope", &multisense::ImuSample::gyroscope)
.def_readwrite("magnetometer", &multisense::ImuSample::magnetometer)
.def_readwrite("sample_time", &multisense::ImuSample::sample_time)
.def_readwrite("ptp_sample_time", &multisense::ImuSample::ptp_sample_time);

// ImuFrame
py::class_<multisense::ImuFrame>(m, "ImuFrame")
.def(py::init<>())
PYBIND11_JSON_SUPPORT(multisense::ImuFrame)
.def_readonly("samples", &multisense::ImuFrame::samples);

// ImuRate
py::class_<multisense::ImuRate>(m, "ImuRate")
.def(py::init<>())
Expand Down Expand Up @@ -704,6 +729,7 @@ PYBIND11_MODULE(_libmultisense, m) {
.def("connect", &multisense::Channel::connect)
.def("disconnect", &multisense::Channel::disconnect)
.def("get_next_image_frame", &multisense::Channel::get_next_image_frame, py::call_guard<py::gil_scoped_release>())
.def("get_next_imu_frame", &multisense::Channel::get_next_imu_frame, py::call_guard<py::gil_scoped_release>())
.def("get_config", &multisense::Channel::get_config, py::call_guard<py::gil_scoped_release>())
.def("set_config", &multisense::Channel::set_config, py::call_guard<py::gil_scoped_release>())
.def("get_calibration", &multisense::Channel::get_calibration, py::call_guard<py::gil_scoped_release>())
Expand Down
29 changes: 29 additions & 0 deletions source/LibMultiSense/include/MultiSense/MultiSenseSerialization.hh
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,20 @@ namespace nlohmann
}
};

template <>
struct adl_serializer<multisense::TimeT>
{
static void to_json(json& j, const multisense::TimeT &t)
{
j = t.time_since_epoch().count();
}

static void from_json(const json& j, multisense::TimeT &t)
{
t = multisense::TimeT(std::chrono::nanoseconds(j.get<std::chrono::nanoseconds::rep>()));
}
};

///
/// @brief Handle generic optional
///
Expand Down Expand Up @@ -426,6 +440,21 @@ NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE(MultiSenseInfo::ImuInfo,
gyroscope,
magnetometer)

NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE(ImuSample::Measurement,
x,
y,
z)

NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE(ImuSample,
accelerometer,
gyroscope,
magnetometer,
sample_time,
ptp_sample_time)

NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE(ImuFrame,
samples)

NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE(MultiSenseInfo,
device,
version,
Expand Down
Loading