#include <smartek_camera_node.h>
|
typedef smartek_camera::SmartekCameraConfig | Config |
|
Definition at line 38 of file smartek_camera_node.h.
SmartekCameraNode::SmartekCameraNode |
( |
| ) |
|
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.
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 |
void SmartekCameraNode::publishGigeImage |
( |
const gige::IImageBitmapInterface & |
img, |
|
|
const gige::IImageInfo & |
imgInfo |
|
) |
| |
|
private |
Publish an image obtained from the GigEVision API
- Parameters
-
img | the image to be published |
imgInfo | the 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 |
void SmartekCameraNode::run |
( |
| ) |
|
sensor_msgs::CameraInfo SmartekCameraNode::cameraInfo_ |
|
private |
Config SmartekCameraNode::config_ |
|
private |
TimestampSynchronizer::Options SmartekCameraNode::defaultTimesyncOptions_ |
|
private |
std::string SmartekCameraNode::frame_id_ |
|
private |
bool SmartekCameraNode::isCameraConnected_ |
|
private |
gige::IAlgorithm SmartekCameraNode::m_colorPipelineAlg_ |
|
private |
gige::IImageBitmap SmartekCameraNode::m_colorPipelineBitmap_ |
|
private |
gige::IParams SmartekCameraNode::m_colorPipelineParams_ |
|
private |
gige::IResults SmartekCameraNode::m_colorPipelineResults_ |
|
private |
double SmartekCameraNode::m_defaultGain_ |
|
private |
bool SmartekCameraNode::m_defaultGainNotSet_ |
|
private |
gige::IDevice SmartekCameraNode::m_device_ |
|
private |
gige::IImageInfo SmartekCameraNode::m_imageInfo_ |
|
private |
gige::IImageProcAPI SmartekCameraNode::m_imageProcApi_ |
|
private |
std::unique_ptr<TimestampSynchronizer> SmartekCameraNode::ptimestampSynchronizer_ |
|
private |
dynamic_reconfigure::Server<Config>::CallbackType SmartekCameraNode::reconfigureCallback_ |
|
private |
dynamic_reconfigure::Server<Config> SmartekCameraNode::reconfigureServer_ |
|
private |
std::string SmartekCameraNode::serialNumber_ |
|
private |
The documentation for this class was generated from the following files: