36 #ifndef STCAMERA_STCAMERA_NODE_H 37 #define STCAMERA_STCAMERA_NODE_H 45 #include <omronsentech_camera/GenTLInfo.h> 46 #include <omronsentech_camera/DeviceConnection.h> 47 #include <omronsentech_camera/GetDeviceList.h> 48 #include <omronsentech_camera/GetModuleList.h> 49 #include <omronsentech_camera/GetSDKInfo.h> 50 #include <omronsentech_camera/GetGigEIPi.h> 51 #include <omronsentech_camera/SetGigEIPi.h> 56 typedef std::map<std::string, omronsentech_camera::DeviceConnection>
106 const StApi::IStDeviceInfo *p_devinfo);
116 omronsentech_camera::GetDeviceList::Request &req,
117 omronsentech_camera::GetDeviceList::Response &res);
126 omronsentech_camera::GetModuleList::Request &req,
127 omronsentech_camera::GetModuleList::Response &res);
135 omronsentech_camera::GetSDKInfo::Response &res);
144 omronsentech_camera::GetGigEIPi::Response &res);
153 omronsentech_camera::SetGigEIPi::Response &res);
201 const StApi::IStSystemInfo *p_tlinfo,
202 StApi::IStInterface *p_iface,
203 const StApi::IStDeviceInfo *p_devinfo,
204 std::string device_namespace =
"",
205 bool connected =
false);
bool getSDKInfoCallback(omronsentech_camera::GetSDKInfo::Request &req, omronsentech_camera::GetSDKInfo::Response &res)
ros::Publisher msg_device_connection_
ros::ServiceServer srv_get_gige_ip_i_
StApi::CStApiAutoInit stapi_autoinit_
bool getModuleListCallback(omronsentech_camera::GetModuleList::Request &req, omronsentech_camera::GetModuleList::Response &res)
bool setGigEIPCallback(omronsentech_camera::SetGigEIPi::Request &req, omronsentech_camera::SetGigEIPi::Response &res)
Class implementation for stcamera_node.
Base class to control a connected camera.
bool getGigEIPCallback(omronsentech_camera::GetGigEIPi::Request &req, omronsentech_camera::GetGigEIPi::Response &res)
bool initializeCamera(StApi::IStInterface *p_iface, const StApi::IStDeviceInfo *p_devinfo)
std::map< std::string, omronsentech_camera::DeviceConnection > MapDeviceConnection
std::map< std::string, StCameraInterface * > MapCameraInterface
MapCameraInterface map_camera_
StApi::CIStSystemPtrArray stapi_systems_
ros::ServiceServer srv_get_sdk_info_
bool getDeviceListCallback(omronsentech_camera::GetDeviceList::Request &req, omronsentech_camera::GetDeviceList::Response &res)
MapDeviceConnection map_connection_
std::mutex mtx_update_device_list_
Class to handle ROS parameter.
Class to handle ROS parameter.
std::mutex mtx_map_camera_
ros::ServiceServer srv_get_device_list_
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)
ros::ServiceServer srv_set_gige_ip_i_
ros::ServiceServer srv_get_module_list_