Public Member Functions | Public Attributes | List of all members
CameraParameters Struct Reference

#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::VirtualObjectHandlervirtualObjectHandler = nullptr
 
bool waitForCamera = false
 
std::string wristFrame
 

Detailed Description

The camera parameters that can be used for different camera types (Monocular, Stereo and StructuredLight).

Definition at line 175 of file camera.h.

Constructor & Destructor Documentation

◆ CameraParameters()

CameraParameters::CameraParameters ( ensenso::ros::NodeHandle nh,
std::string const &  cameraType,
std::string  serial 
)

Definition at line 19 of file camera.cpp.

Member Data Documentation

◆ cameraFrame

std::string CameraParameters::cameraFrame

The tf frame in which the data is captured by the camera.

Definition at line 206 of file camera.h.

◆ captureTimeout

int CameraParameters::captureTimeout = 0

Optional capture timeout for a stereo camera.

Definition at line 245 of file camera.h.

◆ fileCameraPath

std::string CameraParameters::fileCameraPath

The path to the data of the file camera.

Definition at line 191 of file camera.h.

◆ fixed

bool CameraParameters::fixed = false

Whether the camera is fixed in the world or moves with a robot.

Definition at line 196 of file camera.h.

◆ isFileCamera

bool CameraParameters::isFileCamera = false

Whether the camera is a file camera.

Definition at line 186 of file camera.h.

◆ linkFrame

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.

Definition at line 219 of file camera.h.

◆ robotFrame

std::string CameraParameters::robotFrame

Optional tf frame of the robot's base for a hand-eye calibration of a stereo camera. For a fixed camera, this defaults to cameraFrame, for a moving camera it needs to be specified if you want to perform a hand-eye calibration.

Definition at line 234 of file camera.h.

◆ serial

std::string CameraParameters::serial

The camera serial.

Definition at line 180 of file camera.h.

◆ targetFrame

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.

Definition at line 227 of file camera.h.

◆ virtualObjectHandler

std::unique_ptr<ensenso_camera::VirtualObjectHandler> CameraParameters::virtualObjectHandler = nullptr

Optional VirtualObjectHandler for a stereo camera.

Definition at line 250 of file camera.h.

◆ waitForCamera

bool CameraParameters::waitForCamera = false

Whether the node should wait for the camera to become available.

Definition at line 201 of file camera.h.

◆ wristFrame

std::string CameraParameters::wristFrame

Optional tf frame of the robot's wrist for a hand-eye calibration of a stereo camera. For a moving camera, this defaults to cameraFrame, for a fixed camera it needs to be specified if you want to perform a hand-eye calibration.

Definition at line 240 of file camera.h.


The documentation for this struct was generated from the following files:


ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46