LibMultiSense
LibMultiSense Documentation
multisense Namespace Reference

Classes

struct  CameraCalibration
 
class  Channel
 
struct  Image
 Represents a single image plus metadata. More...
 
struct  ImageFrame
 A frame containing multiple images (indexed by DataSource). More...
 
struct  ImuFrame
 A collection of IMU samples from the camera. More...
 
struct  ImuRange
 The range for each sensor along with the corresponding sampling resolution. More...
 
struct  ImuRate
 A sample rate, and what impact it has on bandwidth. More...
 
struct  ImuSample
 A single IMU sample from the camera. More...
 
struct  MultiSenseConfig
 Complete configuration object for configuring the MultiSense. More...
 
struct  MultiSenseInfo
 Static status info for the MultiSense. More...
 
struct  MultiSenseStatus
 Consolidated status information which can be queried on demand from the MultiSense. More...
 
struct  Point
 Make sure our Points and point clouds are packed for applications which might need to handle the underlying raw data. More...
 
struct  Point< void >
 Single point definition with no color. More...
 
struct  PointCloud
 
struct  StereoCalibration
 

Typedefs

using TimeT = std::chrono::time_point< std::chrono::system_clock, std::chrono::nanoseconds >
 

Enumerations

enum  Status : uint8_t {
  Status::UNKNOWN, Status::OK, Status::TIMEOUT, Status::INTERNAL_ERROR,
  Status::FAILED, Status::UNSUPPORTED, Status::EXCEPTION, Status::UNINITIALIZED,
  Status::INCOMPLETE_APPLICATION
}
 
enum  DataSource : uint16_t {
  DataSource::UNKNOWN, DataSource::ALL, DataSource::LEFT_MONO_RAW, DataSource::RIGHT_MONO_RAW,
  DataSource::LEFT_MONO_COMPRESSED, DataSource::RIGHT_MONO_COMPRESSED, DataSource::LEFT_RECTIFIED_RAW, DataSource::RIGHT_RECTIFIED_RAW,
  DataSource::LEFT_RECTIFIED_COMPRESSED, DataSource::RIGHT_RECTIFIED_COMPRESSED, DataSource::LEFT_DISPARITY_RAW, DataSource::LEFT_DISPARITY_COMPRESSED,
  DataSource::AUX_COMPRESSED, DataSource::AUX_RECTIFIED_COMPRESSED, DataSource::AUX_LUMA_RAW, DataSource::AUX_LUMA_RECTIFIED_RAW,
  DataSource::AUX_CHROMA_RAW, DataSource::AUX_CHROMA_RECTIFIED_RAW, DataSource::AUX_RAW, DataSource::AUX_RECTIFIED_RAW,
  DataSource::COST_RAW, DataSource::IMU
}
 Identifies which camera or data source the image is from. More...
 
enum  ColorImageEncoding : uint16_t { ColorImageEncoding::NONE, ColorImageEncoding::YCBCR420 }
 

