![]() |
LibMultiSense
LibMultiSense Documentation
|
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 | ImageHistogram |
| A object containing histogram data for a image. 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... | |
| class | MultiChannelSynchronizer |
| Helper class which provides a interface to synchronize data across multiple channels. 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 | Pixel |
| Pixel coordinates in a image. 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 |
| A pointcloud containing a collection of colorized points. More... | |
| class | QMatrix |
| struct | StereoCalibration |
Typedefs | |
| using | TimeT = std::chrono::time_point< std::chrono::system_clock, std::chrono::nanoseconds > |
Enumerations | |
| enum class | Status : uint8_t { UNKNOWN , OK , TIMEOUT , INTERNAL_ERROR , FAILED , UNSUPPORTED , EXCEPTION , UNINITIALIZED , INCOMPLETE_APPLICATION } |
| enum class | DataSource : uint16_t { 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 } |
| Identifies which camera or data source the image is from. More... | |
| enum class | ColorImageEncoding : uint16_t { NONE , YCBCR420 } |
Functions | |
| MULTISENSE_API bool | frames_synchronized (const std::vector< ImageFrame > &frames, const std::chrono::nanoseconds &tolerance) |
| Free function which determines if a collection of frames are synchronized within a given tolerance. | |
| 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. | |
| MULTISENSE_API bool | write_image (const Image &image, const std::filesystem::path &path) |
| Write a image to a specific path on disk. | |
| MULTISENSE_API std::optional< Image > | create_depth_image (const ImageFrame &frame, const Image::PixelFormat &depth_format, const DataSource &disparity_source=DataSource::LEFT_DISPARITY_RAW, bool compute_in_aux_frame=false, float invalid_value=0) |
| Create a depth image from a image frame. | |
| MULTISENSE_API std::optional< Point< void > > | get_aux_3d_point (const ImageFrame &frame, const Pixel &rectified_aux_pixel, size_t max_pixel_search_window, double pixel_epsilon, const DataSource &disparity_source=DataSource::LEFT_DISPARITY_RAW) |
| for a given pixel in the aux image, return the corresponding 3D point associated with the aux pixel | |
| MULTISENSE_API 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. | |
| MULTISENSE_API std::optional< Image > | create_bgr_image (const ImageFrame &frame, const DataSource &output_source) |
| Convert a YCbCr420 luma + chroma image into a BGR color image. | |
| 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. | |
| 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. | |
| 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 ply file. | |
| using multisense::TimeT = typedef std::chrono::time_point<std::chrono::system_clock, std::chrono::nanoseconds> |
Definition at line 66 of file MultiSenseTypes.hh.
|
strong |
| Enumerator | |
|---|---|
| NONE | |
| YCBCR420 | |
Definition at line 110 of file MultiSenseTypes.hh.
|
strong |
Identifies which camera or data source the image is from.
Definition at line 84 of file MultiSenseTypes.hh.
|
strong |
| Enumerator | |
|---|---|
| UNKNOWN | |
| OK | |
| TIMEOUT | |
| INTERNAL_ERROR | |
| FAILED | |
| UNSUPPORTED | |
| EXCEPTION | |
| UNINITIALIZED | |
| INCOMPLETE_APPLICATION | |
Definition at line 68 of file MultiSenseTypes.hh.
| 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.
| luma | The luma component (Y) of the YCbCr420 image |
| chroma | The chroma components (CbCr) of the YCbCr420 image |
| output_source | The source type to associate witht he 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.
| frame | The image frame containing the luma/chroma components of the YCbCr420 image |
| output_source | The source type to associate witht he image |
| 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.
| disparity | A disparity image to convert to a pointcloud |
| color | Optional color image to use for colorization |
| max_range | The max range in meters of a point from the camera origin to be considered valid |
| calibration | The stereo calibration used to convert disparity images to 3D, and project points into color images |
Definition at line 232 of file MultiSenseUtilities.hh.
| 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.
| frame | A frame containing images to convert to a pointcloud |
| color_source | The datasorce of the color image in the input frame |
| max_range | The max range in meters of a point from the camera origin to be considered valid |
Definition at line 335 of file MultiSenseUtilities.hh.
| 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, |
||
| bool | compute_in_aux_frame = false, |
||
| float | invalid_value = 0 |
||
| ) |
Create a depth image from a image frame.
| depth_format | Supported formats include MONO16 and FLOAT32. Note MONO16 will be quantized to millimeters) |
| compute_in_aux_frame | Compute the depth image so it's returned in the aux camera's image frame |
| invalid_value | The value to set invalid depth measurements to. (i.e. points where disparity = 0) |
| MULTISENSE_API std::optional< PointCloud< void > > multisense::create_pointcloud | ( | const ImageFrame & | frame, |
| double | max_range, | ||
| const DataSource & | disparity_source = DataSource::LEFT_DISPARITY_RAW |
||
| ) |
| MULTISENSE_API bool multisense::frames_synchronized | ( | const std::vector< ImageFrame > & | frames, |
| const std::chrono::nanoseconds & | tolerance | ||
| ) |
Free function which determines if a collection of frames are synchronized within a given tolerance.
| frames | Frames to check for synchronization |
| tolerance | The max time difference between any frames for them to be considered valid |
| MULTISENSE_API std::optional< Point< void > > multisense::get_aux_3d_point | ( | const ImageFrame & | frame, |
| const Pixel & | rectified_aux_pixel, | ||
| size_t | max_pixel_search_window, | ||
| double | pixel_epsilon, | ||
| const DataSource & | disparity_source = DataSource::LEFT_DISPARITY_RAW |
||
| ) |
for a given pixel in the aux image, return the corresponding 3D point associated with the aux pixel
| frame | The image frame which contains a disparity image |
| rectified_aux_pixel | The aux pixel to compute depth for |
| max_pixel_search_window | The maximum number of pixels to search for a corresponding valid disparity pixel. 256 is the max value |
| pixel_epsilon | The threshold, in pixels, for a disparity projection to match the aux pixel location. Values On the order of 0.5 pixels make sense here |
| 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"} } | |||
| ) |
| MULTISENSE_API std::string multisense::to_string | ( | const Status & | status | ) |
Convert a status object to a user readable string.
| 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
| image | The image to write to disk |
| path | The path to write the image to |
| MULTISENSE_API bool multisense::write_pointcloud_ply | ( | const PointCloud< Color > & | point_cloud, |
| const std::filesystem::path & | path | ||
| ) |
Write a point cloud to a ply file.
| point_cloud | The pointcloud to write to a ply file |
| path | The output path to save the ply file to |
Definition at line 375 of file MultiSenseUtilities.hh.