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 onCalibrateHandEye (ensenso_camera_msgs::CalibrateHandEyeGoalConstPtr const &goal)
 
void onCalibrateWorkspace (ensenso_camera_msgs::CalibrateWorkspaceGoalConstPtr const &goal)
 
void onFitPrimitive (ensenso_camera_msgs::FitPrimitiveGoalConstPtr const &goal)
 
void onLocatePattern (ensenso_camera_msgs::LocatePatternGoalConstPtr const &goal)
 
void onProjectPattern (ensenso_camera_msgs::ProjectPatternGoalConstPtr const &goal)
 
void onRequestData (ensenso_camera_msgs::RequestDataGoalConstPtr const &goal)
 
void onSetParameter (ensenso_camera_msgs::SetParameterGoalConstPtr const &goal) override
 
void onTelecentricProjection (ensenso_camera_msgs::TelecentricProjectionGoalConstPtr const &goal)
 
void onTexturedPointCloud (ensenso_camera_msgs::TexturedPointCloudGoalConstPtr const &goal)
 
bool open () override
 
void startServers () const override
 
 StereoCamera (ros::NodeHandle nh, std::string serial, std::string fileCameraPath, bool fixed, std::string cameraFrame, std::string targetFrame, std::string robotFrame, std::string wristFrame, std::string linkFrame, int captureTimeout, std::unique_ptr< ensenso_camera::VirtualObjectHandler > virtualObjectHandler=nullptr)
 
- Public Member Functions inherited from Camera
 Camera (ros::NodeHandle const &n, std::string serial, std::string fileCameraPath, bool fixed, std::string cameraFrame, std::string targetFrame, std::string linkFrame)
 
void close ()
 
virtual void initStatusTimer ()
 
virtual void initTfPublishTimer ()
 
bool loadSettings (std::string const &jsonFile, bool saveAsDefaultParameters=false)
 
void onAccessTree (ensenso_camera_msgs::AccessTreeGoalConstPtr const &goal)
 
void onExecuteCommand (ensenso_camera_msgs::ExecuteCommandGoalConstPtr const &goal)
 
void onGetParameter (ensenso_camera_msgs::GetParameterGoalConstPtr const &goal)
 

Private Member Functions

ros::Time capture () const override
 
std::vector< StereoCalibrationPatterncollectPattern (bool clearBuffer=false) const
 
void fillCameraInfoFromNxLib (sensor_msgs::CameraInfoPtr const &info, bool right, bool rectified=false) const
 
void loadParameterSet (std::string name, ProjectorState projector=projectorDontCare)
 
ensenso_camera_msgs::ParameterPtr readParameter (std::string const &key) const override
 
void saveParameterSet (std::string name, bool projectorWasSet)
 
void updateCameraInfo () override
 
void writeParameter (ensenso_camera_msgs::Parameter const &parameter) override
 

Private Attributes

std::unique_ptr< CalibrateHandEyeServercalibrateHandEyeServer
 
std::unique_ptr< CalibrateWorkspaceServercalibrateWorkspaceServer
 
int captureTimeout
 
image_transport::CameraPublisher depthImagePublisher
 
image_transport::Publisher disparityMapPublisher
 
std::unique_ptr< FitPrimitiveServerfitPrimitiveServer
 
std::string handEyeCalibrationPatternBuffer
 
std::vector< tf2::TransformhandEyeCalibrationRobotPoses
 
sensor_msgs::CameraInfoPtr leftCameraInfo
 
image_transport::CameraPublisher leftRawImagePublisher
 
sensor_msgs::CameraInfoPtr leftRectifiedCameraInfo
 
image_transport::CameraPublisher leftRectifiedImagePublisher
 
std::unique_ptr< LocatePatternServerlocatePatternServer
 
ros::Publisher pointCloudPublisher
 
ros::Publisher pointCloudPublisherColor
 
image_transport::Publisher projectedImagePublisher
 
ros::Publisher projectedPointCloudPublisher
 
std::unique_ptr< ProjectPatternServerprojectPatternServer
 
std::unique_ptr< RequestDataServerrequestDataServer
 
sensor_msgs::CameraInfoPtr rightCameraInfo
 
image_transport::CameraPublisher rightRawImagePublisher
 
sensor_msgs::CameraInfoPtr rightRectifiedCameraInfo
 
image_transport::CameraPublisher rightRectifiedImagePublisher
 
std::string robotFrame
 
std::unique_ptr< TelecentricProjectionServertelecentricProjectionServer
 
std::unique_ptr< TexturedPointCloudServertexturedPointCloudServer
 
std::unique_ptr< ensenso_camera::VirtualObjectHandlervirtualObjectHandler
 
std::string wristFrame
 

Additional Inherited Members

- Protected Member Functions inherited from Camera
bool cameraIsAvailable () const
 
bool cameraIsOpen () const
 
virtual geometry_msgs::TransformStamped estimatePatternPose (ros::Time imageTimestamp=ros::Time::now(), std::string const &targetFrame="", bool latestPatternOnly=false) const
 
virtual std::vector< geometry_msgs::TransformStamped > estimatePatternPoses (ros::Time imageTimestamp=ros::Time::now(), std::string const &targetFrame="") const
 
void fillBasicCameraInfoFromNxLib (sensor_msgs::CameraInfoPtr const &info) const
 
tf2::Transform getCameraToLinkTransform ()
 
void loadParameterSet (std::string name)
 
void publishCameraLink ()
 
void publishCurrentLinks (ros::TimerEvent const &timerEvent=ros::TimerEvent())
 
virtual void publishStatus (ros::TimerEvent const &event) const
 
void saveDefaultParameterSet ()
 
void saveParameterSet (std::string name)
 
geometry_msgs::TransformStamped stampedLinkToCamera ()
 
void updateGlobalLink (ros::Time time=ros::Time::now(), std::string frame="", bool useCachedTransformation=false) const
 
void updateTransformations (tf2::Transform const &targetFrameTransformation) const
 
- Protected Attributes inherited from Camera
std::unique_ptr< AccessTreeServeraccessTreeServer
 
std::string cameraFrame
 
NxLibItem cameraNode
 
ros::Timer cameraPosePublisher
 
bool createdFileCamera = false
 
std::string currentParameterSet
 
NxLibItem defaultParameters
 
std::unique_ptr< ExecuteCommandServerexecuteCommandServer
 
std::string fileCameraPath
 
bool fixed
 
std::unique_ptr< GetParameterServergetParameterServer
 
bool isFileCamera
 
std::string linkFrame
 
ros::NodeHandle nh
 
std::mutex nxLibMutex
 
VersionInfo nxLibVersion
 
std::map< std::string, ParameterSetparameterSets
 
std::string serial
 
std::unique_ptr< SetParameterServersetParameterServer
 
ros::Publisher statusPublisher
 
ros::Timer statusTimer
 
std::string targetFrame
 
tf2_ros::Buffer tfBuffer
 
std::map< std::string, geometry_msgs::TransformStamped > transformationCache
 
std::unique_ptr< tf2_ros::TransformBroadcastertransformBroadcaster
 
std::unique_ptr< tf2_ros::TransformListenertransformListener
 

Detailed Description

Definition at line 33 of file stereo_camera.h.

Constructor & Destructor Documentation

StereoCamera::StereoCamera ( ros::NodeHandle  nh,
std::string  serial,
std::string  fileCameraPath,
bool  fixed,
std::string  cameraFrame,
std::string  targetFrame,
std::string  robotFrame,
std::string  wristFrame,
std::string  linkFrame,
int  captureTimeout,
std::unique_ptr< ensenso_camera::VirtualObjectHandler virtualObjectHandler = nullptr 
)

Definition at line 15 of file stereo_camera.cpp.

Member Function Documentation

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 1147 of file stereo_camera.cpp.

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 1186 of file stereo_camera.cpp.

void StereoCamera::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
infoThe CameraInfo message to which the calibration should be written.
rightWhether to use the calibration from the right camera instead of the left one.

Definition at line 1265 of file stereo_camera.cpp.

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 1110 of file stereo_camera.cpp.

void StereoCamera::onCalibrateHandEye ( ensenso_camera_msgs::CalibrateHandEyeGoalConstPtr const &  goal)

Callback for the calibrate_hand_eye action.

Definition at line 636 of file stereo_camera.cpp.

void StereoCamera::onCalibrateWorkspace ( ensenso_camera_msgs::CalibrateWorkspaceGoalConstPtr const &  goal)

Callback for the calibrate_workspace action.

Definition at line 859 of file stereo_camera.cpp.

void StereoCamera::onFitPrimitive ( ensenso_camera_msgs::FitPrimitiveGoalConstPtr const &  goal)

Callback for the fit_primitive action.

Definition at line 87 of file stereo_camera.cpp.

void StereoCamera::onLocatePattern ( ensenso_camera_msgs::LocatePatternGoalConstPtr const &  goal)

Callback for the locate_pattern action.

Definition at line 455 of file stereo_camera.cpp.

void StereoCamera::onProjectPattern ( ensenso_camera_msgs::ProjectPatternGoalConstPtr const &  goal)

Callback for the project_pattern action.

Definition at line 565 of file stereo_camera.cpp.

void StereoCamera::onRequestData ( ensenso_camera_msgs::RequestDataGoalConstPtr const &  goal)

Callback for the request_data action.

Definition at line 204 of file stereo_camera.cpp.

