class
ICameraBridgeSensor bridge interface.
Derived classes
- class BipedalLocomotion::Perception::Capture::RealSense
- Realsense driver class.
- class YarpCameraBridge
- YarpCameraBridge Yarp implementation of the ICameraBridge interface Currently available interfaces.
Public types
- using unique_ptr = std::unique_ptr<ICameraBridge>
- using shared_ptr = std::shared_ptr<ICameraBridge>
- using weak_ptr = std::weak_ptr<ICameraBridge>
Constructors, destructors, conversion operators
- ~ICameraBridge() defaulted virtual
- Destructor.
Public functions
-
auto initialize(std::weak_ptr<const ParametersHandler::
IParametersHandler> handler) -> bool pure virtual - Initialize estimator.
- auto getRGBCamerasList(std::vector<std::string>& rgbCamerasList) -> bool virtual
- Get rgb cameras.
- auto getRGBDCamerasList(std::vector<std::string>& rgbdCamerasList) -> bool virtual
- Get RGBD cameras.
- auto getColorImage(const std::string& camName, cv::Mat& colorImg, std::optional<std::reference_wrapper<double>> receiveTimeInSeconds = {}) -> bool virtual
- Get color image from the camera.
- auto getDepthImage(const std::string& camName, cv::Mat& depthImg, std::optional<std::reference_wrapper<double>> receiveTimeInSeconds = {}) -> bool virtual
- Get depth image.
- auto getMetaData() const -> const CameraBridgeMetaData& pure virtual
- Get the stored metadata.
- auto isValid() const -> bool pure virtual
- Determines the validity of the object retrieved with getMetadata()
Protected functions
-
auto populateCameraBridgeOptionsFromConfig(std::weak_ptr<BipedalLocomotion::
ParametersHandler:: IParametersHandler> handler, CameraBridgeOptions& cameraBridgeOptions) -> bool virtual - Helper method to maintain CameraBridgeOptions struct by populating it from the configuration parameters.
-
auto populateCameraListsFromConfig(std::weak_ptr<BipedalLocomotion::
ParametersHandler:: IParametersHandler> handler, const CameraBridgeOptions& cameraBridgeOptions, CameraLists& cameraLists) -> bool virtual - Helper method to maintain CameraLists struct by populating it from the configuration parameters.
-
auto populateCameraBridgeMetaDataFromConfig(std::weak_ptr<BipedalLocomotion::
ParametersHandler:: IParametersHandler> handler, CameraBridgeMetaData& cameraBridgeMetaData) -> bool virtual - Helper method to maintain CameraBridgeMetaData struct by populating it from the configuration parameters.
Function documentation
bool BipedalLocomotion:: RobotInterface:: ICameraBridge:: initialize(std::weak_ptr<const ParametersHandler:: IParametersHandler> handler) pure virtual
Initialize estimator.
Parameters | |
---|---|
handler in | Parameters handler |
bool BipedalLocomotion:: RobotInterface:: ICameraBridge:: getRGBCamerasList(std::vector<std::string>& rgbCamerasList) virtual
Get rgb cameras.
Parameters | |
---|---|
rgbCamerasList out | list of rgb cameras attached to the bridge |
Returns | true/false in case of success/failure |
bool BipedalLocomotion:: RobotInterface:: ICameraBridge:: getRGBDCamerasList(std::vector<std::string>& rgbdCamerasList) virtual
Get RGBD cameras.
Parameters | |
---|---|
rgbdCamerasList out | list of rgbd cameras attached to the bridge |
Returns | true/false in case of success/failure |
bool BipedalLocomotion:: RobotInterface:: ICameraBridge:: getColorImage(const std::string& camName,
cv::Mat& colorImg,
std::optional<std::reference_wrapper<double>> receiveTimeInSeconds = {}) virtual
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:: RobotInterface:: ICameraBridge:: getDepthImage(const std::string& camName,
cv::Mat& depthImg,
std::optional<std::reference_wrapper<double>> receiveTimeInSeconds = {}) virtual
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 CameraBridgeMetaData& BipedalLocomotion:: RobotInterface:: ICameraBridge:: getMetaData() const pure virtual
Get the stored metadata.
Returns | a const reference to the metadata |
---|
bool BipedalLocomotion:: RobotInterface:: ICameraBridge:: isValid() const pure virtual
Determines the validity of the object retrieved with getMetadata()
Returns | True if the object is valid, false otherwise. |
---|
bool BipedalLocomotion:: RobotInterface:: ICameraBridge:: populateCameraBridgeOptionsFromConfig(std::weak_ptr<BipedalLocomotion:: ParametersHandler:: IParametersHandler> handler,
CameraBridgeOptions& cameraBridgeOptions) virtual protected
Helper method to maintain CameraBridgeOptions struct by populating it from the configuration parameters.
Parameters | |
---|---|
handler in | Parameters handler |
cameraBridgeOptions in | CameraBridgeOptions to hold the bridge options for streaming sensor measurements |
bool BipedalLocomotion:: RobotInterface:: ICameraBridge:: populateCameraListsFromConfig(std::weak_ptr<BipedalLocomotion:: ParametersHandler:: IParametersHandler> handler,
const CameraBridgeOptions& cameraBridgeOptions,
CameraLists& cameraLists) virtual protected
Helper method to maintain CameraLists struct by populating it from the configuration parameters.
Parameters | |
---|---|
handler in | Parameters handler |
cameraBridgeOptions in | configured object of CameraBridgeOptions |
cameraLists in | CameraLists object holding list of connected sensor devices |
bool BipedalLocomotion:: RobotInterface:: ICameraBridge:: populateCameraBridgeMetaDataFromConfig(std::weak_ptr<BipedalLocomotion:: ParametersHandler:: IParametersHandler> handler,
CameraBridgeMetaData& cameraBridgeMetaData) virtual protected
Helper method to maintain CameraBridgeMetaData struct by populating it from the configuration parameters.
Parameters | |
---|---|
handler in | Parameters handler |
cameraBridgeMetaData |