C++ API and example

1. Introduction

This page exist in order to extract the examples from the Doxygen documentation, Please have look at the end of this page there are all the examples.

2. C++ API and example

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 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
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.

Private Members

cv::VideoCapture video_capture_
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

Private Members

pybind11::object cameras_

Python object to access cameras in pyBullet.

pybind11::module numpy_

The numpy module.

bool render_images_

If false, no images are rendered.

Images in observations will be uninitialised.

robot_interfaces::TriFingerTypes::BaseDataPtr robot_data_

Pointer to robot data, needed for time synchronisation.

time_series::Index last_update_robot_time_index_

Last robot time index at which a camera observation was returned.

int frame_rate_in_robot_steps_

Number of robot time steps after which the next frame should be fetched.

TriCameraInfo sensor_info_ = {}

Sensor info for the cameras.

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.

Private Functions

PylonDriver(bool downsample_images, Settings settings)

Base constructor to be called by public constructors.

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

  • settingsSettings for the camera.

void init(const std::string &device_user_id)

Initialize the camera connection (to be called in the constructor).

void set_camera_configuration()
PylonDriver(bool downsample_images, Settings settings)

Base constructor to be called by public constructors.

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

  • settingsSettings for the camera.

void init(const std::string &device_user_id)

Initialize the camera connection (to be called in the constructor).

void set_camera_configuration()

Private Members

std::shared_ptr<const PylonDriverSettings> settings_
trifinger_cameras::CameraInfo camera_info_ = {}
std::string device_user_id_
const bool downsample_images_
Pylon::PylonAutoInitTerm auto_init_term_
Pylon::CInstantCamera camera_
Pylon::CImageFormatConverter format_converter_
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.

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.

Private Functions

void parse_file(const std::filesystem::path &file)
void parse_file(const std::filesystem::path &file)

Private Members

toml::table config_
std::shared_ptr<PylonDriverSettings> pylon_driver_settings_
std::shared_ptr<TriCameraDriverSettings> tricamera_driver_settings_
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.

Private Functions

void init(Settings settings)
void init(Settings settings)

Private Members

std::chrono::time_point<std::chrono::system_clock> last_update_time_
PylonDriver camera1_
PylonDriver camera2_
PylonDriver camera3_
TriCameraInfo sensor_info_ = {}
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.

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
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
namespace robot_interfaces
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.

file camera_observation.hpp
#include <opencv2/opencv.hpp>
#include <serialization_utils/cereal_cvmat.hpp>

Defines the observation structure to be used by any camera.

License:

BSD 3-clause

Copyright

2020, Max Planck Gesellschaft. All rights reserved.

file camera_observation.hpp
#include <opencv2/opencv.hpp>
#include <serialization_utils/cereal_cvmat.hpp>

Defines the observation structure to be used by any camera.

License:

BSD 3-clause

Copyright

2020, Max Planck Gesellschaft. All rights reserved.

file camera_parameters.hpp
#include <ostream>
#include <string>
#include <Eigen/Eigen>
#include <serialization_utils/cereal_eigen.hpp>

License:

BSD 3-clause

Copyright

2020 Max Planck Gesellschaft. All rights reserved.

file camera_parameters.hpp
#include <ostream>
#include <string>
#include <Eigen/Eigen>
#include <serialization_utils/cereal_eigen.hpp>

License:

BSD 3-clause

Copyright

2020 Max Planck Gesellschaft. All rights reserved.

file opencv_driver.hpp
#include <robot_interfaces/sensors/sensor_driver.hpp>
#include <trifinger_cameras/camera_observation.hpp>
#include <trifinger_cameras/camera_parameters.hpp>

Driver to interface with the camera using OpenCV.

License:

BSD 3-clause

Copyright

2020, Max Planck Gesellschaft. All rights reserved.

file opencv_driver.hpp
#include <robot_interfaces/sensors/sensor_driver.hpp>
#include <trifinger_cameras/camera_observation.hpp>
#include <trifinger_cameras/camera_parameters.hpp>

Driver to interface with the camera using OpenCV.

License:

BSD 3-clause

Copyright

2020, Max Planck Gesellschaft. All rights reserved.

file parse_yml.h
#include <istream>
#include <string>
#include <trifinger_cameras/camera_parameters.hpp>
file parse_yml.h
#include <istream>
#include <string>
#include <trifinger_cameras/camera_parameters.hpp>
file pybullet_tricamera_driver.hpp
#include <pybind11/embed.h>
#include <robot_interfaces/finger_types.hpp>
#include <robot_interfaces/sensors/sensor_driver.hpp>
#include <trifinger_cameras/camera_parameters.hpp>
#include <trifinger_cameras/settings.hpp>
#include <trifinger_cameras/tricamera_observation.hpp>

TriCameraDriver for simulation (using rendered images) cameras.

Copyright

2020, Max Planck Gesellschaft. All rights reserved.

file pybullet_tricamera_driver.hpp
#include <pybind11/embed.h>
#include <robot_interfaces/finger_types.hpp>
#include <robot_interfaces/sensors/sensor_driver.hpp>
#include <trifinger_cameras/camera_parameters.hpp>
#include <trifinger_cameras/settings.hpp>
#include <trifinger_cameras/tricamera_observation.hpp>

TriCameraDriver for simulation (using rendered images) cameras.

Copyright

2020, Max Planck Gesellschaft. All rights reserved.

file pylon_driver.hpp
#include <filesystem>
#include <pylon/PylonIncludes.h>
#include <robot_interfaces/sensors/sensor_driver.hpp>
#include <trifinger_cameras/camera_observation.hpp>
#include <trifinger_cameras/camera_parameters.hpp>
#include <trifinger_cameras/settings.hpp>

Driver to interface with the camera using Pylon.

License:

BSD 3-clause

Copyright

2020 Max Planck Gesellschaft. All rights reserved.

References- https://www.baslerweb.com/en/sales-support/downloads/document-downloads/pylon-sdk-samples-manual/ https://github.com/basler/pylon-ros-camera/blob/9f3832127fc39a2c181cbeb5257054352e2ef7fe/pylon_camera/src/pylon_camera/pylon_camera.cpp#L132

file pylon_driver.hpp
#include <filesystem>
#include <pylon/PylonIncludes.h>
#include <robot_interfaces/sensors/sensor_driver.hpp>
#include <trifinger_cameras/camera_observation.hpp>
#include <trifinger_cameras/camera_parameters.hpp>
#include <trifinger_cameras/settings.hpp>

Driver to interface with the camera using Pylon.

License:

BSD 3-clause

Copyright

2020 Max Planck Gesellschaft. All rights reserved.

References- https://www.baslerweb.com/en/sales-support/downloads/document-downloads/pylon-sdk-samples-manual/ https://github.com/basler/pylon-ros-camera/blob/9f3832127fc39a2c181cbeb5257054352e2ef7fe/pylon_camera/src/pylon_camera/pylon_camera.cpp#L132

file settings.hpp
#include <filesystem>
#include <ostream>
#include <string>
#include <ament_index_cpp/get_package_share_directory.hpp>
#include <toml++/toml.hpp>

License:

BSD 3-clause

Copyright

2020 Max Planck Gesellschaft. All rights reserved.

file settings.hpp
#include <filesystem>
#include <ostream>
#include <string>
#include <ament_index_cpp/get_package_share_directory.hpp>
#include <toml++/toml.hpp>

License:

BSD 3-clause

Copyright

2020 Max Planck Gesellschaft. All rights reserved.

file tricamera_driver.hpp
#include <array>
#include <chrono>
#include <filesystem>
#include <string>
#include <cereal/types/array.hpp>
#include <robot_interfaces/sensors/sensor_driver.hpp>
#include <trifinger_cameras/camera_parameters.hpp>
#include <trifinger_cameras/pylon_driver.hpp>
#include <trifinger_cameras/tricamera_observation.hpp>

Wrapper on the Pylon Driver to synchronise three pylon dependent cameras.

License:

BSD 3-clause

Copyright

2020, Max Planck Gesellschaft. All rights reserved.

file tricamera_driver.hpp
#include <array>
#include <chrono>
#include <filesystem>
#include <string>
#include <cereal/types/array.hpp>
#include <robot_interfaces/sensors/sensor_driver.hpp>
#include <trifinger_cameras/camera_parameters.hpp>
#include <trifinger_cameras/pylon_driver.hpp>
#include <trifinger_cameras/tricamera_observation.hpp>

Wrapper on the Pylon Driver to synchronise three pylon dependent cameras.

License:

BSD 3-clause

Copyright

2020, Max Planck Gesellschaft. All rights reserved.

file tricamera_observation.hpp
#include “camera_observation.hpp

Defines the observation structure to be used for using three pylon dependent cameras together.

License:

BSD 3-clause

Copyright

2020, Max Planck Gesellschaft. All rights reserved.

file tricamera_observation.hpp
#include “camera_observation.hpp

Defines the observation structure to be used for using three pylon dependent cameras together.

License:

BSD 3-clause

Copyright

2020, Max Planck Gesellschaft. All rights reserved.

file py_camera_types.cpp
#include <pybind11/pybind11.h>
#include <pybind11/stl/filesystem.h>
#include <pybind11_opencv/cvbind.hpp>
#include <trifinger_cameras/camera_observation.hpp>
#include <trifinger_cameras/camera_parameters.hpp>
#include <trifinger_cameras/opencv_driver.hpp>
#include <trifinger_cameras/settings.hpp>
#include <robot_interfaces/sensors/pybind_sensors.hpp>
#include <robot_interfaces/sensors/sensor_driver.hpp>

Create bindings for camera sensors.

License:

BSD 3-clause

Copyright

2020, Max Planck Gesellschaft. All rights reserved.

Functions

PYBIND11_MODULE(py_camera_types, m)
file py_tricamera_types.cpp
#include <pybind11/stl/filesystem.h>
#include <trifinger_cameras/pybullet_tricamera_driver.hpp>
#include <trifinger_cameras/tricamera_observation.hpp>
#include <robot_interfaces/sensors/pybind_sensors.hpp>
#include <robot_interfaces/sensors/sensor_driver.hpp>

Create bindings for three pylon dependent camera sensors.

License:

BSD 3-clause

Copyright

2020, Max Planck Gesellschaft. All rights reserved.

Functions

PYBIND11_MODULE(py_tricamera_types, m)
page license

File camera_observation.hpp

BSD 3-clause

File camera_observation.hpp

BSD 3-clause

File camera_parameters.hpp

BSD 3-clause

File camera_parameters.hpp

BSD 3-clause

File opencv_driver.hpp

BSD 3-clause

File opencv_driver.hpp

BSD 3-clause

File py_camera_types.cpp

BSD 3-clause

File py_tricamera_types.cpp

BSD 3-clause

File pylon_driver.hpp

BSD 3-clause

File pylon_driver.hpp

BSD 3-clause

File settings.hpp

BSD 3-clause

File settings.hpp

BSD 3-clause

File tricamera_driver.hpp

BSD 3-clause

File tricamera_driver.hpp

BSD 3-clause

File tricamera_observation.hpp

BSD 3-clause

File tricamera_observation.hpp

BSD 3-clause

dir include
dir install/trifinger_cameras/include
dir install
dir srcpy
dir include/trifinger_cameras
dir install/trifinger_cameras
dir install/trifinger_cameras/include/trifinger_cameras