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

#include <mono_camera.h>

Inheritance diagram for MonoCamera:
Inheritance graph
[legend]

Public Member Functions

ros::Time capture () const override
 
 MonoCamera (ros::NodeHandle nh, std::string serial, std::string fileCameraPath, bool fixed, std::string cameraFrame, std::string targetFrame, std::string linkFrame)
 
void onLocatePattern (ensenso_camera_msgs::LocatePatternMonoGoalConstPtr const &goal)
 
void onRequestData (ensenso_camera_msgs::RequestDataMonoGoalConstPtr const &goal)
 
void onSetParameter (ensenso_camera_msgs::SetParameterGoalConstPtr const &goal) override
 
bool open () override
 
void startServers () const override
 
- 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

std::vector< MonoCalibrationPatterncollectPattern (bool clearBuffer=false) const
 
geometry_msgs::TransformStamped estimatePatternPose (ros::Time imageTimestamp=ros::Time::now(), std::string const &targetFrame="", bool latestPatternOnly=false) const override
 
std::vector< geometry_msgs::TransformStamped > estimatePatternPoses (ros::Time imageTimestamp=ros::Time::now(), std::string const &targetFrame="") const override
 
void fillCameraInfoFromNxLib (sensor_msgs::CameraInfoPtr const &info, bool rectified=false)
 
void updateCameraInfo () override
 

Private Attributes

sensor_msgs::CameraInfoPtr cameraInfo
 
std::unique_ptr< LocatePatternMonoServerlocatePatternServer
 
image_transport::CameraPublisher rawImagePublisher
 
sensor_msgs::CameraInfoPtr rectifiedCameraInfo
 
image_transport::CameraPublisher rectifiedImagePublisher
 
std::unique_ptr< RequestDataMonoServerrequestDataServer
 

Additional Inherited Members

- Protected Member Functions inherited from Camera
bool cameraIsAvailable () const
 
bool cameraIsOpen () 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
 
virtual ensenso_camera_msgs::ParameterPtr readParameter (std::string const &key) 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
 
virtual void writeParameter (ensenso_camera_msgs::Parameter const &parameter)
 
- 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 11 of file mono_camera.h.

Constructor & Destructor Documentation

MonoCamera::MonoCamera ( ros::NodeHandle  nh,
std::string  serial,
std::string  fileCameraPath,
bool  fixed,
std::string  cameraFrame,
std::string  targetFrame,
std::string  linkFrame 
)

Definition at line 6 of file mono_camera.cpp.

Member Function Documentation

ros::Time MonoCamera::capture ( ) const
overridevirtual

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

Implements Camera.

Definition at line 24 of file mono_camera.cpp.

std::vector< MonoCalibrationPattern > MonoCamera::collectPattern ( bool  clearBuffer = false) const
private

Definition at line 326 of file mono_camera.cpp.

geometry_msgs::TransformStamped MonoCamera::estimatePatternPose ( ros::Time  imageTimestamp = ros::Time::now(),
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.

Reimplemented from Camera.

Definition at line 379 of file mono_camera.cpp.

std::vector< geometry_msgs::TransformStamped > MonoCamera::estimatePatternPoses ( ros::Time  imageTimestamp = ros::Time::now(),
std::string const &  targetFrame = "" 
) const
overrideprivatevirtual

Estimate the pose of each pattern in the pattern buffer for mono cameras.

Reimplemented from Camera.

Definition at line 406 of file mono_camera.cpp.

void MonoCamera::fillCameraInfoFromNxLib ( sensor_msgs::CameraInfoPtr const &  info,
bool  rectified = false 
)
private

Definition at line 64 of file mono_camera.cpp.

void MonoCamera::onLocatePattern ( ensenso_camera_msgs::LocatePatternMonoGoalConstPtr const &  goal)

Definition at line 218 of file mono_camera.cpp.

void MonoCamera::onRequestData ( ensenso_camera_msgs::RequestDataMonoGoalConstPtr const &  goal)

Callback for the request_data action.

Definition at line 103 of file mono_camera.cpp.

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

Callback for the set_parameter action.

Implements Camera.

Definition at line 178 of file mono_camera.cpp.

bool MonoCamera::open ( )
overridevirtual

Reimplemented from Camera.

Definition at line 49 of file mono_camera.cpp.

void MonoCamera::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 96 of file mono_camera.cpp.

void MonoCamera::updateCameraInfo ( )
overrideprivatevirtual

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

Implements Camera.

Definition at line 58 of file mono_camera.cpp.

Member Data Documentation

sensor_msgs::CameraInfoPtr MonoCamera::cameraInfo
private

Definition at line 14 of file mono_camera.h.

std::unique_ptr<LocatePatternMonoServer> MonoCamera::locatePatternServer
private

Definition at line 18 of file mono_camera.h.

image_transport::CameraPublisher MonoCamera::rawImagePublisher
private

Definition at line 20 of file mono_camera.h.

sensor_msgs::CameraInfoPtr MonoCamera::rectifiedCameraInfo
private

Definition at line 15 of file mono_camera.h.

image_transport::CameraPublisher MonoCamera::rectifiedImagePublisher
private

Definition at line 21 of file mono_camera.h.

std::unique_ptr<RequestDataMonoServer> MonoCamera::requestDataServer
private

Definition at line 17 of file mono_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