Go to the documentation of this file.
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>
46 #include <MultiSense/MultiSenseChannel.hh>
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>()); \
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>(); \
67 .def("__repr__", [](const Type &obj) { \
68 const nlohmann::json j = obj; \
72 #define PYBIND11_JSON_SUPPORT(Type)
75 namespace py = pybind11;
78 m.doc() =
"Pybind11 bindings for the LibMultiSense C++ Library";
81 py::enum_<multisense::Status>(m,
"Status")
93 py::enum_<multisense::DataSource>(m,
"DataSource")
117 py::enum_<multisense::ColorImageEncoding>(m,
"ColorImageEncoding")
122 py::enum_<multisense::CameraCalibration::DistortionType>(m,
"DistortionType")
128 py::class_<multisense::CameraCalibration>(m,
"CameraCalibration")
138 py::class_<multisense::StereoCalibration>(m,
"StereoCalibration")
146 py::enum_<multisense::Image::PixelFormat>(m,
"PixelFormat")
156 py::class_<multisense::Image>(m,
"Image")
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;
170 element_size =
sizeof(uint8_t);
171 format = py::format_descriptor<uint8_t>::format();
172 strides = {
sizeof(uint8_t) * image.
width,
sizeof(uint8_t)};
177 element_size =
sizeof(uint16_t);
178 format = py::format_descriptor<uint16_t>::format();
179 strides = {
sizeof(uint16_t) * image.
width,
sizeof(uint16_t)};
184 element_size =
sizeof(uint8_t);
185 format = py::format_descriptor<uint8_t>::format();
187 strides = {
sizeof(uint8_t) * image.
width * 3,
sizeof(uint8_t) * 3,
sizeof(uint8_t)};
192 element_size =
sizeof(
float);
193 format = py::format_descriptor<float>::format();
194 strides = {
sizeof(
float) * image.
width,
sizeof(
float)};
197 default: {
throw std::runtime_error(
"Unknown pixel format");}
201 return py::array(py::buffer_info(
218 py::class_<multisense::ImageFrame>(m,
"ImageFrame")
231 py::class_<multisense::ImuRate>(m,
"ImuRate")
234 .def(py::self == py::self)
239 py::class_<multisense::ImuRange>(m,
"ImuRange")
242 .def(py::self == py::self)
248 py::class_<multisense::MultiSenseConfig::StereoConfig>(m,
"StereoConfig")
251 .def(py::self == py::self)
255 py::class_<multisense::MultiSenseConfig::ManualExposureConfig>(m,
"ManualExposureConfig")
258 .def(py::self == py::self)
263 py::class_<multisense::MultiSenseConfig::AutoExposureRoiConfig>(m,
"AutoExposureRoiConfig")
266 .def(py::self == py::self)
273 py::class_<multisense::MultiSenseConfig::AutoExposureConfig>(m,
"AutoExposureConfig")
276 .def(py::self == py::self)
285 py::class_<multisense::MultiSenseConfig::ManualWhiteBalanceConfig>(m,
"ManualWhiteBalanceConfig")
288 .def(py::self == py::self)
293 py::class_<multisense::MultiSenseConfig::AutoWhiteBalanceConfig>(m,
"AutoWhiteBalanceConfig")
296 .def(py::self == py::self)
301 py::class_<multisense::MultiSenseConfig::ImageConfig>(m,
"ImageConfig")
304 .def(py::self == py::self)
314 py::class_<multisense::MultiSenseConfig::AuxConfig>(m,
"AuxConfig")
317 .def(py::self == py::self)
324 py::enum_<multisense::MultiSenseConfig::MaxDisparities>(m,
"MaxDisparities")
330 py::class_<multisense::MultiSenseConfig::TimeConfig>(m,
"TimeConfig")
333 .def(py::self == py::self)
337 py::class_<multisense::MultiSenseConfig::NetworkTransmissionConfig>(m,
"NetworkTransmissionConfig")
340 .def(py::self == py::self)
344 py::class_<multisense::MultiSenseConfig::ImuConfig::OperatingMode>(m,
"ImuOperatingMode")
347 .def(py::self == py::self)
353 py::class_<multisense::MultiSenseConfig::ImuConfig>(m,
"ImuConfig")
356 .def(py::self == py::self)
363 py::enum_<multisense::MultiSenseConfig::LightingConfig::ExternalConfig::FlashMode>(m,
"FlashMode")
369 py::class_<multisense::MultiSenseConfig::LightingConfig::InternalConfig>(m,
"LightingConfigInternalConfig")
372 .def(py::self == py::self)
377 py::class_<multisense::MultiSenseConfig::LightingConfig::ExternalConfig>(m,
"LightingConfigExternalConfig")
380 .def(py::self == py::self)
387 py::class_<multisense::MultiSenseConfig::LightingConfig>(m,
"LightingConfig")
390 .def(py::self == py::self)
391 .def(py::self == py::self)
396 py::class_<multisense::MultiSenseConfig>(m,
"MultiSenseConfig")
399 .def(py::self == py::self)
413 py::class_<multisense::MultiSenseStatus::PtpStatus>(m,
"PtpStatus")
423 py::class_<multisense::MultiSenseStatus::CameraStatus>(m,
"CameraStatus")
430 py::class_<multisense::MultiSenseStatus::TemperatureStatus>(m,
"TemperatureStatus")
439 py::class_<multisense::MultiSenseStatus::PowerStatus>(m,
"PowerStatus")
447 py::class_<multisense::MultiSenseStatus::ClientNetworkStatus>(m,
"ClientNetworkStatus")
455 py::class_<multisense::MultiSenseStatus::TimeStatus>(m,
"TimeStatus")
465 py::class_<multisense::MultiSenseStatus>(m,
"MultiSenseStatus")
477 py::class_<multisense::MultiSenseInfo::DeviceInfo::PcbInfo>(m,
"PcbInfo")
484 py::enum_<multisense::MultiSenseInfo::DeviceInfo::HardwareRevision>(m,
"HardwareRevision")
498 py::enum_<multisense::MultiSenseInfo::DeviceInfo::ImagerType>(m,
"ImagerType")
509 py::enum_<multisense::MultiSenseInfo::DeviceInfo::LightingType>(m,
"LightingType")
518 py::enum_<multisense::MultiSenseInfo::MultiSenseInfo::DeviceInfo::LensType>(m,
"LensType")
524 py::class_<multisense::MultiSenseInfo::MultiSenseInfo::NetworkInfo>(m,
"NetworkInfo")
532 py::class_<multisense::MultiSenseInfo::DeviceInfo>(m,
"DeviceInfo")
555 py::class_<multisense::MultiSenseInfo::Version>(m,
"Version")
558 .def(
"__lt__", &multisense::MultiSenseInfo::Version::operator<)
565 py::class_<multisense::MultiSenseInfo::MultiSenseInfo::SensorVersion>(m,
"SensorVersion")
573 py::class_<multisense::MultiSenseInfo::SupportedOperatingMode>(m,
"SupportedOperatingMode")
582 py::class_<multisense::MultiSenseInfo::ImuInfo::Source>(m,
"ImuSource")
591 py::class_<multisense::MultiSenseInfo::ImuInfo>(m,
"ImuInfo")
600 py::class_<multisense::MultiSenseInfo>(m,
"MultiSenseInfo")
610 py::enum_<multisense::Channel::ChannelImplementation>(m,
"ChannelImplementation")
614 py::class_<multisense::Channel::ReceiveBufferConfig>(m,
"ReceiveBufferConfig")
623 py::class_<multisense::Channel::Config>(m,
"ChannelConfig")
635 py::class_<multisense::Channel, std::unique_ptr<multisense::Channel>>(m,
"Channel")
664 py::class_<multisense::Point<void>>(m,
"Point")
670 py::class_<multisense::Point<uint8_t>>(m,
"PointLuma8")
677 py::class_<multisense::Point<uint16_t>>(m,
"PointLuma16")
684 py::class_<multisense::Point<std::array<uint8_t, 3>>>(m,
"PointBGR")
691 py::class_<multisense::PointCloud<void>>(m,
"PointCloud")
696 const std::vector<size_t> shape = {
static_cast<size_t>(cloud.
cloud.size()), 3};
698 const size_t element_size =
sizeof(
float);
699 const std::string format = py::format_descriptor<float>::format();;
701 return py::array(py::buffer_info(
702 const_cast<uint8_t*
>(
reinterpret_cast<const uint8_t*
>(cloud.
cloud.data())),
710 py::class_<multisense::PointCloud<uint8_t>>(m,
"PointCloudLuma8")
715 const std::vector<size_t> shape = {
static_cast<size_t>(cloud.
cloud.size()), 3};
721 const std::string format = py::format_descriptor<float>::format();;
723 return py::array(py::buffer_info(
724 const_cast<uint8_t*
>(
reinterpret_cast<const uint8_t*
>(cloud.
cloud.data())),
733 const std::vector<size_t> shape = {
static_cast<size_t>(cloud.
cloud.size())};
737 return py::array(py::buffer_info(
738 const_cast<uint8_t*
>(
reinterpret_cast<const uint8_t*
>(cloud.
cloud.data())),
747 py::class_<multisense::PointCloud<uint16_t>>(m,
"PointCloudLuma16")
752 const std::vector<size_t> shape = {
static_cast<size_t>(cloud.
cloud.size()), 3};
758 const std::string format = py::format_descriptor<float>::format();;
760 return py::array(py::buffer_info(
761 const_cast<uint8_t*
>(
reinterpret_cast<const uint8_t*
>(cloud.
cloud.data())),
770 const std::vector<size_t> shape = {
static_cast<size_t>(cloud.
cloud.size())};
774 return py::array(py::buffer_info(
775 const_cast<uint8_t*
>(
reinterpret_cast<const uint8_t*
>(cloud.
cloud.data())),
783 py::class_<multisense::PointCloud<std::array<uint8_t, 3>>>(m,
"PointCloudBGR")
788 const std::vector<size_t> shape = {
static_cast<size_t>(cloud.
cloud.size()), 3};
794 const std::string format = py::format_descriptor<float>::format();;
796 return py::array(py::buffer_info(
797 const_cast<uint8_t*
>(
reinterpret_cast<const uint8_t*
>(cloud.
cloud.data())),
806 const std::vector<size_t> shape = {
static_cast<size_t>(cloud.
cloud.size())};
810 return py::array(py::buffer_info(
811 const_cast<uint8_t*
>(
reinterpret_cast<const uint8_t*
>(cloud.
cloud.data())),
825 py::gil_scoped_release release;
830 m.def(
"write_pointcloud_ply",
833 py::gil_scoped_release release;
838 m.def(
"write_pointcloud_ply",
841 py::gil_scoped_release release;
846 m.def(
"write_pointcloud_ply",
849 py::gil_scoped_release release;
854 m.def(
"write_pointcloud_ply",
857 py::gil_scoped_release release;
868 m.def(
"create_gray8_pointcloud",
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>&,
880 &multisense::create_color_pointcloud<uint8_t>),
881 py::call_guard<py::gil_scoped_release>());
883 m.def(
"create_gray16_pointcloud",
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>&,
895 &multisense::create_color_pointcloud<uint16_t>),
896 py::call_guard<py::gil_scoped_release>());
898 m.def(
"create_bgr_pointcloud",
899 static_cast<std::optional<multisense::PointCloud<std::array<uint8_t, 3>
>>(*)(
const multisense::ImageFrame&,
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>&,
911 py::call_guard<py::gil_scoped_release>());
SensorVersion version
Sensor Version info.
constexpr bool has_aux_camera() const
Determine if the MultiSense has a Aux color camera.
@ RIGHT_RECTIFIED_COMPRESSED
float power_supply_temperature
Temperature of the internal switching power supply in Celsius.
float target_threshold
The fraction of pixels which must be equal or below the pixel value set by the target intensity pixel...
CameraStatus camera
The current camera status.
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...
std::optional< Image > create_bgr_image(const ImageFrame &frame, const DataSource &output_source)
Convert a YCbCr420 luma + chroma image into a BGR color image.
std::optional< TemperatureStatus > temperature
The current temperature status.
float nominal_stereo_baseline
The nominal stereo baseline in meters.
Lighting config for lights driven by GPIO outputs from the MultiSense.
uint32_t number_of_lights
The number of lights the MultiSense controls.
TimeT camera_timestamp
The timestamp associated with the image based on the camera's clock. Starts at 0 on boot.
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.
The network configuration for the MultiSense.
LensType lens_type
The type of the primary imager.
Complete configuration object for configuring the MultiSense. Can be updated during camera operation.
int height
Height of the image in pixels.
uint32_t height
The height of the output image in pixels.
uint32_t height
The operating height of the MultiSense in pixels. For available operating resolutions see the MultiSe...
bool auto_white_balance_enabled
Enable or disable auto white balance.
ImageConfig image_config
The image configuration to use for the main stereo pair.
Manual white balance specific configuration.
std::string camera_name
The name of the MultiSense variant. This value can store at most 32 characters.
TimeT frame_time
The MultiSense timestamp associated with the frame.
@ INTERNAL
Lights driven internally.
Single point definition with a custom color type.
CameraCalibration left
Calibration information for the left camera.
uint32_t samples_per_frame
The number of IMU samples which should be included in a IMU frame.
@ OUTPUT_TRIGGER
A GPIO line is used to trigger an external light.
std::vector< ImuRange > ranges
The available ranges supported by this operating mode.
std::optional< CameraCalibration > aux
Calibration information for the aux camera (optional 3rd center camera)
float input_voltage
The current input voltage in volts.
Image specific configuration for the Aux imager.
TimeT ptp_timestamp
The timestamp associated with the image based using the camera's clock which is potentially PTP synch...
uint32_t imager_width
The native width of the primary imager.
ImagerType imager_type
The type of the imager.
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...
const Image & get_image(const DataSource &source) const
Retrieve image by DataSource. Throws if not found.
uint32_t imager_height
The native height of the primary imager.
std::chrono::microseconds exposure_time
The manual exposure time in microseconds Valid range is [0, 33000].
Config for the IMU sensor.
std::optional< Source > gyroscope
Configuration specific to the gyroscope.
std::string to_string() const
Convert a Version info to string for convenience.
size_t large_buffer_size
The size of each small buffer in bytes.
std::optional< PtpStatus > ptp
The current ptp status. Only valid if ptp is enabled.
std::string serial_number
The unique serial number of the MultiSense This value can store at most 32 characters.
ImageConfig image_config
Image configuration for the Aux imager.
A frame containing multiple images (indexed by DataSource).
float fpga_temperature
Temperature of the FPGA in Celsius.
bool flash
Enable flashing of the light.
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...
TimeT ptp_frame_time
The MultiSense ptp timestamp associated with the frame.
bool has_image(const DataSource &source) const
Check if we have an image for a given data source.
bool auto_exposure_enabled
Enable or disable auto exposure.
Info about the available IMU configurations.
bool connect_on_initialization
Connect to the camera when the Channel is initialized.
Auto white balance specific configuration.
float target_intensity
The auto-exposure algorithm in digital imaging endeavors to achieve a specified target intensity,...
Lighting config for lights integrated into the MultiSense.
std::optional< int16_t > mtu
The MTU to use for sending and receiving data from the camera. Setting the MTU to nullopt will trigge...
bool grandmaster_present
Status of the grandmaster clock. true if synchronized to a non-local grandmaster OR if a non-local gr...
@ PATTERN_PROJECTOR_OUTPUT_TRIGGER
A pattern projector with a GPIO line used to trigger a external light.
FlashMode flash
Configure flash mode.
float bandwith_cutoff
The bandwith cutoff for a given IMU mode in Hz.
virtual Status connect(const Config &config)=0
Initialize the connection to the camera.
std::array< std::array< float, 4 >, 3 > P
Rectified projection matrix which takes points in the origin camera coordinate frame and projects the...
std::optional< std::string > interface
An optional name of network interface to bind to. (i.e. eth0)
std::optional< ExternalConfig > external
The external lighting config. Will be nullopt if the camera does not support internal lighting contro...
std::string name
The name of the IMU sensor.
virtual Status set_calibration(const StereoCalibration &calibration)=0
Set the current stereo calibration. The calibration is expected to be or the full-resolution operatin...
float sample_rate
The sample rate for the sensor in Hz.
std::array< std::array< float, 3 >, 3 > K
Unrectified camera projection matrix stored in row-major ordering.
@ PATTERN_PROJECTOR
A pattern projector.
@ LEFT_DISPARITY_COMPRESSED
Auto-exposure Region-of-Interest (ROI) specific configuration.
float blue
The manual blue white-balance setting Valid range is [0.25, 4].
std::optional< OperatingMode > gyroscope
Configuration for the onboard gyroscope.
std::optional< TimeConfig > time_config
Config for the MultiSense time-sync options.
StereoConfig stereo_config
The stereo configuration to use.
std::optional< AutoWhiteBalanceConfig > auto_white_balance
The white balance parameters to use if auto white balance is enabled.
The range for each sensor along with the corresponding sampling resolution.
std::vector< float > D
Coefficients for the distortion model.
virtual MultiSenseConfig get_config()=0
Get the current MultiSense configuration.
uint16_t steps_from_local_to_grandmaster
The number of network hops from the grandmaster to the camera's clock.
Auto-exposure specific configuration.
std::string imager_name
The name of the imager used by the primary camera. For stereo cameras this is the Left/Right stereo p...
AutoExposureRoiConfig roi
The auto exposure region-of-interest used to restrict the portion of the image which the auto exposur...
constexpr bool has_main_stereo_color() const
Determine if the MultiSense's main stereo pair supports color.
bool packet_delay_enabled
Add a small delay between the transmission of each packet to hopefully interact better with slower cl...
uint16_t command_port
The UDP port on the MultiSense which accepts user commands. All production firmware builds use port 9...
std::string gateway
The gateway of the camera (i.e. X.X.X.X)
CameraCalibration calibration
The scaled calibration associated with the image.
Stereo specific configuration.
DataSource
Identifies which camera or data source the image is from.
std::optional< OperatingMode > magnetometer
Configuration for the onboard magnetometer.
DataSource source
The camera data source which this image corresponds to.
Image specific configuration.
std::chrono::microseconds max_exposure_time
The max exposure time auto exposure algorithm can set in microseconds Valid range is [0,...
Config for a specific IMU operating mode. There are separate modes for each of the IMU sensors (i....
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.
std::optional< AutoExposureConfig > auto_exposure
The exposure config to use if auto exposure is enabled.
std::chrono::nanoseconds path_delay
The estimate delay of the PTP synchronization messages from the grandmaster.
std::shared_ptr< const std::vector< uint8_t > > raw_data
A pointer to the raw image data sent from the camera.
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 ...
virtual StereoCalibration get_calibration()=0
Get the current stereo calibration. The output calibration will correspond to the full-resolution ope...
StereoCalibration calibration
The scaled calibration for the entire camera.
uint32_t revision
The revision number of the PCB.
std::map< DataSource, Image > images
The images associated with each source in the frame.
std::optional< Source > magnetometer
Configuration specific to the magnetometer.
std::optional< Source > accelerometer
Configuration specific to the accelerometer.
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.
virtual Status start_streams(const std::vector< DataSource > &sources)=0
Start a collection of data sources streaming from the camera.
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.
std::optional< LightingConfig > lighting_config
The lighting configuration for the camera. If invalid, the camera does not support lighting configura...
std::optional< OperatingMode > accelerometer
Configuration for the onboard accelerometer.
A valid operating mode for the MultiSense.
std::vector< DataSource > supported_sources
Data sources supported at that mode.
float left_imager_temperature
Temperature of the left imager in Celsius.
virtual std::optional< MultiSenseStatus > get_system_status()=0
Query the current system status.
PYBIND11_MODULE(_libmultisense, m)
virtual Status set_config(const MultiSenseConfig &config)=0
Get set the current MultiSense configuration.
std::vector< SupportedOperatingMode > operating_modes
Supported operating modes.
float fpga_power
The current power draw of the FPGA in Watts.
std::string firmware_build_date
The date the firmware running on the camera was built.
std::optional< InternalConfig > internal
The internal lighting config. Will be nullopt if the camera does not support internal lighting contro...
uint16_t top_left_y_position
The y value of the top left corner of the ROI in the full resolution image. Note (0,...
uint16_t width
The width of the ROI in the full resolution image. A value of 0 disables the ROI.
virtual std::optional< ImageFrame > get_next_image_frame()=0
A blocking call that waits for one image frame from the camera.
std::array< uint8_t, 8 > grandmaster_id
The id of the current grandmaster clock (8 bytes, 0xXXXXXX.XXXX.XXXXXX)
Info for the PCBs contained in the unit.
ImuRange range
The specific IMU range configuration specified in ImuInfo::Source.
float frames_per_second
The target framerate the MultiSense should operate at.
std::string netmask
The netmask of the camera (i.e. X.X.X.X)
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...
uint32_t minor
Minor version number.
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.
uint16_t height
The height of the ROI in the full resolution image. A value of 0 disables the ROI.
uint32_t width
The width of the output image in pixels.
std::optional< ImuInfo > imu
Supported operating modes for the IMU sensors (accelerometer, gyroscope, magnetometer)....
int64_t frame_id
The unique monotonically increasing ID for each frame populated by the MultiSense.
int64_t image_data_offset
An offset into the raw_data pointer where the image data starts.
The Device information associated with the MultiSense. The DeviceInfo is used to determine what featu...
std::string device
The name of the IMU chip.
bool enabled
Enable the current source.
Manual exposure specific configuration.
float max_gain
The auto exposure algorithm adjusts both exposure and gain. This caps the gain the auto exposure algo...
@ EXTERNAL
Drive lights via an external output.
std::optional< ManualExposureConfig > manual_exposure
The exposure config to use if auto exposure is disabled.
std::vector< Point< Color > > cloud
std::chrono::nanoseconds grandmaster_offset
Offset between the camera's PTP Hardware Clock and the grandmaster clock.
float right_imager_temperature
Temperature of the right imager in Celsius.
float intensity
Lighting brightness ranging from 0 to 100.0. A value of 0 will turn off the LEDs.
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...
A sample rate, and what impact it has on bandwidth.
bool system_ok
Summary of the current MultiSense state. True if the MultiSense is operating properly.
uint32_t major
Major version number.
@ AUX_CHROMA_RECTIFIED_RAW
Version information for the MultiSense.
bool processing_pipeline_ok
True if the onboard processing pipeline is ok and currently processing images.
std::string ip_address
the IP address of the MultiSense camera to connect to
size_t dropped_messages
The total number of dropped messages on the client side.
size_t invalid_packets
The total number of invalid packets received on the client side.
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.
std::string ip_address
The ip address of the camera (i.e. X.X.X.X)
HardwareRevision hardware_revision
The hardware revision of the MultiSense.
float nominal_focal_length
The nominal focal length for the primary lens in meters.
CameraCalibration right
Calibration information for the right camera.
float red
The manual red white-balance setting Valid range is [0.25, 4].
std::string lens_name
The name of the lens used for the primary camera For stereo cameras this is the Left/Right stereo pai...
std::string build_date
The date the MultiSense was manufactured This value can store at most 32 characters.
std::optional< ManualWhiteBalanceConfig > manual_white_balance
The white balance parameters to use if auto white balance is disabled.
uint32_t decay
The decay rate used for auto-white-balance Valid range [0, 20].
std::chrono::nanoseconds client_host_time
The time of the host machine running the client when the status request was sent.
size_t num_small_buffers
The number of small buffers to preallocate for receiving small MultiSense messages.
DistortionType distortion_type
The type of the distortion model used for the unrectified camera.
ReceiveBufferConfig receive_buffer_configuration
Config for the number and size of internal buffers used to receive data without recurring memory allo...
uint32_t width
The operating width of the MultiSense in pixels. For available operating resolutions see the MultiSen...
uint64_t hardware_version
ID for the version of hardware.
void add_image(const Image &image)
Add an image to the frame, keyed by the image's DataSource.
float range
The max value the sensor can return. This value is +/- units for the given source.
Static status info for the MultiSense. Will not change during camera operation.
@ LEGACY
Use the Legacy MultiSense wire protocol implemented as part of LibMultiSense.
float resolution
The min resolution the sensor can return. In units per LSB.
float nominal_relative_aperture
The nominal relative aperture for the primary camera modules in f-stop.
Config for time-based controls.
std::string name
The name of the PCB This value can store at most 32 characters.
uint32_t decay
The desired auto-exposure decay rate. A larger value increases the number of frames it takes for the ...
std::optional< PowerStatus > power
The current power status.
float sharpening_percentage
The percentage strength of the sharpening gain to apply to the aux image Valid range is [0,...
float input_current
The current input current in Amperes.
ImuRate rate
The specific IMU rate configuration specified in ImuInfo::Source table.
@ AUX_RECTIFIED_COMPRESSED
Lighting configuration for the camera.
bool cameras_ok
True if the cameras are operating and currently streaming data.
std::optional< TimeStatus > time
The current timing status information.
Represents a single image plus metadata.
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.
bool ptp_enabled
Enable PTP sync on the camera.
ColorImageEncoding aux_color_encoding
The encoding of the aux color image(s) in the frame.
virtual void disconnect()=0
Disconnect from the camera.
float intensity
Lighting brightness ranging from 0 to 100.0. A value of 0 will turn off the LEDs.
float postfilter_strength
This is used to filter low confidence stereo data before it is sent to the host. Larger numbers indic...
DeviceInfo device
Device info.
MaxDisparities disparities
The max number of pixels the MultiSense searches when computing the disparity output.
uint16_t top_left_x_position
The x value of the top left corner of the ROI in the full resolution image. Note (0,...
std::optional< NetworkTransmissionConfig > network_config
Config to control network transmission settings.
float gain
The desired electrical and digital gain used to brighten the image. Valid range is [1....
bool sharpening_enabled
Enable sharpening.
uint8_t sharpening_limit
The maximum difference in pixels that sharpening is is allowed to change between neighboring pixels....
MultiSenseInfo::Version firmware_version
The version of the firmware running on the camera.
size_t num_large_buffers
The number of large buffers to preallocate for receiving MultiSense sensor data.
std::optional< ImuConfig > imu_config
The imu configuration to use for the camera. Will be invalid if sensor does not contain an IMU.
Convenience wrapper for a version number See https://semver.org/.
std::optional< std::chrono::milliseconds > receive_timeout
Timeout to use when waiting for MultiSense command responses. Setting the timeout to nullopt will res...
size_t received_messages
The total number of valid messages received from the client.
std::optional< PointCloud< void > > create_pointcloud(const ImageFrame &frame, double max_range, const DataSource &disparity_source)
std::vector< PcbInfo > pcb_info
Information about each PCB.
size_t small_buffer_size
The size of each small buffer in bytes.
float threshold
The auto white balance threshold Valid range [0.0, 1.0].
virtual MultiSenseInfo get_info()=0
Get the static information associated with the camera.
std::vector< ImuRate > rates
The available rates supported by this operating mode.
int width
Width of the image in pixels.
Information about the IMU onboard the MultiSense.
Config for transmitting packets from the MultiSense to the host.
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...
Certain implementations may use a fixed set of internal buffers to manage incoming camera data....
MultiSenseConfig::MaxDisparities disparities
Supported operating disparity.
PixelFormat format
The format of the image data stored in the raw_data stored in the raw_data buffer.
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.
std::string to_string(const Status &status)
Convert a status object to a user readable string.
std::chrono::nanoseconds camera_time
The camera's system time when the status message request was received.
NetworkInfo network
The network configuration of the MultiSense.
LightingType lighting_type
The type of lighting used in the MultiSense.
std::chrono::nanoseconds network_delay
The estimated network delay between when the status request was sent, and when the status request was...
#define PYBIND11_JSON_SUPPORT(Type)
uint32_t patch
Patch version number.
float gamma
Set the gamma correction for the image. Valid range [1.0, 2.2].
ClientNetworkStatus client_network
The current client network statistics.
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...
@ LEFT_RECTIFIED_COMPRESSED
Single point definition with no color.
std::optional< AuxConfig > aux_config
The image configuration to use for the aux camera if present.
Consolidated status information which can be queried on demand from the MultiSense....