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

#include <camera.h>

Public Member Functions

 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)
 
void close ()
 
bool loadSettings (std::string const &jsonFile, bool saveAsDefaultParameters=false)
 
void onAccessTree (ensenso_camera_msgs::AccessTreeGoalConstPtr const &goal)
 
void onCalibrateHandEye (ensenso_camera_msgs::CalibrateHandEyeGoalConstPtr const &goal)
 
void onCalibrateWorkspace (ensenso_camera_msgs::CalibrateWorkspaceGoalConstPtr const &goal)
 
void onExecuteCommand (ensenso_camera_msgs::ExecuteCommandGoalConstPtr const &goal)
 
void onFitPrimitive (ensenso_camera_msgs::FitPrimitiveGoalConstPtr const &goal)
 
void onGetParameter (ensenso_camera_msgs::GetParameterGoalConstPtr 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)
 
bool open ()
 
void startServers () const
 

Private Member Functions

bool cameraIsAvailable () const
 
bool cameraIsOpen () const
 
ros::Time capture () const
 
std::vector< CalibrationPatterncollectPattern (bool clearBuffer=false) const
 
tf::Stamped< tf::PoseestimatePatternPose (ros::Time imageTimestamp=ros::Time::now(), std::string const &targetFrame="", bool latestPatternOnly=false) const
 
std::vector< tf::Stamped< tf::Pose > > estimatePatternPoses (ros::Time imageTimestamp=ros::Time::now(), std::string const &targetFrame="") const
 
void fillCameraInfoFromNxLib (sensor_msgs::CameraInfoPtr const &info, bool right, bool rectified=false) const
 
void loadParameterSet (std::string name, ProjectorState projector=projectorDontCare)
 
void publishStatus (ros::TimerEvent const &event) const
 
ensenso_camera_msgs::ParameterPtr readParameter (std::string const &key) const
 
void saveDefaultParameterSet ()
 
void saveParameterSet (std::string name, bool projectorWritten=false)
 
void updateCameraInfo ()
 
void updateTransformations (ros::Time time=ros::Time::now(), std::string targetFrame="", bool useCachedTransformation=false) const
 
void updateTransformations (tf::Pose const &targetFrameTransformation) const
 
void writeParameter (ensenso_camera_msgs::Parameter const &parameter)
 

Private Attributes

std::unique_ptr< AccessTreeServeraccessTreeServer
 
std::unique_ptr< CalibrateHandEyeServercalibrateHandEyeServer
 
std::unique_ptr< CalibrateWorkspaceServercalibrateWorkspaceServer
 
std::string cameraFrame
 
NxLibItem cameraNode
 
bool createdFileCamera
 
std::string currentParameterSet
 
NxLibItem defaultParameters
 
image_transport::CameraPublisher depthImagePublisher
 
image_transport::Publisher disparityMapPublisher
 
std::unique_ptr< ExecuteCommandServerexecuteCommandServer
 
std::string fileCameraPath
 
std::unique_ptr< FitPrimitiveServerfitPrimitiveServer
 
bool fixed
 
std::unique_ptr< GetParameterServergetParameterServer
 
std::string handEyeCalibrationPatternBuffer
 
std::vector< tf::PosehandEyeCalibrationRobotPoses
 
bool isFileCamera
 
sensor_msgs::CameraInfoPtr leftCameraInfo
 
image_transport::CameraPublisher leftRawImagePublisher
 
sensor_msgs::CameraInfoPtr leftRectifiedCameraInfo
 
image_transport::CameraPublisher leftRectifiedImagePublisher
 
std::unique_ptr< LocatePatternServerlocatePatternServer
 
std::mutex nxLibMutex
 
std::map< std::string, ParameterSetparameterSets
 
ros::Publisher pointCloudPublisher
 
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::string serial
 
std::unique_ptr< SetParameterServersetParameterServer
 
ros::Publisher statusPublisher
 
ros::Timer statusTimer
 
std::string targetFrame
 
std::map< std::string, tf::StampedTransformtransformationCache
 
tf::TransformBroadcaster transformBroadcaster
 
tf::TransformListener transformListener
 
std::string wristFrame
 

Detailed Description

Definition at line 87 of file camera.h.

Constructor & Destructor Documentation

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 
)

Definition at line 137 of file camera.cpp.

Member Function Documentation

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.

ros::Time Camera::capture ( ) const
private

Capture a new pair of images. Returns the timestamp of the (first) captured image.

Definition at line 1383 of file camera.cpp.

void Camera::close ( )

Definition at line 255 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.

tf::Stamped< tf::Pose > Camera::estimatePatternPose ( ros::Time  imageTimestamp = ros::Time::now(),
std::string const &  targetFrame = "",
bool  latestPatternOnly = false 
) const
private

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.

