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

Class to control a connected GigEVision camera. More...

#include <stcamera_interface_gev.h>

Inheritance diagram for stcamera::StCameraInterfaceGEV:
Inheritance graph
[legend]

Public Member Functions

bool getIPCallback (omronsentech_camera::GetGigEIP::Request &req, omronsentech_camera::GetGigEIP::Response &res)
 
bool setIPCallback (omronsentech_camera::SetGigEIP::Request &req, omronsentech_camera::SetGigEIP::Response &res)
 
 StCameraInterfaceGEV (StApi::IStDeviceReleasable *dev, ros::NodeHandle nh_parent, const std::string &camera_namespace, StParameter *param, uint32_t queue_size=STCAMERA_QUEUE_SIZE)
 
virtual ~StCameraInterfaceGEV ()
 
- Public Member Functions inherited from stcamera::StCameraInterface
bool deviceIsLost ()
 
 StCameraInterface (StApi::IStDeviceReleasable *dev, ros::NodeHandle nh_parent, const std::string &camera_namespace, StParameter *param, uint32_t queue_size=STCAMERA_QUEUE_SIZE)
 
virtual ~StCameraInterface ()
 

Protected Attributes

ros::ServiceServer srv_get_gige_ip_
 
ros::ServiceServer srv_set_gige_ip_
 
- Protected Attributes inherited from stcamera::StCameraInterface
bool bool_acquisition_is_started_
 
bool bool_event_datastream_
 
bool bool_event_device_
 
bool bool_event_interface_
 
bool bool_event_system_
 
std::string camera_namespace_
 
camera_info_manager::CameraInfoManager cinfo_
 
bool destroyed_
 
image_transport::ImageTransport it_
 
image_transport::CameraPublisher it_campub_
 
int32_t last_error_
 
MapChunk map_chunk_
 
MapCallback map_event_datastream_
 
MapCallback map_event_interface_
 
MapCallback map_event_localdevice_
 
MapCallback map_event_remotedevice_
 
MapCallback map_event_system_
 
MapPublisher map_msg_event_
 
ros::Publisher msg_chunk_
 
std::mutex mtx_acquisition_
 
std::mutex mtx_chunk_
 
std::mutex mtx_event_
 
ros::NodeHandle nh_
 
StParameterparam_
 
uint32_t queue_size_
 
ros::ServiceServer srv_enable_chunk_
 
ros::ServiceServer srv_enable_event_acquisition_
 
ros::ServiceServer srv_enable_event_node_
 
ros::ServiceServer srv_enable_image_acquisition_
 
ros::ServiceServer srv_enable_trigger_
 
ros::ServiceServer srv_execute_node_
 
ros::ServiceServer srv_get_chunk_list_
 
ros::ServiceServer srv_get_enum_list_
 
ros::ServiceServer srv_get_event_acquisition_status_list_
 
ros::ServiceServer srv_get_event_node_status_list_
 
ros::ServiceServer srv_get_genicam_node_info_
 
ros::ServiceServer srv_get_image_acquisition_status_
 
ros::ServiceServer srv_get_last_error_
 
ros::ServiceServer srv_get_trigger_list_
 
ros::ServiceServer srv_read_node_
 
ros::ServiceServer srv_read_node_bool_
 
ros::ServiceServer srv_read_node_enum_
 
ros::ServiceServer srv_read_node_float_
 
ros::ServiceServer srv_read_node_int_
 
ros::ServiceServer srv_read_node_string_
 
ros::ServiceServer srv_send_soft_trigger_
 
ros::ServiceServer srv_write_node_
 
ros::ServiceServer srv_write_node_bool_
 
ros::ServiceServer srv_write_node_enum_int_
 
ros::ServiceServer srv_write_node_enum_str_
 
ros::ServiceServer srv_write_node_float_
 
ros::ServiceServer srv_write_node_int_
 
ros::ServiceServer srv_write_node_string_
 
