#include <camera.h>
Definition at line 87 of file camera.h.
Camera::Camera |
( |
ros::NodeHandle |
nh, |
|
|
std::string const & |
serial, |
|
|
std::string const & |
fileCameraPath, |
|
|
bool |
fixed, |
|
|
std::string const & |
cameraFrame, |
|
|
std::string const & |
targetFrame, |
|
|
std::string const & |
robotFrame, |
|
|
std::string const & |
wristFrame |
|
) |
| |
bool Camera::cameraIsAvailable |
( |
| ) |
const |
|
private |
Check whether the camera is available for opening.
Definition at line 1269 of file camera.cpp.
bool Camera::cameraIsOpen |
( |
| ) |
const |
|
private |
Check whether the camera is still open in the NxLib.
Definition at line 1275 of file camera.cpp.
Capture a new pair of images. Returns the timestamp of the (first) captured image.
Definition at line 1383 of file camera.cpp.
std::vector< CalibrationPattern > Camera::collectPattern |
( |
bool |
clearBuffer = false | ) |
const |
|
private |
Try to collect patterns on the current images. For the command to be successful, the patterns must be decodable and visible in both cameras.
Definition at line 1401 of file camera.cpp.
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.
Definition at line 1480 of file camera.cpp.
Estimate the pose of each pattern in the pattern buffer.
Definition at line 1505 of file camera.cpp.
void Camera::fillCameraInfoFromNxLib |
( |
sensor_msgs::CameraInfoPtr const & |
info, |
|
|
bool |
right, |
|
|
bool |
rectified = false |
|
) |
| const |
|
private |
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 1581 of file camera.cpp.
Load the parameter set with the given name. If it does not exist yet, it will be created by copying the current default parameters.
The projector and front light will be enabled according to the given flag, unless they have been manually enabled or disabled for the current parameter set.
Definition at line 1326 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 294 of file camera.cpp.
void Camera::onAccessTree |
( |
ensenso_camera_msgs::AccessTreeGoalConstPtr const & |
goal | ) |
|
Callback for the access_tree
action.
Definition at line 354 of file camera.cpp.
void Camera::onCalibrateHandEye |
( |
ensenso_camera_msgs::CalibrateHandEyeGoalConstPtr const & |
goal | ) |
|
Callback for the calibrate_hand_eye
action.
Definition at line 978 of file camera.cpp.
void Camera::onCalibrateWorkspace |
( |
ensenso_camera_msgs::CalibrateWorkspaceGoalConstPtr const & |
goal | ) |
|
Callback for the calibrate_workspace
action.
Definition at line 1197 of file camera.cpp.
void Camera::onExecuteCommand |
( |
ensenso_camera_msgs::ExecuteCommandGoalConstPtr const & |
goal | ) |
|
Callback for the execute_command
action.
Definition at line 408 of file camera.cpp.
void Camera::onFitPrimitive |
( |
ensenso_camera_msgs::FitPrimitiveGoalConstPtr const & |
goal | ) |
|
Callback for the fit_primitive
action.
Definition at line 426 of file camera.cpp.
void Camera::onGetParameter |
( |
ensenso_camera_msgs::GetParameterGoalConstPtr const & |
goal | ) |
|
Callback for the get_parameter
action.
Definition at line 543 of file camera.cpp.
void Camera::onLocatePattern |
( |
ensenso_camera_msgs::LocatePatternGoalConstPtr const & |
goal | ) |
|
Callback for the locate_pattern
action.
Definition at line 797 of file camera.cpp.
void Camera::onProjectPattern |
( |
ensenso_camera_msgs::ProjectPatternGoalConstPtr const & |
goal | ) |
|
Callback for the project_pattern
action.
Definition at line 905 of file camera.cpp.
void Camera::onRequestData |
( |
ensenso_camera_msgs::RequestDataGoalConstPtr const & |
goal | ) |
|
Callback for the request_data
action.
Definition at line 613 of file camera.cpp.
void Camera::onSetParameter |
( |
ensenso_camera_msgs::SetParameterGoalConstPtr const & |
goal | ) |
|
Callback for the set_parameter
action.
Definition at line 562 of file camera.cpp.
Publish a diagnostic message indicating whether the camera is still open and usable in the NxLib.
Definition at line 1281 of file camera.cpp.
ensenso_camera_msgs::ParameterPtr Camera::readParameter |
( |
std::string const & |
key | ) |
const |
|
private |
void Camera::saveDefaultParameterSet |
( |
| ) |
|
|
private |
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 1303 of file camera.cpp.
void Camera::saveParameterSet |
( |
std::string |
name, |
|
|
bool |
projectorWritten = false |
|
) |
| |
|
private |
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 1308 of file camera.cpp.
void Camera::startServers |
( |
| ) |
const |
Start the action servers. The camera must already be open, otherwise the actions might access parts of the NxLib that are not initialized yet.
Definition at line 277 of file camera.cpp.
void Camera::updateCameraInfo |
( |
| ) |
|
|
private |
Update the cached CameraInfo messages that will be published together with the images.
Definition at line 1668 of file camera.cpp.
void Camera::updateTransformations |
( |
ros::Time |
time = ros::Time::now() , |
|
|
std::string |
targetFrame = "" , |
|
|
bool |
useCachedTransformation = false |
|
) |
| const |
|
private |
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. |
targetFrame | 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 1532 of file camera.cpp.
void Camera::updateTransformations |
( |
tf::Pose const & |
targetFrameTransformation | ) |
const |
|
private |
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 1575 of file camera.cpp.
void Camera::writeParameter |
( |
ensenso_camera_msgs::Parameter const & |
parameter | ) |
|
|
private |
std::string Camera::cameraFrame |
|
private |
NxLibItem Camera::cameraNode |
|
private |
bool Camera::createdFileCamera |
|
private |
std::string Camera::currentParameterSet |
|
private |
NxLibItem Camera::defaultParameters |
|
private |
std::string Camera::fileCameraPath |
|
private |
std::string Camera::handEyeCalibrationPatternBuffer |
|
private |
std::vector<tf::Pose> Camera::handEyeCalibrationRobotPoses |
|
private |
bool Camera::isFileCamera |
|
private |
sensor_msgs::CameraInfoPtr Camera::leftCameraInfo |
|
private |
sensor_msgs::CameraInfoPtr Camera::leftRectifiedCameraInfo |
|
private |
std::mutex Camera::nxLibMutex |
|
mutableprivate |
sensor_msgs::CameraInfoPtr Camera::rightCameraInfo |
|
private |
sensor_msgs::CameraInfoPtr Camera::rightRectifiedCameraInfo |
|
private |
std::string Camera::robotFrame |
|
private |
std::string Camera::serial |
|
private |
std::string Camera::targetFrame |
|
private |
std::string Camera::wristFrame |
|
private |
The documentation for this class was generated from the following files: