vimba_ros.h
Go to the documentation of this file.
1 
33 #ifndef VIMBA_ROS_H
34 #define VIMBA_ROS_H
35 
37 
38 #include <avt_vimba_camera/AvtVimbaCameraConfig.h>
40 
41 #include <ros/ros.h>
42 #include <dynamic_reconfigure/SensorLevels.h>
43 #include <sensor_msgs/Image.h>
44 #include <sensor_msgs/CameraInfo.h>
45 #include <sensor_msgs/SetCameraInfo.h>
48 #include <dynamic_reconfigure/server.h>
50 
51 #include <string>
52 #include <map>
53 
57 using AVT::VmbAPI::IFrameObserverPtr;
58 
59 namespace avt_vimba_camera {
60 
62  Freerun,
63  FixedRate,
64  Software,
65  SyncIn1,
66  SyncIn2,
67  SyncIn3,
68  SyncIn4
69 };
70 
76 };
77 
87 };
88 
90  Off,
93 };
94 
95 class VimbaROS {
96  public:
98  int getWidth();
99  int getHeight();
100  int getMaxWidth();
101  int getMaxHeight();
102 
103  private:
104  // true if camera is started
105  bool running_;
107 
108  // ROS Nodehandles
111  // ROS image transport
113  // ROS Camera publisher
115  // ROS Service to get images
117  // Subscriber for input trigger time
119 
120  // ROS params
122  std::string frame_id_;
123  std::string trigger_source_;
125 
126  // ROS messages
127  typedef dynamic_reconfigure::SensorLevels Levels;
128  sensor_msgs::CameraInfo cam_info_;
130 
131  // Dynamic reconfigure
132  typedef avt_vimba_camera::AvtVimbaCameraConfig Config;
133  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
134  ReconfigureServer reconfigure_server_;
135 
136  // Camera configuration
138 
139  // Vimba singleton
141  // IFrame Observer
143  // The currently streaming camera
145  // Current frame
147  // The max width
149  // The max height
151  // A readable value for every Vimba error code
152  std::map<VmbErrorType, std::string> vimba_error_code_to_message_;
153 
154  /*************/
155  /* FUNCTIONS */
156  /*************/
157 
158  template<typename T> bool getFeatureValue(const std::string& feature_str, T& val);
159  bool getFeatureValue(const std::string& feature_str, std::string& val);
160  template<typename T> bool setFeatureValue(const std::string& feature_str, const T& val);
161  bool runCommand(const std::string& command_str);
162 
163  void updateAcquisitionConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
164  void updateExposureConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
165  void updateGainConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
166  void updateWhiteBalanceConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
167  void updateImageModeConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
168  void updateROIConfig(Config& config, FeaturePtrVector feature_ptr_vec);
169  void updateBandwidthConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
170  void updatePixelFormatConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
171  void updateGPIOConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
172  void updatePtpModeConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
173  void updateIrisConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
174 
175  void start(Config& config);
176  void stop();
177  void frameCallback(const FramePtr vimba_frame_ptr);
178  void pollCallback(polled_camera::GetPolledImage::Request& req,
179  polled_camera::GetPolledImage::Response& rsp,
180  sensor_msgs::Image& image,
181  sensor_msgs::CameraInfo& info);
182  bool frameToImage(const FramePtr vimba_frame_ptr, sensor_msgs::Image& image);
183 
184 
185  // Configure camera info
186  void updateCameraInfo(const Config& config);
187  // Dynamic Reconfigure Callback
188  void configure(Config& newconfig, uint32_t level);
189 
190  // Init function to setup AVT Vimba SDK
191  void initApi(void);
192  // Translates Vimba error codes to readable error messages
193  std::string errorCodeToMessage(VmbErrorType eErr);
194  // Translates Vimba access mode codes to readable messages
195  std::string accessModeToString(VmbAccessModeType modeType);
196  // Parser of Vimba Interface Type
197  std::string interfaceToString(VmbInterfaceType interfaceType);
198  // Parser of trigger mode to non-readable integer
199  int getTriggerModeInt(std::string mode);
200  // Open the required camera
201  CameraPtr openCamera(std::string id);
202  // Dummy function to print all features of a camera
203  void printAllCameraFeatures(CameraPtr camera);
204  // Dummy function to list all cameras
205  void listAvailableCameras(void);
206 };
207 }
208 
209 #endif
void updateAcquisitionConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
void configure(Config &newconfig, uint32_t level)
CameraPtr openCamera(std::string id)
NetPointer< Frame, AVT::VmbAPINET::Frame > FramePtr
ros::NodeHandle nhp_
Definition: vimba_ros.h:110
void updatePixelFormatConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
VmbInt64_t vimba_camera_max_width_
Definition: vimba_ros.h:148
std::map< VmbErrorType, std::string > vimba_error_code_to_message_
Definition: vimba_ros.h:152
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: vimba_ros.h:133
long long VmbInt64_t
void updateWhiteBalanceConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
void pollCallback(polled_camera::GetPolledImage::Request &req, polled_camera::GetPolledImage::Response &rsp, sensor_msgs::Image &image, sensor_msgs::CameraInfo &info)
void updateIrisConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
std::string trigger_source_
Definition: vimba_ros.h:123
bool runCommand(const std::string &command_str)
VimbaSystem & vimba_system_
Definition: vimba_ros.h:140
void updateGPIOConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
void updateBandwidthConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
ReconfigureServer reconfigure_server_
Definition: vimba_ros.h:134
bool setFeatureValue(const std::string &feature_str, const T &val)
VmbErrorType
VmbAccessModeType
Definition: VimbaC.h:122
void updateROIConfig(Config &config, FeaturePtrVector feature_ptr_vec)
image_transport::ImageTransport it_
Definition: vimba_ros.h:112
void frameCallback(const FramePtr vimba_frame_ptr)
FrameObserver * vimba_frame_observer_ptr_
Definition: vimba_ros.h:142
dynamic_reconfigure::SensorLevels Levels
Definition: vimba_ros.h:127
image_transport::CameraPublisher streaming_pub_
Definition: vimba_ros.h:114
std::string errorCodeToMessage(VmbErrorType eErr)
VimbaROS(ros::NodeHandle nh, ros::NodeHandle nhp)
NetPointer< Camera, AVT::VmbAPINET::Camera > CameraPtr
bool getFeatureValue(const std::string &feature_str, T &val)
ros::NodeHandle nh_
Definition: vimba_ros.h:109
ros::Subscriber trigger_sub_
Definition: vimba_ros.h:118
VmbInterfaceType
Definition: VimbaC.h:107
void printAllCameraFeatures(CameraPtr camera)
sensor_msgs::CameraInfo cam_info_
Definition: vimba_ros.h:128
bool frameToImage(const FramePtr vimba_frame_ptr, sensor_msgs::Image &image)
void updateImageModeConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
void updateExposureConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
boost::shared_ptr< camera_info_manager::CameraInfoManager > cinfo_
Definition: vimba_ros.h:129
polled_camera::PublicationServer poll_srv_
Definition: vimba_ros.h:116
void updatePtpModeConfig(const Config &config, FeaturePtrVector feature_ptr_vec)
std::vector< FeaturePtr > FeaturePtrVector
Definition: Feature.h:46
void start(Config &config)
std::string interfaceToString(VmbInterfaceType interfaceType)
void updateCameraInfo(const Config &config)
std::string accessModeToString(VmbAccessModeType modeType)
int getTriggerModeInt(std::string mode)
avt_vimba_camera::AvtVimbaCameraConfig Config
Definition: vimba_ros.h:132
VmbInt64_t vimba_camera_max_height_
Definition: vimba_ros.h:150
void updateGainConfig(const Config &config, FeaturePtrVector feature_ptr_vec)


avt_vimba_camera
Author(s): Miquel Massot , Allied Vision Technologies
autogenerated on Mon Jun 10 2019 12:50:39