#include <camera.h>
Definition at line 255 of file camera.h.
◆ Camera()
◆ 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()
Capture a new pair of images. Returns the timestamp of the (first) captured image.
Implemented in StereoCamera, and MonoCamera.
◆ close()
◆ 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 |
◆ 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()
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 |
◆ 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 |
◆ open()
◆ 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()
◆ publishStatus()
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 |
◆ accessTreeServer
std::unique_ptr<AccessTreeServer> Camera::accessTreeServer |
|
protected |
◆ cameraNode
NxLibItem Camera::cameraNode |
|
protected |
◆ cameraPosePublisher
◆ createdFileCamera
bool Camera::createdFileCamera = false |
|
protected |
◆ currentParameterSet
std::string Camera::currentParameterSet |
|
protected |
◆ defaultParameters
NxLibItem Camera::defaultParameters |
|
protected |
◆ executeCommandServer
std::unique_ptr<ExecuteCommandServer> Camera::executeCommandServer |
|
protected |
◆ getParameterServer
std::unique_ptr<GetParameterServer> Camera::getParameterServer |
|
protected |
◆ nh
◆ nxLibMutex
std::mutex Camera::nxLibMutex |
|
mutableprotected |
◆ nxLibVersion
◆ parameterSets
◆ params
◆ setParameterServer
std::unique_ptr<SetParameterServer> Camera::setParameterServer |
|
protected |
◆ statusPublisher
◆ statusTimer
◆ tfBuffer
◆ transformationCache
std::map<std::string, geometry_msgs::msg::TransformStamped> Camera::transformationCache |
|
mutableprotected |
◆ transformBroadcaster
◆ transformListener
The documentation for this class was generated from the following files: