37 #ifndef STCAMERA_STCAMERA_INTERFACE_GEV_H 38 #define STCAMERA_STCAMERA_INTERFACE_GEV_H 42 #include <omronsentech_camera/GetGigEIP.h> 43 #include <omronsentech_camera/SetGigEIP.h> 45 #include <sys/socket.h> 46 #include <netinet/in.h> 47 #include <arpa/inet.h> 74 const std::string &camera_namespace,
88 bool getIPCallback(omronsentech_camera::GetGigEIP::Request &req,
89 omronsentech_camera::GetGigEIP::Response &res);
97 bool setIPCallback(omronsentech_camera::SetGigEIP::Request &req,
98 omronsentech_camera::SetGigEIP::Response &res);
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
Class to control a connected GigEVision camera.
Base class to control a connected camera.
bool setIPCallback(omronsentech_camera::SetGigEIP::Request &req, omronsentech_camera::SetGigEIP::Response &res)
ros::ServiceServer srv_get_gige_ip_
bool getIPCallback(omronsentech_camera::GetGigEIP::Request &req, omronsentech_camera::GetGigEIP::Response &res)
Base class to control a connected camera.
virtual ~StCameraInterfaceGEV()
Class to handle ROS parameter.
StCameraInterfaceGEV(StApi::IStDeviceReleasable *dev, ros::NodeHandle nh_parent, const std::string &camera_namespace, StParameter *param, uint32_t queue_size=STCAMERA_QUEUE_SIZE)
ros::ServiceServer srv_set_gige_ip_