class
YarpCameraBridgeYarpCameraBridge Yarp implementation of the ICameraBridge interface Currently available interfaces.
- Depth Cameras through RGBD sensor interface
- Camera images through OpenCV Grabber interface
The YarpCameraBridge expects a list of device drivers through the yarp::dev::PolyDriverList object. Each PolyDriver object in the list is compared with the configured sensor names and the assumptions listed below to infer the sensor types and relevant interfaces in order to to read the relevant data.
MAJOR ASSUMPTIONS
- Every sensor unit(device driver) attached to this Bridge is identified by a unique name
- The images are available through a FrameGrabber interface (RGB only) and a RGBD interface (RGB and Depth).
- The current internal design (read all sensors in a serial fashion) may not be suitable for a heavy measurement set
The parameters for writing the configuration file for this class is given as,
Group | Parameter | Type | Description | Mandatory |
---|---|---|---|---|
Cameras | Expects cameras to be opened either as remote frame grabber ("RemoteFrameGrabber") with IFrameGrabber interface or rgbd sensor ("RGBDSensorClient") with IRGBDSensor interface | Yes | ||
rgbd_cameras_list | vector of strings | list containing the devices opened as RGBDSensorClients containing the IRGBD sensor interface | Yes | |
rgbd_image_width | vector of integers | list containing the image width dimensions of RGBD cameras. The list must be the same size and order as rgbd_list. If not provided, the size of the image is taken from the YarpInterface after calling YarpCameraBridge:: | No | |
rgbd_image_height | vector of integers | list containing the image height dimensions of RGBD cameras. The list must be the same size and order as rgbd_list. If not provided the size of the image is taken from the YarpInterface after calling YarpCameraBridge:: | No | |
rgb_cameras_list | vector of strings | list containing the devices opened as RemoteFrameGrabber devices containing the IFrameGrabber interface | Yes | |
rgb_image_width | vector of integers | list containing the image width dimensions of RGB cameras. The list must be the same size and order as rgb_list. If not provided the size of the image is taken from the YarpInterface after calling YarpCameraBridge:: | No | |
rgb_image_height | vector of integers | list containing the image height dimensions of RGB cameras. The list must be the same size and order as rgb_list. If not provided the size of the image is taken from the YarpInterface after calling YarpCameraBridge:: | No |
Base classes
- class ICameraBridge
- Sensor bridge interface.
Constructors, destructors, conversion operators
- YarpCameraBridge()
- Constructor.
- ~YarpCameraBridge()
- Destructor.
Public functions
-
auto initialize(std::weak_ptr<const BipedalLocomotion::
ParametersHandler:: IParametersHandler> handler) -> bool final - Initialize estimator.
- auto setDriversList(const yarp::dev::PolyDriverList& deviceDriversList) -> bool
- Set the list of device drivers from which the sensor measurements need to be streamed.
- auto isValid() const -> bool final
- Determines the validity of the object retrieved with getMetadata()
-
auto get() const -> const BipedalLocomotion::
RobotInterface:: CameraBridgeMetaData& - Get the object.
-
auto getMetaData() const -> const BipedalLocomotion::
RobotInterface:: CameraBridgeMetaData& final - Get the stored metadata.
- 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 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.
Function documentation
bool BipedalLocomotion:: RobotInterface:: YarpCameraBridge:: initialize(std::weak_ptr<const BipedalLocomotion:: ParametersHandler:: IParametersHandler> handler) final
Initialize estimator.
Parameters | |
---|---|
handler in | Parameters handler |
bool BipedalLocomotion:: RobotInterface:: YarpCameraBridge:: setDriversList(const yarp::dev::PolyDriverList& deviceDriversList)
Set the list of device drivers from which the sensor measurements need to be streamed.
Parameters | |
---|---|
deviceDriversList | device drivers holding the pointer to sensor interfaces |
Returns | True/False in case of success/failure. |
bool BipedalLocomotion:: RobotInterface:: YarpCameraBridge:: isValid() const final
Determines the validity of the object retrieved with getMetadata()
Returns | True if the object is valid, false otherwise. |
---|
const BipedalLocomotion:: RobotInterface:: CameraBridgeMetaData& BipedalLocomotion:: RobotInterface:: YarpCameraBridge:: get() const
Get the object.
Returns | a const reference of the requested object. |
---|
const BipedalLocomotion:: RobotInterface:: CameraBridgeMetaData& BipedalLocomotion:: RobotInterface:: YarpCameraBridge:: getMetaData() const final
Get the stored metadata.
Returns | a const reference to the metadata |
---|
bool BipedalLocomotion:: RobotInterface:: YarpCameraBridge:: 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:: RobotInterface:: YarpCameraBridge:: getRGBDCamerasList(std::vector<std::string>& rgbdCamerasList) final
Get RGBD cameras.
Parameters | |
---|---|
rgbdCamerasList out | list of depth cameras attached to the bridge |
Returns | true/false in case of success/failure |
bool BipedalLocomotion:: RobotInterface:: YarpCameraBridge:: 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:: RobotInterface:: YarpCameraBridge:: 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 gyroscope |
depthImg out | depth image as cv Mat object |
receiveTimeInSeconds out | time at which the measurement was received |
Returns | true/false in case of success/failure |