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 <string>
46 #include <mutex>
47 
48 using AVT::VmbAPI::CameraPtr;
49 using AVT::VmbAPI::FramePtr;
50 using AVT::VmbAPI::IFrameObserverPtr;
52 
53 namespace avt_vimba_camera
54 {
56 {
63 };
64 
66 {
67 public:
68  typedef avt_vimba_camera::AvtVimbaCameraConfig Config;
69  typedef std::function<void(const FramePtr)> frameCallbackFunc;
70 
72  AvtVimbaCamera(const std::string& name);
73 
74  void start(const std::string& ip_str, const std::string& guid_str, const std::string& frame_id,
75  bool print_all_features = false);
76  void stop();
77 
78  void updateConfig(Config& config);
79  void startImaging();
80  void stopImaging();
81 
82  // Utility functions
83  double getTimestampRealTime(VmbUint64_t timestamp_ticks);
84  bool isOpened()
85  {
86  return opened_;
87  }
88 
89  // Getters
90  double getTimestamp();
91  double getDeviceTemp();
92  int getSensorWidth();
93  int getSensorHeight();
94 
95  // Setters
96  void setCallback(frameCallbackFunc callback)
97  {
98  userFrameCallback = callback;
99  }
100 
101 private:
102  Config config_;
103 
105  // IFrame Observer
106  SP_DECL(FrameObserver) frame_obs_ptr_;
107  // The currently streaming camera
108  CameraPtr vimba_camera_ptr_;
109  // Current frame
111  // Tick frequency of the on-board clock. Equal to 1 GHz when PTP is in use.
113 
114  // Mutex
115  std::mutex config_mutex_;
116 
118  bool opened_;
120  bool on_init_;
121  std::string name_;
122  std::string guid_;
123  std::string frame_id_;
124 
126  std::string diagnostic_msg_;
127 
128  CameraPtr openCamera(const std::string& id_str, bool print_all_features);
129 
130  frameCallbackFunc userFrameCallback;
131  void frameCallback(const FramePtr vimba_frame_ptr);
132 
133  template <typename T>
134  VmbErrorType setFeatureValue(const std::string& feature_str, const T& val);
135  template <typename T>
136  bool getFeatureValue(const std::string& feature_str, T& val);
137  bool getFeatureValue(const std::string& feature_str, std::string& val);
138  template <typename Vimba_Type, typename Std_Type>
139  void configureFeature(const std::string& feature_str, const Vimba_Type& val_in, Std_Type& val_out);
140  void configureFeature(const std::string& feature_str, const std::string& val_in, std::string& val_out);
141  bool runCommand(const std::string& command_str);
142  void printAllCameraFeatures(const CameraPtr& camera);
143 
144  void updateAcquisitionConfig(Config& config);
145  void updateExposureConfig(Config& config);
146  void updateGammaConfig(Config& config);
147  void updateDspsubregionConfig(Config& config);
148  void updateGainConfig(Config& config);
149  void updateWhiteBalanceConfig(Config& config);
150  void updateImageModeConfig(Config& config);
151  void updateROIConfig(Config& config);
152  void updateBandwidthConfig(Config& config);
153  void updatePixelFormatConfig(Config& config);
154  void updatePtpModeConfig(Config& config);
155  void updateGPIOConfig(Config& config);
156  void updateUSBGPIOConfig(Config& config);
157  void updateIrisConfig(Config& config);
158 
160 };
161 } // namespace avt_vimba_camera
162 #endif
void updatePtpModeConfig(Config &config)
void printAllCameraFeatures(const CameraPtr &camera)
void updateWhiteBalanceConfig(Config &config)
void getCurrentState(diagnostic_updater::DiagnosticStatusWrapper &stat)
long long VmbInt64_t
void updateImageModeConfig(Config &config)
void updatePixelFormatConfig(Config &config)
void updateUSBGPIOConfig(Config &config)
double getTimestampRealTime(VmbUint64_t timestamp_ticks)
VmbErrorType
void setCallback(frameCallbackFunc callback)
void frameCallback(const FramePtr vimba_frame_ptr)
avt_vimba_camera::AvtVimbaCameraConfig Config
unsigned long long VmbUint64_t
bool getFeatureValue(const std::string &feature_str, T &val)
void updateBandwidthConfig(Config &config)
void updateExposureConfig(Config &config)
VmbErrorType setFeatureValue(const std::string &feature_str, const T &val)
CameraPtr openCamera(const std::string &id_str, bool print_all_features)
std::function< void(const FramePtr)> frameCallbackFunc
void configureFeature(const std::string &feature_str, const Vimba_Type &val_in, Std_Type &val_out)
void updateDspsubregionConfig(Config &config)
diagnostic_updater::Updater updater_
void updateGammaConfig(Config &config)
void updateAcquisitionConfig(Config &config)
void start(const std::string &ip_str, const std::string &guid_str, const std::string &frame_id, bool print_all_features=false)
bool runCommand(const std::string &command_str)
SP_DECL(FrameObserver) frame_obs_ptr_


avt_vimba_camera
Author(s): Allied Vision Technologies, Miquel Massot
autogenerated on Fri Jun 2 2023 02:21:10