avt_vimba_camera.h
Go to the documentation of this file.
1 
33 #ifndef AVT_VIMBA_CAMERA_H
34 #define AVT_VIMBA_CAMERA_H
35 
37 
38 #include <avt_vimba_camera/AvtVimbaCameraConfig.h>
41 
44 
45 #include <boost/function.hpp>
46 #include <boost/thread.hpp>
47 
48 #include <string>
49 
53 using AVT::VmbAPI::IFrameObserverPtr;
54 
55 namespace avt_vimba_camera {
56 
65 };
66 
74 };
75 
77  public:
79  AvtVimbaCamera(std::string name);
80  void start(std::string ip_str, std::string guid_str, bool debug_prints = true);
81  void stop();
82  double getTimestamp(void);
83  bool resetTimestamp(void);
84  double getDeviceTemp(void);
85 
87  return vimba_camera_ptr_;
88  }
89 
90  int getWidth();
91  int getHeight();
92  int getMaxWidth();
93  int getMaxHeight();
94 
95  // Pass callback function pointer
96  typedef boost::function<void (const FramePtr)> frameCallbackFunc;
98  userFrameCallback = callback;
99  }
100 
101  typedef avt_vimba_camera::AvtVimbaCameraConfig Config;
102  void updateConfig(Config& config);
103  void startImaging(void);
104  void stopImaging(void);
105  bool isOpened(void) { return opened_; }
106 
107  private:
108  Config config_;
109 
111  // IFrame Observer
113  // The currently streaming camera
115  // Current frame
117  // The max width
119  // The max height
121 
122  // Mutex
123  boost::mutex config_mutex_;
124 
125  bool opened_;
127  bool on_init_;
129  std::string name_;
130 
133  std::string diagnostic_msg_;
134 
135  // ROS params
137  std::string guid_;
138  std::string frame_id_;
139  std::string trigger_source_;
141 
142  CameraPtr openCamera(std::string id_str);
143 
144  frameCallbackFunc userFrameCallback;
145  void frameCallback(const FramePtr vimba_frame_ptr);
146  void defaultFrameCallback(const FramePtr vimba_frame_ptr) {
147  std::cout << "[AvtVimbaCamera] No frame callback provided." << std::endl;
148  }
149 
150  template<typename T>
151  bool setFeatureValue(const std::string& feature_str, const T& val);
152  template<typename T>
153  bool getFeatureValue(const std::string& feature_str, T& val);
154  bool getFeatureValue(const std::string& feature_str, std::string& val);
155  bool runCommand(const std::string& command_str);
156  std::string interfaceToString(VmbInterfaceType interfaceType);
157  std::string accessModeToString(VmbAccessModeType modeType);
158  int getTriggerModeInt(std::string mode_str);
159  void printAllCameraFeatures(const CameraPtr& camera);
160 
161  void updateAcquisitionConfig(Config& config);
162  void updateExposureConfig(Config& config);
163  void updateGainConfig(Config& config);
164  void updateWhiteBalanceConfig(Config& config);
165  void updateImageModeConfig(Config& config);
166  void updateROIConfig(Config& config);
167  void updateBandwidthConfig(Config& config);
168  void updatePixelFormatConfig(Config& config);
169  void updatePtpModeConfig(Config& config);
170  void updateGPIOConfig(Config& config);
171  void updateIrisConfig(Config& config);
172 
174 
175 };
176 }
177 #endif
void updatePtpModeConfig(Config &config)
std::string interfaceToString(VmbInterfaceType interfaceType)
void printAllCameraFeatures(const CameraPtr &camera)
void updateWhiteBalanceConfig(Config &config)
NetPointer< Frame, AVT::VmbAPINET::Frame > FramePtr
void getCurrentState(diagnostic_updater::DiagnosticStatusWrapper &stat)
long long VmbInt64_t
void updateImageModeConfig(Config &config)
void updatePixelFormatConfig(Config &config)
CameraPtr openCamera(std::string id_str)
void setCallback(frameCallbackFunc callback=&avt_vimba_camera::AvtVimbaCamera::defaultFrameCallback)
int getTriggerModeInt(std::string mode_str)
VmbAccessModeType
Definition: VimbaC.h:122
void frameCallback(const FramePtr vimba_frame_ptr)
boost::function< void(const FramePtr)> frameCallbackFunc
avt_vimba_camera::AvtVimbaCameraConfig Config
void start(std::string ip_str, std::string guid_str, bool debug_prints=true)
NetPointer< Camera, AVT::VmbAPINET::Camera > CameraPtr
bool setFeatureValue(const std::string &feature_str, const T &val)
bool getFeatureValue(const std::string &feature_str, T &val)
void updateBandwidthConfig(Config &config)
void updateExposureConfig(Config &config)
VmbInterfaceType
Definition: VimbaC.h:107
diagnostic_updater::Updater updater_
void updateAcquisitionConfig(Config &config)
void defaultFrameCallback(const FramePtr vimba_frame_ptr)
std::string accessModeToString(VmbAccessModeType modeType)
bool runCommand(const std::string &command_str)


avt_vimba_camera
Author(s): Miquel Massot , Allied Vision Technologies
autogenerated on Wed Jun 5 2019 22:22:40