Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
stcamera::StCameraNode Class Reference

Class implementation for stcamera_node. More...

#include <stcamera_node.h>

Public Member Functions

virtual void init ()
 
virtual void spin ()
 
 StCameraNode ()
 
 StCameraNode (ros::NodeHandle nh)
 
virtual ~StCameraNode ()
 

Protected Member Functions

bool getDeviceListCallback (omronsentech_camera::GetDeviceList::Request &req, omronsentech_camera::GetDeviceList::Response &res)
 
bool getGigEIPCallback (omronsentech_camera::GetGigEIPi::Request &req, omronsentech_camera::GetGigEIPi::Response &res)
 
bool getModuleListCallback (omronsentech_camera::GetModuleList::Request &req, omronsentech_camera::GetModuleList::Response &res)
 
bool getSDKInfoCallback (omronsentech_camera::GetSDKInfo::Request &req, omronsentech_camera::GetSDKInfo::Response &res)
 
bool initializeCamera (StApi::IStInterface *p_iface, const StApi::IStDeviceInfo *p_devinfo)
 
bool setGigEIPCallback (omronsentech_camera::SetGigEIPi::Request &req, omronsentech_camera::SetGigEIPi::Response &res)
 

Protected Attributes

MapCameraInterface map_camera_
 
MapDeviceConnection map_connection_
 
ros::Publisher msg_device_connection_
 
ros::NodeHandle nh_
 
StParameter param_
 
ros::ServiceServer srv_get_device_list_
 
ros::ServiceServer srv_get_gige_ip_i_
 
ros::ServiceServer srv_get_module_list_
 
ros::ServiceServer srv_get_sdk_info_
 
ros::ServiceServer srv_set_gige_ip_i_
 
StApi::CStApiAutoInit stapi_autoinit_
 
StApi::CIStSystemPtrArray stapi_systems_
 

Private Member Functions

omronsentech_camera::DeviceConnection fillDeviceConnectionData (const StApi::IStSystemInfo *p_tlinfo, StApi::IStInterface *p_iface, const StApi::IStDeviceInfo *p_devinfo, std::string device_namespace="", bool connected=false)
 

Private Attributes

std::mutex mtx_map_camera_
 
std::mutex mtx_update_device_list_
 

Detailed Description

Class implementation for stcamera_node.

This class implements the stcamera_node.

Definition at line 64 of file stcamera_node.h.

Constructor & Destructor Documentation

stcamera::StCameraNode::StCameraNode ( )

Default Constructor.

Definition at line 57 of file stcamera_node.cpp.

stcamera::StCameraNode::StCameraNode ( ros::NodeHandle  nh)

Constructor with parent node. This constructor is used by Nodelet.

Parameters
[in]nhParent node.

Definition at line 80 of file stcamera_node.cpp.

stcamera::StCameraNode::~StCameraNode ( )
virtual

Destructor.

Definition at line 103 of file stcamera_node.cpp.

Member Function Documentation

omronsentech_camera::DeviceConnection stcamera::StCameraNode::fillDeviceConnectionData ( const StApi::IStSystemInfo *  p_tlinfo,
StApi::IStInterface *  p_iface,
const StApi::IStDeviceInfo *  p_devinfo,
std::string  device_namespace = "",
bool  connected = false 
)
private

Helper function to fill the structure of DeviceConnection.

Parameters
[in]p_tlinfoPointer to the IStSystemInfo of the device.
[in]p_ifacePointer to the IStInterface of the device.
[in]p_devinfoPointer to the IStDeviceInfo of the device.
[in]device_namespaceNamespace of the device.
[in]connectedwhether the device is connected or not.
Returns
Filled DeviceConnection.

Definition at line 567 of file stcamera_node.cpp.

bool stcamera::StCameraNode::getDeviceListCallback ( omronsentech_camera::GetDeviceList::Request &  req,
omronsentech_camera::GetDeviceList::Response &  res 
)
protected

ROS service callback for obtaining list of all detected devices including the disallowed camera to connect.

Parameters
[in]reqROS service request
[out]resROS service response
Returns
Always true.

Definition at line 359 of file stcamera_node.cpp.

bool stcamera::StCameraNode::getGigEIPCallback ( omronsentech_camera::GetGigEIPi::Request &  req,
omronsentech_camera::GetGigEIPi::Response &  res 
)
protected

ROS service callback for obtaining IP address information of the given GigEVision camera which is not opened yet.

Parameters
[in]reqROS service request
[out]resROS service response
Returns
True on success. False on failure.

Definition at line 446 of file stcamera_node.cpp.

bool stcamera::StCameraNode::getModuleListCallback ( omronsentech_camera::GetModuleList::Request &  req,
omronsentech_camera::GetModuleList::Response &  res 
)
protected

