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
97  {
99  }
100 
101 private:
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 
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
avt_vimba_camera::AvtVimbaCamera::getSensorHeight
int getSensorHeight()
Definition: avt_vimba_camera.cpp:342
avt_vimba_camera::AvtVimbaCamera::diagnostic_msg_
std::string diagnostic_msg_
Definition: avt_vimba_camera.h:126
avt_vimba_camera::CameraState
CameraState
Definition: avt_vimba_camera.h:55
avt_vimba_camera::AvtVimbaCamera::name_
std::string name_
Definition: avt_vimba_camera.h:121
avt_vimba_camera::AvtVimbaCamera::updateDspsubregionConfig
void updateDspsubregionConfig(Config &config)
Definition: avt_vimba_camera.cpp:991
avt_vimba_camera::AvtVimbaCamera::start
void start(const std::string &ip_str, const std::string &guid_str, const std::string &frame_id, bool print_all_features=false)
Definition: avt_vimba_camera.cpp:85
avt_vimba_camera::AvtVimbaCamera::updateIrisConfig
void updateIrisConfig(Config &config)
Definition: avt_vimba_camera.cpp:884
AVT::VmbAPI::VimbaSystem
Definition: VimbaSystem.h:48
avt_vimba_camera::AvtVimbaCamera::guid_
std::string guid_
Definition: avt_vimba_camera.h:122
avt_vimba_camera::ERROR
@ ERROR
Definition: avt_vimba_camera.h:61
frame_observer.h
avt_vimba_camera::IDLE
@ IDLE
Definition: avt_vimba_camera.h:58
avt_vimba_camera::AvtVimbaApi
Definition: avt_vimba_api.h:52
callback
void callback(const sensor_msgs::ImageConstPtr &msg)
avt_vimba_camera::AvtVimbaCamera::config_mutex_
std::mutex config_mutex_
Definition: avt_vimba_camera.h:115
avt_vimba_camera::AvtVimbaCamera::Config
avt_vimba_camera::AvtVimbaCameraConfig Config
Definition: avt_vimba_camera.h:68
avt_vimba_camera::AvtVimbaCamera::vimba_timestamp_tick_freq_
VmbInt64_t vimba_timestamp_tick_freq_
Definition: avt_vimba_camera.h:112
avt_vimba_camera::AvtVimbaCamera::on_init_
bool on_init_
Definition: avt_vimba_camera.h:120
VmbErrorType
VmbErrorType
Definition: VmbCommonTypes.h:106
avt_vimba_camera::AvtVimbaCamera::frameCallback
void frameCallback(const FramePtr vimba_frame_ptr)
Definition: avt_vimba_camera.cpp:293
diagnostic_updater::Updater
avt_vimba_camera::OPENING
@ OPENING
Definition: avt_vimba_camera.h:57
avt_vimba_camera::AvtVimbaCamera
Definition: avt_vimba_camera.h:65
avt_vimba_camera::AvtVimbaCamera::stopImaging
void stopImaging()
Definition: avt_vimba_camera.cpp:198
FrameObserver
Definition: frame_observer.h:42
VimbaCPP.h
publisher.h
avt_vimba_camera::AvtVimbaCamera::vimba_camera_ptr_
CameraPtr vimba_camera_ptr_
Definition: avt_vimba_camera.h:108
avt_vimba_camera::FORMAT_ERROR
@ FORMAT_ERROR
Definition: avt_vimba_camera.h:60
avt_vimba_camera::AvtVimbaCamera::AvtVimbaCamera
AvtVimbaCamera()
Definition: avt_vimba_camera.cpp:66
diagnostic_updater.h
avt_vimba_camera::AvtVimbaCamera::configureFeature
void configureFeature(const std::string &feature_str, const Vimba_Type &val_in, Std_Type &val_out)
Definition: avt_vimba_camera.cpp:561
VmbUint64_t
unsigned long long VmbUint64_t
Definition: VmbCommonTypes.h:77
avt_vimba_camera::AvtVimbaCamera::userFrameCallback
frameCallbackFunc userFrameCallback
Definition: avt_vimba_camera.h:130
avt_vimba_camera::AvtVimbaCamera::isOpened
bool isOpened()
Definition: avt_vimba_camera.h:84
avt_vimba_camera::AvtVimbaCamera::updatePixelFormatConfig
void updatePixelFormatConfig(Config &config)
Definition: avt_vimba_camera.cpp:1182
avt_vimba_camera::AvtVimbaCamera::updateUSBGPIOConfig
void updateUSBGPIOConfig(Config &config)
Definition: avt_vimba_camera.cpp:1221
avt_vimba_camera::AvtVimbaCamera::getCurrentState
void getCurrentState(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: avt_vimba_camera.cpp:1237
avt_vimba_camera::AvtVimbaCamera::printAllCameraFeatures
void printAllCameraFeatures(const CameraPtr &camera)
Definition: avt_vimba_camera.cpp:648
avt_vimba_camera::AvtVimbaCamera::updateBandwidthConfig
void updateBandwidthConfig(Config &config)
Definition: avt_vimba_camera.cpp:1167
avt_vimba_camera::AvtVimbaCamera::openCamera
CameraPtr openCamera(const std::string &id_str, bool print_all_features)
Definition: avt_vimba_camera.cpp:225
avt_vimba_camera::AvtVimbaCamera::updateGPIOConfig
void updateGPIOConfig(Config &config)
Definition: avt_vimba_camera.cpp:1196
avt_vimba_camera::AvtVimbaCamera::frame_id_
std::string frame_id_
Definition: avt_vimba_camera.h:123
avt_vimba_camera::AvtVimbaCamera::updateAcquisitionConfig
void updateAcquisitionConfig(Config &config)
Definition: avt_vimba_camera.cpp:829
avt_vimba_camera::AvtVimbaCamera::runCommand
bool runCommand(const std::string &command_str)
Definition: avt_vimba_camera.cpp:613
avt_vimba_camera::AvtVimbaCamera::updateGammaConfig
void updateGammaConfig(Config &config)
Definition: avt_vimba_camera.cpp:978
avt_vimba_camera::AvtVimbaCamera::startImaging
void startImaging()
Definition: avt_vimba_camera.cpp:170
avt_vimba_camera::AvtVimbaCamera::vimba_frame_ptr_
FramePtr vimba_frame_ptr_
Definition: avt_vimba_camera.h:110
avt_vimba_camera::AvtVimbaCamera::updatePtpModeConfig
void updatePtpModeConfig(Config &config)
Definition: avt_vimba_camera.cpp:1092
VmbInt64_t
long long VmbInt64_t
Definition: VmbCommonTypes.h:75
avt_vimba_camera::AvtVimbaCamera::setCallback
void setCallback(frameCallbackFunc callback)
Definition: avt_vimba_camera.h:96
avt_vimba_camera::AvtVimbaCamera::updateImageModeConfig
void updateImageModeConfig(Config &config)
Definition: avt_vimba_camera.cpp:1107
avt_vimba_camera::AvtVimbaCamera::getFeatureValue
bool getFeatureValue(const std::string &feature_str, T &val)
Definition: avt_vimba_camera.cpp:430
avt_vimba_camera::AvtVimbaCamera::opened_
bool opened_
Definition: avt_vimba_camera.h:118
avt_vimba_camera::AvtVimbaCamera::stop
void stop()
Definition: avt_vimba_camera.cpp:162
avt_vimba_camera::OK
@ OK
Definition: avt_vimba_camera.h:62
avt_vimba_camera::AvtVimbaCamera::getSensorWidth
int getSensorWidth()
Definition: avt_vimba_camera.cpp:329
avt_vimba_camera::AvtVimbaCamera::updateWhiteBalanceConfig
void updateWhiteBalanceConfig(Config &config)
Definition: avt_vimba_camera.cpp:1060
avt_vimba_camera::AvtVimbaCamera::SP_DECL
SP_DECL(FrameObserver) frame_obs_ptr_
avt_vimba_camera::CAMERA_NOT_FOUND
@ CAMERA_NOT_FOUND
Definition: avt_vimba_camera.h:59
avt_vimba_camera::AvtVimbaCamera::streaming_
bool streaming_
Definition: avt_vimba_camera.h:119
avt_vimba_camera
Definition: avt_vimba_api.h:50
avt_vimba_camera::AvtVimbaCamera::updateExposureConfig
void updateExposureConfig(Config &config)
Definition: avt_vimba_camera.cpp:912
avt_vimba_camera::AvtVimbaCamera::setFeatureValue
VmbErrorType setFeatureValue(const std::string &feature_str, const T &val)
Definition: avt_vimba_camera.cpp:362
avt_vimba_camera::AvtVimbaCamera::config_
Config config_
Definition: avt_vimba_camera.h:102
avt_vimba_camera::AvtVimbaCamera::getDeviceTemp
double getDeviceTemp()
Definition: avt_vimba_camera.cpp:319
diagnostic_updater::DiagnosticStatusWrapper
avt_vimba_camera::AvtVimbaCamera::getTimestampRealTime
double getTimestampRealTime(VmbUint64_t timestamp_ticks)
Definition: avt_vimba_camera.cpp:355
avt_vimba_camera::AvtVimbaCamera::updateConfig
void updateConfig(Config &config)
Definition: avt_vimba_camera.cpp:788
avt_vimba_camera::AvtVimbaCamera::updateGainConfig
void updateGainConfig(Config &config)
Definition: avt_vimba_camera.cpp:1017
avt_vimba_camera::AvtVimbaCamera::api_
AvtVimbaApi api_
Definition: avt_vimba_camera.h:104
avt_vimba_camera::AvtVimbaCamera::frameCallbackFunc
std::function< void(const FramePtr)> frameCallbackFunc
Definition: avt_vimba_camera.h:69
avt_vimba_camera::AvtVimbaCamera::camera_state_
CameraState camera_state_
Definition: avt_vimba_camera.h:117
avt_vimba_camera::AvtVimbaCamera::updateROIConfig
void updateROIConfig(Config &config)
Definition: avt_vimba_camera.cpp:1141
avt_vimba_camera::AvtVimbaCamera::getTimestamp
double getTimestamp()
Definition: avt_vimba_camera.cpp:306
avt_vimba_camera::AvtVimbaCamera::updater_
diagnostic_updater::Updater updater_
Definition: avt_vimba_camera.h:125
avt_vimba_api.h


avt_vimba_camera
Author(s): Allied Vision Technologies, Miquel Massot
autogenerated on Sat Jun 3 2023 02:14:12