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 (ros::NodeHandle const &n, std::string serial, std::string fileCameraPath, bool fixed, std::string cameraFrame, std::string targetFrame, std::string linkFrame)
 
void close ()
 
virtual void initStatusTimer ()
 
virtual void initTfPublishTimer ()
 
bool loadSettings (std::string const &jsonFile, bool saveAsDefaultParameters=false)
 
void onAccessTree (ensenso_camera_msgs::AccessTreeGoalConstPtr const &goal)
 
void onExecuteCommand (ensenso_camera_msgs::ExecuteCommandGoalConstPtr const &goal)
 
void onGetParameter (ensenso_camera_msgs::GetParameterGoalConstPtr const &goal)
 
virtual void onSetParameter (ensenso_camera_msgs::SetParameterGoalConstPtr const &goal)=0
 
virtual bool open ()
 
virtual void startServers () const
 

Protected Member Functions

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

Protected Attributes

std::unique_ptr< AccessTreeServeraccessTreeServer
 
std::string cameraFrame
 
NxLibItem cameraNode
 
ros::Timer cameraPosePublisher
 
bool createdFileCamera = false
 
std::string currentParameterSet
 
NxLibItem defaultParameters
 
std::unique_ptr< ExecuteCommandServerexecuteCommandServer
 
std::string fileCameraPath
 
bool fixed
 
std::unique_ptr< GetParameterServergetParameterServer
 
bool isFileCamera
 
std::string linkFrame
 
ros::NodeHandle nh
 
std::mutex nxLibMutex
 
VersionInfo nxLibVersion
 
std::map< std::string, ParameterSetparameterSets
 
std::string serial
 
std::unique_ptr< SetParameterServersetParameterServer
 
ros::Publisher statusPublisher
 
ros::Timer statusTimer
 
std::string targetFrame
 
tf2_ros::Buffer tfBuffer
 
std::map< std::string, geometry_msgs::TransformStamped > transformationCache
 
std::unique_ptr< tf2_ros::TransformBroadcastertransformBroadcaster
 
std::unique_ptr< tf2_ros::TransformListenertransformListener
 

Detailed Description

Definition at line 179 of file camera.h.

Constructor & Destructor Documentation

Camera::Camera ( ros::NodeHandle const &  n,
std::string  serial,
std::string  fileCameraPath,
bool  fixed,
std::string  cameraFrame,
std::string  targetFrame,
std::string  linkFrame 
)

Definition at line 17 of file camera.cpp.

Member Function Documentation

bool Camera::cameraIsAvailable ( ) const
protected

Check whether the camera is available for opening.

Definition at line 208 of file camera.cpp.

bool Camera::cameraIsOpen ( ) const
protected

Check whether the camera is still open in the NxLib.

Definition at line 214 of file camera.cpp.

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

void Camera::close ( )

Definition at line 485 of file camera.cpp.

geometry_msgs::TransformStamped Camera::estimatePatternPose ( ros::Time  imageTimestamp = ros::Time::now(),
std::string const &  targetFrame = "",
bool  latestPatternOnly = false 
) const
protectedvirtual

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.

Reimplemented in MonoCamera.

Definition at line 330 of file camera.cpp.

std::vector< geometry_msgs::TransformStamped > Camera::estimatePatternPoses ( ros::Time  imageTimestamp = ros::Time::now(),
std::string const &  targetFrame = "" 
) const
protectedvirtual

Estimate the pose of each pattern in the pattern buffer.

Reimplemented in MonoCamera.

Definition at line 303 of file camera.cpp.

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

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

Parameters
infoThe CameraInfo message to which the calibration should be written.
rightWhether to use the calibration from the right camera instead of the left one.

Definition at line 242 of file camera.cpp.

tf2::Transform Camera::getCameraToLinkTransform ( )
protected

Definition at line 591 of file camera.cpp.

void Camera::initStatusTimer ( )
virtual

Initialize the status Timer

Definition at line 620 of file camera.cpp.

void Camera::initTfPublishTimer ( )
virtual

Start publishing the camera links to tf

Definition at line 615 of file camera.cpp.

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 525 of file camera.cpp.

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 57 of file camera.cpp.

void Camera::onAccessTree ( ensenso_camera_msgs::AccessTreeGoalConstPtr const &  goal)

Callback for the access_tree action.

Definition at line 117 of file camera.cpp.

