Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
Camera Class Referenceabstract

#include <camera.h>

Inheritance diagram for Camera:
Inheritance graph
[legend]

Public Member Functions

 Camera (ensenso::ros::NodeHandle &nh, CameraParameters params)
 
void close ()
 
virtual void init ()=0
 
bool loadSettings (std::string const &jsonFile, bool saveAsDefaultParameters=false)
 
void onAccessTree (ensenso::action::AccessTreeGoalConstPtr const &goal)
 
void onExecuteCommand (ensenso::action::ExecuteCommandGoalConstPtr const &goal)
 
void onGetParameter (ensenso::action::GetParameterGoalConstPtr const &goal)
 
virtual void onSetParameter (ensenso::action::SetParameterGoalConstPtr const &goal)=0
 
bool open ()
 
virtual void startServers () const
 
virtual void updateCameraTypeSpecifics ()
 

Protected Member Functions

bool cameraIsAvailable () const
 
bool cameraIsOpen () const
 
virtual ensenso::ros::Time capture () const =0
 
virtual geometry_msgs::msg::PoseStamped estimatePatternPose (ensenso::ros::Time imageTimestamp, std::string const &targetFrame="", bool latestPatternOnly=false) const =0
 
virtual std::vector< geometry_msgs::msg::PoseStamped > estimatePatternPoses (ensenso::ros::Time imageTimestamp, std::string const &targetFrame="") const =0
 
void fillBasicCameraInfoFromNxLib (sensor_msgs::msg::CameraInfoPtr const &info) const
 
tf2::Transform getCameraToLinkTransform ()
 
std::string getNxLibTargetFrameName () const
 
bool hasLink () const
 
virtual void initStatusTimer ()
 
virtual void initTfPublishTimer ()
 
void loadParameterSet (std::string name)
 
void publishCameraLink ()
 
void publishCurrentLinks (TIMER_CALLBACK_DECLARATION_ARGS)
 
void publishStatus (TIMER_CALLBACK_DECLARATION_ARGS)
 
virtual ensenso::msg::ParameterPtr readParameter (std::string const &key) const
 
void saveDefaultParameterSet ()
 
void saveParameterSet (std::string name)
 
geometry_msgs::msg::TransformStamped stampedLinkToCamera ()
 
virtual void updateCameraInfo ()=0
 
void updateGlobalLink (ensenso::ros::Time time, std::string targetFrame="", bool useCachedTransformation=false) const
 
void updateTransformations (tf2::Transform const &targetFrameTransformation) const
 
virtual void writeParameter (ensenso::msg::Parameter const &parameter)
 

Protected Attributes

std::unique_ptr< AccessTreeServer > accessTreeServer
 
NxLibItem cameraNode
 
ensenso::ros::Timer cameraPosePublisher
 
bool createdFileCamera = false
 
std::string currentParameterSet
 
NxLibItem defaultParameters
 
std::unique_ptr< ExecuteCommandServer > executeCommandServer
 
std::unique_ptr< GetParameterServer > getParameterServer
 
ensenso::ros::NodeHandle nh
 
std::mutex nxLibMutex
 
NxLibVersion nxLibVersion
 
std::map< std::string, ParameterSetparameterSets
 
CameraParameters params
 
std::unique_ptr< SetParameterServer > setParameterServer
 
ensenso::ros::Publisher< diagnostic_msgs::msg::DiagnosticArray > statusPublisher
 
ensenso::ros::Timer statusTimer
 
std::unique_ptr< tf2_ros::BuffertfBuffer
 
std::map< std::string, geometry_msgs::msg::TransformStamped > transformationCache
 
std::unique_ptr< tf2_ros::TransformBroadcastertransformBroadcaster
 
std::unique_ptr< tf2_ros::TransformListenertransformListener
 

Detailed Description

Definition at line 255 of file camera.h.

Constructor & Destructor Documentation

◆ Camera()

Camera::Camera ( ensenso::ros::NodeHandle nh,
CameraParameters  params 
)

Definition at line 101 of file camera.cpp.

Member Function Documentation

◆ cameraIsAvailable()

bool Camera::cameraIsAvailable ( ) const
protected

Check whether the camera is available for opening.

Definition at line 285 of file camera.cpp.

◆ cameraIsOpen()

bool Camera::cameraIsOpen ( ) const
protected

Check whether the camera is still open in the NxLib.

Definition at line 291 of file camera.cpp.

◆ capture()

virtual ensenso::ros::Time Camera::capture ( ) const
protectedpure virtual

Capture a new pair of images. Returns the timestamp of the (first) captured image.

Implemented in StereoCamera, and MonoCamera.

◆ close()

void Camera::close ( )

Close the camera.

Definition at line 575 of file camera.cpp.

◆ estimatePatternPose()

virtual geometry_msgs::msg::PoseStamped Camera::estimatePatternPose ( ensenso::ros::Time  imageTimestamp,
std::string const &  targetFrame = "",
bool  latestPatternOnly = false 
) const
protectedpure virtual

