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

#include <smartek_camera_node.h>

Public Member Functions

void run ()
 
 SmartekCameraNode ()
 
 ~SmartekCameraNode ()
 

Private Types

typedef smartek_camera::SmartekCameraConfig Config
 

Private Member Functions

void initTimestampSynchronizer ()
 
void processFrames ()
 
void publishGigeImage (const gige::IImageBitmapInterface &img, const gige::IImageInfo &imgInfo)
 
void reconfigure_callback (Config &config, uint32_t level)
 

Private Attributes

sensor_msgs::CameraInfo cameraInfo_
 
image_transport::CameraPublisher cameraPublisher_
 
Config config_
 
TimestampSynchronizer::Options defaultTimesyncOptions_
 
std::string frame_id_
 
bool isCameraConnected_
 
gige::IAlgorithm m_colorPipelineAlg_
 
gige::IImageBitmap m_colorPipelineBitmap_
 
gige::IParams m_colorPipelineParams_
 
gige::IResults m_colorPipelineResults_
 
double m_defaultGain_
 
bool m_defaultGainNotSet_
 
gige::IDevice m_device_
 
gige::IImageInfo m_imageInfo_
 
gige::IImageProcAPI m_imageProcApi_
 
ros::NodeHandle n_
 
ros::NodeHandle np_
 
std::unique_ptr< camera_info_manager::CameraInfoManagerpcameraInfoManager_
 
std::unique_ptr< image_transport::ImageTransportpimageTransport_
 
std::unique_ptr< TimestampSynchronizer > ptimestampSynchronizer_
 
dynamic_reconfigure::Server< Config >::CallbackType reconfigureCallback_
 
dynamic_reconfigure::Server< ConfigreconfigureServer_
 
std::string serialNumber_
 

Detailed Description

Definition at line 38 of file smartek_camera_node.h.

Member Typedef Documentation

typedef smartek_camera::SmartekCameraConfig SmartekCameraNode::Config
private

Definition at line 55 of file smartek_camera_node.h.

Constructor & Destructor Documentation

SmartekCameraNode::SmartekCameraNode ( )

Constructor for the Smartek camera driver ROS node.

Definition at line 93 of file smartek_camera_node.cpp.

SmartekCameraNode::~SmartekCameraNode ( )

Destructor for the Smartek camera driver ROS node. Stops image acquisition and communication with the camera.

Definition at line 222 of file smartek_camera_node.cpp.

Member Function Documentation

void SmartekCameraNode::initTimestampSynchronizer ( )
private

Set the default parameters of the TimestampSynchronizer class and construct an instance.

Definition at line 12 of file smartek_camera_node.cpp.

void SmartekCameraNode::processFrames ( )
private

Definition at line 239 of file smartek_camera_node.cpp.

void SmartekCameraNode::publishGigeImage ( const gige::IImageBitmapInterface &  img,
const gige::IImageInfo &  imgInfo 
)
private

Publish an image obtained from the GigEVision API

Parameters
imgthe image to be published
imgInfothe object from which the frame number and sensor timestamp are read

Definition at line 33 of file smartek_camera_node.cpp.

void SmartekCameraNode::reconfigure_callback ( Config config,
uint32_t  level 
)
private

Definition at line 191 of file smartek_camera_node.cpp.

void SmartekCameraNode::run ( )

Processes frames until a ROS exit signal is received.

Definition at line 86 of file smartek_camera_node.cpp.

Member Data Documentation

sensor_msgs::CameraInfo SmartekCameraNode::cameraInfo_
private

Definition at line 70 of file smartek_camera_node.h.

image_transport::CameraPublisher SmartekCameraNode::cameraPublisher_
private

Definition at line 67 of file smartek_camera_node.h.

Config SmartekCameraNode::config_
private

Definition at line 61 of file smartek_camera_node.h.

TimestampSynchronizer::Options SmartekCameraNode::defaultTimesyncOptions_
private

Definition at line 88 of file smartek_camera_node.h.

std::string SmartekCameraNode::frame_id_
private

Definition at line 62 of file smartek_camera_node.h.

bool SmartekCameraNode::isCameraConnected_
private

Definition at line 75 of file smartek_camera_node.h.

gige::IAlgorithm SmartekCameraNode::m_colorPipelineAlg_
private

Definition at line 82 of file smartek_camera_node.h.

gige::IImageBitmap SmartekCameraNode::m_colorPipelineBitmap_
private

Definition at line 85 of file smartek_camera_node.h.

gige::IParams SmartekCameraNode::m_colorPipelineParams_
private

Definition at line 83 of file smartek_camera_node.h.

gige::IResults SmartekCameraNode::m_colorPipelineResults_
private

Definition at line 84 of file smartek_camera_node.h.

double SmartekCameraNode::m_defaultGain_
private

Definition at line 92 of file smartek_camera_node.h.

bool SmartekCameraNode::m_defaultGainNotSet_
private

Definition at line 91 of file smartek_camera_node.h.

gige::IDevice SmartekCameraNode::m_device_
private

Definition at line 79 of file smartek_camera_node.h.

gige::IImageInfo SmartekCameraNode::m_imageInfo_
private

Definition at line 86 of file smartek_camera_node.h.

gige::IImageProcAPI SmartekCameraNode::m_imageProcApi_
private

Definition at line 80 of file smartek_camera_node.h.

ros::NodeHandle SmartekCameraNode::n_
private

Definition at line 64 of file smartek_camera_node.h.

ros::NodeHandle SmartekCameraNode::np_
private

Definition at line 65 of file smartek_camera_node.h.

std::unique_ptr<camera_info_manager::CameraInfoManager> SmartekCameraNode::pcameraInfoManager_
private

Definition at line 69 of file smartek_camera_node.h.

std::unique_ptr<image_transport::ImageTransport> SmartekCameraNode::pimageTransport_
private

Definition at line 68 of file smartek_camera_node.h.

std::unique_ptr<TimestampSynchronizer> SmartekCameraNode::ptimestampSynchronizer_
private

Definition at line 89 of file smartek_camera_node.h.

dynamic_reconfigure::Server<Config>::CallbackType SmartekCameraNode::reconfigureCallback_
private

Definition at line 73 of file smartek_camera_node.h.

dynamic_reconfigure::Server<Config> SmartekCameraNode::reconfigureServer_
private

Definition at line 72 of file smartek_camera_node.h.

std::string SmartekCameraNode::serialNumber_
private

Definition at line 76 of file smartek_camera_node.h.


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


smartek_camera
Author(s): Juraj Oršulić
autogenerated on Mon Jun 10 2019 15:10:30