StApi::CIStDevicePtr tl_dev_
 
StApi::CIStDataStreamPtr tl_ds_
 

Additional Inherited Members

- Protected Member Functions inherited from stcamera::StCameraInterface
bool enableChunkCallback (omronsentech_camera::EnableChunk::Request &req, omronsentech_camera::EnableChunk::Response &res)
 
bool enableEventAcquisitionCallback (omronsentech_camera::EnableEventAcquisition::Request &req, omronsentech_camera::EnableEventAcquisition::Response &res)
 
bool enableEventNodeCallback (omronsentech_camera::EnableEventNode::Request &req, omronsentech_camera::EnableEventNode::Response &res)
 
bool enableImageAcquisitionCallback (omronsentech_camera::EnableImageAcquisition::Request &req, omronsentech_camera::EnableImageAcquisition::Response &res)
 
bool enableTriggerCallback (omronsentech_camera::EnableTrigger::Request &req, omronsentech_camera::EnableTrigger::Response &res)
 
void eventDataStreamCB (StApi::IStCallbackParamBase *p, void *pvContext)
 
void eventDeviceCB (StApi::IStCallbackParamBase *p, void *pvContext)
 
void eventGenApiNodeCB (GenApi::INode *p, void *pvContext)
 
void eventInterfaceCB (StApi::IStCallbackParamBase *p, void *pvContext)
 
void eventSystemCB (StApi::IStCallbackParamBase *p, void *pvContext)
 
bool executeNodeCallback (omronsentech_camera::ExecuteNode::Request &req, omronsentech_camera::ExecuteNode::Response &res)
 
MapCallbackgetCallbackMap (std::string &module_name)
 
bool getChunkListCallback (omronsentech_camera::GetChunkList::Request &req, omronsentech_camera::GetChunkList::Response &res)
 
bool getEnumListCallback (omronsentech_camera::GetEnumList::Request &req, omronsentech_camera::GetEnumList::Response &res)
 
bool getEventAcquisitionStatusListCallback (omronsentech_camera::GetEventAcquisitionStatusList::Request &req, omronsentech_camera::GetEventAcquisitionStatusList::Response &res)
 
bool getEventNodeStatusListCallback (omronsentech_camera::GetEventNodeStatusList::Request &req, omronsentech_camera::GetEventNodeStatusList::Response &res)
 
bool getGenICamNodeInfoCallback (omronsentech_camera::GetGenICamNodeInfo::Request &req, omronsentech_camera::GetGenICamNodeInfo::Response &res)
 
bool getImageAcquisitionStatusCallback (omronsentech_camera::GetImageAcquisitionStatus::Request &req, omronsentech_camera::GetImageAcquisitionStatus::Response &res)
 
bool getLastErrorCallback (omronsentech_camera::GetLastError::Request &req, omronsentech_camera::GetLastError::Response &res)
 
GenApi::INodeMap * getNodeMap (std::string &module_name)
 
bool getTriggerListCallback (omronsentech_camera::GetTriggerList::Request &req, omronsentech_camera::GetTriggerList::Response &res)
 
void initializeCameraInfo ()
 
void publishEventDefault (omronsentech_camera::Event &msg)
 
bool readNodeBoolCallback (omronsentech_camera::ReadNodeBool::Request &req, omronsentech_camera::ReadNodeBool::Response &res)
 
bool readNodeCallback (omronsentech_camera::ReadNode::Request &req, omronsentech_camera::ReadNode::Response &res)
 
bool readNodeEnumCallback (omronsentech_camera::ReadNodeEnum::Request &req, omronsentech_camera::ReadNodeEnum::Response &res)
 
bool readNodeFloatCallback (omronsentech_camera::ReadNodeFloat::Request &req, omronsentech_camera::ReadNodeFloat::Response &res)
 
bool readNodeIntCallback (omronsentech_camera::ReadNodeInt::Request &req, omronsentech_camera::ReadNodeInt::Response &res)
 