Estimate the pose of a pattern in the given tf frame. The pattern must already be contained in the pattern buffer (that is, you should call collectPattern before this function).

When the latestPatternOnly flag is set, the estimated position will be the one of the latest pattern in the buffer. Otherwise the function assumes that all observations are of the same pattern. It will then average their positions to increase the accuracy of the pose estimation.

Implemented in StereoCamera, and MonoCamera.

◆ estimatePatternPoses()

virtual std::vector<geometry_msgs::msg::PoseStamped> Camera::estimatePatternPoses ( ensenso::ros::Time  imageTimestamp,
std::string const &  targetFrame = "" 
) const
protectedpure virtual

Estimate the pose of each pattern in the pattern buffer.

Implemented in StereoCamera, and MonoCamera.

◆ fillBasicCameraInfoFromNxLib()

void Camera::fillBasicCameraInfoFromNxLib ( sensor_msgs::msg::CameraInfoPtr const &  info) const
protected

Read the camera calibration from the NxLib and write it into a CameraInfo message.

Definition at line 324 of file camera.cpp.

◆ getCameraToLinkTransform()

tf2::Transform Camera::getCameraToLinkTransform ( )
protected

Create a transform from camera to link frame.

Definition at line 674 of file camera.cpp.

◆ getNxLibTargetFrameName()

std::string Camera::getNxLibTargetFrameName ( ) const
protected

Return the target frame name for links in the NxLib.

Definition at line 351 of file camera.cpp.

◆ hasLink()

bool Camera::hasLink ( ) const
protected

Check whether the camera has an internal link.

Definition at line 297 of file camera.cpp.

◆ init()

virtual void Camera::init ( )
pure virtual

Initialize the camera.

Implemented in StereoCamera, and MonoCamera.

◆ initStatusTimer()

void Camera::initStatusTimer ( )
protectedvirtual

Initialize the status Timer.

Definition at line 704 of file camera.cpp.

◆ initTfPublishTimer()

void Camera::initTfPublishTimer ( )
protectedvirtual

Start publishing the camera links to tf.

Definition at line 699 of file camera.cpp.

◆ loadParameterSet()

void Camera::loadParameterSet ( std::string  name)
protected

Load the parameter set with the given name. If it does not exist yet, it will be created by copying the current default parameters.

Definition at line 615 of file camera.cpp.

◆ loadSettings()

bool Camera::loadSettings ( std::string const &  jsonFile,
bool  saveAsDefaultParameters = false 
)

Load the camera settings from the given JSON file. The resulting parameters will also be saved as the default values for new parameter sets.

Returns true if the settings could be applied successfully.

Definition at line 129 of file camera.cpp.

◆ onAccessTree()

void Camera::onAccessTree ( ensenso::action::AccessTreeGoalConstPtr const &  goal)

Callback for the access_tree action.

Definition at line 195 of file camera.cpp.

◆ onExecuteCommand()

void Camera::onExecuteCommand ( ensenso::action::ExecuteCommandGoalConstPtr const &  goal)

Callback for the execute_command action.

Definition at line 248 of file camera.cpp.

◆ onGetParameter()

void Camera::onGetParameter ( ensenso::action::GetParameterGoalConstPtr const &  goal)

Callback for the get_parameter action.

Definition at line 266 of file camera.cpp.

◆ onSetParameter()

virtual void Camera::onSetParameter ( ensenso::action::SetParameterGoalConstPtr const &  goal)
pure virtual

Callback for the set_parameter action.

Implemented in StereoCamera, and MonoCamera.

◆ open()

bool Camera::open ( )

Open the camera.

Definition at line 478 of file camera.cpp.

◆ publishCameraLink()

void Camera::publishCameraLink ( )
protected

Publish both the internal calibrated link and, if existing, the global link from the camera to the global frame.

Definition at line 655 of file camera.cpp.

◆ publishCurrentLinks()

void Camera::publishCurrentLinks ( TIMER_CALLBACK_DECLARATION_ARGS  )
protected

Callback wrapper for publishCameraLink(). Can be used e.g. with ros::NodeHandle::createTimer().

The timerEvent parameter defines the rate with which the transformations are getting published.

Definition at line 650 of file camera.cpp.

◆ publishStatus()

void Camera::publishStatus ( TIMER_CALLBACK_DECLARATION_ARGS  )
protected

Publish a diagnostic message indicating whether the camera is still open and usable in the NxLib.

Definition at line 302 of file camera.cpp.

◆ readParameter()

ensenso::msg::ParameterPtr Camera::readParameter ( std::string const &  key) const
protectedvirtual

Read the parameter with the given key from the NxLib tree.

Reimplemented in StereoCamera.

Definition at line 406 of file camera.cpp.

◆ saveDefaultParameterSet()

void Camera::saveDefaultParameterSet ( )
protected

Read the current parameters from the camera node and store them as the default parameter set that will later be used for creating new parameter sets.

Definition at line 597 of file camera.cpp.

◆ saveParameterSet()

