Class trifinger_cameras::TriCameraDriver¶
- 
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 = false, 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 – Not supported anymore. Must be to - false.
- settings – Settings 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 = false, 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 – Not supported anymore. Must be to - false.
- settings – Settings 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 = false, 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 – Not supported anymore. Must be to - false.
- settings – Settings 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 = false, 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 – Not supported anymore. Must be to - false.
- settings – Settings 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. 
 
- 
TriCameraDriver(const std::string &device_id_1, const std::string &device_id_2, const std::string &device_id_3, bool downsample_images = false, Settings settings = Settings())¶