Base class to control a connected camera. More...
#include <mutex>
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <camera_info_manager/camera_info_manager.h>
#include <sensor_msgs/image_encodings.h>
#include <sensor_msgs/CameraInfo.h>
#include <omronsentech_camera/Event.h>
#include <omronsentech_camera/Chunk.h>
#include <omronsentech_camera/ReadNode.h>
#include <omronsentech_camera/ReadNodeBool.h>
#include <omronsentech_camera/ReadNodeEnum.h>
#include <omronsentech_camera/ReadNodeInt.h>
#include <omronsentech_camera/ReadNodeFloat.h>
#include <omronsentech_camera/ReadNodeString.h>
#include <omronsentech_camera/WriteNode.h>
#include <omronsentech_camera/WriteNodeBool.h>
#include <omronsentech_camera/WriteNodeEnumInt.h>
#include <omronsentech_camera/WriteNodeEnumStr.h>
#include <omronsentech_camera/WriteNodeInt.h>
#include <omronsentech_camera/WriteNodeFloat.h>
#include <omronsentech_camera/WriteNodeString.h>
#include <omronsentech_camera/ExecuteNode.h>
#include <omronsentech_camera/EnableChunk.h>
#include <omronsentech_camera/EnableTrigger.h>
#include <omronsentech_camera/EnableEventNode.h>
#include <omronsentech_camera/EnableImageAcquisition.h>
#include <omronsentech_camera/EnableEventAcquisition.h>
#include <omronsentech_camera/GetImageAcquisitionStatus.h>
#include <omronsentech_camera/GetEventAcquisitionStatusList.h>
#include <omronsentech_camera/GetEventNodeStatusList.h>
#include <omronsentech_camera/GetChunkList.h>
#include <omronsentech_camera/GetTriggerList.h>
#include <omronsentech_camera/GetEnumList.h>
#include <omronsentech_camera/GetGenICamNodeInfo.h>
#include <omronsentech_camera/SendSoftTrigger.h>
#include <omronsentech_camera/GetLastError.h>
#include <StApi_TL.h>
#include "omronsentech_camera/stparameter.h"
#include "omronsentech_camera/stheader.h"
Go to the source code of this file.
Classes | |
struct | stcamera::StCallback |
class | stcamera::StCameraInterface |
Base class to control a connected camera. More... | |
Namespaces | |
stcamera | |
Macros | |
#define | CATCH_COMMON_ERR() |
#define | CHECK_NULLPTR(P, X, MSG) |
#define | RETURN_ERR(X, MSG) |
Typedefs | |
typedef std::map< std::string, struct StCallback > | stcamera::MapCallback |
typedef std::map< std::string, StCameraInterface * > | stcamera::MapCameraInterface |
typedef std::map< std::string, GenApi::INode * > | stcamera::MapChunk |
typedef std::map< std::string, ros::Publisher > | stcamera::MapPublisher |
Base class to control a connected camera.
This is a base class to control a connected camera, including callback for services.
Definition in file stcamera_interface.h.
#define CATCH_COMMON_ERR | ( | ) |
Macro for common exception.
Definition at line 101 of file stcamera_interface.h.
#define CHECK_NULLPTR | ( | P, | |
X, | |||
MSG | |||
) |
Macro for checking null.
Definition at line 97 of file stcamera_interface.h.
#define RETURN_ERR | ( | X, | |
MSG | |||
) |
Macro for failure callback.
Definition at line 91 of file stcamera_interface.h.