ROS service callback for obtaining all module name: System, Interface, LocalDevice, RemoteDevice, DataStream.

Parameters
[in]reqROS service request
[out]resROS service response
Returns
Always true.

Definition at line 408 of file stcamera_node.cpp.

bool stcamera::StCameraNode::getSDKInfoCallback ( omronsentech_camera::GetSDKInfo::Request &  req,
omronsentech_camera::GetSDKInfo::Response &  res 
)
protected

ROS service callback for obtaining SentechSDK and GenTL information.

Parameters
[in]reqROS service request
[out]resROS service response
Returns
Always true.

Definition at line 422 of file stcamera_node.cpp.

void stcamera::StCameraNode::init ( )
virtual

Initialization. This function is called by constructor. In the initialization, list of allowed camera to connect is retrieved and the GenTL modules are initialized.

Definition at line 118 of file stcamera_node.cpp.

bool stcamera::StCameraNode::initializeCamera ( StApi::IStInterface *  p_iface,
const StApi::IStDeviceInfo *  p_devinfo 
)
protected

Function to initialize a camera. In this function, whether connection to the given camera is allowed will be checked.

Parameters
[in]p_ifacePointer to the IStInterface of the camera.
[in]p_devinfoPointer to the IStDeviceInfo of the device.
Returns
True if the camera is successfully initialized. False otherwise.

Definition at line 268 of file stcamera_node.cpp.

bool stcamera::StCameraNode::setGigEIPCallback ( omronsentech_camera::SetGigEIPi::Request &  req,
omronsentech_camera::SetGigEIPi::Response &  res 
)
protected

ROS service callback for assigning IP address to the given GigEVision camera which is not opened yet.

Parameters
[in]reqROS service request
[out]resROS service response
Returns
True on success. False on failure.

Definition at line 509 of file stcamera_node.cpp.

void stcamera::StCameraNode::spin ( )
virtual

Function called inside process loop. In this function, device availability is checked. Any device lost will be announced through device_connection topic. Any new found device will be processed through calling initializeCamera() .

Definition at line 174 of file stcamera_node.cpp.

Member Data Documentation

MapCameraInterface stcamera::StCameraNode::map_camera_
protected

Store the list of allowed camera or connected camera and the corresponding instances.

Definition at line 160 of file stcamera_node.h.

MapDeviceConnection stcamera::StCameraNode::map_connection_
protected

Store the list of all detected camera (including disallowed to connect) and the camera information.

Definition at line 164 of file stcamera_node.h.

ros::Publisher stcamera::StCameraNode::msg_device_connection_
protected

Publisher for announcing any device lost or newly found device that is allowed to connect.

Definition at line 171 of file stcamera_node.h.

std::mutex stcamera::StCameraNode::mtx_map_camera_
private

Guard to prevent race when accessing map_camera_.

Definition at line 211 of file stcamera_node.h.

std::mutex stcamera::StCameraNode::mtx_update_device_list_
private

Guard to prevent race when looking for new devices.

Definition at line 208 of file stcamera_node.h.

ros::NodeHandle stcamera::StCameraNode::nh_
protected

Main node handle for stcamera_node

Definition at line 156 of file stcamera_node.h.

StParameter stcamera::StCameraNode::param_
protected

StParameter instance

Definition at line 167 of file stcamera_node.h.

ros::ServiceServer stcamera::StCameraNode::srv_get_device_list_
protected

Server for get_device_list

Definition at line 174 of file stcamera_node.h.

ros::ServiceServer stcamera::StCameraNode::srv_get_gige_ip_i_
protected

Server for get_gige_ip

Definition at line 180 of file stcamera_node.h.

ros::ServiceServer stcamera::StCameraNode::srv_get_module_list_
protected

Server for get_module_list

Definition at line 176 of file stcamera_node.h.

ros::ServiceServer stcamera::StCameraNode::srv_get_sdk_info_
protected

Server for get_sdk_info

Definition at line 178 of file stcamera_node.h.

ros::ServiceServer stcamera::StCameraNode::srv_set_gige_ip_i_
protected

Server for set_gige_ip

Definition at line 182 of file stcamera_node.h.

StApi::CStApiAutoInit stcamera::StCameraNode::stapi_autoinit_
protected

Variable for auto initialization of SentechSDK

Definition at line 185 of file stcamera_node.h.

StApi::CIStSystemPtrArray stcamera::StCameraNode::stapi_systems_
protected

List of GenTL instances used by SentechSDK

Definition at line 188 of file stcamera_node.h.


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


omronsentech_camera
Author(s): OSE ROS Support
autogenerated on Tue Jul 2 2019 19:44:14