void StereoCamera::onSetParameter ( ensenso_camera_msgs::SetParameterGoalConstPtr const &  goal)
overridevirtual

Callback for the set_parameter action.

Implements Camera.

Definition at line 404 of file stereo_camera.cpp.

void StereoCamera::onTelecentricProjection ( ensenso_camera_msgs::TelecentricProjectionGoalConstPtr const &  goal)

Callback for the project_telecentric action.

Definition at line 931 of file stereo_camera.cpp.

void StereoCamera::onTexturedPointCloud ( ensenso_camera_msgs::TexturedPointCloudGoalConstPtr const &  goal)

Callback for the texture_point_cloud action.

Definition at line 1037 of file stereo_camera.cpp.

bool StereoCamera::open ( )
overridevirtual

Reimplemented from Camera.

Definition at line 65 of file stereo_camera.cpp.

ensenso_camera_msgs::ParameterPtr StereoCamera::readParameter ( std::string const &  key) const
overrideprivatevirtual

Reimplemented from Camera.

Definition at line 1351 of file stereo_camera.cpp.

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 1094 of file stereo_camera.cpp.

void StereoCamera::startServers ( ) const
overridevirtual

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 from Camera.

Definition at line 74 of file stereo_camera.cpp.

void StereoCamera::updateCameraInfo ( )
overrideprivatevirtual

Update the cached CameraInfo messages that will be published together with the images.

Implements Camera.

Definition at line 1343 of file stereo_camera.cpp.

void StereoCamera::writeParameter ( ensenso_camera_msgs::Parameter const &  parameter)
overrideprivatevirtual

Reimplemented from Camera.

Definition at line 1392 of file stereo_camera.cpp.

Member Data Documentation

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

Definition at line 45 of file stereo_camera.h.

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

Definition at line 46 of file stereo_camera.h.

int StereoCamera::captureTimeout
private

Definition at line 72 of file stereo_camera.h.

image_transport::CameraPublisher StereoCamera::depthImagePublisher
private

Definition at line 58 of file stereo_camera.h.

image_transport::Publisher StereoCamera::disparityMapPublisher
private

Definition at line 57 of file stereo_camera.h.

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

Definition at line 47 of file stereo_camera.h.

std::string StereoCamera::handEyeCalibrationPatternBuffer
private

Definition at line 68 of file stereo_camera.h.

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

Definition at line 69 of file stereo_camera.h.

sensor_msgs::CameraInfoPtr StereoCamera::leftCameraInfo
private

Definition at line 39 of file stereo_camera.h.

image_transport::CameraPublisher StereoCamera::leftRawImagePublisher
private

Definition at line 53 of file stereo_camera.h.

sensor_msgs::CameraInfoPtr StereoCamera::leftRectifiedCameraInfo
private

Definition at line 41 of file stereo_camera.h.

image_transport::CameraPublisher StereoCamera::leftRectifiedImagePublisher
private

Definition at line 55 of file stereo_camera.h.

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

Definition at line 48 of file stereo_camera.h.

ros::Publisher StereoCamera::pointCloudPublisher
private

Definition at line 61 of file stereo_camera.h.

ros::Publisher StereoCamera::pointCloudPublisherColor
private

Definition at line 61 of file stereo_camera.h.

image_transport::Publisher StereoCamera::projectedImagePublisher
private

Definition at line 59 of file stereo_camera.h.

ros::Publisher StereoCamera::projectedPointCloudPublisher
private

Definition at line 61 of file stereo_camera.h.

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

Definition at line 49 of file stereo_camera.h.

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

Definition at line 44 of file stereo_camera.h.

sensor_msgs::CameraInfoPtr StereoCamera::rightCameraInfo
private

Definition at line 40 of file stereo_camera.h.

image_transport::CameraPublisher StereoCamera::rightRawImagePublisher
private

Definition at line 54 of file stereo_camera.h.

sensor_msgs::CameraInfoPtr StereoCamera::rightRectifiedCameraInfo
private

Definition at line 42 of file stereo_camera.h.

image_transport::CameraPublisher StereoCamera::rightRectifiedImagePublisher
private

Definition at line 56 of file stereo_camera.h.

std::string StereoCamera::robotFrame
private

Definition at line 36 of file stereo_camera.h.

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

Definition at line 51 of file stereo_camera.h.

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

Definition at line 50 of file stereo_camera.h.

std::unique_ptr<ensenso_camera::VirtualObjectHandler> StereoCamera::virtualObjectHandler
private

Definition at line 76 of file stereo_camera.h.

std::string StereoCamera::wristFrame
private

Definition at line 37 of file stereo_camera.h.


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


ensenso_camera
Author(s): Ensenso
autogenerated on Thu May 6 2021 02:50:06