Functions

 NLOHMANN_JSON_SERIALIZE_ENUM (Status, { {Status::UNKNOWN, "UNKNOWN"}, {Status::OK, "OK"}, {Status::TIMEOUT, "TIMEOUT"}, {Status::INTERNAL_ERROR, "INTERNAL_ERROR"}, {Status::FAILED, "FAILED"}, {Status::UNSUPPORTED, "UNSUPPORTED"}, {Status::EXCEPTION, "EXCEPTION"}, {Status::UNINITIALIZED, "UNINITIALIZED"}, {Status::INCOMPLETE_APPLICATION, "INCOMPLETE_APPLICATION"} }) NLOHMANN_JSON_SERIALIZE_ENUM(DataSource
 
MULTISENSE_API std::string to_string (const Status &status)
 Convert a status object to a user readable string. More...
 
MULTISENSE_API bool write_image (const Image &image, const std::filesystem::path &path)
 Write a image to a specific path on disk. More...
 
MULTISENSE_API std::optional< Imagecreate_depth_image (const ImageFrame &frame, const Image::PixelFormat &depth_format, const DataSource &disparity_source=DataSource::LEFT_DISPARITY_RAW, float invalid_value=0)
 Create a depth image from a image frame. More...
 
MULTISENSE_API std::optional< Imagecreate_bgr_from_ycbcr420 (const Image &luma, const Image &chroma, const DataSource &output_source)
 Convert a YCbCr420 luma + chroma image into a BGR color image. More...
 
MULTISENSE_API std::optional< Imagecreate_bgr_image (const ImageFrame &frame, const DataSource &output_source)
 Convert a YCbCr420 luma + chroma image into a BGR color image. More...
 
template<typename Color >
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. More...
 
template<typename Color >
MULTISENSE_API std::optional< PointCloud< Color > > create_color_pointcloud (const ImageFrame &frame, double max_range, const DataSource &color_source=DataSource::UNKNOWN, const DataSource &disparity_source=DataSource::LEFT_DISPARITY_RAW)
 Create a point cloud from a image frame and a color source. More...
 
MULTISENSE_API std::optional< PointCloud< void > > create_pointcloud (const ImageFrame &frame, double max_range, const DataSource &disparity_source=DataSource::LEFT_DISPARITY_RAW)
 
template<typename Color >
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. More...
 

Typedef Documentation

◆ TimeT

using multisense::TimeT = typedef std::chrono::time_point<std::chrono::system_clock, std::chrono::nanoseconds>

Definition at line 65 of file MultiSenseTypes.hh.

Enumeration Type Documentation

◆ ColorImageEncoding

enum multisense::ColorImageEncoding : uint16_t
strong
Enumerator
NONE 
YCBCR420 

Definition at line 109 of file MultiSenseTypes.hh.

◆ DataSource

enum multisense::DataSource : uint16_t
strong

Identifies which camera or data source the image is from.

Enumerator
UNKNOWN 
ALL 
LEFT_MONO_RAW 
RIGHT_MONO_RAW 
LEFT_MONO_COMPRESSED 
RIGHT_MONO_COMPRESSED 
LEFT_RECTIFIED_RAW 
RIGHT_RECTIFIED_RAW 
LEFT_RECTIFIED_COMPRESSED 
RIGHT_RECTIFIED_COMPRESSED 
LEFT_DISPARITY_RAW 
LEFT_DISPARITY_COMPRESSED 
AUX_COMPRESSED 
AUX_RECTIFIED_COMPRESSED 
AUX_LUMA_RAW 
AUX_LUMA_RECTIFIED_RAW 
AUX_CHROMA_RAW 
AUX_CHROMA_RECTIFIED_RAW 
AUX_RAW 
AUX_RECTIFIED_RAW 
COST_RAW 
IMU 

Definition at line 83 of file MultiSenseTypes.hh.

◆ Status

enum multisense::Status : uint8_t
strong
Enumerator
UNKNOWN 
OK 
TIMEOUT 
INTERNAL_ERROR 
FAILED 
UNSUPPORTED 
EXCEPTION 
UNINITIALIZED 
INCOMPLETE_APPLICATION 

Definition at line 67 of file MultiSenseTypes.hh.

Function Documentation

◆ create_bgr_from_ycbcr420()

MULTISENSE_API std::optional<Image> multisense::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.

◆ create_bgr_image()

MULTISENSE_API std::optional<Image> multisense::create_bgr_image ( const ImageFrame frame,
const DataSource output_source 
)

Convert a YCbCr420 luma + chroma image into a BGR color image.

◆ create_color_pointcloud() [1/2]

template<typename Color >
MULTISENSE_API std::optional<PointCloud<Color> > multisense::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 at line 126 of file MultiSenseUtilities.hh.

◆ create_color_pointcloud() [2/2]

template<typename Color >
MULTISENSE_API std::optional<PointCloud<Color> > multisense::create_color_pointcloud ( const ImageFrame frame,
double  max_range,
const DataSource color_source = DataSource::UNKNOWN,
const DataSource disparity_source = DataSource::LEFT_DISPARITY_RAW 
)

Create a point cloud from a image frame and a color source.

Definition at line 240 of file MultiSenseUtilities.hh.

◆ create_depth_image()

MULTISENSE_API std::optional<Image> multisense::create_depth_image ( const ImageFrame frame,
const Image::PixelFormat depth_format,
const DataSource disparity_source = DataSource::LEFT_DISPARITY_RAW,
float  invalid_value = 0 
)

Create a depth image from a image frame.

Parameters
depth_formatSupported formats include MONO16 and FLOAT32. Note MONO16 will be quantized to millimeters)
invalid_valueThe value to set invalid depth measurements to. (i.e. points where disparity = 0)

◆ create_pointcloud()

MULTISENSE_API std::optional<PointCloud<void> > multisense::create_pointcloud ( const ImageFrame frame,
double  max_range,
const DataSource disparity_source = DataSource::LEFT_DISPARITY_RAW 
)

◆ NLOHMANN_JSON_SERIALIZE_ENUM()

multisense::NLOHMANN_JSON_SERIALIZE_ENUM ( Status  ,
{ {Status::UNKNOWN, "UNKNOWN"}, {Status::OK, "OK"}, {Status::TIMEOUT, "TIMEOUT"}, {Status::INTERNAL_ERROR, "INTERNAL_ERROR"}, {Status::FAILED, "FAILED"}, {Status::UNSUPPORTED, "UNSUPPORTED"}, {Status::EXCEPTION, "EXCEPTION"}, {Status::UNINITIALIZED, "UNINITIALIZED"}, {Status::INCOMPLETE_APPLICATION, "INCOMPLETE_APPLICATION"} }   
)

◆ to_string()

MULTISENSE_API std::string multisense::to_string ( const Status status)

Convert a status object to a user readable string.

◆ write_image()

MULTISENSE_API bool multisense::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

◆ write_pointcloud_ply()

template<typename Color >
MULTISENSE_API bool multisense::write_pointcloud_ply ( const PointCloud< Color > &  point_cloud,
const std::filesystem::path &  path 
)

Write a point cloud to a ASCII ply file.

Definition at line 276 of file MultiSenseUtilities.hh.