Public Member Functions | Private Member Functions | Private Attributes | List of all members
StereoCamera Class Reference

#include <stereo_camera.h>

Inheritance diagram for StereoCamera:
Inheritance graph
[legend]

Public Member Functions

void init () override
 
void onCalibrateHandEye (ensenso::action::CalibrateHandEyeGoalConstPtr const &goal)
 
void onCalibrateWorkspace (ensenso::action::CalibrateWorkspaceGoalConstPtr const &goal)
 
void onFitPrimitive (ensenso::action::FitPrimitiveGoalConstPtr const &goal)
 
void onLocatePattern (ensenso::action::LocatePatternGoalConstPtr const &goal)
 
void onProjectPattern (ensenso::action::ProjectPatternGoalConstPtr const &goal)
 
void onRequestData (ensenso::action::RequestDataGoalConstPtr const &goal)
 
void onSetParameter (ensenso::action::SetParameterGoalConstPtr const &goal) override
 
void onTelecentricProjection (ensenso::action::TelecentricProjectionGoalConstPtr const &goal)
 
void onTexturedPointCloud (ensenso::action::TexturedPointCloudGoalConstPtr const &goal)
 
 StereoCamera (ensenso::ros::NodeHandle &nh, CameraParameters params)
 
- Public Member Functions inherited from Camera
 Camera (ensenso::ros::NodeHandle &nh, CameraParameters params)
 
void close ()
 
bool loadSettings (std::string const &jsonFile, bool saveAsDefaultParameters=false)
 
void onAccessTree (ensenso::action::AccessTreeGoalConstPtr const &goal)
 
void onExecuteCommand (ensenso::action::ExecuteCommandGoalConstPtr const &goal)
 
void onGetParameter (ensenso::action::GetParameterGoalConstPtr const &goal)
 
bool open ()
 

Private Member Functions

void addDisparityMapOffset (sensor_msgs::msg::CameraInfoPtr const &info) const
 
void advertiseTopics ()
 
ensenso::ros::Time capture () const override
 
std::vector< StereoCalibrationPatterncollectPattern (bool clearBuffer=false) const
 
geometry_msgs::msg::PoseStamped estimatePatternPose (ensenso::ros::Time imageTimestamp, std::string const &targetFrame="", bool latestPatternOnly=false) const override
 
std::vector< geometry_msgs::msg::PoseStamped > estimatePatternPoses (ensenso::ros::Time imageTimestamp, std::string const &targetFrame="") const override
 
void fillCameraInfoFromNxLib (sensor_msgs::msg::CameraInfoPtr const &info, bool right, bool rectified=false) const
 
bool hasDisparityMap () const
 
bool hasDownloadedImages () const
 
bool hasRawImages () const
 
bool hasRightCamera () const
 
bool isSSeries () const
 
bool isXrSeries () const
 
void loadParameterSet (std::string name, ProjectorState projector=projectorDontCare)
 
ensenso::msg::ParameterPtr readParameter (std::string const &key) const override
 
void saveParameterSet (std::string name, bool projectorWasSet)
 
void startServers () const override
 
ensenso::ros::Time timestampOfCapturedImage () const
 
void updateCameraInfo () override
 
void updateCameraTypeSpecifics () override
 
void writeParameter (ensenso::msg::Parameter const &parameter) override
 

Private Attributes

std::unique_ptr< CalibrateHandEyeServer > calibrateHandEyeServer
 
std::unique_ptr< CalibrateWorkspaceServer > calibrateWorkspaceServer
 
image_transport::CameraPublisher depthImagePublisher
 
image_transport::CameraPublisher disparityMapPublisher
 
std::unique_ptr< FitPrimitiveServer > fitPrimitiveServer
 
std::string handEyeCalibrationPatternBuffer
 
std::vector< tf2::TransformhandEyeCalibrationRobotTransforms
 
sensor_msgs::msg::CameraInfoPtr leftCameraInfo
 
image_transport::CameraPublisher leftRawImagePublisher
 
sensor_msgs::msg::CameraInfoPtr leftRectifiedCameraInfo
 
image_transport::CameraPublisher leftRectifiedImagePublisher
 
