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

Base class to control a connected camera. More...

#include <stcamera_interface.h>

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

Public Member Functions

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 Member Functions

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)
 

Protected Attributes

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_
 

Detailed Description

Base class to control a connected camera.

This is a base class to control a connected camera, including callback for services.

Definition at line 145 of file stcamera_interface.h.

Constructor & Destructor Documentation

stcamera::StCameraInterface::StCameraInterface ( 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 41 of file stcamera_interface.cpp.

stcamera::StCameraInterface::~StCameraInterface ( )
virtual

Destructor.

All event node callbacks are deregistered and the callbacks are released here.

Definition at line 268 of file stcamera_interface.cpp.

Member Function Documentation

bool stcamera::StCameraInterface::deviceIsLost ( )

Check if the device is disconnected.

Returns
True if device is already disconnected. False otherwise.

Definition at line 312 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::enableChunkCallback ( omronsentech_camera::EnableChunk::Request &  req,
omronsentech_camera::EnableChunk::Response &  res 
)
protected

ROS service callback for enabling or disabling chunk.

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 1041 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::enableEventAcquisitionCallback ( omronsentech_camera::EnableEventAcquisition::Request &  req,
omronsentech_camera::EnableEventAcquisition::Response &  res 
)
protected

ROS service callback for enabling or disabling event acquisition.

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 1412 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::enableEventNodeCallback ( omronsentech_camera::EnableEventNode::Request &  req,
omronsentech_camera::EnableEventNode::Response &  res 
)
protected

ROS service callback for enabling or disabling GenICam event.

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 1261 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::enableImageAcquisitionCallback ( omronsentech_camera::EnableImageAcquisition::Request &  req,
omronsentech_camera::EnableImageAcquisition::Response &  res 
)
protected

ROS service callback for enabling or disabling image acquisition.

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 1378 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::enableTriggerCallback ( omronsentech_camera::EnableTrigger::Request &  req,
omronsentech_camera::EnableTrigger::Response &  res 
)
protected

ROS service callback for enabling or disabling trigger.

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 1184 of file stcamera_interface.cpp.

void stcamera::StCameraInterface::eventDataStreamCB ( StApi::IStCallbackParamBase *  p,
void *  pvContext 
)
protected

GenTL DataStream event callback function.

This function is called automatically when any GenTL DataStream event occured. Except for GenTL EVENT_NEW_BUFFER of which data is published throught image_transport mechanism or chunk topic, other event data is published through the default event topic.

Parameters
[in]pPointer to the callback handle.
[in]pvContextuser's pointer (not used).

Definition at line 423 of file stcamera_interface.cpp.

void stcamera::StCameraInterface::eventDeviceCB ( StApi::IStCallbackParamBase *  p,
void *  pvContext 
)
protected

GenTL Device event callback function.

This function is called automatically when any GenTL Device event occured. The event data is published through the default event topic.

Parameters
[in]pPointer to the callback handle.
[in]pvContextuser's pointer (not used).

Definition at line 354 of file stcamera_interface.cpp.

void stcamera::StCameraInterface::eventGenApiNodeCB ( GenApi::INode *  p,
void *  pvContext 
)
protected

GenICam node event callback function.

This function is called automatically if a GenICam node event is registered. The event data is published through either the custom event topic provided when enabling the event or the default event topic.

Parameters
[in]pPointer to the GenICam node callback.
[in]pvContextuser's pointer (pointer to the MapCallback of which the event belongs to)

Definition at line 373 of file stcamera_interface.cpp.

void stcamera::StCameraInterface::eventInterfaceCB ( StApi::IStCallbackParamBase *  p,
void *  pvContext 
)
protected

GenTL Interface event callback function.

This function is called automatically when any GenTL Interface event occured. The event data is published through the default event topic.

Parameters
[in]pPointer to the callback handle.
[in]pvContextuser's pointer (not used).

Definition at line 336 of file stcamera_interface.cpp.

void stcamera::StCameraInterface::eventSystemCB ( StApi::IStCallbackParamBase *  p,
void *  pvContext 
)
protected

GenTL System event callback function.

This function is called automatically when any GenTL System event occured.

Parameters
[in]pPointer to the callback handle.
[in]pvContextuser's pointer (not used).

Definition at line 318 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::executeNodeCallback ( omronsentech_camera::ExecuteNode::Request &  req,
omronsentech_camera::ExecuteNode::Response &  res 
)
protected

ROS service callback for executing GenICam node that has command interface type.

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 1020 of file stcamera_interface.cpp.

MapCallback * stcamera::StCameraInterface::getCallbackMap ( std::string &  module_name)
protected

A helper function to obtain one of event callback mapping for a given module name.

Parameters
[in]module_nameName of the module: System, Interface, LocalDevice, RemoteDevice, DataStream.
Returns
nullptr if module name is invalid. Otherwise the callback map that corresponds to the module.

Definition at line 2200 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::getChunkListCallback ( omronsentech_camera::GetChunkList::Request &  req,
omronsentech_camera::GetChunkList::Response &  res 
)
protected

ROS service callback for obtaining chunks provided by the camera.

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 1572 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::getEnumListCallback ( omronsentech_camera::GetEnumList::Request &  req,
omronsentech_camera::GetEnumList::Response &  res 
)
protected

ROS service callback for obtaining enumeration entry of a given GenICam node with interface type of enumeration.

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 1704 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::getEventAcquisitionStatusListCallback ( omronsentech_camera::GetEventAcquisitionStatusList::Request &  req,
omronsentech_camera::GetEventAcquisitionStatusList::Response &  res 
)
protected

ROS service callback for obtaining event acquisition status.

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 1485 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::getEventNodeStatusListCallback ( omronsentech_camera::GetEventNodeStatusList::Request &  req,
omronsentech_camera::GetEventNodeStatusList::Response &  res 
)
protected

ROS service callback for obtaining GenICam node events status.

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 1503 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::getGenICamNodeInfoCallback ( omronsentech_camera::GetGenICamNodeInfo::Request &  req,
omronsentech_camera::GetGenICamNodeInfo::Response &  res 
)
protected

ROS service callback for obtaining information of a given GenICam node.

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 1736 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::getImageAcquisitionStatusCallback ( omronsentech_camera::GetImageAcquisitionStatus::Request &  req,
omronsentech_camera::GetImageAcquisitionStatus::Response &  res 
)
protected

ROS service callback for obtaining image acquisition status.

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 1476 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::getLastErrorCallback ( omronsentech_camera::GetLastError::Request &  req,
omronsentech_camera::GetLastError::Response &  res 
)
protected

ROS service callback for obtaining the last error.

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

Definition at line 2006 of file stcamera_interface.cpp.

GenApi::INodeMap * stcamera::StCameraInterface::getNodeMap ( std::string &  module_name)
protected

A helper function to obtain the GenICam node for a given module name.

Parameters
[in]module_nameName of the module: System, Interface, LocalDevice, RemoteDevice, DataStream.
Returns
nullptr if module name is invalid. Otherwise GenICam node of the module.

Definition at line 2174 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::getTriggerListCallback ( omronsentech_camera::GetTriggerList::Request &  req,
omronsentech_camera::GetTriggerList::Response &  res 
)
protected

ROS service callback for obtaining triggers provided by the camera.

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 1630 of file stcamera_interface.cpp.

void stcamera::StCameraInterface::initializeCameraInfo ( )
protected

Initialize information of the camera. This information is delivered to image subscribers upon publishing acquired images.

Definition at line 2080 of file stcamera_interface.cpp.

void stcamera::StCameraInterface::publishEventDefault ( omronsentech_camera::Event &  msg)
protected

A helper function to publish an event through the default event publisher.

Parameters
[in]msgThe message to deliver.

Definition at line 2225 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::readNodeBoolCallback ( omronsentech_camera::ReadNodeBool::Request &  req,
omronsentech_camera::ReadNodeBool::Response &  res 
)
protected

ROS service callback for obtaining GenICam node value with boolean interface type.

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 697 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::readNodeCallback ( omronsentech_camera::ReadNode::Request &  req,
omronsentech_camera::ReadNode::Response &  res 
)
protected

ROS service callback for obtaining GenICam node value regardless the node value's interface type.

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 630 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::readNodeEnumCallback ( omronsentech_camera::ReadNodeEnum::Request &  req,
omronsentech_camera::ReadNodeEnum::Response &  res 
)
protected

ROS service callback for obtaining GenICam node value with enumeration interface type.

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 717 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::readNodeFloatCallback ( omronsentech_camera::ReadNodeFloat::Request &  req,
omronsentech_camera::ReadNodeFloat::Response &  res 
)
protected

ROS service callback for obtaining GenICam node value with float interface type.

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 758 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::readNodeIntCallback ( omronsentech_camera::ReadNodeInt::Request &  req,
omronsentech_camera::ReadNodeInt::Response &  res 
)
protected

ROS service callback for obtaining GenICam node value with integer interface type.

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 738 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::readNodeStringCallback ( omronsentech_camera::ReadNodeString::Request &  req,
omronsentech_camera::ReadNodeString::Response &  res 
)
protected

ROS service callback for obtaining GenICam node value with string interface type.

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 778 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::sendSoftTriggerCallback ( omronsentech_camera::SendSoftTrigger::Request &  req,
omronsentech_camera::SendSoftTrigger::Response &  res 
)
protected

ROS service callback for sending software trigger execution command to the camera.

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 1979 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::writeNodeBoolCallback ( omronsentech_camera::WriteNodeBool::Request &  req,
omronsentech_camera::WriteNodeBool::Response &  res 
)
protected

ROS service callback for writing GenICam node value with boolean interface type.

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 894 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::writeNodeCallback ( omronsentech_camera::WriteNode::Request &  req,
omronsentech_camera::WriteNode::Response &  res 
)
protected

ROS service callback for writing GenICam node value regardless the node value's interface type.

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 799 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::writeNodeEnumIntCallback ( omronsentech_camera::WriteNodeEnumInt::Request &  req,
omronsentech_camera::WriteNodeEnumInt::Response &  res 
)
protected

ROS service callback for writing GenICam node value with enumeration interface type, where the input is the integer value of the enumeration entry.

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 914 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::writeNodeEnumStrCallback ( omronsentech_camera::WriteNodeEnumStr::Request &  req,
omronsentech_camera::WriteNodeEnumStr::Response &  res 
)
protected

ROS service callback for writing GenICam node value with enumeration interface type, where the input is the symbolic name of the enumeration entry.

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 934 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::writeNodeFloatCallback ( omronsentech_camera::WriteNodeFloat::Request &  req,
omronsentech_camera::WriteNodeFloat::Response &  res 
)
protected

ROS service callback for writing GenICam node value with float interface type.

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 976 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::writeNodeIntCallback ( omronsentech_camera::WriteNodeInt::Request &  req,
omronsentech_camera::WriteNodeInt::Response &  res 
)
protected

ROS service callback for writing GenICam node value with integer interface type.

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 956 of file stcamera_interface.cpp.

bool stcamera::StCameraInterface::writeNodeStringCallback ( omronsentech_camera::WriteNodeString::Request &  req,
omronsentech_camera::WriteNodeString::Response &  res 
)
protected

ROS service callback for writing GenICam node value with string interface type.

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 997 of file stcamera_interface.cpp.

Member Data Documentation

bool stcamera::StCameraInterface::bool_acquisition_is_started_
protected

Flag to indicate if image acquisition is being enabled or not.

Definition at line 650 of file stcamera_interface.h.

bool stcamera::StCameraInterface::bool_event_datastream_
protected

Flag to indicate if GenTL DataStream event is being enabled or not.

Definition at line 662 of file stcamera_interface.h.

bool stcamera::StCameraInterface::bool_event_device_
protected

Flag to indicate if GenTL Device event is being enabled or not.

Definition at line 660 of file stcamera_interface.h.

bool stcamera::StCameraInterface::bool_event_interface_
protected

Flag to indicate if GenTL Interface event is being enabled or not.

Definition at line 658 of file stcamera_interface.h.

bool stcamera::StCameraInterface::bool_event_system_
protected

Flag to indicate if GenTL System event is being enabled or not.

Definition at line 656 of file stcamera_interface.h.

std::string stcamera::StCameraInterface::camera_namespace_
protected

Namespace of the camera. The namespace is generated by using StParameter::getNamespace() function.

Definition at line 552 of file stcamera_interface.h.

camera_info_manager::CameraInfoManager stcamera::StCameraInterface::cinfo_
protected

Used for managing the camera info.

Definition at line 570 of file stcamera_interface.h.

bool stcamera::StCameraInterface::destroyed_
protected

destroyed

Definition at line 699 of file stcamera_interface.h.

image_transport::ImageTransport stcamera::StCameraInterface::it_
protected

Used for delivering image to subscriber.

Definition at line 567 of file stcamera_interface.h.

image_transport::CameraPublisher stcamera::StCameraInterface::it_campub_
protected

Publisher for image data.

Definition at line 573 of file stcamera_interface.h.

int32_t stcamera::StCameraInterface::last_error_
protected

Store the last error code

Definition at line 696 of file stcamera_interface.h.

MapChunk stcamera::StCameraInterface::map_chunk_
protected

Map the chunk name with the chunk's GenICam node

Definition at line 693 of file stcamera_interface.h.

MapCallback stcamera::StCameraInterface::map_event_datastream_
protected

Map the GenICam event node callback name (DataStream module) with the structure StCallback (pair of topic name and the pointer to the callback instance.

Definition at line 688 of file stcamera_interface.h.

MapCallback stcamera::StCameraInterface::map_event_interface_
protected

Map the GenICam event node callback name (Interface module) with the structure StCallback (pair of topic name and the pointer to the callback instance.

Definition at line 673 of file stcamera_interface.h.

MapCallback stcamera::StCameraInterface::map_event_localdevice_
protected

Map the GenICam event node callback name (LocalDevice module) with the structure StCallback (pair of topic name and the pointer to the callback instance.

Definition at line 678 of file stcamera_interface.h.

MapCallback stcamera::StCameraInterface::map_event_remotedevice_
protected

Map the GenICam event node callback name (RemoteDevice module) with the structure StCallback (pair of topic name and the pointer to the callback instance.

Definition at line 683 of file stcamera_interface.h.

MapCallback stcamera::StCameraInterface::map_event_system_
protected

Map the GenICam event node callback name (System module) with the structure StCallback (pair of topic name and the pointer to the callback instance.

Definition at line 668 of file stcamera_interface.h.

MapPublisher stcamera::StCameraInterface::map_msg_event_
protected

Map of event publisher in pair of (topic name, publisher).

Definition at line 579 of file stcamera_interface.h.

ros::Publisher stcamera::StCameraInterface::msg_chunk_
protected

Publisher for chunk data.

Definition at line 576 of file stcamera_interface.h.

std::mutex stcamera::StCameraInterface::mtx_acquisition_
protected

Guard to prevent race when enabling or disabling image acquisition.

Definition at line 648 of file stcamera_interface.h.

std::mutex stcamera::StCameraInterface::mtx_chunk_
protected

Guard to prevent race when enabling or disabling chunk.

Definition at line 691 of file stcamera_interface.h.

std::mutex stcamera::StCameraInterface::mtx_event_
protected

Guard to prevent race when enabling or disabling event acquisition.

Definition at line 653 of file stcamera_interface.h.

ros::NodeHandle stcamera::StCameraInterface::nh_
protected

Child node handle for the camera.

Definition at line 561 of file stcamera_interface.h.

StParameter* stcamera::StCameraInterface::param_
protected

Pointer to the instance of StParameter.

Definition at line 564 of file stcamera_interface.h.

uint32_t stcamera::StCameraInterface::queue_size_
protected

Queue size for publisher (used when dynamically advertise custom topic name).

Definition at line 584 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_enable_chunk_
protected

Server for enable_chunk

Definition at line 617 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_enable_event_acquisition_
protected

Server for enable_event_acquisition

Definition at line 625 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_enable_event_node_
protected

Server for enable_event_node

Definition at line 621 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_enable_image_acquisition_
protected

Server for enable_image_acquisition

Definition at line 623 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_enable_trigger_
protected

Server for enable_trigger

Definition at line 619 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_execute_node_
protected

Server for execute_node

Definition at line 614 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_get_chunk_list_
protected

Server for get_chunk_list

Definition at line 634 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_get_enum_list_
protected

Server for get_enum_list

Definition at line 638 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_get_event_acquisition_status_list_
protected

Server for get_event_acquisition_status_list

Definition at line 630 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_get_event_node_status_list_
protected

Server for get_event_node_status_list

Definition at line 632 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_get_genicam_node_info_
protected

Server for get_genicam_node_info

Definition at line 640 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_get_image_acquisition_status_
protected

Server for get_image_acquisition_status

Definition at line 628 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_get_last_error_
protected

Server for get_last_error

Definition at line 645 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_get_trigger_list_
protected

Server for get_trigger_list

Definition at line 636 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_read_node_
protected

Server for read_node

Definition at line 587 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_read_node_bool_
protected

Server for read_node_bool

Definition at line 589 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_read_node_enum_
protected

Server for read_node_enum

Definition at line 591 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_read_node_float_
protected

Server for read_node_float

Definition at line 595 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_read_node_int_
protected

Server for read_node_int

Definition at line 593 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_read_node_string_
protected

Server for read_node_string

Definition at line 597 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_send_soft_trigger_
protected

Server for send_soft_trigger

Definition at line 643 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_write_node_
protected

Server for write_node

Definition at line 600 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_write_node_bool_
protected

Server for write_node_bool

Definition at line 602 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_write_node_enum_int_
protected

Server for write_node_enum_int

Definition at line 604 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_write_node_enum_str_
protected

Server for write_node_enum_str

Definition at line 606 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_write_node_float_
protected

Server for write_node_float

Definition at line 610 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_write_node_int_
protected

Server for write_node_int

Definition at line 608 of file stcamera_interface.h.

ros::ServiceServer stcamera::StCameraInterface::srv_write_node_string_
protected

Server for write_node_string

Definition at line 612 of file stcamera_interface.h.

StApi::CIStDevicePtr stcamera::StCameraInterface::tl_dev_
protected

Smart pointer to the CIStDevice that holds the device instance.

Definition at line 555 of file stcamera_interface.h.

StApi::CIStDataStreamPtr stcamera::StCameraInterface::tl_ds_
protected

Smart pointer to the CIStDevice that holds the device's datastream.

Definition at line 558 of file stcamera_interface.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