#include <camera.h>
Definition at line 179 of file camera.h.
Camera::Camera |
( |
ros::NodeHandle const & |
n, |
|
|
std::string |
serial, |
|
|
std::string |
fileCameraPath, |
|
|
bool |
fixed, |
|
|
std::string |
cameraFrame, |
|
|
std::string |
targetFrame, |
|
|
std::string |
linkFrame |
|
) |
| |
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.
Capture a new pair of images. Returns the timestamp of the (first) captured image.
Implemented in StereoCamera, and MonoCamera.
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
-
info | The CameraInfo message to which the calibration should be written. |
right | Whether to use the calibration from the right camera instead of the left one. |
Definition at line 242 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 |
void Camera::publishCameraLink |
( |
| ) |
|
|
protected |
Publishes both the internal calibrated link and, if exists, the global link from camera frame to global frame;
- Parameters
-
timerEvent | Defines the rate with which the trnsformations are getting published. |
Definition at line 560 of file camera.cpp.
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 |
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 |
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
-
time | The timestamp from which the transformation should be taken. |
frame | The TF frame in which the camera should return the data. Uses the node's target frame by default. |
useCachedTransformation | Do 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 |
std::string Camera::cameraFrame |
|
protected |
NxLibItem Camera::cameraNode |
|
protected |
bool Camera::createdFileCamera = false |
|
protected |
std::string Camera::currentParameterSet |
|
protected |
NxLibItem Camera::defaultParameters |
|
protected |
std::string Camera::fileCameraPath |
|
protected |
bool Camera::isFileCamera |
|
protected |
std::string Camera::linkFrame |
|
protected |
std::mutex Camera::nxLibMutex |
|
mutableprotected |
std::string Camera::serial |
|
protected |
std::string Camera::targetFrame |
|
protected |
std::map<std::string, geometry_msgs::TransformStamped> Camera::transformationCache |
|
mutableprotected |
The documentation for this class was generated from the following files: