Namespace trifinger_cameras

namespace trifinger_cameras

Functions

std::ostream &operator<<(std::ostream &os, const CameraParameters &cp)
bool readCalibrationYml(std::istream &in, std::string &camera_name, CameraParameters &cam_info)

Read calibration parameters from a YAML file.

Parameters:
  • in – Input stream to read from

  • camera_name[out] Name of the camera

  • cam_info[out] Camera parameters

bool readCalibrationYml(const std::string &file_name, std::string &camera_name, CameraParameters &cam_info)

Read calibration parameters from a YAML file.

Parameters:
  • file_name – File to read

  • camera_name[out] Name of the camera

  • cam_info[out] Camera parameters

void pylon_connect(std::string_view device_user_id, Pylon::CInstantCamera *camera)

Connect to Pylon camera.

Parameters:
  • device_user_id – The user-defined name of the camera. Can be set with the executable pylon_write_device_user_id_to_camera. Pass empty string to simply connect to the first camera found.

  • camera – Pointer to the Pylon::CInstantCamera instance to which the camera will be attached.

struct CameraObservation

Observation structure to store cv::Mat images with corresponding timestamps.

Public Functions

inline CameraObservation()
template<class Archive>
inline void serialize(Archive &archive)
inline CameraObservation()
template<class Archive>
inline void serialize(Archive &archive)

Public Members

cv::Mat image
double timestamp

Public Static Attributes

static constexpr size_t width = 270
static constexpr size_t height = 270
struct CameraParameters

Subclassed by trifinger_cameras::CameraInfo, trifinger_cameras::CameraInfo

Public Functions

template<class Archive>
inline void serialize(Archive &archive)
template<class Archive>
inline void serialize(Archive &archive)

Public Members

unsigned int image_width
unsigned int image_height
Eigen::Matrix3d camera_matrix
Eigen::Matrix<double, 1, 5> distortion_coefficients
Eigen::Matrix4d tf_world_to_camera
struct CameraInfo : public trifinger_cameras::CameraParameters, public trifinger_cameras::CameraParameters

Public Functions

template<class Archive>
inline void serialize(Archive &archive)
template<class Archive>
inline void serialize(Archive &archive)

Public Members

float frame_rate_fps
struct TriCameraInfo

Public Functions

TriCameraInfo() = default
inline TriCameraInfo(CameraInfo camera1, CameraInfo camera2, CameraInfo camera3)
template<class Archive>
inline void serialize(Archive &archive)
TriCameraInfo() = default
inline TriCameraInfo(CameraInfo camera1, CameraInfo camera2, CameraInfo camera3)
template<class Archive>
inline void serialize(Archive &archive)

Public Members

std::array<CameraInfo, 3> camera
class OpenCVDriver : public robot_interfaces::SensorDriver<CameraObservation, CameraInfo>, public robot_interfaces::SensorDriver<CameraObservation, CameraInfo>
#include <opencv_driver.hpp>

Driver for interacting with any camera using OpenCV.

Public Functions

OpenCVDriver(int device_id)
CameraObservation get_observation()

Grab a single frame along with its timestamp.

Returns:

Image frame consisting of an image matrix and the time at which it was grabbed.

OpenCVDriver(int device_id)
CameraObservation get_observation()

Grab a single frame along with its timestamp.

Returns:

Image frame consisting of an image matrix and the time at which it was grabbed.

class PyBulletTriCameraDriver : public robot_interfaces::SensorDriver<TriCameraObservation, TriCameraInfo>, public robot_interfaces::SensorDriver<TriCameraObservation, TriCameraInfo>

Driver to get rendered camera images from pyBullet.

Public Functions

PyBulletTriCameraDriver(robot_interfaces::TriFingerTypes::BaseDataPtr robot_data, bool render_images = true, Settings settings = Settings())
TriCameraInfo get_sensor_info() override

Get the camera parameters (image size and calibration coefficients).

Important: The calibration coefficients are only set if the driver is initialized with rendering enabled. Otherwise, they will be all zero.

trifinger_cameras::TriCameraObservation get_observation() override

Get the latest observation from the three cameras.

Returns:

TricameraObservation

PyBulletTriCameraDriver(robot_interfaces::TriFingerTypes::BaseDataPtr robot_data, bool render_images = true, Settings settings = Settings())
TriCameraInfo get_sensor_info() override

Get the camera parameters (image size and calibration coefficients).

Important: The calibration coefficients are only set if the driver is initialized with rendering enabled. Otherwise, they will be all zero.

trifinger_cameras::TriCameraObservation get_observation() override

Get the latest observation from the three cameras.

Returns:

TricameraObservation

class PylonDriver : public robot_interfaces::SensorDriver<CameraObservation, CameraInfo>, public robot_interfaces::SensorDriver<CameraObservation, CameraInfo>
#include <pylon_driver.hpp>

Driver for interacting with a camera via Pylon and storing images using OpenCV.

Public Functions

PylonDriver(const std::string &device_user_id, bool downsample_images = true, Settings settings = Settings())

Connect to camera based on name.

When using this constructor, the camera calibration coefficients returned by get_sensor_info will be set to zero.

Parameters:
  • device_user_id – “DeviceUserID” of the camera. Pass empty string to connect to first camera found (useful if only one camera is connected).

  • downsample_images – If set to true (default), images are downsampled to half their original size.

  • settingsSettings for the camera.

PylonDriver(const std::filesystem::path &camera_calibration_file, bool downsample_images = true, Settings settings = Settings())

Connect to camera based on calibration file.

The provided calibration file is expected to be in YAML format and contain the “camera_name” (= DeviceUserID) as well as calibration coefficients. The latter will be used in the CameraInfo returned by get_sensor_info.

Parameters:
  • camera_calibration_file – Path to the camera calibration file.

  • downsample_images – If set to true (default), images are downsampled to half their original size.

  • settingsSettings for the camera.

~PylonDriver()
virtual CameraInfo get_sensor_info() override

Get the camera parameters (image size and calibration coefficients).

Important: The calibration coefficients are only set if the driver is initialized with a calibration file (see constructor). Otherwise, they will be empty.

virtual CameraObservation get_observation() override

Get the latest observation (image frame + timestamp of when the frame’s grabbed).

Returns:

CameraObservation

PylonDriver(const std::string &device_user_id, bool downsample_images = true, Settings settings = Settings())

Connect to camera based on name.

When using this constructor, the camera calibration coefficients returned by get_sensor_info will be set to zero.

Parameters:
  • device_user_id – “DeviceUserID” of the camera. Pass empty string to connect to first camera found (useful if only one camera is connected).

  • downsample_images – If set to true (default), images are downsampled to half their original size.

  • settingsSettings for the camera.

PylonDriver(const std::filesystem::path &camera_calibration_file, bool downsample_images = true, Settings settings = Settings())

Connect to camera based on calibration file.

The provided calibration file is expected to be in YAML format and contain the “camera_name” (= DeviceUserID) as well as calibration coefficients. The latter will be used in the CameraInfo returned by get_sensor_info.

Parameters:
  • camera_calibration_file – Path to the camera calibration file.

  • downsample_images – If set to true (default), images are downsampled to half their original size.

  • settingsSettings for the camera.

~PylonDriver()
virtual CameraInfo get_sensor_info() override

Get the camera parameters (image size and calibration coefficients).

Important: The calibration coefficients are only set if the driver is initialized with a calibration file (see constructor). Otherwise, they will be empty.

virtual CameraObservation get_observation() override

Get the latest observation (image frame + timestamp of when the frame’s grabbed).

Returns:

CameraObservation

Public Static Functions

static cv::Mat downsample_raw_image(const cv::Mat &image)

Downsample raw Bayer pattern by factor 2.

Downsample a raw image by factor two, preserving the Bayer pattern.

Parameters:

image – Original image.

Returns:

Downsampled image.

static cv::Mat downsample_raw_image(const cv::Mat &image)

Downsample raw Bayer pattern by factor 2.

Downsample a raw image by factor two, preserving the Bayer pattern.

Parameters:

image – Original image.

Returns:

Downsampled image.

struct PylonDriverSettings
#include <settings.hpp>

Settings of the PylonDriver.

Public Members

std::string pylon_settings_file

Path to the file with the settings that are sent to the Pylon camera.

Public Static Functions

static std::shared_ptr<PylonDriverSettings> load_from_toml(const toml::table &config)

Load from TOML table, using default values for unspecified parameters.

static std::shared_ptr<PylonDriverSettings> load_from_toml(const toml::table &config)

Load from TOML table, using default values for unspecified parameters.

Public Static Attributes

static constexpr std::string_view CONFIG_SECTION = "pylon_driver"

Name of the corresponding section in the config file.

struct TriCameraDriverSettings
#include <settings.hpp>

Settings of the TriCameraDriver.

Public Members

float frame_rate_fps

Frame rate at which images are fetched from the camera.

Important: This must not be higher than AcquisitionFrameRate which is defined in the Pylon settings file.

Public Static Functions

static std::shared_ptr<TriCameraDriverSettings> load_from_toml(const toml::table &config)

Load from TOML table, using default values for unspecified parameters.

static std::shared_ptr<TriCameraDriverSettings> load_from_toml(const toml::table &config)

Load from TOML table, using default values for unspecified parameters.

Public Static Attributes

static constexpr std::string_view CONFIG_SECTION = "tricamera_driver"

Name of the corresponding section in the config file.

