bindings.cc
Go to the documentation of this file.
1 
37 #include <iostream>
38 
39 #include <pybind11/pybind11.h>
40 #include <pybind11/chrono.h>
41 #include <pybind11/functional.h>
42 #include <pybind11/numpy.h>
43 #include <pybind11/operators.h>
44 #include <pybind11/stl.h>
45 
46 #include <MultiSense/MultiSenseChannel.hh>
48 
49 #ifdef BUILD_JSON
51 
52 #define PYBIND11_JSON_SUPPORT(Type) \
53  .def(py::init([](const py::dict &d) { \
54  py::module json = py::module::import("json"); \
55  py::object json_str = json.attr("dumps")(d); \
56  const nlohmann::json j = nlohmann::json::parse(json_str.cast<std::string>()); \
57  Type t{}; \
58  j.get_to(t); \
59  return t; \
60  })) \
61  .def_property_readonly("json", [](const Type &obj) { \
62  const nlohmann::json j = obj; \
63  py::module json = py::module::import("json"); \
64  py::object result = json.attr("loads")(j.dump()); \
65  return result.cast<py::dict>(); \
66  }) \
67  .def("__repr__", [](const Type &obj) { \
68  const nlohmann::json j = obj; \
69  return j.dump(); \
70  })
71 #else
72 #define PYBIND11_JSON_SUPPORT(Type)
73 #endif
74 
75 namespace py = pybind11;
76 
77 PYBIND11_MODULE(_libmultisense, m) {
78  m.doc() = "Pybind11 bindings for the LibMultiSense C++ Library";
79 
80  // Status
81  py::enum_<multisense::Status>(m, "Status")
82  .value("OK", multisense::Status::OK)
83  .value("TIMEOUT", multisense::Status::TIMEOUT)
84  .value("INTERNAL_ERROR", multisense::Status::INTERNAL_ERROR)
85  .value("FAILED", multisense::Status::FAILED)
86  .value("UNSUPPORTED", multisense::Status::UNSUPPORTED)
87  .value("UNKNOWN", multisense::Status::UNKNOWN)
88  .value("EXCEPTION", multisense::Status::EXCEPTION)
89  .value("UNINITIALIZED", multisense::Status::UNINITIALIZED)
90  .value("INCOMPLETE_APPLICATION", multisense::Status::INCOMPLETE_APPLICATION);
91 
92  // DataSource
93  py::enum_<multisense::DataSource>(m, "DataSource")
94  .value("UNKNOWN", multisense::DataSource::UNKNOWN)
95  .value("ALL", multisense::DataSource::ALL)
96  .value("LEFT_MONO_RAW", multisense::DataSource::LEFT_MONO_RAW)
97  .value("RIGHT_MONO_RAW", multisense::DataSource::RIGHT_MONO_RAW)
98  .value("LEFT_MONO_COMPRESSED", multisense::DataSource::LEFT_MONO_COMPRESSED)
99  .value("RIGHT_MONO_COMPRESSED", multisense::DataSource::RIGHT_MONO_COMPRESSED)
100  .value("LEFT_RECTIFIED_RAW", multisense::DataSource::LEFT_RECTIFIED_RAW)
101  .value("RIGHT_RECTIFIED_RAW", multisense::DataSource::RIGHT_RECTIFIED_RAW)
102  .value("LEFT_RECTIFIED_COMPRESSED", multisense::DataSource::LEFT_RECTIFIED_COMPRESSED)
103  .value("RIGHT_RECTIFIED_COMPRESSED", multisense::DataSource::RIGHT_RECTIFIED_COMPRESSED)
104  .value("LEFT_DISPARITY_RAW", multisense::DataSource::LEFT_DISPARITY_RAW)
105  .value("LEFT_DISPARITY_COMPRESSED", multisense::DataSource::LEFT_DISPARITY_COMPRESSED)
106  .value("AUX_COMPRESSED", multisense::DataSource::AUX_COMPRESSED)
107  .value("AUX_RECTIFIED_COMPRESSED", multisense::DataSource::AUX_RECTIFIED_COMPRESSED)
108  .value("AUX_LUMA_RAW", multisense::DataSource::AUX_LUMA_RAW)
109  .value("AUX_LUMA_RECTIFIED_RAW", multisense::DataSource::AUX_LUMA_RECTIFIED_RAW)
110  .value("AUX_CHROMA_RAW", multisense::DataSource::AUX_CHROMA_RAW)
111  .value("AUX_CHROMA_RECTIFIED_RAW", multisense::DataSource::AUX_CHROMA_RECTIFIED_RAW)
112  .value("AUX_RAW", multisense::DataSource::AUX_RAW)
113  .value("AUX_RECTIFIED_RAW", multisense::DataSource::AUX_RECTIFIED_RAW)
114  .value("COST_RAW", multisense::DataSource::COST_RAW);
115 
116  // ColorImageEncoding
117  py::enum_<multisense::ColorImageEncoding>(m, "ColorImageEncoding")
119  .value("YCBCR420", multisense::ColorImageEncoding::YCBCR420);
120 
121  // CameraCalibration::DistortionType
122  py::enum_<multisense::CameraCalibration::DistortionType>(m, "DistortionType")
126 
127  // CameraCalibration
128  py::class_<multisense::CameraCalibration>(m, "CameraCalibration")
129  .def(py::init<>())
131  .def_readwrite("K", &multisense::CameraCalibration::K)
132  .def_readwrite("R", &multisense::CameraCalibration::R)
133  .def_readwrite("P", &multisense::CameraCalibration::P)
134  .def_readwrite("distortion_type", &multisense::CameraCalibration::distortion_type)
135  .def_readwrite("D", &multisense::CameraCalibration::D);
136 
137  // StereoCalibration
138  py::class_<multisense::StereoCalibration>(m, "StereoCalibration")
139  .def(py::init<>())
141  .def_readwrite("left", &multisense::StereoCalibration::left)
142  .def_readwrite("right", &multisense::StereoCalibration::right)
143  .def_readwrite("aux", &multisense::StereoCalibration::aux);
144 
145  // Image::PixelFormat
146  py::enum_<multisense::Image::PixelFormat>(m, "PixelFormat")
147  .value("UNKNOWN", multisense::Image::PixelFormat::UNKNOWN)
151  .value("FLOAT32", multisense::Image::PixelFormat::FLOAT32)
153  .value("H264", multisense::Image::PixelFormat::H264);
154 
155  // Image
156  py::class_<multisense::Image>(m, "Image")
157  .def(py::init<>())
158  .def_property_readonly("as_array", [](const multisense::Image& image)
159  {
160 
161  std::vector<size_t> shape = {static_cast<size_t>(image.height), static_cast<size_t>(image.width)};
162  std::vector<size_t> strides;
163  size_t element_size = 0;
164  std::string format;
165 
166  switch (image.format)
167  {
169  {
170  element_size = sizeof(uint8_t);
171  format = py::format_descriptor<uint8_t>::format();
172  strides = {sizeof(uint8_t) * image.width, sizeof(uint8_t)};
173  break;
174  }
176  {
177  element_size = sizeof(uint16_t);
178  format = py::format_descriptor<uint16_t>::format();
179  strides = {sizeof(uint16_t) * image.width, sizeof(uint16_t)};
180  break;
181  }
183  {
184  element_size = sizeof(uint8_t);
185  format = py::format_descriptor<uint8_t>::format();
186  shape.push_back(3);
187  strides = {sizeof(uint8_t) * image.width * 3, sizeof(uint8_t) * 3, sizeof(uint8_t)};
188  break;
189  }
191  {
192  element_size = sizeof(float);
193  format = py::format_descriptor<float>::format();
194  strides = {sizeof(float) * image.width, sizeof(float)};
195  break;
196  }
197  default: {throw std::runtime_error("Unknown pixel format");}
198  }
199 
200  // Map the cv::Mat to a NumPy array without copying the data
201  return py::array(py::buffer_info(
202  const_cast<uint8_t*>(image.raw_data->data() + image.image_data_offset),
203  element_size,
204  format,
205  shape.size(),
206  shape,
207  strides));
208  })
209  .def_readonly("format", &multisense::Image::format)
210  .def_readonly("width", &multisense::Image::width)
211  .def_readonly("height", &multisense::Image::height)
212  .def_readonly("camera_timestamp", &multisense::Image::camera_timestamp)
213  .def_readonly("ptp_timestamp", &multisense::Image::ptp_timestamp)
214  .def_readonly("source", &multisense::Image::source)
215  .def_readonly("calibration", &multisense::Image::calibration);
216 
217  // ImageFrame
218  py::class_<multisense::ImageFrame>(m, "ImageFrame")
219  .def(py::init<>())
220  .def("add_image", &multisense::ImageFrame::add_image)
221  .def("get_image", &multisense::ImageFrame::get_image)
222  .def("has_image", &multisense::ImageFrame::has_image)
223  .def_readonly("frame_id", &multisense::ImageFrame::frame_id)
224  .def_readonly("images", &multisense::ImageFrame::images)
225  .def_readonly("calibration", &multisense::ImageFrame::calibration)
226  .def_readonly("frame_time", &multisense::ImageFrame::frame_time)
227  .def_readonly("ptp_frame_time", &multisense::ImageFrame::ptp_frame_time)
228  .def_readonly("aux_color_encoding", &multisense::ImageFrame::aux_color_encoding);
229 
230  // ImuRate
231  py::class_<multisense::ImuRate>(m, "ImuRate")
232  .def(py::init<>())
234  .def(py::self == py::self)
235  .def_readwrite("sample_rate", &multisense::ImuRate::sample_rate)
236  .def_readwrite("bandwith_cutoff", &multisense::ImuRate::bandwith_cutoff);
237 
238  // ImuRange
239  py::class_<multisense::ImuRange>(m, "ImuRange")
240  .def(py::init<>())
242  .def(py::self == py::self)
243  .def_readwrite("range", &multisense::ImuRange::range)
244  .def_readwrite("resolution", &multisense::ImuRange::resolution);
245 
246 
247  // MultiSenseConfig::StereoCalibration
248  py::class_<multisense::MultiSenseConfig::StereoConfig>(m, "StereoConfig")
249  .def(py::init<>())
251  .def(py::self == py::self)
252  .def_readwrite("postfilter_strength", &multisense::MultiSenseConfig::StereoConfig::postfilter_strength);
253 
254  // MultiSenseConfig::ManualExposureConfig
255  py::class_<multisense::MultiSenseConfig::ManualExposureConfig>(m, "ManualExposureConfig")
256  .def(py::init<>())
258  .def(py::self == py::self)
261 
262  // MultiSenseConfig::AutoExposureRoiConfig
263  py::class_<multisense::MultiSenseConfig::AutoExposureRoiConfig>(m, "AutoExposureRoiConfig")
264  .def(py::init<>())
266  .def(py::self == py::self)
271 
272  // MultiSenseConfig::AutoExposureConfig
273  py::class_<multisense::MultiSenseConfig::AutoExposureConfig>(m, "AutoExposureConfig")
274  .def(py::init<>())
276  .def(py::self == py::self)
277  .def_readwrite("max_exposure_time", &multisense::MultiSenseConfig::AutoExposureConfig::max_exposure_time)
279  .def_readwrite("target_intensity", &multisense::MultiSenseConfig::AutoExposureConfig::target_intensity)
280  .def_readwrite("target_threshold", &multisense::MultiSenseConfig::AutoExposureConfig::target_threshold)
283 
284  // MultiSenseConfig::ManualWhiteBalanceConfig
285  py::class_<multisense::MultiSenseConfig::ManualWhiteBalanceConfig>(m, "ManualWhiteBalanceConfig")
286  .def(py::init<>())
288  .def(py::self == py::self)
291 
292  // MultiSenseConfig::AutoWhiteBalanceConfig
293  py::class_<multisense::MultiSenseConfig::AutoWhiteBalanceConfig>(m, "AutoWhiteBalanceConfig")
294  .def(py::init<>())
296  .def(py::self == py::self)
299 
300  // MultiSenseConfig::ImageConfig
301  py::class_<multisense::MultiSenseConfig::ImageConfig>(m, "ImageConfig")
302  .def(py::init<>())
304  .def(py::self == py::self)
305  .def_readwrite("gamma", &multisense::MultiSenseConfig::ImageConfig::gamma)
306  .def_readwrite("auto_exposure_enabled", &multisense::MultiSenseConfig::ImageConfig::auto_exposure_enabled)
307  .def_readwrite("manual_exposure", &multisense::MultiSenseConfig::ImageConfig::manual_exposure)
308  .def_readwrite("auto_exposure", &multisense::MultiSenseConfig::ImageConfig::auto_exposure)
309  .def_readwrite("auto_white_balance_enabled", &multisense::MultiSenseConfig::ImageConfig::auto_white_balance_enabled)
310  .def_readwrite("manual_white_balance", &multisense::MultiSenseConfig::ImageConfig::manual_white_balance)
311  .def_readwrite("auto_white_balance", &multisense::MultiSenseConfig::ImageConfig::auto_white_balance);
312 
313  // MultiSenseConfig::AuxConfig
314  py::class_<multisense::MultiSenseConfig::AuxConfig>(m, "AuxConfig")
315  .def(py::init<>())
317  .def(py::self == py::self)
318  .def_readwrite("image_config", &multisense::MultiSenseConfig::AuxConfig::image_config)
319  .def_readwrite("sharpening_enabled", &multisense::MultiSenseConfig::AuxConfig::sharpening_enabled)
320  .def_readwrite("sharpening_percentage", &multisense::MultiSenseConfig::AuxConfig::sharpening_percentage)
321  .def_readwrite("sharpening_limit", &multisense::MultiSenseConfig::AuxConfig::sharpening_limit);
322 
323  // MultiSenseConfig::MaxDisparities
324  py::enum_<multisense::MultiSenseConfig::MaxDisparities>(m, "MaxDisparities")
328 
329  // MultiSenseConfig::TimeConfig
330  py::class_<multisense::MultiSenseConfig::TimeConfig>(m, "TimeConfig")
331  .def(py::init<>())
333  .def(py::self == py::self)
334  .def_readwrite("ptp_enabled", &multisense::MultiSenseConfig::TimeConfig::ptp_enabled);
335 
336  // MultiSenseConfig::NetworkTransmissionConfig
337  py::class_<multisense::MultiSenseConfig::NetworkTransmissionConfig>(m, "NetworkTransmissionConfig")
338  .def(py::init<>())
340  .def(py::self == py::self)
342 
343  // MultiSenseConfig::ImuConfig::OperatingMode
344  py::class_<multisense::MultiSenseConfig::ImuConfig::OperatingMode>(m, "ImuOperatingMode")
345  .def(py::init<>())
347  .def(py::self == py::self)
351 
352  // MultiSenseConfig::ImuConfig
353  py::class_<multisense::MultiSenseConfig::ImuConfig>(m, "ImuConfig")
354  .def(py::init<>())
356  .def(py::self == py::self)
357  .def_readwrite("samples_per_frame", &multisense::MultiSenseConfig::ImuConfig::samples_per_frame)
358  .def_readwrite("accelerometer", &multisense::MultiSenseConfig::ImuConfig::accelerometer)
359  .def_readwrite("gyroscope", &multisense::MultiSenseConfig::ImuConfig::gyroscope)
360  .def_readwrite("magnetometer", &multisense::MultiSenseConfig::ImuConfig::magnetometer);
361 
362  // MultiSenseConfig::LightingConfig::ExternalConfig::FlashMode
363  py::enum_<multisense::MultiSenseConfig::LightingConfig::ExternalConfig::FlashMode>(m, "FlashMode")
367 
368  // MultiSenseConfig::LightingConfig::InternalConfig
369  py::class_<multisense::MultiSenseConfig::LightingConfig::InternalConfig>(m, "LightingConfigInternalConfig")
370  .def(py::init<>())
372  .def(py::self == py::self)
375 
376  // MultiSenseConfig::LightingConfig::ExternalConfig
377  py::class_<multisense::MultiSenseConfig::LightingConfig::ExternalConfig>(m, "LightingConfigExternalConfig")
378  .def(py::init<>())
380  .def(py::self == py::self)
385 
386  // MultiSenseConfig::LightingConfig
387  py::class_<multisense::MultiSenseConfig::LightingConfig>(m, "LightingConfig")
388  .def(py::init<>())
390  .def(py::self == py::self)
391  .def(py::self == py::self)
392  .def_readwrite("internal", &multisense::MultiSenseConfig::LightingConfig::internal)
393  .def_readwrite("external", &multisense::MultiSenseConfig::LightingConfig::external);
394 
395  // MultiSenseConfig
396  py::class_<multisense::MultiSenseConfig>(m, "MultiSenseConfig")
397  .def(py::init<>())
399  .def(py::self == py::self)
400  .def_readwrite("width", &multisense::MultiSenseConfig::width)
401  .def_readwrite("height", &multisense::MultiSenseConfig::height)
402  .def_readwrite("disparities", &multisense::MultiSenseConfig::disparities)
403  .def_readwrite("frames_per_second", &multisense::MultiSenseConfig::frames_per_second)
404  .def_readwrite("stereo_config", &multisense::MultiSenseConfig::stereo_config)
405  .def_readwrite("image_config", &multisense::MultiSenseConfig::image_config)
406  .def_readwrite("aux_config", &multisense::MultiSenseConfig::aux_config)
407  .def_readwrite("time_config", &multisense::MultiSenseConfig::time_config)
408  .def_readwrite("network_config", &multisense::MultiSenseConfig::network_config)
409  .def_readwrite("imu_config", &multisense::MultiSenseConfig::imu_config)
410  .def_readwrite("lighting_config", &multisense::MultiSenseConfig::lighting_config);
411 
412  // MultiSenseStatus::PtpStatus
413  py::class_<multisense::MultiSenseStatus::PtpStatus>(m, "PtpStatus")
414  .def(py::init<>())
416  .def_readwrite("grandmaster_present", &multisense::MultiSenseStatus::PtpStatus::grandmaster_present)
417  .def_readwrite("grandmaster_id", &multisense::MultiSenseStatus::PtpStatus::grandmaster_id)
418  .def_readwrite("grandmaster_offset", &multisense::MultiSenseStatus::PtpStatus::grandmaster_offset)
419  .def_readwrite("path_delay", &multisense::MultiSenseStatus::PtpStatus::path_delay)
420  .def_readwrite("steps_from_local_to_grandmaster", &multisense::MultiSenseStatus::PtpStatus::steps_from_local_to_grandmaster);
421 
422  // MultiSenseStatus::CameraStatus
423  py::class_<multisense::MultiSenseStatus::CameraStatus>(m, "CameraStatus")
424  .def(py::init<>())
426  .def_readwrite("cameras_ok", &multisense::MultiSenseStatus::CameraStatus::cameras_ok)
427  .def_readwrite("processing_pipeline_ok", &multisense::MultiSenseStatus::CameraStatus::processing_pipeline_ok);
428 
429  // MultiSenseStatus::TemperatureStatus
430  py::class_<multisense::MultiSenseStatus::TemperatureStatus>(m, "TemperatureStatus")
431  .def(py::init<>())
433  .def_readwrite("fpga_temperature", &multisense::MultiSenseStatus::TemperatureStatus::fpga_temperature)
434  .def_readwrite("left_imager_temperature", &multisense::MultiSenseStatus::TemperatureStatus::left_imager_temperature)
435  .def_readwrite("right_imager_temperature", &multisense::MultiSenseStatus::TemperatureStatus::right_imager_temperature)
436  .def_readwrite("power_supply_temperature", &multisense::MultiSenseStatus::TemperatureStatus::power_supply_temperature);
437 
438  // MultiSenseStatus::PowerStatus
439  py::class_<multisense::MultiSenseStatus::PowerStatus>(m, "PowerStatus")
440  .def(py::init<>())
442  .def_readwrite("input_voltage", &multisense::MultiSenseStatus::PowerStatus::input_voltage)
443  .def_readwrite("input_current", &multisense::MultiSenseStatus::PowerStatus::input_current)
444  .def_readwrite("fpga_power", &multisense::MultiSenseStatus::PowerStatus::fpga_power);
445 
446  // MultiSenseStatus::ClientNetworkStatus
447  py::class_<multisense::MultiSenseStatus::ClientNetworkStatus>(m, "ClientNetworkStatus")
448  .def(py::init<>())
452  .def_readwrite("invalid_packets", &multisense::MultiSenseStatus::ClientNetworkStatus::invalid_packets);
453 
454  // MultiSenseStatus::TimeStatus
455  py::class_<multisense::MultiSenseStatus::TimeStatus>(m, "TimeStatus")
456  .def(py::init<>())
458  .def_readwrite("camera_time", &multisense::MultiSenseStatus::TimeStatus::camera_time)
459  .def_readwrite("client_host_time", &multisense::MultiSenseStatus::TimeStatus::client_host_time)
460  .def_readwrite("network_delay", &multisense::MultiSenseStatus::TimeStatus::network_delay)
463 
464  // MultiSenseStatus
465  py::class_<multisense::MultiSenseStatus>(m, "MultiSenseStatus")
466  .def(py::init<>())
468  .def_readwrite("system_ok", &multisense::MultiSenseStatus::system_ok)
469  .def_readwrite("ptp", &multisense::MultiSenseStatus::ptp)
470  .def_readwrite("camera", &multisense::MultiSenseStatus::camera)
471  .def_readwrite("temperature", &multisense::MultiSenseStatus::temperature)
472  .def_readwrite("power", &multisense::MultiSenseStatus::power)
473  .def_readwrite("client_network", &multisense::MultiSenseStatus::client_network)
474  .def_readwrite("time", &multisense::MultiSenseStatus::time);
475 
476  // MultiSenseInfo::DeviceInfo::PcbInfo
477  py::class_<multisense::MultiSenseInfo::DeviceInfo::PcbInfo>(m, "PcbInfo")
478  .def(py::init<>())
482 
483  // MultiSenseInfo::DeviceInfo::HardwareRevision
484  py::enum_<multisense::MultiSenseInfo::DeviceInfo::HardwareRevision>(m, "HardwareRevision")
496 
497  // MultiSenseInfo::DeviceInfo::ImagerType
498  py::enum_<multisense::MultiSenseInfo::DeviceInfo::ImagerType>(m, "ImagerType")
507 
508  // MultiSenseInfo::DeviceInfo::LightingType
509  py::enum_<multisense::MultiSenseInfo::DeviceInfo::LightingType>(m, "LightingType")
516 
517  // MultiSenseInfo::DeviceInfo::LensType
518  py::enum_<multisense::MultiSenseInfo::MultiSenseInfo::DeviceInfo::LensType>(m, "LensType")
522 
523  // MultiSenseInfo::NetworkInfo
524  py::class_<multisense::MultiSenseInfo::MultiSenseInfo::NetworkInfo>(m, "NetworkInfo")
525  .def(py::init<>())
527  .def_readwrite("ip_address", &multisense::MultiSenseInfo::NetworkInfo::ip_address)
528  .def_readwrite("gateway", &multisense::MultiSenseInfo::NetworkInfo::gateway)
529  .def_readwrite("netmask", &multisense::MultiSenseInfo::NetworkInfo::netmask);
530 
531  // MultiSenseInfo::DeviceInfo
532  py::class_<multisense::MultiSenseInfo::DeviceInfo>(m, "DeviceInfo")
533  .def(py::init<>())
535  .def_readwrite("camera_name", &multisense::MultiSenseInfo::DeviceInfo::camera_name)
536  .def_readwrite("build_date", &multisense::MultiSenseInfo::DeviceInfo::build_date)
537  .def_readwrite("serial_number", &multisense::MultiSenseInfo::DeviceInfo::serial_number)
538  .def_readwrite("hardware_revision", &multisense::MultiSenseInfo::DeviceInfo::hardware_revision)
539  .def_readwrite("pcb_info", &multisense::MultiSenseInfo::DeviceInfo::pcb_info)
540  .def_readwrite("imager_name", &multisense::MultiSenseInfo::DeviceInfo::imager_name)
541  .def_readwrite("imager_type", &multisense::MultiSenseInfo::DeviceInfo::imager_type)
542  .def_readwrite("imager_width", &multisense::MultiSenseInfo::DeviceInfo::imager_width)
543  .def_readwrite("imager_height", &multisense::MultiSenseInfo::DeviceInfo::imager_height)
544  .def_readwrite("lens_name", &multisense::MultiSenseInfo::DeviceInfo::lens_name)
545  .def_readwrite("lens_type", &multisense::MultiSenseInfo::DeviceInfo::lens_type)
546  .def_readwrite("nominal_stereo_baseline", &multisense::MultiSenseInfo::DeviceInfo::nominal_stereo_baseline)
547  .def_readwrite("nominal_focal_length", &multisense::MultiSenseInfo::DeviceInfo::nominal_focal_length)
548  .def_readwrite("nominal_relative_aperture", &multisense::MultiSenseInfo::DeviceInfo::nominal_relative_aperture)
549  .def_readwrite("lighting_type", &multisense::MultiSenseInfo::DeviceInfo::lighting_type)
550  .def_readwrite("number_of_lights", &multisense::MultiSenseInfo::DeviceInfo::number_of_lights)
553 
554  // MultiSenseInfo::Version
555  py::class_<multisense::MultiSenseInfo::Version>(m, "Version")
556  .def(py::init<>())
558  .def("__lt__", &multisense::MultiSenseInfo::Version::operator<)
559  .def_readwrite("major", &multisense::MultiSenseInfo::Version::major)
560  .def_readwrite("minor", &multisense::MultiSenseInfo::Version::minor)
561  .def_readwrite("patch", &multisense::MultiSenseInfo::Version::patch)
563 
564  // MultiSenseInfo::SensorVersion
565  py::class_<multisense::MultiSenseInfo::MultiSenseInfo::SensorVersion>(m, "SensorVersion")
566  .def(py::init<>())
568  .def_readwrite("firmware_build_date", &multisense::MultiSenseInfo::SensorVersion::firmware_build_date)
569  .def_readwrite("firmware_version", &multisense::MultiSenseInfo::SensorVersion::firmware_version)
570  .def_readwrite("hardware_version", &multisense::MultiSenseInfo::SensorVersion::hardware_version);
571 
572  // MultiSenseInfo::SupportedOperatingMode
573  py::class_<multisense::MultiSenseInfo::SupportedOperatingMode>(m, "SupportedOperatingMode")
574  .def(py::init<>())
579  .def_readwrite("supported_sources", &multisense::MultiSenseInfo::SupportedOperatingMode::supported_sources);
580 
581  // MultiSenseInfo::ImuInfo::Source
582  py::class_<multisense::MultiSenseInfo::ImuInfo::Source>(m, "ImuSource")
583  .def(py::init<>())
586  .def_readwrite("device", &multisense::MultiSenseInfo::ImuInfo::Source::device)
588  .def_readwrite("ranges", &multisense::MultiSenseInfo::ImuInfo::Source::ranges);
589 
590  // MultiSenseInfo::ImuInfo
591  py::class_<multisense::MultiSenseInfo::ImuInfo>(m, "ImuInfo")
592  .def(py::init<>())
594  .def_readwrite("accelerometer", &multisense::MultiSenseInfo::ImuInfo::accelerometer)
595  .def_readwrite("gyroscope", &multisense::MultiSenseInfo::ImuInfo::gyroscope)
596  .def_readwrite("magnetometer", &multisense::MultiSenseInfo::ImuInfo::magnetometer);
597 
598 
599  // MultiSenseInfo
600  py::class_<multisense::MultiSenseInfo>(m, "MultiSenseInfo")
601  .def(py::init<>())
603  .def_readwrite("device", &multisense::MultiSenseInfo::device)
604  .def_readwrite("version", &multisense::MultiSenseInfo::version)
605  .def_readwrite("operating_modes", &multisense::MultiSenseInfo::operating_modes)
606  .def_readwrite("imu", &multisense::MultiSenseInfo::imu)
607  .def_readwrite("network", &multisense::MultiSenseInfo::network);
608 
609  // ChannelImplementation
610  py::enum_<multisense::Channel::ChannelImplementation>(m, "ChannelImplementation")
612 
613  // Channel::ReceiveBufferConfig
614  py::class_<multisense::Channel::ReceiveBufferConfig>(m, "ReceiveBufferConfig")
615  .def(py::init<>())
617  .def_readwrite("num_small_buffers", &multisense::Channel::ReceiveBufferConfig::num_small_buffers)
618  .def_readwrite("small_buffer_size", &multisense::Channel::ReceiveBufferConfig::small_buffer_size)
619  .def_readwrite("num_large_buffers", &multisense::Channel::ReceiveBufferConfig::num_large_buffers)
620  .def_readwrite("large_buffer_size", &multisense::Channel::ReceiveBufferConfig::large_buffer_size);
621 
622  // Channel::ChannelConfig
623  py::class_<multisense::Channel::Config>(m, "ChannelConfig")
624  .def(py::init<>())
626  .def_readwrite("ip_address", &multisense::Channel::Config::ip_address)
627  .def_readwrite("mtu", &multisense::Channel::Config::mtu)
628  .def_readwrite("receive_timeout", &multisense::Channel::Config::receive_timeout)
629  .def_readwrite("command_port", &multisense::Channel::Config::command_port)
630  .def_readwrite("interface", &multisense::Channel::Config::interface)
631  .def_readwrite("receive_buffer_configuration", &multisense::Channel::Config::receive_buffer_configuration)
632  .def_readwrite("connect_on_initialization", &multisense::Channel::Config::connect_on_initialization);
633 
634  // Channel
635  py::class_<multisense::Channel, std::unique_ptr<multisense::Channel>>(m, "Channel")
636  .def_static("create", &multisense::Channel::create, py::return_value_policy::move,
637  py::arg("config"),
639  .def("__enter__", [](multisense::Channel &self) -> multisense::Channel &
640  {
641  return self;
642  })
643  .def("__exit__", [](multisense::Channel &, py::object, py::object, py::object)
644  {
645  return false;
646  })
647  .def("start_streams", &multisense::Channel::start_streams, py::call_guard<py::gil_scoped_release>())
648  .def("stop_streams", &multisense::Channel::stop_streams, py::call_guard<py::gil_scoped_release>())
649  .def("add_image_frame_callback", &multisense::Channel::add_image_frame_callback, py::call_guard<py::gil_scoped_acquire>())
650  .def("add_imu_frame_callback", &multisense::Channel::add_imu_frame_callback, py::call_guard<py::gil_scoped_acquire>())
651  .def("connect", &multisense::Channel::connect)
652  .def("disconnect", &multisense::Channel::disconnect)
653  .def("get_next_image_frame", &multisense::Channel::get_next_image_frame, py::call_guard<py::gil_scoped_release>())
654  .def("get_config", &multisense::Channel::get_config, py::call_guard<py::gil_scoped_release>())
655  .def("set_config", &multisense::Channel::set_config, py::call_guard<py::gil_scoped_release>())
656  .def("get_calibration", &multisense::Channel::get_calibration, py::call_guard<py::gil_scoped_release>())
657  .def("set_calibration", &multisense::Channel::set_calibration, py::call_guard<py::gil_scoped_release>())
658  .def("get_info", &multisense::Channel::get_info, py::call_guard<py::gil_scoped_release>())
659  .def("set_device_info", &multisense::Channel::set_device_info, py::call_guard<py::gil_scoped_release>())
660  .def("get_system_status", &multisense::Channel::get_system_status, py::call_guard<py::gil_scoped_release>())
661  .def("set_network_config", &multisense::Channel::set_network_config, py::call_guard<py::gil_scoped_release>());
662 
663  // Utilities
664  py::class_<multisense::Point<void>>(m, "Point")
665  .def(py::init<>())
666  .def_readwrite("x", &multisense::Point<void>::x)
667  .def_readwrite("y", &multisense::Point<void>::y)
668  .def_readwrite("z", &multisense::Point<void>::z);
669 
670  py::class_<multisense::Point<uint8_t>>(m, "PointLuma8")
671  .def(py::init<>())
672  .def_readwrite("x", &multisense::Point<uint8_t>::x)
673  .def_readwrite("y", &multisense::Point<uint8_t>::y)
674  .def_readwrite("z", &multisense::Point<uint8_t>::z)
675  .def_readwrite("color", &multisense::Point<uint8_t>::color);
676 
677  py::class_<multisense::Point<uint16_t>>(m, "PointLuma16")
678  .def(py::init<>())
679  .def_readwrite("x", &multisense::Point<uint16_t>::x)
680  .def_readwrite("y", &multisense::Point<uint16_t>::y)
681  .def_readwrite("z", &multisense::Point<uint16_t>::z)
682  .def_readwrite("color", &multisense::Point<uint16_t>::color);
683 
684  py::class_<multisense::Point<std::array<uint8_t, 3>>>(m, "PointBGR")
685  .def(py::init<>())
686  .def_readwrite("x", &multisense::Point<std::array<uint8_t, 3>>::x)
687  .def_readwrite("y", &multisense::Point<std::array<uint8_t, 3>>::y)
688  .def_readwrite("z", &multisense::Point<std::array<uint8_t, 3>>::z)
689  .def_readwrite("color", &multisense::Point<std::array<uint8_t, 3>>::color);
690 
691  py::class_<multisense::PointCloud<void>>(m, "PointCloud")
692  .def(py::init<>())
693  .def_readwrite("cloud", &multisense::PointCloud<void>::cloud)
694  .def_property_readonly("as_array", [](const multisense::PointCloud<void> &cloud)
695  {
696  const std::vector<size_t> shape = {static_cast<size_t>(cloud.cloud.size()), 3};
697  const std::vector<size_t> strides = {sizeof(multisense::Point<void>), sizeof(float)};
698  const size_t element_size = sizeof(float);
699  const std::string format = py::format_descriptor<float>::format();;
700 
701  return py::array(py::buffer_info(
702  const_cast<uint8_t*>(reinterpret_cast<const uint8_t*>(cloud.cloud.data())),
703  element_size,
704  format,
705  shape.size(),
706  shape,
707  strides));
708  });
709 
710  py::class_<multisense::PointCloud<uint8_t>>(m, "PointCloudLuma8")
711  .def(py::init<>())
712  .def_readwrite("cloud", &multisense::PointCloud<uint8_t>::cloud)
713  .def_property_readonly("as_array", [](const multisense::PointCloud<uint8_t> &cloud)
714  {
715  const std::vector<size_t> shape = {static_cast<size_t>(cloud.cloud.size()), 3};
716  //
717  // Make sure we skip over the color
718  //
719  const std::vector<size_t> strides = {sizeof(multisense::Point<uint8_t>), sizeof(float)};
720  const size_t element_size = sizeof(multisense::Point<uint8_t>);
721  const std::string format = py::format_descriptor<float>::format();;
722 
723  return py::array(py::buffer_info(
724  const_cast<uint8_t*>(reinterpret_cast<const uint8_t*>(cloud.cloud.data())),
725  element_size,
726  format,
727  2,
728  shape,
729  strides));
730  })
731  .def_property_readonly("as_raw_array", [](const multisense::PointCloud<uint8_t> &cloud)
732  {
733  const std::vector<size_t> shape = {static_cast<size_t>(cloud.cloud.size())};
734  const std::vector<size_t> strides = {sizeof(multisense::Point<uint8_t>)};
735  const size_t element_size = sizeof(multisense::Point<uint8_t>);
736 
737  return py::array(py::buffer_info(
738  const_cast<uint8_t*>(reinterpret_cast<const uint8_t*>(cloud.cloud.data())),
739  element_size,
740  "13B",
741  1,
742  shape,
743  strides));
744  });
745 
746 
747  py::class_<multisense::PointCloud<uint16_t>>(m, "PointCloudLuma16")
748  .def(py::init<>())
749  .def_readwrite("cloud", &multisense::PointCloud<uint16_t>::cloud)
750  .def_property_readonly("as_array", [](const multisense::PointCloud<uint16_t> &cloud)
751  {
752  const std::vector<size_t> shape = {static_cast<size_t>(cloud.cloud.size()), 3};
753  //
754  // Make sure we skip over the color
755  //
756  const std::vector<size_t> strides = {sizeof(multisense::Point<uint16_t>), sizeof(float)};
757  const size_t element_size = sizeof(multisense::Point<uint16_t>);
758  const std::string format = py::format_descriptor<float>::format();;
759 
760  return py::array(py::buffer_info(
761  const_cast<uint8_t*>(reinterpret_cast<const uint8_t*>(cloud.cloud.data())),
762  element_size,
763  format,
764  2,
765  shape,
766  strides));
767  })
768  .def_property_readonly("as_raw_array", [](const multisense::PointCloud<uint16_t> &cloud)
769  {
770  const std::vector<size_t> shape = {static_cast<size_t>(cloud.cloud.size())};
771  const std::vector<size_t> strides = {sizeof(multisense::Point<uint16_t>)};
772  const size_t element_size = sizeof(multisense::Point<uint16_t>);
773 
774  return py::array(py::buffer_info(
775  const_cast<uint8_t*>(reinterpret_cast<const uint8_t*>(cloud.cloud.data())),
776  element_size,
777  "14B",
778  1,
779  shape,
780  strides));
781  });
782 
783  py::class_<multisense::PointCloud<std::array<uint8_t, 3>>>(m, "PointCloudBGR")
784  .def(py::init<>())
785  .def_readwrite("cloud", &multisense::PointCloud<std::array<uint8_t, 3>>::cloud)
786  .def_property_readonly("as_array", [](const multisense::PointCloud<std::array<uint8_t, 3>> &cloud)
787  {
788  const std::vector<size_t> shape = {static_cast<size_t>(cloud.cloud.size()), 3};
789  //
790  // Make sure we skip over the color
791  //
792  const std::vector<size_t> strides = {sizeof(multisense::Point<std::array<uint8_t, 3>>), sizeof(float)};
793  const size_t element_size = sizeof(multisense::Point<std::array<uint8_t, 3>>);
794  const std::string format = py::format_descriptor<float>::format();;
795 
796  return py::array(py::buffer_info(
797  const_cast<uint8_t*>(reinterpret_cast<const uint8_t*>(cloud.cloud.data())),
798  element_size,
799  format,
800  2,
801  shape,
802  strides));
803  })
804  .def_property_readonly("as_raw_array", [](const multisense::PointCloud<std::array<uint8_t, 3>> &cloud)
805  {
806  const std::vector<size_t> shape = {static_cast<size_t>(cloud.cloud.size())};
807  const std::vector<size_t> strides = {sizeof(multisense::Point<std::array<uint8_t, 3>>)};
808  const size_t element_size = sizeof(multisense::Point<std::array<uint8_t, 3>>);
809 
810  return py::array(py::buffer_info(
811  const_cast<uint8_t*>(reinterpret_cast<const uint8_t*>(cloud.cloud.data())),
812  element_size,
813  "15B",
814  1,
815  shape,
816  strides));
817  });
818 
819 
820  m.def("to_string", &multisense::to_string, py::call_guard<py::gil_scoped_release>());
821 
822  m.def("write_image",
823  [](const multisense::Image &image, const std::string &path)
824  {
825  py::gil_scoped_release release;
826  return multisense::write_image(image, std::filesystem::path{path});
827  }
828  );
829 
830  m.def("write_pointcloud_ply",
831  [](const multisense::PointCloud<void> &pointcloud, const std::string &path)
832  {
833  py::gil_scoped_release release;
834  return multisense::write_pointcloud_ply(pointcloud, std::filesystem::path{path});
835  }
836  );
837 
838  m.def("write_pointcloud_ply",
839  [](const multisense::PointCloud<uint8_t> &pointcloud, const std::string &path)
840  {
841  py::gil_scoped_release release;
842  return multisense::write_pointcloud_ply(pointcloud, std::filesystem::path{path});
843  }
844  );
845 
846  m.def("write_pointcloud_ply",
847  [](const multisense::PointCloud<uint16_t> &pointcloud, const std::string &path)
848  {
849  py::gil_scoped_release release;
850  return multisense::write_pointcloud_ply(pointcloud, std::filesystem::path{path});
851  }
852  );
853 
854  m.def("write_pointcloud_ply",
855  [](const multisense::PointCloud<std::array<uint8_t, 3>> &pointcloud, const std::string &path)
856  {
857  py::gil_scoped_release release;
858  return multisense::write_pointcloud_ply(pointcloud, std::filesystem::path{path});
859  }
860  );
861 
862  m.def("create_pointcloud", &multisense::create_pointcloud, py::call_guard<py::gil_scoped_release>());
863 
864  //
865  // Handle creation of colorized pointclouds with either just an ImageFrame, or the explicit disparity
866  // and color images
867  //
868  m.def("create_gray8_pointcloud",
869  static_cast<std::optional<multisense::PointCloud<uint8_t>>(*)(const multisense::ImageFrame&,
870  double,
871  const multisense::DataSource&,
872  const multisense::DataSource&)>(
873  &multisense::create_color_pointcloud<uint8_t>),
874  py::call_guard<py::gil_scoped_release>());
875  m.def("create_gray8_pointcloud",
876  static_cast<std::optional<multisense::PointCloud<uint8_t>>(*)(const multisense::Image&,
877  const std::optional<multisense::Image>&,
878  double,
880  &multisense::create_color_pointcloud<uint8_t>),
881  py::call_guard<py::gil_scoped_release>());
882 
883  m.def("create_gray16_pointcloud",
884  static_cast<std::optional<multisense::PointCloud<uint16_t>>(*)(const multisense::ImageFrame&,
885  double,
886  const multisense::DataSource&,
887  const multisense::DataSource&)>(
888  &multisense::create_color_pointcloud<uint16_t>),
889  py::call_guard<py::gil_scoped_release>());
890  m.def("create_gray16_pointcloud",
891  static_cast<std::optional<multisense::PointCloud<uint16_t>>(*)(const multisense::Image&,
892  const std::optional<multisense::Image>&,
893  double,
895  &multisense::create_color_pointcloud<uint16_t>),
896  py::call_guard<py::gil_scoped_release>());
897 
898  m.def("create_bgr_pointcloud",
899  static_cast<std::optional<multisense::PointCloud<std::array<uint8_t, 3>>>(*)(const multisense::ImageFrame&,
900  double,
901  const multisense::DataSource&,
902  const multisense::DataSource&)>(
903  &multisense::create_color_pointcloud<std::array<uint8_t, 3>>),
904  py::call_guard<py::gil_scoped_release>());
905  m.def("create_bgr_pointcloud",
906  static_cast<std::optional<multisense::PointCloud<std::array<uint8_t, 3>>>(*)(const multisense::Image&,
907  const std::optional<multisense::Image>&,
908  double,
910  &multisense::create_color_pointcloud<std::array<uint8_t, 3>>),
911  py::call_guard<py::gil_scoped_release>());
912 
913  m.def("create_depth_image", &multisense::create_depth_image, py::call_guard<py::gil_scoped_release>());
914 
915  m.def("create_bgr_from_ycbcr420", &multisense::create_bgr_from_ycbcr420, py::call_guard<py::gil_scoped_release>());
916 
917  m.def("create_bgr_image", &multisense::create_bgr_image, py::call_guard<py::gil_scoped_release>());
918 }
multisense::MultiSenseInfo::version
SensorVersion version
Sensor Version info.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1645
multisense::MultiSenseInfo::DeviceInfo::has_aux_camera
constexpr bool has_aux_camera() const
Determine if the MultiSense has a Aux color camera.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1473
multisense::DataSource::RIGHT_RECTIFIED_COMPRESSED
@ RIGHT_RECTIFIED_COMPRESSED
multisense::MultiSenseStatus::TemperatureStatus::power_supply_temperature
float power_supply_temperature
Temperature of the internal switching power supply in Celsius.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1146
multisense::MultiSenseConfig::AutoExposureConfig::target_threshold
float target_threshold
The fraction of pixels which must be equal or below the pixel value set by the target intensity pixel...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:595
multisense::Status::INCOMPLETE_APPLICATION
@ INCOMPLETE_APPLICATION
multisense::MultiSenseStatus::PtpStatus
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1084
multisense::DataSource::RIGHT_MONO_COMPRESSED
@ RIGHT_MONO_COMPRESSED
multisense::MultiSenseStatus::camera
CameraStatus camera
The current camera status.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1236
multisense::CameraCalibration::R
std::array< std::array< float, 3 >, 3 > R
Rotation matrix which takes points in the unrectified camera frame and transform them in to the recti...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:136
multisense::create_bgr_image
std::optional< Image > create_bgr_image(const ImageFrame &frame, const DataSource &output_source)
Convert a YCbCr420 luma + chroma image into a BGR color image.
Definition: utilities.cc:340
multisense::MultiSenseStatus::temperature
std::optional< TemperatureStatus > temperature
The current temperature status.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1241
multisense::MultiSenseInfo::DeviceInfo::nominal_stereo_baseline
float nominal_stereo_baseline
The nominal stereo baseline in meters.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1448
multisense::MultiSenseConfig::LightingConfig::ExternalConfig
Lighting config for lights driven by GPIO outputs from the MultiSense.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:931
multisense::MultiSenseInfo::DeviceInfo::number_of_lights
uint32_t number_of_lights
The number of lights the MultiSense controls.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1468
multisense::Image::camera_timestamp
TimeT camera_timestamp
The timestamp associated with the image based on the camera's clock. Starts at 0 on boot.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:237
multisense::Channel::add_image_frame_callback
virtual void add_image_frame_callback(std::function< void(const ImageFrame &)> callback)=0
Setup user callback that will be invoked whenever a new image frame is received.
multisense::MultiSenseInfo::NetworkInfo
The network configuration for the MultiSense.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1267
multisense::Status::UNKNOWN
@ UNKNOWN
multisense::MultiSenseInfo::DeviceInfo::lens_type
LensType lens_type
The type of the primary imager.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1443
multisense::MultiSenseConfig
Complete configuration object for configuring the MultiSense. Can be updated during camera operation.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:478
multisense::Image::height
int height
Height of the image in pixels.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:231
multisense::MultiSenseInfo::SupportedOperatingMode::height
uint32_t height
The height of the output image in pixels.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1577
multisense::MultiSenseInfo::DeviceInfo::LensType::STANDARD
@ STANDARD
multisense::MultiSenseConfig::height
uint32_t height
The operating height of the MultiSense in pixels. For available operating resolutions see the MultiSe...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1011
multisense::MultiSenseConfig::ImageConfig::auto_white_balance_enabled
bool auto_white_balance_enabled
Enable or disable auto white balance.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:704
multisense::MultiSenseConfig::image_config
ImageConfig image_config
The image configuration to use for the main stereo pair.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1031
multisense::MultiSenseConfig::ManualWhiteBalanceConfig
Manual white balance specific configuration.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:626
multisense::MultiSenseInfo::DeviceInfo::HardwareRevision::MONOCAM
@ MONOCAM
multisense::MultiSenseInfo::DeviceInfo::camera_name
std::string camera_name
The name of the MultiSense variant. This value can store at most 32 characters.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1387
multisense::ImageFrame::frame_time
TimeT frame_time
The MultiSense timestamp associated with the frame.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:349
multisense::MultiSenseInfo::DeviceInfo::LightingType::INTERNAL
@ INTERNAL
Lights driven internally.
multisense::Point
Single point definition with a custom color type.
Definition: MultiSenseUtilities.hh:60
multisense::StereoCalibration::left
CameraCalibration left
Calibration information for the left camera.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:171
multisense::DataSource::AUX_RECTIFIED_RAW
@ AUX_RECTIFIED_RAW
multisense::MultiSenseConfig::LightingConfig::ExternalConfig::FlashMode::NONE
@ NONE
multisense::MultiSenseConfig::ImuConfig::samples_per_frame
uint32_t samples_per_frame
The number of IMU samples which should be included in a IMU frame.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:870
multisense::MultiSenseInfo::DeviceInfo::LightingType::OUTPUT_TRIGGER
@ OUTPUT_TRIGGER
A GPIO line is used to trigger an external light.
multisense::StereoCalibration
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:166
multisense::Status::UNINITIALIZED
@ UNINITIALIZED
multisense::MultiSenseInfo::DeviceInfo::HardwareRevision::ST25
@ ST25
multisense::PointCloud
Definition: MultiSenseUtilities.hh:80
multisense::MultiSenseInfo::ImuInfo::Source::ranges
std::vector< ImuRange > ranges
The available ranges supported by this operating mode.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1618
multisense::StereoCalibration::aux
std::optional< CameraCalibration > aux
Calibration information for the aux camera (optional 3rd center camera)
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:181
multisense::MultiSenseStatus::PowerStatus::input_voltage
float input_voltage
The current input voltage in volts.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1154
multisense::MultiSenseConfig::AuxConfig
Image specific configuration for the Aux imager.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:734
multisense::Image::ptp_timestamp
TimeT ptp_timestamp
The timestamp associated with the image based using the camera's clock which is potentially PTP synch...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:243
multisense::MultiSenseInfo::DeviceInfo::imager_width
uint32_t imager_width
The native width of the primary imager.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1426
multisense::MultiSenseInfo::DeviceInfo::imager_type
ImagerType imager_type
The type of the imager.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1421
multisense::MultiSenseInfo::DeviceInfo::LensType::UNKNOWN
@ UNKNOWN
multisense::MultiSenseConfig::LightingConfig::ExternalConfig::pulses_per_exposure
uint32_t pulses_per_exposure
The number of pulses of the light per single exposure. This is used to trigger the light or output si...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:960
multisense::ImageFrame::get_image
const Image & get_image(const DataSource &source) const
Retrieve image by DataSource. Throws if not found.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:313
multisense::MultiSenseInfo::DeviceInfo::imager_height
uint32_t imager_height
The native height of the primary imager.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1431
multisense::MultiSenseConfig::ManualExposureConfig::exposure_time
std::chrono::microseconds exposure_time
The manual exposure time in microseconds Valid range is [0, 33000].
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:516
multisense::MultiSenseConfig::ImuConfig
Config for the IMU sensor.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:834
multisense::MultiSenseInfo::ImuInfo::gyroscope
std::optional< Source > gyroscope
Configuration specific to the gyroscope.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1629
multisense::MultiSenseInfo::Version::to_string
std::string to_string() const
Convert a Version info to string for convenience.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1527
multisense::Channel::ReceiveBufferConfig::large_buffer_size
size_t large_buffer_size
The size of each small buffer in bytes.
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:82
multisense::MultiSenseStatus::ptp
std::optional< PtpStatus > ptp
The current ptp status. Only valid if ptp is enabled.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1231
multisense::MultiSenseInfo::DeviceInfo::serial_number
std::string serial_number
The unique serial number of the MultiSense This value can store at most 32 characters.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1399
multisense::MultiSenseConfig::AuxConfig::image_config
ImageConfig image_config
Image configuration for the Aux imager.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:739
multisense::ImageFrame
A frame containing multiple images (indexed by DataSource).
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:300
multisense::MultiSenseStatus::TemperatureStatus::fpga_temperature
float fpga_temperature
Temperature of the FPGA in Celsius.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1131
MultiSenseUtilities.hh
multisense::MultiSenseConfig::LightingConfig::InternalConfig::flash
bool flash
Enable flashing of the light.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:917
multisense::MultiSenseConfig::LightingConfig::ExternalConfig::startup_time
std::chrono::microseconds startup_time
The time it takes for the light to reach full brightness. This will be used to ensure the light is at...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:966
multisense::DataSource::AUX_COMPRESSED
@ AUX_COMPRESSED
multisense::ImageFrame::ptp_frame_time
TimeT ptp_frame_time
The MultiSense ptp timestamp associated with the frame.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:354
multisense::ImageFrame::has_image
bool has_image(const DataSource &source) const
Check if we have an image for a given data source.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:326
multisense::MultiSenseInfo::DeviceInfo::HardwareRevision::UNKNOWN
@ UNKNOWN
multisense::MultiSenseConfig::LightingConfig::ExternalConfig::FlashMode::SYNC_WITH_MAIN_STEREO
@ SYNC_WITH_MAIN_STEREO
multisense::MultiSenseConfig::ImageConfig::auto_exposure_enabled
bool auto_exposure_enabled
Enable or disable auto exposure.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:689
multisense::MultiSenseInfo::ImuInfo::Source
Info about the available IMU configurations.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1598
multisense::Channel::Config::connect_on_initialization
bool connect_on_initialization
Connect to the camera when the Channel is initialized.
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:125
multisense::Image::PixelFormat::UNKNOWN
@ UNKNOWN
multisense::MultiSenseConfig::AutoWhiteBalanceConfig
Auto white balance specific configuration.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:652
multisense::MultiSenseConfig::AutoExposureConfig::target_intensity
float target_intensity
The auto-exposure algorithm in digital imaging endeavors to achieve a specified target intensity,...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:589
multisense::MultiSenseConfig::LightingConfig::InternalConfig
Lighting config for lights integrated into the MultiSense.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:907
multisense::Channel::Config::mtu
std::optional< int16_t > mtu
The MTU to use for sending and receiving data from the camera. Setting the MTU to nullopt will trigge...
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:97
multisense::Image::PixelFormat::MONO8
@ MONO8
multisense::MultiSenseStatus::PtpStatus::grandmaster_present
bool grandmaster_present
Status of the grandmaster clock. true if synchronized to a non-local grandmaster OR if a non-local gr...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1090
multisense::MultiSenseInfo::DeviceInfo::LightingType::PATTERN_PROJECTOR_OUTPUT_TRIGGER
@ PATTERN_PROJECTOR_OUTPUT_TRIGGER
A pattern projector with a GPIO line used to trigger a external light.
multisense::MultiSenseConfig::LightingConfig::ExternalConfig::flash
FlashMode flash
Configure flash mode.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:951
multisense::ImuRate::bandwith_cutoff
float bandwith_cutoff
The bandwith cutoff for a given IMU mode in Hz.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:439
multisense::Channel::connect
virtual Status connect(const Config &config)=0
Initialize the connection to the camera.
multisense::CameraCalibration::P
std::array< std::array< float, 4 >, 3 > P
Rectified projection matrix which takes points in the origin camera coordinate frame and projects the...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:142
multisense::MultiSenseInfo::DeviceInfo::LensType::FISHEYE
@ FISHEYE
multisense::Channel::Config::interface
std::optional< std::string > interface
An optional name of network interface to bind to. (i.e. eth0)
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:114
multisense::MultiSenseConfig::LightingConfig::external
std::optional< ExternalConfig > external
The external lighting config. Will be nullopt if the camera does not support internal lighting contro...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:990
multisense::MultiSenseInfo::DeviceInfo::HardwareRevision::S30
@ S30
multisense::MultiSenseInfo::ImuInfo::Source::name
std::string name
The name of the IMU sensor.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1603
multisense::Channel::set_calibration
virtual Status set_calibration(const StereoCalibration &calibration)=0
Set the current stereo calibration. The calibration is expected to be or the full-resolution operatin...
multisense::ImuRate::sample_rate
float sample_rate
The sample rate for the sensor in Hz.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:434
multisense::CameraCalibration::K
std::array< std::array< float, 3 >, 3 > K
Unrectified camera projection matrix stored in row-major ordering.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:130
multisense::DataSource::LEFT_RECTIFIED_RAW
@ LEFT_RECTIFIED_RAW
multisense::MultiSenseInfo::DeviceInfo::ImagerType::UNKNOWN
@ UNKNOWN
multisense::MultiSenseInfo::DeviceInfo::LightingType::PATTERN_PROJECTOR
@ PATTERN_PROJECTOR
A pattern projector.
multisense::DataSource::AUX_LUMA_RAW
@ AUX_LUMA_RAW
multisense::MultiSenseStatus::TemperatureStatus
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1126
multisense::DataSource::LEFT_DISPARITY_COMPRESSED
@ LEFT_DISPARITY_COMPRESSED
multisense::DataSource::AUX_LUMA_RECTIFIED_RAW
@ AUX_LUMA_RECTIFIED_RAW
multisense::DataSource::RIGHT_MONO_RAW
@ RIGHT_MONO_RAW
multisense::DataSource::LEFT_MONO_RAW
@ LEFT_MONO_RAW
multisense::MultiSenseConfig::AutoExposureRoiConfig
Auto-exposure Region-of-Interest (ROI) specific configuration.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:530
multisense::MultiSenseConfig::ManualWhiteBalanceConfig::blue
float blue
The manual blue white-balance setting Valid range is [0.25, 4].
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:638
multisense::MultiSenseConfig::ImuConfig::gyroscope
std::optional< OperatingMode > gyroscope
Configuration for the onboard gyroscope.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:880
multisense::MultiSenseConfig::time_config
std::optional< TimeConfig > time_config
Config for the MultiSense time-sync options.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1041
multisense::MultiSenseConfig::stereo_config
StereoConfig stereo_config
The stereo configuration to use.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1026
multisense::MultiSenseConfig::ImageConfig::auto_white_balance
std::optional< AutoWhiteBalanceConfig > auto_white_balance
The white balance parameters to use if auto white balance is enabled.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:714
multisense::ImuRange
The range for each sensor along with the corresponding sampling resolution.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:453
multisense::CameraCalibration::D
std::vector< float > D
Coefficients for the distortion model.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:152
multisense::Channel::get_config
virtual MultiSenseConfig get_config()=0
Get the current MultiSense configuration.
multisense::MultiSenseStatus::PtpStatus::steps_from_local_to_grandmaster
uint16_t steps_from_local_to_grandmaster
The number of network hops from the grandmaster to the camera's clock.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1110
multisense::MultiSenseConfig::AutoExposureConfig
Auto-exposure specific configuration.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:566
multisense::Channel::Config
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:85
multisense::MultiSenseInfo::DeviceInfo::imager_name
std::string imager_name
The name of the imager used by the primary camera. For stereo cameras this is the Left/Right stereo p...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1416
multisense::MultiSenseConfig::AutoExposureConfig::roi
AutoExposureRoiConfig roi
The auto exposure region-of-interest used to restrict the portion of the image which the auto exposur...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:607
multisense::MultiSenseInfo::DeviceInfo::has_main_stereo_color
constexpr bool has_main_stereo_color() const
Determine if the MultiSense's main stereo pair supports color.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1489
multisense::MultiSenseConfig::NetworkTransmissionConfig::packet_delay_enabled
bool packet_delay_enabled
Add a small delay between the transmission of each packet to hopefully interact better with slower cl...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:820
multisense::Channel::Config::command_port
uint16_t command_port
The UDP port on the MultiSense which accepts user commands. All production firmware builds use port 9...
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:109
multisense::Image::PixelFormat::JPEG
@ JPEG
multisense::MultiSenseInfo::NetworkInfo::gateway
std::string gateway
The gateway of the camera (i.e. X.X.X.X)
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1277
multisense::Image::calibration
CameraCalibration calibration
The scaled calibration associated with the image.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:253
multisense::CameraCalibration::DistortionType::RATIONAL_POLYNOMIAL
@ RATIONAL_POLYNOMIAL
multisense::MultiSenseConfig::StereoConfig
Stereo specific configuration.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:483
multisense::MultiSenseStatus::ClientNetworkStatus
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1167
multisense::MultiSenseInfo::DeviceInfo::ImagerType::FLIR_TAU2
@ FLIR_TAU2
multisense::DataSource
DataSource
Identifies which camera or data source the image is from.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:83
multisense::MultiSenseConfig::ImuConfig::magnetometer
std::optional< OperatingMode > magnetometer
Configuration for the onboard magnetometer.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:885
multisense::Image::source
DataSource source
The camera data source which this image corresponds to.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:248
multisense::MultiSenseConfig::ImageConfig
Image specific configuration.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:678
multisense::MultiSenseConfig::AutoExposureConfig::max_exposure_time
std::chrono::microseconds max_exposure_time
The max exposure time auto exposure algorithm can set in microseconds Valid range is [0,...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:572
multisense::MultiSenseConfig::ImuConfig::OperatingMode
Config for a specific IMU operating mode. There are separate modes for each of the IMU sensors (i....
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:840
multisense::create_depth_image
std::optional< Image > create_depth_image(const ImageFrame &frame, const Image::PixelFormat &depth_format, const DataSource &disparity_source, float invalid_value)
Create a depth image from a image frame.
Definition: utilities.cc:191
multisense::MultiSenseConfig::ImageConfig::auto_exposure
std::optional< AutoExposureConfig > auto_exposure
The exposure config to use if auto exposure is enabled.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:699
multisense::MultiSenseStatus::PtpStatus::path_delay
std::chrono::nanoseconds path_delay
The estimate delay of the PTP synchronization messages from the grandmaster.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1105
multisense::Image::raw_data
std::shared_ptr< const std::vector< uint8_t > > raw_data
A pointer to the raw image data sent from the camera.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:206
multisense::Channel::set_device_info
virtual Status set_device_info(const MultiSenseInfo::DeviceInfo &device_info, const std::string &key)=0
Set the camera's device info. This setting is protected via a key since invalid values in the device ...
multisense::Channel::get_calibration
virtual StereoCalibration get_calibration()=0
Get the current stereo calibration. The output calibration will correspond to the full-resolution ope...
multisense::ImageFrame::calibration
StereoCalibration calibration
The scaled calibration for the entire camera.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:344
multisense::MultiSenseInfo::DeviceInfo::PcbInfo::revision
uint32_t revision
The revision number of the PCB.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1304
multisense::DataSource::ALL
@ ALL
multisense::MultiSenseConfig::MaxDisparities::D256
@ D256
256 pixels
multisense::MultiSenseInfo::DeviceInfo::HardwareRevision::KS21i
@ KS21i
multisense::ImageFrame::images
std::map< DataSource, Image > images
The images associated with each source in the frame.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:339
multisense::MultiSenseInfo::ImuInfo::magnetometer
std::optional< Source > magnetometer
Configuration specific to the magnetometer.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1634
multisense::MultiSenseInfo::ImuInfo::accelerometer
std::optional< Source > accelerometer
Configuration specific to the accelerometer.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1624
multisense::MultiSenseInfo::DeviceInfo::ImagerType::AR0234_GREY
@ AR0234_GREY
multisense::create_color_pointcloud
MULTISENSE_API std::optional< PointCloud< Color > > create_color_pointcloud(const Image &disparity, const std::optional< Image > &color, double max_range, const StereoCalibration &calibration)
Create a point cloud from a image frame and a color source.
Definition: MultiSenseUtilities.hh:126
multisense::Channel::start_streams
virtual Status start_streams(const std::vector< DataSource > &sources)=0
Start a collection of data sources streaming from the camera.
multisense::MultiSenseInfo::DeviceInfo::HardwareRevision::KS21_SILVER
@ KS21_SILVER
multisense::MultiSenseInfo::DeviceInfo::HardwareRevision::ST21
@ ST21
multisense::create_bgr_from_ycbcr420
std::optional< Image > create_bgr_from_ycbcr420(const Image &luma, const Image &chroma, const DataSource &output_source)
Convert a YCbCr420 luma + chroma image into a BGR color image.
Definition: utilities.cc:292
multisense::MultiSenseConfig::lighting_config
std::optional< LightingConfig > lighting_config
The lighting configuration for the camera. If invalid, the camera does not support lighting configura...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1057
multisense::MultiSenseConfig::ImuConfig::accelerometer
std::optional< OperatingMode > accelerometer
Configuration for the onboard accelerometer.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:875
multisense::MultiSenseInfo::SupportedOperatingMode
A valid operating mode for the MultiSense.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1567
multisense::MultiSenseInfo::SupportedOperatingMode::supported_sources
std::vector< DataSource > supported_sources
Data sources supported at that mode.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1587
multisense::MultiSenseStatus::TemperatureStatus::left_imager_temperature
float left_imager_temperature
Temperature of the left imager in Celsius.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1136
multisense::Channel::get_system_status
virtual std::optional< MultiSenseStatus > get_system_status()=0
Query the current system status.
PYBIND11_MODULE
PYBIND11_MODULE(_libmultisense, m)
Definition: bindings.cc:77
multisense::Channel::set_config
virtual Status set_config(const MultiSenseConfig &config)=0
Get set the current MultiSense configuration.
multisense::MultiSenseInfo::operating_modes
std::vector< SupportedOperatingMode > operating_modes
Supported operating modes.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1650
multisense::MultiSenseStatus::PowerStatus::fpga_power
float fpga_power
The current power draw of the FPGA in Watts.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1164
multisense::Image::PixelFormat::MONO16
@ MONO16
multisense::DataSource::COST_RAW
@ COST_RAW
multisense::MultiSenseInfo::SensorVersion::firmware_build_date
std::string firmware_build_date
The date the firmware running on the camera was built.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1551
multisense::MultiSenseInfo::DeviceInfo::HardwareRevision::S27
@ S27
multisense::MultiSenseConfig::LightingConfig::internal
std::optional< InternalConfig > internal
The internal lighting config. Will be nullopt if the camera does not support internal lighting contro...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:984
multisense::MultiSenseConfig::AutoExposureRoiConfig::top_left_y_position
uint16_t top_left_y_position
The y value of the top left corner of the ROI in the full resolution image. Note (0,...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:541
multisense::MultiSenseConfig::AutoExposureRoiConfig::width
uint16_t width
The width of the ROI in the full resolution image. A value of 0 disables the ROI.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:545
multisense::Channel::get_next_image_frame
virtual std::optional< ImageFrame > get_next_image_frame()=0
A blocking call that waits for one image frame from the camera.
multisense::MultiSenseStatus::PtpStatus::grandmaster_id
std::array< uint8_t, 8 > grandmaster_id
The id of the current grandmaster clock (8 bytes, 0xXXXXXX.XXXX.XXXXXX)
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1095
multisense::MultiSenseInfo::DeviceInfo::PcbInfo
Info for the PCBs contained in the unit.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1295
multisense::MultiSenseConfig::ImuConfig::OperatingMode::range
ImuRange range
The specific IMU range configuration specified in ImuInfo::Source.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:856
multisense::MultiSenseConfig::frames_per_second
float frames_per_second
The target framerate the MultiSense should operate at.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1021
multisense::MultiSenseInfo::NetworkInfo::netmask
std::string netmask
The netmask of the camera (i.e. X.X.X.X)
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1282
multisense::MultiSenseStatus::TimeStatus::offset_to_host
std::chrono::nanoseconds offset_to_host() const
Compute the time offset which can manually be added to all camera timestamps to change the camera tim...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1208
multisense::MultiSenseInfo::Version::minor
uint32_t minor
Minor version number.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1517
multisense::write_pointcloud_ply
MULTISENSE_API bool write_pointcloud_ply(const PointCloud< Color > &point_cloud, const std::filesystem::path &path)
Write a point cloud to a ASCII ply file.
Definition: MultiSenseUtilities.hh:276
multisense::MultiSenseConfig::AutoExposureRoiConfig::height
uint16_t height
The height of the ROI in the full resolution image. A value of 0 disables the ROI.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:549
multisense::MultiSenseInfo::SupportedOperatingMode::width
uint32_t width
The width of the output image in pixels.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1572
multisense::MultiSenseInfo::imu
std::optional< ImuInfo > imu
Supported operating modes for the IMU sensors (accelerometer, gyroscope, magnetometer)....
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1656
multisense::ImageFrame::frame_id
int64_t frame_id
The unique monotonically increasing ID for each frame populated by the MultiSense.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:334
multisense::Image::image_data_offset
int64_t image_data_offset
An offset into the raw_data pointer where the image data starts.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:211
multisense::MultiSenseInfo::DeviceInfo
The Device information associated with the MultiSense. The DeviceInfo is used to determine what featu...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1290
multisense::MultiSenseInfo::DeviceInfo::LightingType::NONE
@ NONE
No lights.
multisense::MultiSenseInfo::ImuInfo::Source::device
std::string device
The name of the IMU chip.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1608
multisense::MultiSenseConfig::ImuConfig::OperatingMode::enabled
bool enabled
Enable the current source.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:845
multisense::MultiSenseConfig::ManualExposureConfig
Manual exposure specific configuration.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:504
multisense::MultiSenseConfig::AutoExposureConfig::max_gain
float max_gain
The auto exposure algorithm adjusts both exposure and gain. This caps the gain the auto exposure algo...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:601
multisense::DataSource::LEFT_MONO_COMPRESSED
@ LEFT_MONO_COMPRESSED
multisense::MultiSenseInfo::DeviceInfo::LightingType::EXTERNAL
@ EXTERNAL
Drive lights via an external output.
multisense::Status::EXCEPTION
@ EXCEPTION
multisense::Status::UNSUPPORTED
@ UNSUPPORTED
multisense::MultiSenseConfig::ImageConfig::manual_exposure
std::optional< ManualExposureConfig > manual_exposure
The exposure config to use if auto exposure is disabled.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:694
multisense::PointCloud::cloud
std::vector< Point< Color > > cloud
Definition: MultiSenseUtilities.hh:82
multisense::MultiSenseStatus::PtpStatus::grandmaster_offset
std::chrono::nanoseconds grandmaster_offset
Offset between the camera's PTP Hardware Clock and the grandmaster clock.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1100
multisense::MultiSenseInfo::DeviceInfo::HardwareRevision::S7
@ S7
multisense::MultiSenseStatus::TemperatureStatus::right_imager_temperature
float right_imager_temperature
Temperature of the right imager in Celsius.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1141
multisense::MultiSenseConfig::LightingConfig::InternalConfig::intensity
float intensity
Lighting brightness ranging from 0 to 100.0. A value of 0 will turn off the LEDs.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:912
multisense::Status::OK
@ OK
multisense::Channel::set_network_config
virtual Status set_network_config(const MultiSenseInfo::NetworkInfo &config, const std::optional< std::string > &broadcast_interface)=0
Update the network configuration of the MultiSense. This will require a hardware reboot of the MultiS...
multisense::ImuRate
A sample rate, and what impact it has on bandwidth.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:429
multisense::MultiSenseStatus::system_ok
bool system_ok
Summary of the current MultiSense state. True if the MultiSense is operating properly.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1226
multisense::MultiSenseInfo::Version::major
uint32_t major
Major version number.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1512
multisense::CameraCalibration::DistortionType::NONE
@ NONE
multisense::DataSource::AUX_CHROMA_RECTIFIED_RAW
@ AUX_CHROMA_RECTIFIED_RAW
multisense::MultiSenseInfo::SensorVersion
Version information for the MultiSense.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1546
multisense::DataSource::AUX_RAW
@ AUX_RAW
multisense::MultiSenseStatus::CameraStatus::processing_pipeline_ok
bool processing_pipeline_ok
True if the onboard processing pipeline is ok and currently processing images.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1123
multisense::Status::TIMEOUT
@ TIMEOUT
multisense::Channel::Config::ip_address
std::string ip_address
the IP address of the MultiSense camera to connect to
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:90
multisense::Channel
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:46
multisense::MultiSenseInfo::DeviceInfo::ImagerType::CMV4000_COLOR
@ CMV4000_COLOR
multisense::MultiSenseStatus::ClientNetworkStatus::dropped_messages
size_t dropped_messages
The total number of dropped messages on the client side.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1177
multisense::CameraCalibration::DistortionType::PLUMBBOB
@ PLUMBBOB
multisense::MultiSenseStatus::ClientNetworkStatus::invalid_packets
size_t invalid_packets
The total number of invalid packets received on the client side.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1182
multisense::Image::PixelFormat::BGR8
@ BGR8
multisense::Channel::create
static std::unique_ptr< Channel > create(const Config &config, const ChannelImplementation &impl=ChannelImplementation::LEGACY)
Factory create function which allows for switching between different channel implementations.
Definition: factory.cc:42
multisense::MultiSenseInfo::NetworkInfo::ip_address
std::string ip_address
The ip address of the camera (i.e. X.X.X.X)
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1272
multisense::MultiSenseInfo::DeviceInfo::ImagerType::AR0239_COLOR
@ AR0239_COLOR
multisense::MultiSenseInfo::DeviceInfo::hardware_revision
HardwareRevision hardware_revision
The hardware revision of the MultiSense.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1404
multisense::MultiSenseInfo::DeviceInfo::nominal_focal_length
float nominal_focal_length
The nominal focal length for the primary lens in meters.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1453
multisense::MultiSenseInfo::DeviceInfo::HardwareRevision::S21
@ S21
multisense::StereoCalibration::right
CameraCalibration right
Calibration information for the right camera.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:176
multisense::MultiSenseConfig::ManualWhiteBalanceConfig::red
float red
The manual red white-balance setting Valid range is [0.25, 4].
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:632
multisense::MultiSenseInfo::DeviceInfo::lens_name
std::string lens_name
The name of the lens used for the primary camera For stereo cameras this is the Left/Right stereo pai...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1438
multisense::MultiSenseInfo::DeviceInfo::build_date
std::string build_date
The date the MultiSense was manufactured This value can store at most 32 characters.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1393
multisense::MultiSenseConfig::MaxDisparities::D128
@ D128
128 pixels
multisense::MultiSenseConfig::ImageConfig::manual_white_balance
std::optional< ManualWhiteBalanceConfig > manual_white_balance
The white balance parameters to use if auto white balance is disabled.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:709
multisense::MultiSenseConfig::AutoWhiteBalanceConfig::decay
uint32_t decay
The decay rate used for auto-white-balance Valid range [0, 20].
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:658
multisense::MultiSenseStatus::TimeStatus::client_host_time
std::chrono::nanoseconds client_host_time
The time of the host machine running the client when the status request was sent.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1195
multisense::Status::FAILED
@ FAILED
multisense::Channel::ReceiveBufferConfig::num_small_buffers
size_t num_small_buffers
The number of small buffers to preallocate for receiving small MultiSense messages.
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:70
multisense::CameraCalibration::distortion_type
DistortionType distortion_type
The type of the distortion model used for the unrectified camera.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:147
multisense::MultiSenseInfo::DeviceInfo::ImagerType::CMV2000_COLOR
@ CMV2000_COLOR
multisense::Channel::Config::receive_buffer_configuration
ReceiveBufferConfig receive_buffer_configuration
Config for the number and size of internal buffers used to receive data without recurring memory allo...
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:120
multisense::ColorImageEncoding::YCBCR420
@ YCBCR420
multisense::MultiSenseConfig::width
uint32_t width
The operating width of the MultiSense in pixels. For available operating resolutions see the MultiSen...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1005
multisense::MultiSenseInfo::SensorVersion::hardware_version
uint64_t hardware_version
ID for the version of hardware.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1561
multisense::ImageFrame::add_image
void add_image(const Image &image)
Add an image to the frame, keyed by the image's DataSource.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:305
multisense::ImuRange::range
float range
The max value the sensor can return. This value is +/- units for the given source.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:458
multisense::ColorImageEncoding::NONE
@ NONE
multisense::MultiSenseInfo
Static status info for the MultiSense. Will not change during camera operation.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1262
multisense::Channel::ChannelImplementation::LEGACY
@ LEGACY
Use the Legacy MultiSense wire protocol implemented as part of LibMultiSense.
multisense::ImuRange::resolution
float resolution
The min resolution the sensor can return. In units per LSB.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:463
multisense::MultiSenseInfo::DeviceInfo::nominal_relative_aperture
float nominal_relative_aperture
The nominal relative aperture for the primary camera modules in f-stop.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1458
multisense::MultiSenseConfig::TimeConfig
Config for time-based controls.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:795
multisense::MultiSenseInfo::DeviceInfo::PcbInfo::name
std::string name
The name of the PCB This value can store at most 32 characters.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1300
multisense::DataSource::RIGHT_RECTIFIED_RAW
@ RIGHT_RECTIFIED_RAW
multisense::DataSource::AUX_CHROMA_RAW
@ AUX_CHROMA_RAW
multisense::MultiSenseConfig::AutoExposureConfig::decay
uint32_t decay
The desired auto-exposure decay rate. A larger value increases the number of frames it takes for the ...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:579
multisense::MultiSenseStatus::power
std::optional< PowerStatus > power
The current power status.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1246
multisense::MultiSenseConfig::AuxConfig::sharpening_percentage
float sharpening_percentage
The percentage strength of the sharpening gain to apply to the aux image Valid range is [0,...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:750
MultiSenseSerialization.hh
multisense::MultiSenseStatus::PowerStatus::input_current
float input_current
The current input current in Amperes.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1159
multisense::MultiSenseConfig::ImuConfig::OperatingMode::rate
ImuRate rate
The specific IMU rate configuration specified in ImuInfo::Source table.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:851
multisense::MultiSenseInfo::DeviceInfo::ImagerType::CMV2000_GREY
@ CMV2000_GREY
multisense::MultiSenseStatus::CameraStatus
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1113
multisense::DataSource::AUX_RECTIFIED_COMPRESSED
@ AUX_RECTIFIED_COMPRESSED
multisense::MultiSenseConfig::LightingConfig
Lighting configuration for the camera.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:902
multisense::MultiSenseStatus::CameraStatus::cameras_ok
bool cameras_ok
True if the cameras are operating and currently streaming data.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1118
multisense::MultiSenseStatus::time
std::optional< TimeStatus > time
The current timing status information.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1256
multisense::MultiSenseConfig::MaxDisparities::D64
@ D64
64 pixels
multisense::MultiSenseStatus::PowerStatus
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1149
multisense::Image
Represents a single image plus metadata.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:187
multisense::write_image
bool write_image(const Image &image, const std::filesystem::path &path)
Write a image to a specific path on disk. The type of serialization is determined by the input path.
Definition: utilities.cc:176
multisense::MultiSenseConfig::TimeConfig::ptp_enabled
bool ptp_enabled
Enable PTP sync on the camera.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:800
multisense::ImageFrame::aux_color_encoding
ColorImageEncoding aux_color_encoding
The encoding of the aux color image(s) in the frame.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:359
multisense::Channel::disconnect
virtual void disconnect()=0
Disconnect from the camera.
multisense::Image::PixelFormat::H264
@ H264
multisense::MultiSenseConfig::LightingConfig::ExternalConfig::intensity
float intensity
Lighting brightness ranging from 0 to 100.0. A value of 0 will turn off the LEDs.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:946
multisense::MultiSenseConfig::StereoConfig::postfilter_strength
float postfilter_strength
This is used to filter low confidence stereo data before it is sent to the host. Larger numbers indic...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:490
multisense::MultiSenseInfo::device
DeviceInfo device
Device info.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1640
multisense::MultiSenseConfig::disparities
MaxDisparities disparities
The max number of pixels the MultiSense searches when computing the disparity output.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1016
multisense::MultiSenseConfig::AutoExposureRoiConfig::top_left_x_position
uint16_t top_left_x_position
The x value of the top left corner of the ROI in the full resolution image. Note (0,...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:536
multisense::MultiSenseConfig::network_config
std::optional< NetworkTransmissionConfig > network_config
Config to control network transmission settings.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1046
multisense::MultiSenseConfig::LightingConfig::ExternalConfig::FlashMode::SYNC_WITH_AUX
@ SYNC_WITH_AUX
multisense::MultiSenseInfo::DeviceInfo::HardwareRevision::KS21
@ KS21
multisense::MultiSenseConfig::ManualExposureConfig::gain
float gain
The desired electrical and digital gain used to brighten the image. Valid range is [1....
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:510
multisense::MultiSenseConfig::AuxConfig::sharpening_enabled
bool sharpening_enabled
Enable sharpening.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:744
multisense::MultiSenseConfig::AuxConfig::sharpening_limit
uint8_t sharpening_limit
The maximum difference in pixels that sharpening is is allowed to change between neighboring pixels....
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:758
multisense::Image::PixelFormat::FLOAT32
@ FLOAT32
multisense::MultiSenseInfo::SensorVersion::firmware_version
MultiSenseInfo::Version firmware_version
The version of the firmware running on the camera.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1556
multisense::Channel::ReceiveBufferConfig::num_large_buffers
size_t num_large_buffers
The number of large buffers to preallocate for receiving MultiSense sensor data.
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:78
multisense::MultiSenseConfig::imu_config
std::optional< ImuConfig > imu_config
The imu configuration to use for the camera. Will be invalid if sensor does not contain an IMU.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1051
multisense::MultiSenseInfo::Version
Convenience wrapper for a version number See https://semver.org/.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1507
multisense::Channel::Config::receive_timeout
std::optional< std::chrono::milliseconds > receive_timeout
Timeout to use when waiting for MultiSense command responses. Setting the timeout to nullopt will res...
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:103
multisense::MultiSenseStatus::ClientNetworkStatus::received_messages
size_t received_messages
The total number of valid messages received from the client.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1172
multisense::create_pointcloud
std::optional< PointCloud< void > > create_pointcloud(const ImageFrame &frame, double max_range, const DataSource &disparity_source)
Definition: utilities.cc:373
multisense::MultiSenseStatus::TimeStatus
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1185
multisense::CameraCalibration
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:115
multisense::MultiSenseInfo::DeviceInfo::pcb_info
std::vector< PcbInfo > pcb_info
Information about each PCB.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1409
multisense::Channel::ReceiveBufferConfig::small_buffer_size
size_t small_buffer_size
The size of each small buffer in bytes.
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:74
multisense::MultiSenseConfig::AutoWhiteBalanceConfig::threshold
float threshold
The auto white balance threshold Valid range [0.0, 1.0].
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:664
multisense::Channel::get_info
virtual MultiSenseInfo get_info()=0
Get the static information associated with the camera.
multisense::MultiSenseInfo::DeviceInfo::ImagerType::CMV4000_GREY
@ CMV4000_GREY
multisense::MultiSenseInfo::ImuInfo::Source::rates
std::vector< ImuRate > rates
The available rates supported by this operating mode.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1613
multisense::Image::width
int width
Width of the image in pixels.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:226
multisense::MultiSenseInfo::ImuInfo
Information about the IMU onboard the MultiSense.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1593
multisense::MultiSenseConfig::NetworkTransmissionConfig
Config for transmitting packets from the MultiSense to the host.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:814
multisense::Channel::stop_streams
virtual Status stop_streams(const std::vector< DataSource > &sources)=0
Stop specific data sources from streaming from the camera. An empty collection of sources will stop a...
multisense::Channel::ReceiveBufferConfig
Certain implementations may use a fixed set of internal buffers to manage incoming camera data....
Definition: LibMultiSense/include/MultiSense/MultiSenseChannel.hh:65
multisense::MultiSenseInfo::SupportedOperatingMode::disparities
MultiSenseConfig::MaxDisparities disparities
Supported operating disparity.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1582
multisense::Image::format
PixelFormat format
The format of the image data stored in the raw_data stored in the raw_data buffer.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:221
multisense::DataSource::UNKNOWN
@ UNKNOWN
multisense::Channel::add_imu_frame_callback
virtual void add_imu_frame_callback(std::function< void(const ImuFrame &)> callback)=0
Setup user callback that will be invoked whenever a new imu frame is received.
multisense::to_string
std::string to_string(const Status &status)
Convert a status object to a user readable string.
Definition: utilities.cc:137
multisense::MultiSenseStatus::TimeStatus::camera_time
std::chrono::nanoseconds camera_time
The camera's system time when the status message request was received.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1190
point_cloud_utility.float
float
Definition: point_cloud_utility.py:114
multisense::MultiSenseInfo::network
NetworkInfo network
The network configuration of the MultiSense.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1661
multisense::MultiSenseInfo::DeviceInfo::lighting_type
LightingType lighting_type
The type of lighting used in the MultiSense.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1463
multisense::MultiSenseStatus::TimeStatus::network_delay
std::chrono::nanoseconds network_delay
The estimated network delay between when the status request was sent, and when the status request was...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1202
multisense::Status::INTERNAL_ERROR
@ INTERNAL_ERROR
PYBIND11_JSON_SUPPORT
#define PYBIND11_JSON_SUPPORT(Type)
Definition: bindings.cc:72
multisense::MultiSenseInfo::Version::patch
uint32_t patch
Patch version number.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1522
multisense::MultiSenseConfig::ImageConfig::gamma
float gamma
Set the gamma correction for the image. Valid range [1.0, 2.2].
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:684
multisense::MultiSenseStatus::client_network
ClientNetworkStatus client_network
The current client network statistics.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1251
multisense::MultiSenseStatus::TimeStatus::apply_offset_to_host
TimeT apply_offset_to_host(const TimeT &input_camera_time) const
Apply the time offset to a camera timestamps to camera timestamp from the reference clock of the came...
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1217
multisense::DataSource::LEFT_RECTIFIED_COMPRESSED
@ LEFT_RECTIFIED_COMPRESSED
multisense::Point< void >
Single point definition with no color.
Definition: MultiSenseUtilities.hh:72
multisense::MultiSenseConfig::aux_config
std::optional< AuxConfig > aux_config
The image configuration to use for the aux camera if present.
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1036
multisense::DataSource::LEFT_DISPARITY_RAW
@ LEFT_DISPARITY_RAW
multisense::MultiSenseStatus
Consolidated status information which can be queried on demand from the MultiSense....
Definition: LibMultiSense/include/MultiSense/MultiSenseTypes.hh:1082


multisense_lib
Author(s):
autogenerated on Thu Apr 17 2025 02:49:08