avt_vimba_camera.h
Go to the documentation of this file.
00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 #ifndef AVT_VIMBA_CAMERA_H
00034 #define AVT_VIMBA_CAMERA_H
00035 
00036 #include <VimbaCPP/Include/VimbaCPP.h>
00037 
00038 #include <avt_vimba_camera/AvtVimbaCameraConfig.h>
00039 #include <avt_vimba_camera/frame_observer.h>
00040 #include <avt_vimba_camera/avt_vimba_api.h>
00041 
00042 #include <diagnostic_updater/diagnostic_updater.h>
00043 #include <diagnostic_updater/publisher.h>
00044 
00045 #include <boost/function.hpp>
00046 #include <boost/thread.hpp>
00047 
00048 #include <string>
00049 
00050 using AVT::VmbAPI::VimbaSystem;
00051 using AVT::VmbAPI::CameraPtr;
00052 using AVT::VmbAPI::FramePtr;
00053 using AVT::VmbAPI::IFrameObserverPtr;
00054 
00055 namespace avt_vimba_camera {
00056 
00057 enum FrameStartTriggerMode {
00058   Freerun,
00059   FixedRate,
00060   Software,
00061   SyncIn1,
00062   SyncIn2,
00063   SyncIn3,
00064   SyncIn4
00065 };
00066 
00067 enum CameraState {
00068   OPENING,
00069   IDLE,
00070   CAMERA_NOT_FOUND,
00071   FORMAT_ERROR,
00072   ERROR,
00073   OK
00074 };
00075 
00076 class AvtVimbaCamera {
00077  public:
00078   AvtVimbaCamera();
00079   AvtVimbaCamera(std::string name);
00080   void start(std::string ip_str, std::string guid_str, bool debug_prints = true);
00081   void stop();
00082   double getTimestamp(void);
00083   bool resetTimestamp(void);
00084   double getDeviceTemp(void);
00085 
00086   CameraPtr getCameraPtr(void) {
00087     return vimba_camera_ptr_;
00088   }
00089 
00090   int getWidth();
00091   int getHeight();
00092   int getMaxWidth();
00093   int getMaxHeight();
00094 
00095   // Pass callback function pointer
00096   typedef boost::function<void (const FramePtr)> frameCallbackFunc;
00097   void setCallback(frameCallbackFunc callback = &avt_vimba_camera::AvtVimbaCamera::defaultFrameCallback) {
00098     userFrameCallback = callback;
00099   }
00100 
00101   typedef avt_vimba_camera::AvtVimbaCameraConfig Config;
00102   void updateConfig(Config& config);
00103   void startImaging(void);
00104   void stopImaging(void);
00105   bool isOpened(void) { return opened_; }
00106 
00107  private:
00108   Config config_;
00109 
00110   AvtVimbaApi api_;
00111   // IFrame Observer
00112   FrameObserver* vimba_frame_observer_ptr_;
00113   // The currently streaming camera
00114   CameraPtr vimba_camera_ptr_;
00115   // Current frame
00116   FramePtr vimba_frame_ptr_;
00117   // The max width
00118   VmbInt64_t vimba_camera_max_width_;
00119   // The max height
00120   VmbInt64_t vimba_camera_max_height_;
00121 
00122   // Mutex
00123   boost::mutex config_mutex_;
00124 
00125   // Thread
00126   boost::thread thread_callback_;
00127 
00128   bool opened_;
00129   bool streaming_;
00130   bool on_init_;
00131   bool show_debug_prints_;
00132   std::string name_;
00133 
00134   diagnostic_updater::Updater updater_;
00135   CameraState camera_state_;
00136   std::string diagnostic_msg_;
00137 
00138   // ROS params
00139   int num_frames_;
00140   std::string guid_;
00141   std::string frame_id_;
00142   std::string trigger_source_;
00143   int trigger_source_int_;
00144 
00145   CameraPtr openCamera(std::string id_str);
00146 
00147   frameCallbackFunc userFrameCallback;
00148   void frameCallback(const FramePtr vimba_frame_ptr);
00149   void defaultFrameCallback(const FramePtr vimba_frame_ptr) {
00150     std::cout << "[AvtVimbaCamera] No frame callback provided." << std::endl;
00151   }
00152 
00153   template<typename T>
00154   bool setFeatureValue(const std::string& feature_str, const T& val);
00155   template<typename T>
00156   bool getFeatureValue(const std::string& feature_str, T& val);
00157   bool getFeatureValue(const std::string& feature_str, std::string& val);
00158   bool runCommand(const std::string& command_str);
00159   std::string interfaceToString(VmbInterfaceType interfaceType);
00160   std::string accessModeToString(VmbAccessModeType modeType);
00161   int getTriggerModeInt(std::string mode_str);
00162   void printAllCameraFeatures(CameraPtr camera);
00163 
00164   void updateAcquisitionConfig(Config& config);
00165   void updateExposureConfig(Config& config);
00166   void updateGainConfig(Config& config);
00167   void updateWhiteBalanceConfig(Config& config);
00168   void updateImageModeConfig(Config& config);
00169   void updateROIConfig(Config& config);
00170   void updateBandwidthConfig(Config& config);
00171   void updatePixelFormatConfig(Config& config);
00172   void updatePtpModeConfig(Config& config);
00173   void updateGPIOConfig(Config& config);
00174 
00175   void getCurrentState(diagnostic_updater::DiagnosticStatusWrapper &stat);
00176 
00177 };
00178 }
00179 #endif


avt_vimba_camera
Author(s): Miquel Massot , Allied Vision Technologies
autogenerated on Thu Jun 6 2019 18:23:39