camera.h
Go to the documentation of this file.
1 #ifndef CAMERA_HEADER
2 #define CAMERA_HEADER
3 
4 #include "std_include.h"
5 #include "serialization.h"
6 #include <boost/archive/binary_oarchive.hpp>
7 #include <boost/filesystem.hpp>
8 
9 using namespace Spinnaker;
10 using namespace Spinnaker::GenApi;
11 using namespace Spinnaker::GenICam;
12 using namespace cv;
13 using namespace std;
14 
15 namespace acquisition {
16 
17  class Camera {
18 
19  public:
20 
21  ~Camera();
22  Camera(CameraPtr);
23 
24  void init();
25  void deinit();
26  void begin_acquisition();
27  void end_acquisition();
28 
29  ImagePtr grab_frame();
30  Mat grab_mat_frame();
31  string get_time_stamp();
32  int get_frame_id();
33 
34  void setEnumValue(string, string);
35  void setIntValue(string, int);
36  void setFloatValue(string, float);
37  void setBoolValue(string, bool);
38 
39  void trigger();
40 
41  void setISPEnable();
42  void setFREnable();
43  void setPixelFormat(gcstring formatPic);
44  void exposureTest();
45  void setResolutionPixels(int width, int height);
46  void setBufferSize(int numBuf);
47  void adcBitDepth(gcstring bitDep);
48  void targetGreyValueTest();
49 
50  // void set_acquisition_mode_continuous();
51  // void set_frame_rate(float);
52  // void set_horizontal_binning(int);
53  // void set_vertical_binning(int);
54  // void set_horizontal_decimation(int);
55  // void set_vertical_decimation(int);
56 
57  // void setTrigDelay(float delay);
58  // void setTrigSelectorFrame();
59  // void setTrigMode();
60  // void setTriggerOverlapOff();
61 
62  string getTLNodeStringValue(string node_string);
63  double getFloatValueMax(string node_string);
64  string get_id();
65  void make_master() { MASTER_ = true; ROS_DEBUG_STREAM( "camera " << get_id() << " set as master"); }
66  bool is_master() { return MASTER_; }
67  void set_color(bool flag) { COLOR_ = flag; }
68  void setGetNextImageTimeout(uint64_t get_next_image_timeout) { GET_NEXT_IMAGE_TIMEOUT_ = get_next_image_timeout; }
69  bool verifyBinning(int binningDesired);
70  void calibrationParamsTest(int calibrationWidth, int calibrationHeight);
71 
72  private:
73 
74  Mat convert_to_mat(ImagePtr);
75 
76  CameraPtr pCam_;
77  int64_t timestamp_;
78  int frameID_;
80 
81  bool COLOR_;
82  bool MASTER_;
84 
85  };
86 
87 }
88 
89 #endif
int64_t timestamp_
Definition: camera.h:77
void setGetNextImageTimeout(uint64_t get_next_image_timeout)
Definition: camera.h:68
CameraPtr pCam_
Definition: camera.h:76
uint64_t GET_NEXT_IMAGE_TIMEOUT_
Definition: camera.h:83
bool is_master()
Definition: camera.h:66
#define ROS_DEBUG_STREAM(args)
void set_color(bool flag)
Definition: camera.h:67
void make_master()
Definition: camera.h:65


spinnaker_sdk_camera_driver
Author(s): Abhishek Bajpayee, Pushyami Kaveti, Vikrant Shah
autogenerated on Sun Feb 14 2021 03:34:42