std::unique_ptr< LocatePatternServer > locatePatternServer
 
PointCloudPublisher< ensenso::pcl::PointCloudColoredpointCloudColoredPublisher
 
PointCloudPublisher< ensenso::pcl::PointCloudNormalspointCloudNormalsPublisher
 
PointCloudPublisher< ensenso::pcl::PointCloudpointCloudProjectedPublisher
 
PointCloudPublisher< ensenso::pcl::PointCloudpointCloudPublisher
 
image_transport::Publisher projectedImagePublisher
 
std::unique_ptr< ProjectPatternServer > projectPatternServer
 
std::unique_ptr< RequestDataServer > requestDataServer
 
sensor_msgs::msg::CameraInfoPtr rightCameraInfo
 
image_transport::CameraPublisher rightRawImagePublisher
 
sensor_msgs::msg::CameraInfoPtr rightRectifiedCameraInfo
 
image_transport::CameraPublisher rightRectifiedImagePublisher
 
std::unique_ptr< TelecentricProjectionServer > telecentricProjectionServer
 
std::unique_ptr< TexturedPointCloudServer > texturedPointCloudServer
 

Additional Inherited Members

- Protected Member Functions inherited from Camera
bool cameraIsAvailable () const
 
bool cameraIsOpen () const
 
void fillBasicCameraInfoFromNxLib (sensor_msgs::msg::CameraInfoPtr const &info) const
 
tf2::Transform getCameraToLinkTransform ()
 
std::string getNxLibTargetFrameName () const
 
bool hasLink () const
 
virtual void initStatusTimer ()
 
virtual void initTfPublishTimer ()
 
void loadParameterSet (std::string name)
 
void publishCameraLink ()
 
void publishCurrentLinks (TIMER_CALLBACK_DECLARATION_ARGS)
 
void publishStatus (TIMER_CALLBACK_DECLARATION_ARGS)
 
void saveDefaultParameterSet ()
 
void saveParameterSet (std::string name)
 
geometry_msgs::msg::TransformStamped stampedLinkToCamera ()
 
void updateGlobalLink (ensenso::ros::Time time, std::string targetFrame="", bool useCachedTransformation=false) const
 
void updateTransformations (tf2::Transform const &targetFrameTransformation) const
 
- Protected Attributes inherited from Camera
std::unique_ptr< AccessTreeServer > accessTreeServer
 
NxLibItem cameraNode
 
ensenso::ros::Timer cameraPosePublisher
 
bool createdFileCamera = false
 
std::string currentParameterSet
 
NxLibItem defaultParameters
 
std::unique_ptr< ExecuteCommandServer > executeCommandServer
 
std::unique_ptr< GetParameterServer > getParameterServer
 
ensenso::ros::NodeHandle nh
 
std::mutex nxLibMutex
 
NxLibVersion nxLibVersion
 
std::map< std::string, ParameterSetparameterSets
 
CameraParameters params
 
std::unique_ptr< SetParameterServer > setParameterServer
 
ensenso::ros::Publisher< diagnostic_msgs::msg::DiagnosticArray > statusPublisher
 
ensenso::ros::Timer statusTimer
 
std::unique_ptr< tf2_ros::BuffertfBuffer
 
std::map< std::string, geometry_msgs::msg::TransformStamped > transformationCache
 
std::unique_ptr< tf2_ros::TransformBroadcastertransformBroadcaster
 
std::unique_ptr< tf2_ros::TransformListenertransformListener
 

Detailed Description

Definition at line 27 of file stereo_camera.h.

Constructor & Destructor Documentation

◆ StereoCamera()

StereoCamera::StereoCamera ( ensenso::ros::NodeHandle nh,
CameraParameters  params 
)

Definition at line 9 of file stereo_camera.cpp.

Member Function Documentation

◆ 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

Advertise all camera topics.

Definition at line 36 of file stereo_camera.cpp.

◆ capture()

ensenso::ros::Time StereoCamera::capture ( ) const
overrideprivatevirtual

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()

std::vector< StereoCalibrationPattern > StereoCamera::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 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

Estimate the pose of each pattern in the pattern buffer.

Implements Camera.

Definition at line 1415 of file stereo_camera.cpp.

◆ 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

Return whether this camera has a disparity map.

Definition at line 1630 of file stereo_camera.cpp.

◆ 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

Return whether this cameras has/stores raw images.

Definition at line 1619 of file stereo_camera.cpp.

◆ hasRightCamera()

bool StereoCamera::hasRightCamera ( ) const
private

Return whether this camera has a right camera sensor.

Definition at line 1614 of file stereo_camera.cpp.

◆ init()

void StereoCamera::init ( )
overridevirtual

Initialize the camera.

Implements Camera.

Definition at line 60 of file stereo_camera.cpp.

◆ isSSeries()

bool StereoCamera::isSSeries ( ) const
private

Return whether this camera is an S-series camera.

Definition at line 1603 of file stereo_camera.cpp.

◆ isXrSeries()

bool StereoCamera::isXrSeries ( ) const
private

Return whether this camera is an XR-Series camera.

Definition at line 1608 of file stereo_camera.cpp.

◆ loadParameterSet()

void StereoCamera::loadParameterSet ( std::string  name,
ProjectorState  projector = projectorDontCare 
)
private

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)

Callback for the calibrate_hand_eye action.

Definition at line 714 of file stereo_camera.cpp.

◆ onCalibrateWorkspace()

void StereoCamera::onCalibrateWorkspace ( ensenso::action::CalibrateWorkspaceGoalConstPtr const &  goal)

Callback for the calibrate_workspace action.

Definition at line 967 of file stereo_camera.cpp.

◆ onFitPrimitive()

void StereoCamera::onFitPrimitive ( ensenso::action::FitPrimitiveGoalConstPtr const &  goal)

Callback for the fit_primitive action.

Definition at line 81 of file stereo_camera.cpp.

◆ onLocatePattern()

void StereoCamera::onLocatePattern ( ensenso::action::LocatePatternGoalConstPtr const &  goal)

Callback for the locate_pattern action.

Definition at line 537 of file stereo_camera.cpp.

◆ onProjectPattern()

void StereoCamera::onProjectPattern ( ensenso::action::ProjectPatternGoalConstPtr const &  goal)

Callback for the project_pattern action.

Definition at line 647 of file stereo_camera.cpp.

◆ onRequestData()

void StereoCamera::onRequestData ( ensenso::action::RequestDataGoalConstPtr const &  goal)

Callback for the request_data action.

Definition at line 198 of file stereo_camera.cpp.

◆ onSetParameter()

void StereoCamera::onSetParameter ( ensenso::action::SetParameterGoalConstPtr const &  goal)
overridevirtual

Callback for the set_parameter action.

Implements Camera.

Definition at line 486 of file stereo_camera.cpp.

◆ onTelecentricProjection()

void StereoCamera::onTelecentricProjection ( ensenso::action::TelecentricProjectionGoalConstPtr const &  goal)

Callback for the project_telecentric action.

Definition at line 1040 of file stereo_camera.cpp.

◆ onTexturedPointCloud()

void StereoCamera::onTexturedPointCloud ( ensenso::action::TexturedPointCloudGoalConstPtr const &  goal)

Callback for the texture_point_cloud action.

Definition at line 1145 of file stereo_camera.cpp.

◆ 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()

ensenso::ros::Time StereoCamera::timestampOfCapturedImage ( ) const
private

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

Write the given parameter to the NxLib tree.

Reimplemented from Camera.

Definition at line 1562 of file stereo_camera.cpp.

Member Data Documentation

◆ calibrateHandEyeServer

std::unique_ptr<CalibrateHandEyeServer> StereoCamera::calibrateHandEyeServer
private

Definition at line 35 of file stereo_camera.h.

◆ calibrateWorkspaceServer

std::unique_ptr<CalibrateWorkspaceServer> StereoCamera::calibrateWorkspaceServer
private

Definition at line 36 of file stereo_camera.h.

◆ depthImagePublisher

image_transport::CameraPublisher StereoCamera::depthImagePublisher
private

Definition at line 49 of file stereo_camera.h.

◆ disparityMapPublisher

