#include <stereo_camera.h>
Definition at line 27 of file stereo_camera.h.
◆ StereoCamera()
◆ addDisparityMapOffset()
void StereoCamera::addDisparityMapOffset |
( |
sensor_msgs::msg::CameraInfoPtr const & |
info | ) |
const |
|
private |
Add the NxLib internal disparity map offset to the given camera info.
Definition at line 1635 of file stereo_camera.cpp.
◆ advertiseTopics()
void StereoCamera::advertiseTopics |
( |
| ) |
|
|
private |
◆ capture()
Capture a new pair of images. Returns the timestamp of the (first) captured image.
Implements Camera.
Definition at line 1281 of file stereo_camera.cpp.
◆ collectPattern()
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 1309 of file stereo_camera.cpp.
◆ estimatePatternPose()
geometry_msgs::msg::PoseStamped StereoCamera::estimatePatternPose |
( |
ensenso::ros::Time |
imageTimestamp, |
|
|
std::string const & |
targetFrame = "" , |
|
|
bool |
latestPatternOnly = false |
|
) |
| const |
|
overrideprivatevirtual |
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.
Implements Camera.
Definition at line 1388 of file stereo_camera.cpp.
◆ estimatePatternPoses()
std::vector< geometry_msgs::msg::PoseStamped > StereoCamera::estimatePatternPoses |
( |
ensenso::ros::Time |
imageTimestamp, |
|
|
std::string const & |
targetFrame = "" |
|
) |
| const |
|
overrideprivatevirtual |
◆ fillCameraInfoFromNxLib()
void StereoCamera::fillCameraInfoFromNxLib |
( |
sensor_msgs::msg::CameraInfoPtr const & |
info, |
|
|
bool |
right, |
|
|
bool |
rectified = false |
|
) |
| const |
|
private |
Read the camera calibration from the NxLib and write it into a CameraInfo message.
When the right flag is set, use the calibration from the right camera instead from the left. The rectified flag indicates whether the images are already rectified.
Definition at line 1441 of file stereo_camera.cpp.
◆ hasDisparityMap()
bool StereoCamera::hasDisparityMap |
( |
| ) |
const |
|
private |
◆ hasDownloadedImages()
bool StereoCamera::hasDownloadedImages |
( |
| ) |
const |
|
private |
Return whether this camera downloads the raw/rectified images.
Definition at line 1625 of file stereo_camera.cpp.
◆ hasRawImages()
bool StereoCamera::hasRawImages |
( |
| ) |
const |
|
private |
◆ hasRightCamera()
bool StereoCamera::hasRightCamera |
( |
| ) |
const |
|
private |
◆ init()
void StereoCamera::init |
( |
| ) |
|
|
overridevirtual |
◆ isSSeries()
bool StereoCamera::isSSeries |
( |
| ) |
const |
|
private |
◆ isXrSeries()
bool StereoCamera::isXrSeries |
( |
| ) |
const |
|
private |
◆ loadParameterSet()
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 1217 of file stereo_camera.cpp.
◆ onCalibrateHandEye()
void StereoCamera::onCalibrateHandEye |
( |
ensenso::action::CalibrateHandEyeGoalConstPtr const & |
goal | ) |
|
◆ onCalibrateWorkspace()
void StereoCamera::onCalibrateWorkspace |
( |
ensenso::action::CalibrateWorkspaceGoalConstPtr const & |
goal | ) |
|
◆ onFitPrimitive()
void StereoCamera::onFitPrimitive |
( |
ensenso::action::FitPrimitiveGoalConstPtr const & |
goal | ) |
|
◆ onLocatePattern()
void StereoCamera::onLocatePattern |
( |
ensenso::action::LocatePatternGoalConstPtr const & |
goal | ) |
|
◆ onProjectPattern()
void StereoCamera::onProjectPattern |
( |
ensenso::action::ProjectPatternGoalConstPtr const & |
goal | ) |
|
◆ onRequestData()
void StereoCamera::onRequestData |
( |
ensenso::action::RequestDataGoalConstPtr const & |
goal | ) |
|
◆ onSetParameter()
void StereoCamera::onSetParameter |
( |
ensenso::action::SetParameterGoalConstPtr const & |
goal | ) |
|
|
overridevirtual |
◆ onTelecentricProjection()
void StereoCamera::onTelecentricProjection |
( |
ensenso::action::TelecentricProjectionGoalConstPtr const & |
goal | ) |
|
◆ onTexturedPointCloud()
void StereoCamera::onTexturedPointCloud |
( |
ensenso::action::TexturedPointCloudGoalConstPtr const & |
goal | ) |
|
◆ readParameter()
ensenso::msg::ParameterPtr StereoCamera::readParameter |
( |
std::string const & |
key | ) |
const |
|
overrideprivatevirtual |
Read the parameter with the given key from the NxLib tree.
Reimplemented from Camera.
Definition at line 1521 of file stereo_camera.cpp.
◆ saveParameterSet()
void StereoCamera::saveParameterSet |
( |
std::string |
name, |
|
|
bool |
projectorWasSet |
|
) |
| |
|
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 1201 of file stereo_camera.cpp.
◆ startServers()
void StereoCamera::startServers |
( |
| ) |
const |
|
overrideprivatevirtual |
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 from Camera.
Definition at line 68 of file stereo_camera.cpp.
◆ timestampOfCapturedImage()
Grab the timestamp of the last captured (raw) image. Handle the different image sources across different camera models (file camera, S-Series, XR-Series or normal stereo camera).
Definition at line 1254 of file stereo_camera.cpp.
◆ updateCameraInfo()
void StereoCamera::updateCameraInfo |
( |
| ) |
|
|
overrideprivatevirtual |
Update the cached CameraInfo messages that will be published together with the images.
Implements Camera.
Definition at line 1510 of file stereo_camera.cpp.
◆ updateCameraTypeSpecifics()
void StereoCamera::updateCameraTypeSpecifics |
( |
| ) |
|
|
overrideprivatevirtual |
Update camera type specifics (used for the S-series, which is a subtype of stereo).
Reimplemented from Camera.
Definition at line 27 of file stereo_camera.cpp.
◆ writeParameter()
void StereoCamera::writeParameter |
( |
ensenso::msg::Parameter const & |
parameter | ) |
|
|
overrideprivatevirtual |
◆ calibrateHandEyeServer
std::unique_ptr<CalibrateHandEyeServer> StereoCamera::calibrateHandEyeServer |
|
private |
◆ calibrateWorkspaceServer
std::unique_ptr<CalibrateWorkspaceServer> StereoCamera::calibrateWorkspaceServer |
|
private |
◆ depthImagePublisher
◆ disparityMapPublisher
◆ fitPrimitiveServer
std::unique_ptr<FitPrimitiveServer> StereoCamera::fitPrimitiveServer |
|
private |
◆ handEyeCalibrationPatternBuffer
std::string StereoCamera::handEyeCalibrationPatternBuffer |
|
private |
◆ handEyeCalibrationRobotTransforms
std::vector<tf2::Transform> StereoCamera::handEyeCalibrationRobotTransforms |
|
private |
◆ leftCameraInfo
sensor_msgs::msg::CameraInfoPtr StereoCamera::leftCameraInfo |
|
private |
◆ leftRawImagePublisher
◆ leftRectifiedCameraInfo
sensor_msgs::msg::CameraInfoPtr StereoCamera::leftRectifiedCameraInfo |
|
private |
◆ leftRectifiedImagePublisher
◆ locatePatternServer
std::unique_ptr<LocatePatternServer> StereoCamera::locatePatternServer |
|
private |
◆ pointCloudColoredPublisher
◆ pointCloudNormalsPublisher
◆ pointCloudProjectedPublisher
◆ pointCloudPublisher
◆ projectedImagePublisher
◆ projectPatternServer
std::unique_ptr<ProjectPatternServer> StereoCamera::projectPatternServer |
|
private |
◆ requestDataServer
std::unique_ptr<RequestDataServer> StereoCamera::requestDataServer |
|
private |
◆ rightCameraInfo
sensor_msgs::msg::CameraInfoPtr StereoCamera::rightCameraInfo |
|
private |
◆ rightRawImagePublisher
◆ rightRectifiedCameraInfo
sensor_msgs::msg::CameraInfoPtr StereoCamera::rightRectifiedCameraInfo |
|
private |
◆ rightRectifiedImagePublisher
◆ telecentricProjectionServer
std::unique_ptr<TelecentricProjectionServer> StereoCamera::telecentricProjectionServer |
|
private |
◆ texturedPointCloudServer
std::unique_ptr<TexturedPointCloudServer> StereoCamera::texturedPointCloudServer |
|
private |
The documentation for this class was generated from the following files: