#include <camera.h>
Public Member Functions | |
CameraParameters (ensenso::ros::NodeHandle &nh, std::string const &cameraType, std::string serial) | |
Public Attributes | |
std::string | cameraFrame |
int | captureTimeout = 0 |
std::string | fileCameraPath |
bool | fixed = false |
bool | isFileCamera = false |
std::string | linkFrame |
std::string | robotFrame |
std::string | serial |
std::string | targetFrame |
std::unique_ptr< ensenso_camera::VirtualObjectHandler > | virtualObjectHandler = nullptr |
bool | waitForCamera = false |
std::string | wristFrame |
The camera parameters that can be used for different camera types (Monocular, Stereo and StructuredLight).
CameraParameters::CameraParameters | ( | ensenso::ros::NodeHandle & | nh, |
std::string const & | cameraType, | ||
std::string | serial | ||
) |
Definition at line 19 of file camera.cpp.
std::string CameraParameters::cameraFrame |
int CameraParameters::captureTimeout = 0 |
std::string CameraParameters::fileCameraPath |
bool CameraParameters::fixed = false |
bool CameraParameters::isFileCamera = false |
std::string CameraParameters::linkFrame |
A helper tf frame.
If the linkFrame parameter is not given, it defaults to targetFrame if targetFrame is given, otherwise linkFrame will be the same as the cameraFrame. If the linkFrame parameter is given, it represents the internal camera link, which is stored for each of the cameras in the NxLib. This camera link stores e.g. the transformation of the hand-eye calibration (fixed) from the camera to the robot base. It can also store a transformation to another camera or the transformation to the workspace, which is received by a workspace calibration. This internal camera link is static and will be published with tf.
std::string CameraParameters::robotFrame |
std::string CameraParameters::targetFrame |
The tf frame in which the user wants to receive the data from the camera. All data is automatically transformed using the current tf transformation between linkFrame and targetFrame (this includes the point cloud as well as poses of calibration patterns). If neither the linkFrame nor the targetFrame parameter is given, it defaults to the cameraFrame. If the linkFrame but not the targetFrame is given, it defaults to the linkFrame.
std::unique_ptr<ensenso_camera::VirtualObjectHandler> CameraParameters::virtualObjectHandler = nullptr |
bool CameraParameters::waitForCamera = false |
std::string CameraParameters::wristFrame |