bool readNodeStringCallback (omronsentech_camera::ReadNodeString::Request &req, omronsentech_camera::ReadNodeString::Response &res)
 
bool sendSoftTriggerCallback (omronsentech_camera::SendSoftTrigger::Request &req, omronsentech_camera::SendSoftTrigger::Response &res)
 
bool writeNodeBoolCallback (omronsentech_camera::WriteNodeBool::Request &req, omronsentech_camera::WriteNodeBool::Response &res)
 
bool writeNodeCallback (omronsentech_camera::WriteNode::Request &req, omronsentech_camera::WriteNode::Response &res)
 
bool writeNodeEnumIntCallback (omronsentech_camera::WriteNodeEnumInt::Request &req, omronsentech_camera::WriteNodeEnumInt::Response &res)
 
bool writeNodeEnumStrCallback (omronsentech_camera::WriteNodeEnumStr::Request &req, omronsentech_camera::WriteNodeEnumStr::Response &res)
 
bool writeNodeFloatCallback (omronsentech_camera::WriteNodeFloat::Request &req, omronsentech_camera::WriteNodeFloat::Response &res)
 
bool writeNodeIntCallback (omronsentech_camera::WriteNodeInt::Request &req, omronsentech_camera::WriteNodeInt::Response &res)
 
bool writeNodeStringCallback (omronsentech_camera::WriteNodeString::Request &req, omronsentech_camera::WriteNodeString::Response &res)
 

Detailed Description

Class to control a connected GigEVision camera.

This class is specific for GigEVision camera. If there is a more specific GigEVision camera to control, derive this class.

Definition at line 58 of file stcamera_interface_gev.h.

Constructor & Destructor Documentation

stcamera::StCameraInterfaceGEV::StCameraInterfaceGEV ( StApi::IStDeviceReleasable *  dev,
ros::NodeHandle  nh_parent,
const std::string &  camera_namespace,
StParameter param,
uint32_t  queue_size = STCAMERA_QUEUE_SIZE 
)

Constructor.

Parameters
[in]devPointer to the IStDeviceReleasable of the device.
[in]nh_parentThe main ROS node handle.
[in]camera_namespaceThe namespace for the device.
[in]paramPointer to the StParameter class instance.
[in]queue_sizeUsed for initializing publisher (Maximum number of outgoing messages to be queued for delivery to subscribers). Default is set to STCAMERA_QUEUE_SIZE

Definition at line 34 of file stcamera_interface_gev.cpp.

stcamera::StCameraInterfaceGEV::~StCameraInterfaceGEV ( )
virtual

Destructor.

Definition at line 49 of file stcamera_interface_gev.cpp.

Member Function Documentation

bool stcamera::StCameraInterfaceGEV::getIPCallback ( omronsentech_camera::GetGigEIP::Request &  req,
omronsentech_camera::GetGigEIP::Response &  res 
)

ROS service callback for obtaining the IP address information.

Parameters
[in]reqROS service request
[out]resROS service response
Returns
true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

Definition at line 53 of file stcamera_interface_gev.cpp.

bool stcamera::StCameraInterfaceGEV::setIPCallback ( omronsentech_camera::SetGigEIP::Request &  req,
omronsentech_camera::SetGigEIP::Response &  res 
)

ROS service callback for assigning IP address to the device.

Parameters
[in]reqROS service request
[out]resROS service response
Returns
true on success. False otherwise. Last error code and description can be retrieved through get_last_error service.

Definition at line 88 of file stcamera_interface_gev.cpp.

Member Data Documentation

ros::ServiceServer stcamera::StCameraInterfaceGEV::srv_get_gige_ip_
protected

Server for obtaining IP address

Definition at line 102 of file stcamera_interface_gev.h.

ros::ServiceServer stcamera::StCameraInterfaceGEV::srv_set_gige_ip_
protected

Server for assigning IP address

Definition at line 105 of file stcamera_interface_gev.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