std::vector< tf::Stamped< tf::Pose > > Camera::estimatePatternPoses ( ros::Time  imageTimestamp = ros::Time::now(),
std::string const &  targetFrame = "" 
) const
private

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
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 1581 of file camera.cpp.

void Camera::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 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.

bool Camera::open ( )

Definition at line 196 of file camera.cpp.

void Camera::publishStatus ( ros::TimerEvent const &  event) const
private

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

Definition at line 1676 of file camera.cpp.

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
timeThe timestamp from which the transformation should be taken.
targetFrameThe TF frame in which the camera should return the data. Uses the node's target frame by default.
useCachedTransformationDo 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

Definition at line 1744 of file camera.cpp.

Member Data Documentation

std::unique_ptr<AccessTreeServer> Camera::accessTreeServer
private

Definition at line 118 of file camera.h.

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

Definition at line 125 of file camera.h.

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

Definition at line 126 of file camera.h.

std::string Camera::cameraFrame
private

Definition at line 102 of file camera.h.

NxLibItem Camera::cameraNode
private

Definition at line 91 of file camera.h.

bool Camera::createdFileCamera
private

Definition at line 97 of file camera.h.

std::string Camera::currentParameterSet
private

Definition at line 145 of file camera.h.

NxLibItem Camera::defaultParameters
private

Definition at line 142 of file camera.h.

image_transport::CameraPublisher Camera::depthImagePublisher
private

Definition at line 134 of file camera.h.

image_transport::Publisher Camera::disparityMapPublisher
private

Definition at line 133 of file camera.h.

std::unique_ptr<ExecuteCommandServer> Camera::executeCommandServer
private

Definition at line 119 of file camera.h.

std::string Camera::fileCameraPath
private

Definition at line 94 of file camera.h.

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

Definition at line 127 of file camera.h.

bool Camera::fixed
private

Definition at line 100 of file camera.h.

std::unique_ptr<GetParameterServer> Camera::getParameterServer
private

Definition at line 120 of file camera.h.

std::string Camera::handEyeCalibrationPatternBuffer
private

Definition at line 154 of file camera.h.

std::vector<tf::Pose> Camera::handEyeCalibrationRobotPoses
private

Definition at line 155 of file camera.h.

bool Camera::isFileCamera
private

Definition at line 93 of file camera.h.

sensor_msgs::CameraInfoPtr Camera::leftCameraInfo
private

Definition at line 110 of file camera.h.

image_transport::CameraPublisher Camera::leftRawImagePublisher
private

Definition at line 129 of file camera.h.

sensor_msgs::CameraInfoPtr Camera::leftRectifiedCameraInfo
private

Definition at line 112 of file camera.h.

image_transport::CameraPublisher Camera::leftRectifiedImagePublisher
private

Definition at line 131 of file camera.h.

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

Definition at line 123 of file camera.h.

std::mutex Camera::nxLibMutex
mutableprivate

Definition at line 108 of file camera.h.

std::map<std::string, ParameterSet> Camera::parameterSets
private

Definition at line 144 of file camera.h.

ros::Publisher Camera::pointCloudPublisher
private

Definition at line 136 of file camera.h.

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

Definition at line 124 of file camera.h.

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

Definition at line 122 of file camera.h.

sensor_msgs::CameraInfoPtr Camera::rightCameraInfo
private

Definition at line 111 of file camera.h.

image_transport::CameraPublisher Camera::rightRawImagePublisher
private

Definition at line 130 of file camera.h.

sensor_msgs::CameraInfoPtr Camera::rightRectifiedCameraInfo
private

Definition at line 113 of file camera.h.

image_transport::CameraPublisher Camera::rightRectifiedImagePublisher
private

Definition at line 132 of file camera.h.

std::string Camera::robotFrame
private

Definition at line 104 of file camera.h.

std::string Camera::serial
private

Definition at line 90 of file camera.h.

std::unique_ptr<SetParameterServer> Camera::setParameterServer
private

Definition at line 121 of file camera.h.

ros::Publisher Camera::statusPublisher
private

Definition at line 138 of file camera.h.

ros::Timer Camera::statusTimer
private

Definition at line 139 of file camera.h.

std::string Camera::targetFrame
private

Definition at line 103 of file camera.h.

std::map<std::string, tf::StampedTransform> Camera::transformationCache
mutableprivate

Definition at line 147 of file camera.h.

tf::TransformBroadcaster Camera::transformBroadcaster
private

Definition at line 116 of file camera.h.

tf::TransformListener Camera::transformListener
private

Definition at line 115 of file camera.h.

std::string Camera::wristFrame
private

Definition at line 105 of file camera.h.


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


ensenso_camera
Author(s): Ensenso
autogenerated on Thu May 16 2019 02:44:23