Class to control a connected GigEVision camera. More...
#include <stcamera_interface_gev.h>
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 () |
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) |
MapCallback * | getCallbackMap (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) |
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.
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.
[in] | dev | Pointer to the IStDeviceReleasable of the device. |
[in] | nh_parent | The main ROS node handle. |
[in] | camera_namespace | The namespace for the device. |
[in] | param | Pointer to the StParameter class instance. |
[in] | queue_size | Used 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.
|
virtual |
Destructor.
Definition at line 49 of file stcamera_interface_gev.cpp.
bool stcamera::StCameraInterfaceGEV::getIPCallback | ( | omronsentech_camera::GetGigEIP::Request & | req, |
omronsentech_camera::GetGigEIP::Response & | res | ||
) |
ROS service callback for obtaining the IP address information.
[in] | req | ROS service request |
[out] | res | ROS service response |
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.
[in] | req | ROS service request |
[out] | res | ROS service response |
Definition at line 88 of file stcamera_interface_gev.cpp.
|
protected |
Server for obtaining IP address
Definition at line 102 of file stcamera_interface_gev.h.
|
protected |
Server for assigning IP address
Definition at line 105 of file stcamera_interface_gev.h.