image_transport::CameraPublisher StereoCamera::disparityMapPublisher
private

Definition at line 48 of file stereo_camera.h.

◆ fitPrimitiveServer

std::unique_ptr<FitPrimitiveServer> StereoCamera::fitPrimitiveServer
private

Definition at line 37 of file stereo_camera.h.

◆ handEyeCalibrationPatternBuffer

std::string StereoCamera::handEyeCalibrationPatternBuffer
private

Definition at line 60 of file stereo_camera.h.

◆ handEyeCalibrationRobotTransforms

std::vector<tf2::Transform> StereoCamera::handEyeCalibrationRobotTransforms
private

Definition at line 61 of file stereo_camera.h.

◆ leftCameraInfo

sensor_msgs::msg::CameraInfoPtr StereoCamera::leftCameraInfo
private

Definition at line 30 of file stereo_camera.h.

◆ leftRawImagePublisher

image_transport::CameraPublisher StereoCamera::leftRawImagePublisher
private

Definition at line 44 of file stereo_camera.h.

◆ leftRectifiedCameraInfo

sensor_msgs::msg::CameraInfoPtr StereoCamera::leftRectifiedCameraInfo
private

Definition at line 32 of file stereo_camera.h.

◆ leftRectifiedImagePublisher

image_transport::CameraPublisher StereoCamera::leftRectifiedImagePublisher
private

Definition at line 46 of file stereo_camera.h.

◆ locatePatternServer

std::unique_ptr<LocatePatternServer> StereoCamera::locatePatternServer
private

Definition at line 38 of file stereo_camera.h.

◆ pointCloudColoredPublisher

PointCloudPublisher<ensenso::pcl::PointCloudColored> StereoCamera::pointCloudColoredPublisher
private

Definition at line 54 of file stereo_camera.h.

◆ pointCloudNormalsPublisher

PointCloudPublisher<ensenso::pcl::PointCloudNormals> StereoCamera::pointCloudNormalsPublisher
private

Definition at line 53 of file stereo_camera.h.

◆ pointCloudProjectedPublisher

PointCloudPublisher<ensenso::pcl::PointCloud> StereoCamera::pointCloudProjectedPublisher
private

Definition at line 55 of file stereo_camera.h.

◆ pointCloudPublisher

PointCloudPublisher<ensenso::pcl::PointCloud> StereoCamera::pointCloudPublisher
private

Definition at line 52 of file stereo_camera.h.

◆ projectedImagePublisher

image_transport::Publisher StereoCamera::projectedImagePublisher
private

Definition at line 50 of file stereo_camera.h.

◆ projectPatternServer

std::unique_ptr<ProjectPatternServer> StereoCamera::projectPatternServer
private

Definition at line 39 of file stereo_camera.h.

◆ requestDataServer

std::unique_ptr<RequestDataServer> StereoCamera::requestDataServer
private

Definition at line 40 of file stereo_camera.h.

◆ rightCameraInfo

sensor_msgs::msg::CameraInfoPtr StereoCamera::rightCameraInfo
private

Definition at line 31 of file stereo_camera.h.

◆ rightRawImagePublisher

image_transport::CameraPublisher StereoCamera::rightRawImagePublisher
private

Definition at line 45 of file stereo_camera.h.

◆ rightRectifiedCameraInfo

sensor_msgs::msg::CameraInfoPtr StereoCamera::rightRectifiedCameraInfo
private

Definition at line 33 of file stereo_camera.h.

◆ rightRectifiedImagePublisher

image_transport::CameraPublisher StereoCamera::rightRectifiedImagePublisher
private

Definition at line 47 of file stereo_camera.h.

◆ telecentricProjectionServer

std::unique_ptr<TelecentricProjectionServer> StereoCamera::telecentricProjectionServer
private

Definition at line 42 of file stereo_camera.h.

◆ texturedPointCloudServer

std::unique_ptr<TexturedPointCloudServer> StereoCamera::texturedPointCloudServer
private

Definition at line 41 of file stereo_camera.h.


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


ensenso_camera
Author(s): Ensenso
autogenerated on Wed Apr 2 2025 02:37:46