class Settings
#include <settings.hpp>

Central class for loading settings.

Central facility to load settings for this package from a TOML file.

For information about the config file format, see Configuration.

Constructing the class will parse the TOML file but actual settings objects for the different modules are only created when the corresponding getter is called the first time.

Public Functions

Settings()

Load configuration from file specified via environment variable.

If the environment variable TRIFINGER_CAMERA_CONFIG is defined, it is expected to contain the path to the configuration file, which is then loaded. If it is not defined, default values are used for all parameters.

Settings(const std::filesystem::path &file)

Load configuration from the specified file.

std::shared_ptr<const PylonDriverSettings> get_pylon_driver_settings()

Get settings for the PylonDriver.

std::shared_ptr<const TriCameraDriverSettings> get_tricamera_driver_settings()

Get settings for the TriCameraDriver.

Settings()

Load configuration from file specified via environment variable.

If the environment variable TRIFINGER_CAMERA_CONFIG is defined, it is expected to contain the path to the configuration file, which is then loaded. If it is not defined, default values are used for all parameters.

Settings(const std::filesystem::path &file)

Load configuration from the specified file.

std::shared_ptr<const PylonDriverSettings> get_pylon_driver_settings()

Get settings for the PylonDriver.

std::shared_ptr<const TriCameraDriverSettings> get_tricamera_driver_settings()

Get settings for the TriCameraDriver.

Public Static Attributes

static constexpr std::string_view ENV_VARIABLE_CONFIG_FILE = "TRIFINGER_CAMERA_CONFIG"

Name of the environment variable to specify the config file path.

class TriCameraDriver : public robot_interfaces::SensorDriver<TriCameraObservation, TriCameraInfo>, public robot_interfaces::SensorDriver<TriCameraObservation, TriCameraInfo>

Driver to create three instances of the PylonDriver and get observations from them.

Public Functions

TriCameraDriver(const std::string &device_id_1, const std::string &device_id_2, const std::string &device_id_3, bool downsample_images = true, Settings settings = Settings())
Parameters:
  • device_id_1 – device user id of first camera

  • device_id_2 – likewise, the 2nd’s

  • device_id_3 – and the 3rd’s

  • downsample_images – If set to true (default), images are downsampled to half their original size.

  • settingsSettings for the cameras.

TriCameraDriver(const std::filesystem::path &camera_calibration_file_1, const std::filesystem::path &camera_calibration_file_2, const std::filesystem::path &camera_calibration_file_3, bool downsample_images = true, Settings settings = Settings())
Parameters:
  • camera_calibration_file_1 – Calibration file of first camera

  • camera_calibration_file_2 – likewise, the 2nd’s

  • camera_calibration_file_3 – and the 3rd’s

  • downsample_images – If set to true (default), images are downsampled to half their original size.

  • settingsSettings for the cameras.

TriCameraInfo get_sensor_info() override

Get the camera parameters (image size and calibration coefficients).

Important: The calibration coefficients are only set if the driver is initialized with calibration files (see constructor). Otherwise, they will be all zero.

TriCameraObservation get_observation() override

Get the latest observation from the three cameras.

Returns:

TricameraObservation

TriCameraDriver(const std::string &device_id_1, const std::string &device_id_2, const std::string &device_id_3, bool downsample_images = true, Settings settings = Settings())
Parameters:
  • device_id_1 – device user id of first camera

  • device_id_2 – likewise, the 2nd’s

  • device_id_3 – and the 3rd’s

  • downsample_images – If set to true (default), images are downsampled to half their original size.

  • settingsSettings for the cameras.

TriCameraDriver(const std::filesystem::path &camera_calibration_file_1, const std::filesystem::path &camera_calibration_file_2, const std::filesystem::path &camera_calibration_file_3, bool downsample_images = true, Settings settings = Settings())
Parameters:
  • camera_calibration_file_1 – Calibration file of first camera

  • camera_calibration_file_2 – likewise, the 2nd’s

  • camera_calibration_file_3 – and the 3rd’s

  • downsample_images – If set to true (default), images are downsampled to half their original size.

  • settingsSettings for the cameras.

TriCameraInfo get_sensor_info() override

Get the camera parameters (image size and calibration coefficients).

Important: The calibration coefficients are only set if the driver is initialized with calibration files (see constructor). Otherwise, they will be all zero.

TriCameraObservation get_observation() override

Get the latest observation from the three cameras.

Returns:

TricameraObservation

Public Members

std::chrono::milliseconds rate

Rate at which images are acquired.

struct TriCameraObservation

An array of three CameraObservation(s)

Public Functions

template<class Archive>
inline void serialize(Archive &archive)
template<class Archive>
inline void serialize(Archive &archive)

Public Members

std::array<CameraObservation, 3> cameras