void Camera::saveParameterSet ( std::string  name)
protected

Save the current settings to the parameter set with the given name.

If the projector or front light have been enabled or disabled manually, the flag should be set. It then disabled the automatic control of the projector and front light for this parameter set.

Definition at line 602 of file camera.cpp.

◆ stampedLinkToCamera()

geometry_msgs::msg::TransformStamped Camera::stampedLinkToCamera ( )
protected

Create a stamped transform message from link to camera frame.

Definition at line 665 of file camera.cpp.

◆ startServers()

void Camera::startServers ( ) const
virtual

Start the action servers. The camera must already be opened, otherwise the actions might access parts of the NxLib that are not initialized yet.

Reimplemented in StereoCamera, and MonoCamera.

Definition at line 120 of file camera.cpp.

◆ updateCameraInfo()

virtual void Camera::updateCameraInfo ( )
protectedpure virtual

Update the cached CameraInfo messages that will be published together with the images.

Implemented in StereoCamera, and MonoCamera.

◆ updateCameraTypeSpecifics()

virtual void Camera::updateCameraTypeSpecifics ( )
inlinevirtual

Update camera type specifics (used for the S-series, which is a subtype of stereo).

Reimplemented in StereoCamera.

Definition at line 307 of file camera.h.

◆ updateGlobalLink()

void Camera::updateGlobalLink ( ensenso::ros::Time  time,
std::string  targetFrame = "",
bool  useCachedTransformation = false 
) const
protected

Update the camera's link node and the transformations in the NxLib according to the current information from tf.

The target frame is node's target frame by default. When the useCachedTransformation flag is set, the transformation is not updated from the tf server and a cached tranformation is used instead.

Definition at line 362 of file camera.cpp.

◆ updateTransformations()

void Camera::updateTransformations ( tf2::Transform const &  targetFrameTransformation) const
protected

Update the camera's link node and the transformations in the NxLib to the given transformation. The given transformation should take data from the camera frame to some target frame.

Definition at line 356 of file camera.cpp.

◆ writeParameter()

void Camera::writeParameter ( ensenso::msg::Parameter const &  parameter)
protectedvirtual

Write the given parameter to the NxLib tree.

Reimplemented in StereoCamera.

Definition at line 445 of file camera.cpp.

Member Data Documentation

◆ accessTreeServer

std::unique_ptr<AccessTreeServer> Camera::accessTreeServer
protected

Definition at line 282 of file camera.h.

◆ cameraNode

NxLibItem Camera::cameraNode
protected

Definition at line 266 of file camera.h.

◆ cameraPosePublisher

ensenso::ros::Timer Camera::cameraPosePublisher
protected

Definition at line 275 of file camera.h.

◆ createdFileCamera

bool Camera::createdFileCamera = false
protected

Definition at line 262 of file camera.h.

◆ currentParameterSet

std::string Camera::currentParameterSet
protected

Definition at line 294 of file camera.h.

◆ defaultParameters

NxLibItem Camera::defaultParameters
protected

Definition at line 291 of file camera.h.

◆ executeCommandServer

std::unique_ptr<ExecuteCommandServer> Camera::executeCommandServer
protected

Definition at line 283 of file camera.h.

◆ getParameterServer

std::unique_ptr<GetParameterServer> Camera::getParameterServer
protected

Definition at line 284 of file camera.h.

◆ nh

ensenso::ros::NodeHandle Camera::nh
protected

Definition at line 271 of file camera.h.

◆ nxLibMutex

std::mutex Camera::nxLibMutex
mutableprotected

Definition at line 269 of file camera.h.

◆ nxLibVersion

NxLibVersion Camera::nxLibVersion
protected

Definition at line 264 of file camera.h.

◆ parameterSets

std::map<std::string, ParameterSet> Camera::parameterSets
protected

Definition at line 293 of file camera.h.

◆ params

CameraParameters Camera::params
protected

Definition at line 258 of file camera.h.

◆ setParameterServer

std::unique_ptr<SetParameterServer> Camera::setParameterServer
protected

Definition at line 285 of file camera.h.

◆ statusPublisher

ensenso::ros::Publisher<diagnostic_msgs::msg::DiagnosticArray> Camera::statusPublisher
protected

Definition at line 273 of file camera.h.

◆ statusTimer

ensenso::ros::Timer Camera::statusTimer
protected

Definition at line 274 of file camera.h.

◆ tfBuffer

std::unique_ptr<tf2_ros::Buffer> Camera::tfBuffer
protected

Definition at line 278 of file camera.h.

◆ transformationCache

std::map<std::string, geometry_msgs::msg::TransformStamped> Camera::transformationCache
mutableprotected

Definition at line 288 of file camera.h.

◆ transformBroadcaster

std::unique_ptr<tf2_ros::TransformBroadcaster> Camera::transformBroadcaster
protected

Definition at line 280 of file camera.h.

◆ transformListener

std::unique_ptr<tf2_ros::TransformListener> Camera::transformListener
protected

Definition at line 279 of file camera.h.


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


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