BipedalLocomotion::Perception::Capture::RealSense class

Realsense driver class.

The following parameters are required to initialize the class

Parameter NameTypeDescriptionMandatoryDefault Value
camera_namestringname of the camera deviceNoRealSense
frame_widthsize_timage frame widthNo640
frame_heightsize_timage frame heightNo480
fpsbooleanframes per secondNo30
stream_colorbooleanflag to enable streaming BGR imagesNofalse
stream_depthbooleanflag to enable streaming depth imagesNofalse
stream_irbooleanflag to enable streaming IR imagesNofalse
stream_pclbooleanflag to enable streaming pointcloudNofalse
align_frames_to_colorbooleanflag to align other images to BGR imagesNofalse

Base classes

class BipedalLocomotion::RobotInterface::ICameraBridge
Sensor bridge interface.
class BipedalLocomotion::RobotInterface::IPointCloudBridge
Sensor bridge interface.

Constructors, destructors, conversion operators

RealSense()
~RealSense()

Public functions

auto initialize(std::weak_ptr<const BipedalLocomotion::ParametersHandler::IParametersHandler> handler) -> bool final
Initialize estimator.
auto isValid() const -> bool final
Determines the validity of the object retrieved with getMetadata()
auto getRGBCamerasList(std::vector<std::string>& rgbCamerasList) -> bool final
Get rgb cameras.
auto getRGBDCamerasList(std::vector<std::string>& rgbdCamerasList) -> bool final
Get RGBD cameras.
auto getPCLDevicesList(std::vector<std::string>& pclDevList) -> bool final
Get RGBD cameras.
auto getColorImage(const std::string& camName, cv::Mat& colorImg, std::optional<std::reference_wrapper<double>> receiveTimeInSeconds = {}) -> bool final
Get color image from the camera.
auto getDepthImage(const std::string& camName, cv::Mat& depthImg, std::optional<std::reference_wrapper<double>> receiveTimeInSeconds = {}) -> bool final
Get depth image.
auto getColorizedDepthImage(const std::string& camName, cv::Mat& depthImg, std::optional<std::reference_wrapper<double>> receiveTimeInSeconds = {}) -> bool
auto getInfraredImage(const std::string& camName, cv::Mat& irImage, std::optional<std::reference_wrapper<double>> receiveTimeInSeconds = {}) -> bool
auto getPointCloud(const std::string& pclDevName, pcl::PointCloud<pcl::PointXYZRGB>::Ptr coloredPointCloud, std::optional<std::reference_wrapper<double>> receiveTimeInSeconds = {}) -> bool final
auto getMetaData() const -> const BipedalLocomotion::RobotInterface::CameraBridgeMetaData& final
Get the stored metadata.

Function documentation

bool BipedalLocomotion::Perception::Capture::RealSense::initialize(std::weak_ptr<const BipedalLocomotion::ParametersHandler::IParametersHandler> handler) final

Initialize estimator.

Parameters
handler in Parameters handler

bool BipedalLocomotion::Perception::Capture::RealSense::isValid() const final

Determines the validity of the object retrieved with getMetadata()

Returns True if the object is valid, false otherwise.

bool BipedalLocomotion::Perception::Capture::RealSense::getRGBCamerasList(std::vector<std::string>& rgbCamerasList) final

Get rgb cameras.

Parameters
rgbCamerasList out list of rgb cameras attached to the bridge
Returns true/false in case of success/failure

bool BipedalLocomotion::Perception::Capture::RealSense::getRGBDCamerasList(std::vector<std::string>& rgbdCamerasList) final

Get RGBD cameras.

Parameters
rgbdCamerasList out list of rgbd cameras attached to the bridge
Returns true/false in case of success/failure

bool BipedalLocomotion::Perception::Capture::RealSense::getPCLDevicesList(std::vector<std::string>& pclDevList) final

Get RGBD cameras.

Returns true/false in case of success/failure

bool BipedalLocomotion::Perception::Capture::RealSense::getColorImage(const std::string& camName, cv::Mat& colorImg, std::optional<std::reference_wrapper<double>> receiveTimeInSeconds = {}) final

Get color image from the camera.

Parameters
camName in name of the camera
colorImg out image as cv Mat object
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

bool BipedalLocomotion::Perception::Capture::RealSense::getDepthImage(const std::string& camName, cv::Mat& depthImg, std::optional<std::reference_wrapper<double>> receiveTimeInSeconds = {}) final

Get depth image.

Parameters
camName in name of the camera
depthImg out depth image as a cv Mat object
receiveTimeInSeconds out time at which the measurement was received
Returns true/false in case of success/failure

const BipedalLocomotion::RobotInterface::CameraBridgeMetaData& BipedalLocomotion::Perception::Capture::RealSense::getMetaData() const final

Get the stored metadata.

Returns a const reference to the metadata