void Camera::onExecuteCommand ( ensenso_camera_msgs::ExecuteCommandGoalConstPtr const &  goal)

Callback for the execute_command action.

Definition at line 171 of file camera.cpp.

void Camera::onGetParameter ( ensenso_camera_msgs::GetParameterGoalConstPtr const &  goal)

Callback for the get_parameter action.

Definition at line 189 of file camera.cpp.

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

Callback for the set_parameter action.

Implemented in StereoCamera, and MonoCamera.

bool Camera::open ( )
virtual

Reimplemented in StereoCamera, and MonoCamera.

Definition at line 427 of file camera.cpp.

void Camera::publishCameraLink ( )
protected

Definition at line 565 of file camera.cpp.

void Camera::publishCurrentLinks ( ros::TimerEvent const &  timerEvent = ros::TimerEvent())
protected

Publishes both the internal calibrated link and, if exists, the global link from camera frame to global frame;

Parameters
timerEventDefines the rate with which the trnsformations are getting published.

Definition at line 560 of file camera.cpp.

void Camera::publishStatus ( ros::TimerEvent const &  event) const
protectedvirtual

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

Definition at line 220 of file camera.cpp.

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

Reimplemented in StereoCamera.

Definition at line 355 of file camera.cpp.

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 507 of file camera.cpp.

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 512 of file camera.cpp.

geometry_msgs::TransformStamped Camera::stampedLinkToCamera ( )
protected

Definition at line 581 of file camera.cpp.

void Camera::startServers ( ) const
virtual

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

Reimplemented in StereoCamera, and MonoCamera.

Definition at line 48 of file camera.cpp.

virtual void Camera::updateCameraInfo ( )
protectedpure virtual

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

Implemented in StereoCamera, and MonoCamera.

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

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

Parameters
timeThe timestamp from which the transformation should be taken.
frameThe TF frame in which the camera should return the data. Uses the node's target frame by default.
useCachedTransformationDo not update the transformation from the TF server, but use a cached one.

Definition at line 259 of file camera.cpp.

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 253 of file camera.cpp.

void Camera::writeParameter ( ensenso_camera_msgs::Parameter const &  parameter)
protectedvirtual

Reimplemented in StereoCamera.

Definition at line 394 of file camera.cpp.

Member Data Documentation

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

Definition at line 214 of file camera.h.

std::string Camera::cameraFrame
protected

Definition at line 199 of file camera.h.

NxLibItem Camera::cameraNode
protected

Definition at line 191 of file camera.h.

ros::Timer Camera::cameraPosePublisher
protected

Definition at line 207 of file camera.h.

bool Camera::createdFileCamera = false
protected

Definition at line 186 of file camera.h.

std::string Camera::currentParameterSet
protected

Definition at line 226 of file camera.h.

NxLibItem Camera::defaultParameters
protected

Definition at line 223 of file camera.h.

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

Definition at line 215 of file camera.h.

std::string Camera::fileCameraPath
protected

Definition at line 183 of file camera.h.

bool Camera::fixed
protected

Definition at line 197 of file camera.h.

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

Definition at line 216 of file camera.h.

bool Camera::isFileCamera
protected

Definition at line 182 of file camera.h.

std::string Camera::linkFrame
protected

Definition at line 200 of file camera.h.

ros::NodeHandle Camera::nh
protected

Definition at line 203 of file camera.h.

std::mutex Camera::nxLibMutex
mutableprotected

Definition at line 194 of file camera.h.

VersionInfo Camera::nxLibVersion
protected

Definition at line 188 of file camera.h.

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

Definition at line 225 of file camera.h.

std::string Camera::serial
protected

Definition at line 190 of file camera.h.

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

Definition at line 217 of file camera.h.

ros::Publisher Camera::statusPublisher
protected

Definition at line 205 of file camera.h.

ros::Timer Camera::statusTimer
protected

Definition at line 206 of file camera.h.

std::string Camera::targetFrame
protected

Definition at line 201 of file camera.h.

tf2_ros::Buffer Camera::tfBuffer
protected

Definition at line 210 of file camera.h.

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

Definition at line 220 of file camera.h.

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

Definition at line 212 of file camera.h.

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

Definition at line 211 of file camera.h.


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


ensenso_camera
Author(s): Ensenso
autogenerated on Thu May 6 2021 02:50:06