avt_vimba_api.h
Go to the documentation of this file.
1 
33 #ifndef AVT_VIMBA_API_H
34 #define AVT_VIMBA_API_H
35 
37 
38 #include <ros/ros.h>
39 #include <sensor_msgs/Image.h>
41 #include <sensor_msgs/fill_image.h>
42 
43 #include <string>
44 #include <map>
45 
46 using AVT::VmbAPI::CameraPtr;
47 using AVT::VmbAPI::FramePtr;
49 
51 {
53 {
54 public:
55  AvtVimbaApi() : vs(VimbaSystem::GetInstance())
56  {
57  }
58 
59  void start()
60  {
61  VmbErrorType err = vs.Startup();
62  if (VmbErrorSuccess == err)
63  {
64  ROS_INFO_STREAM("[Vimba System]: AVT Vimba System initialized successfully");
66  }
67  else
68  {
69  ROS_ERROR_STREAM("[Vimba System]: Could not start Vimba system: " << errorCodeToMessage(err));
70  }
71  }
72 
79  std::string errorCodeToMessage(VmbErrorType error)
80  {
81  std::map<VmbErrorType, std::string> error_msg;
82  error_msg[VmbErrorSuccess] = "Success.";
83  error_msg[VmbErrorApiNotStarted] = "API not started.";
84  error_msg[VmbErrorNotFound] = "Not found.";
85  error_msg[VmbErrorBadHandle] = "Invalid handle ";
86  error_msg[VmbErrorDeviceNotOpen] = "Device not open.";
87  error_msg[VmbErrorInvalidAccess] = "Invalid access.";
88  error_msg[VmbErrorBadParameter] = "Bad parameter.";
89  error_msg[VmbErrorStructSize] = "Wrong DLL version.";
90  error_msg[VmbErrorWrongType] = "Wrong type.";
91  error_msg[VmbErrorInvalidValue] = "Invalid value.";
92  error_msg[VmbErrorTimeout] = "Timeout.";
93  error_msg[VmbErrorOther] = "TL error.";
94  error_msg[VmbErrorInvalidCall] = "Invalid call.";
95  error_msg[VmbErrorNoTL] = "TL not loaded.";
96  error_msg[VmbErrorNotImplemented] = "Not implemented.";
97  error_msg[VmbErrorNotSupported] = "Not supported.";
98  error_msg[VmbErrorResources] = "Resource not available.";
99  error_msg[VmbErrorInternalFault] = "Unexpected fault in VmbApi or driver.";
100  error_msg[VmbErrorMoreData] = "More data returned than memory provided.";
101 
102  std::map<VmbErrorType, std::string>::const_iterator iter = error_msg.find(error);
103  if (error_msg.end() != iter)
104  {
105  return iter->second;
106  }
107  return "Unsupported error code passed.";
108  }
109 
110  std::string interfaceToString(VmbInterfaceType interfaceType)
111  {
112  switch (interfaceType)
113  {
115  return "FireWire";
116  break;
118  return "GigE";
119  break;
120  case VmbInterfaceUsb:
121  return "USB";
122  break;
123  default:
124  return "Unknown";
125  }
126  }
127 
128  std::string accessModeToString(VmbAccessModeType modeType)
129  {
130  if (modeType & VmbAccessModeFull)
131  return "Read and write access";
132  else if (modeType & VmbAccessModeRead)
133  return "Only read access";
134  else if (modeType & VmbAccessModeConfig)
135  return "Device configuration access";
136  else if (modeType & VmbAccessModeLite)
137  return "Device read/write access without feature access (only addresses)";
138  else if (modeType & VmbAccessModeNone)
139  return "No access";
140  else
141  return "Undefined access";
142  }
143 
144  bool frameToImage(const FramePtr vimba_frame_ptr, sensor_msgs::Image& image)
145  {
146  VmbPixelFormatType pixel_format;
147  VmbUint32_t width, height, nSize;
148 
149  vimba_frame_ptr->GetWidth(width);
150  vimba_frame_ptr->GetHeight(height);
151  vimba_frame_ptr->GetPixelFormat(pixel_format);
152  vimba_frame_ptr->GetImageSize(nSize);
153 
154  VmbUint32_t step = nSize / height;
155 
156  // NOTE: YUV and ARGB formats not supported
157  std::string encoding;
158  if (pixel_format == VmbPixelFormatMono8)
160  else if (pixel_format == VmbPixelFormatMono10)
162  else if (pixel_format == VmbPixelFormatMono12)
164  else if (pixel_format == VmbPixelFormatMono12Packed)
166  else if (pixel_format == VmbPixelFormatMono14)
168  else if (pixel_format == VmbPixelFormatMono16)
170  else if (pixel_format == VmbPixelFormatBayerGR8)
172  else if (pixel_format == VmbPixelFormatBayerRG8)
174  else if (pixel_format == VmbPixelFormatBayerGB8)
176  else if (pixel_format == VmbPixelFormatBayerBG8)
178  else if (pixel_format == VmbPixelFormatBayerGR10)
180  else if (pixel_format == VmbPixelFormatBayerRG10)
182  else if (pixel_format == VmbPixelFormatBayerGB10)
184  else if (pixel_format == VmbPixelFormatBayerBG10)
186  else if (pixel_format == VmbPixelFormatBayerGR12)
188  else if (pixel_format == VmbPixelFormatBayerRG12)
190  else if (pixel_format == VmbPixelFormatBayerGB12)
192  else if (pixel_format == VmbPixelFormatBayerBG12)
194  else if (pixel_format == VmbPixelFormatBayerGR12Packed)
196  else if (pixel_format == VmbPixelFormatBayerRG12Packed)
198  else if (pixel_format == VmbPixelFormatBayerGB12Packed)
200  else if (pixel_format == VmbPixelFormatBayerBG12Packed)
202  else if (pixel_format == VmbPixelFormatBayerGR16)
204  else if (pixel_format == VmbPixelFormatBayerRG16)
206  else if (pixel_format == VmbPixelFormatBayerGB16)
208  else if (pixel_format == VmbPixelFormatBayerBG16)
210  else if (pixel_format == VmbPixelFormatRgb8)
212  else if (pixel_format == VmbPixelFormatBgr8)
214  else if (pixel_format == VmbPixelFormatRgba8)
216  else if (pixel_format == VmbPixelFormatBgra8)
218  else if (pixel_format == VmbPixelFormatRgb12)
220  else if (pixel_format == VmbPixelFormatRgb16)
222  else
223  ROS_WARN("Received frame with unsupported pixel format %d", pixel_format);
224  if (encoding == "")
225  return false;
226 
227  VmbUchar_t* buffer_ptr;
228  VmbErrorType err = vimba_frame_ptr->GetImage(buffer_ptr);
229  bool res = false;
230  if (VmbErrorSuccess == err)
231  {
232  res = sensor_msgs::fillImage(image, encoding, height, width, step, buffer_ptr);
233  }
234  else
235  {
236  ROS_ERROR_STREAM("[" << ros::this_node::getName() << "]: Could not GetImage. "
237  << "\n Error: " << errorCodeToMessage(err));
238  }
239  return res;
240  }
241 
242 private:
244 
246  {
247  ROS_INFO("Searching for cameras ...");
248  CameraPtrVector cameras;
249  if (VmbErrorSuccess == vs.Startup())
250  {
251  if (VmbErrorSuccess == vs.GetCameras(cameras))
252  {
253  for (const auto& camera : cameras)
254  {
255  std::string strID;
256  std::string strName;
257  std::string strModelname;
258  std::string strSerialNumber;
259  std::string strInterfaceID;
260  VmbInterfaceType interfaceType;
261  VmbAccessModeType accessType;
262 
263  VmbErrorType err = camera->GetID(strID);
264  if (VmbErrorSuccess != err)
265  {
266  ROS_ERROR_STREAM("[Could not get camera ID. Error code: " << err << "]");
267  }
268 
269  err = camera->GetName(strName);
270  if (VmbErrorSuccess != err)
271  {
272  ROS_ERROR_STREAM("[Could not get camera name. Error code: " << err << "]");
273  }
274 
275  err = camera->GetModel(strModelname);
276  if (VmbErrorSuccess != err)
277  {
278  ROS_ERROR_STREAM("[Could not get camera mode name. Error code: " << err << "]");
279  }
280 
281  err = camera->GetSerialNumber(strSerialNumber);
282  if (VmbErrorSuccess != err)
283  {
284  ROS_ERROR_STREAM("[Could not get camera serial number. Error code: " << err << "]");
285  }
286 
287  err = camera->GetInterfaceID(strInterfaceID);
288  if (VmbErrorSuccess != err)
289  {
290  ROS_ERROR_STREAM("[Could not get interface ID. Error code: " << err << "]");
291  }
292 
293  err = camera->GetInterfaceType(interfaceType);
294  if (VmbErrorSuccess != err)
295  {
296  ROS_ERROR_STREAM("[Could not get interface type. Error code: " << err << "]");
297  }
298 
299  err = camera->GetPermittedAccess(accessType);
300  if (VmbErrorSuccess != err)
301  {
302  ROS_ERROR_STREAM("[Could not get access type. Error code: " << err << "]");
303  }
304 
305  ROS_INFO_STREAM("Found camera named " << strName << ":");
306  ROS_INFO_STREAM(" - Model Name : " << strModelname);
307  ROS_INFO_STREAM(" - Camera ID : " << strID);
308  ROS_INFO_STREAM(" - Serial Number : " << strSerialNumber);
309  ROS_INFO_STREAM(" - Interface ID : " << strInterfaceID);
310  ROS_INFO_STREAM(" - Interface type : " << interfaceToString(interfaceType));
311  ROS_INFO_STREAM(" - Access type : " << accessModeToString(accessType));
312  }
313  }
314  else
315  {
316  ROS_WARN("Could not get cameras from Vimba System");
317  }
318  }
319  else
320  {
321  ROS_WARN("Could not start Vimba System");
322  }
323  }
324 };
325 } // namespace avt_vimba_camera
326 #endif
VmbErrorDeviceNotOpen
@ VmbErrorDeviceNotOpen
Definition: VmbCommonTypes.h:113
VmbPixelFormatBayerGB8
@ VmbPixelFormatBayerGB8
Definition: VmbCommonTypes.h:187
VmbPixelFormatMono14
@ VmbPixelFormatMono14
Definition: VmbCommonTypes.h:182
sensor_msgs::image_encodings::BAYER_RGGB8
const std::string BAYER_RGGB8
fill_image.h
VmbPixelFormatBayerGR16
@ VmbPixelFormatBayerGR16
Definition: VmbCommonTypes.h:209
VmbAccessModeConfig
@ VmbAccessModeConfig
Definition: VimbaC.h:128
AVT::VmbAPI::VimbaSystem
Definition: VimbaSystem.h:48
image_encodings.h
VmbInterfaceType
VmbInterfaceType
Definition: VimbaC.h:107
AVT::VmbAPI::CameraPtrVector
std::vector< CameraPtr > CameraPtrVector
Definition: Camera.h:45
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
VmbAccessModeLite
@ VmbAccessModeLite
Definition: VimbaC.h:129
VmbPixelFormatBayerBG8
@ VmbPixelFormatBayerBG8
Definition: VmbCommonTypes.h:188
VmbAccessModeFull
@ VmbAccessModeFull
Definition: VimbaC.h:126
VmbPixelFormatRgb8
@ VmbPixelFormatRgb8
Definition: VmbCommonTypes.h:214
avt_vimba_camera::AvtVimbaApi
Definition: avt_vimba_api.h:52
VmbAccessModeRead
@ VmbAccessModeRead
Definition: VimbaC.h:127
VmbPixelFormatBgr8
@ VmbPixelFormatBgr8
Definition: VmbCommonTypes.h:215
ros.h
VmbErrorResources
@ VmbErrorResources
Definition: VmbCommonTypes.h:122
VmbErrorType
VmbErrorType
Definition: VmbCommonTypes.h:106
VmbPixelFormatMono16
@ VmbPixelFormatMono16
Definition: VmbCommonTypes.h:183
sensor_msgs::image_encodings::RGBA8
const std::string RGBA8
VmbErrorStructSize
@ VmbErrorStructSize
Definition: VmbCommonTypes.h:116
sensor_msgs::image_encodings::BAYER_GBRG8
const std::string BAYER_GBRG8
avt_vimba_camera::AvtVimbaApi::listAvailableCameras
void listAvailableCameras()
Definition: avt_vimba_api.h:245
VmbPixelFormatBayerRG12
@ VmbPixelFormatBayerRG12
Definition: VmbCommonTypes.h:194
VmbErrorInvalidAccess
@ VmbErrorInvalidAccess
Definition: VmbCommonTypes.h:114
VmbPixelFormatBayerGB12
@ VmbPixelFormatBayerGB12
Definition: VmbCommonTypes.h:195
VmbErrorTimeout
@ VmbErrorTimeout
Definition: VmbCommonTypes.h:120
VmbPixelFormatType
VmbPixelFormatType
Definition: VmbCommonTypes.h:173
AVT::VmbAPI::VimbaSystem::Startup
IMEXPORT VmbErrorType Startup()
Definition: VimbaSystem.cpp:93
sensor_msgs::fillImage
static bool fillImage(Image &image, const std::string &encoding_arg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, const void *data_arg)
VmbPixelFormatRgb12
@ VmbPixelFormatRgb12
Definition: VmbCommonTypes.h:218
VimbaCPP.h
VmbPixelFormatBayerGR10
@ VmbPixelFormatBayerGR10
Definition: VmbCommonTypes.h:189
VmbPixelFormatBayerGB12Packed
@ VmbPixelFormatBayerGB12Packed
Definition: VmbCommonTypes.h:199
sensor_msgs::image_encodings::RGB8
const std::string RGB8
AVT::VmbAPI::VimbaSystem::GetCameras
VmbErrorType GetCameras(CameraPtrVector &cameras)
avt_vimba_camera::AvtVimbaApi::AvtVimbaApi
AvtVimbaApi()
Definition: avt_vimba_api.h:55
VmbPixelFormatBayerRG10
@ VmbPixelFormatBayerRG10
Definition: VmbCommonTypes.h:190
VmbErrorNotImplemented
@ VmbErrorNotImplemented
Definition: VmbCommonTypes.h:125
VmbErrorNotSupported
@ VmbErrorNotSupported
Definition: VmbCommonTypes.h:126
VmbErrorMoreData
@ VmbErrorMoreData
Definition: VmbCommonTypes.h:117
VmbInterfaceUsb
@ VmbInterfaceUsb
Definition: VimbaC.h:112
avt_vimba_camera::AvtVimbaApi::accessModeToString
std::string accessModeToString(VmbAccessModeType modeType)
Definition: avt_vimba_api.h:128
VmbPixelFormatBayerBG10
@ VmbPixelFormatBayerBG10
Definition: VmbCommonTypes.h:192
VmbInterfaceFirewire
@ VmbInterfaceFirewire
Definition: VimbaC.h:110
VmbErrorBadHandle
@ VmbErrorBadHandle
Definition: VmbCommonTypes.h:112
VmbPixelFormatBayerRG16
@ VmbPixelFormatBayerRG16
Definition: VmbCommonTypes.h:210
VmbPixelFormatRgba8
@ VmbPixelFormatRgba8
Definition: VmbCommonTypes.h:226
VmbPixelFormatBayerGB16
@ VmbPixelFormatBayerGB16
Definition: VmbCommonTypes.h:211
VmbInterfaceEthernet
@ VmbInterfaceEthernet
Definition: VimbaC.h:111
VmbErrorNoTL
@ VmbErrorNoTL
Definition: VmbCommonTypes.h:124
VmbErrorOther
@ VmbErrorOther
Definition: VmbCommonTypes.h:121
VmbErrorInvalidValue
@ VmbErrorInvalidValue
Definition: VmbCommonTypes.h:119
sensor_msgs::image_encodings::BAYER_BGGR8
const std::string BAYER_BGGR8
ROS_WARN
#define ROS_WARN(...)
VmbPixelFormatBayerBG16
@ VmbPixelFormatBayerBG16
Definition: VmbCommonTypes.h:212
VmbPixelFormatBgra8
@ VmbPixelFormatBgra8
Definition: VmbCommonTypes.h:227
VmbUint32_t
unsigned int VmbUint32_t
Definition: VmbCommonTypes.h:73
VmbPixelFormatBayerGB10
@ VmbPixelFormatBayerGB10
Definition: VmbCommonTypes.h:191
VmbErrorSuccess
@ VmbErrorSuccess
Definition: VmbCommonTypes.h:108
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
sensor_msgs::image_encodings::TYPE_32SC4
const std::string TYPE_32SC4
VmbErrorInvalidCall
@ VmbErrorInvalidCall
Definition: VmbCommonTypes.h:123
VmbPixelFormatBayerGR12
@ VmbPixelFormatBayerGR12
Definition: VmbCommonTypes.h:193
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
VmbErrorInternalFault
@ VmbErrorInternalFault
Definition: VmbCommonTypes.h:109
VmbPixelFormatBayerRG8
@ VmbPixelFormatBayerRG8
Definition: VmbCommonTypes.h:186
sensor_msgs::image_encodings::BGRA8
const std::string BGRA8
VmbPixelFormatMono12Packed
@ VmbPixelFormatMono12Packed
Definition: VmbCommonTypes.h:180
sensor_msgs::image_encodings::MONO8
const std::string MONO8
VmbPixelFormatMono12
@ VmbPixelFormatMono12
Definition: VmbCommonTypes.h:179
sensor_msgs::image_encodings::MONO16
const std::string MONO16
VmbPixelFormatBayerGR8
@ VmbPixelFormatBayerGR8
Definition: VmbCommonTypes.h:185
avt_vimba_camera::AvtVimbaApi::frameToImage
bool frameToImage(const FramePtr vimba_frame_ptr, sensor_msgs::Image &image)
Definition: avt_vimba_api.h:144
avt_vimba_camera
Definition: avt_vimba_api.h:50
VmbPixelFormatMono10
@ VmbPixelFormatMono10
Definition: VmbCommonTypes.h:177
VmbPixelFormatBayerGR12Packed
@ VmbPixelFormatBayerGR12Packed
Definition: VmbCommonTypes.h:197
VmbErrorWrongType
@ VmbErrorWrongType
Definition: VmbCommonTypes.h:118
avt_vimba_camera::AvtVimbaApi::interfaceToString
std::string interfaceToString(VmbInterfaceType interfaceType)
Definition: avt_vimba_api.h:110
sensor_msgs::image_encodings::TYPE_16SC1
const std::string TYPE_16SC1
sensor_msgs::image_encodings::BGR8
const std::string BGR8
VmbUchar_t
unsigned char VmbUchar_t
Definition: VmbCommonTypes.h:101
VmbAccessModeType
VmbAccessModeType
Definition: VimbaC.h:123
VmbPixelFormatMono8
@ VmbPixelFormatMono8
Definition: VmbCommonTypes.h:176
VmbPixelFormatRgb16
@ VmbPixelFormatRgb16
Definition: VmbCommonTypes.h:222
sensor_msgs::image_encodings::TYPE_16UC3
const std::string TYPE_16UC3
avt_vimba_camera::AvtVimbaApi::vs
VimbaSystem & vs
Definition: avt_vimba_api.h:243
VmbPixelFormatBayerBG12Packed
@ VmbPixelFormatBayerBG12Packed
Definition: VmbCommonTypes.h:200
sensor_msgs::image_encodings::BAYER_GRBG8
const std::string BAYER_GRBG8
avt_vimba_camera::AvtVimbaApi::start
void start()
Definition: avt_vimba_api.h:59
VmbErrorBadParameter
@ VmbErrorBadParameter
Definition: VmbCommonTypes.h:115
VmbPixelFormatBayerRG12Packed
@ VmbPixelFormatBayerRG12Packed
Definition: VmbCommonTypes.h:198
avt_vimba_camera::AvtVimbaApi::errorCodeToMessage
std::string errorCodeToMessage(VmbErrorType error)
Definition: avt_vimba_api.h:79
VmbErrorApiNotStarted
@ VmbErrorApiNotStarted
Definition: VmbCommonTypes.h:110
ROS_INFO
#define ROS_INFO(...)
VmbErrorNotFound
@ VmbErrorNotFound
Definition: VmbCommonTypes.h:111
VmbPixelFormatBayerBG12
@ VmbPixelFormatBayerBG12
Definition: VmbCommonTypes.h:196
VmbAccessModeNone
@ VmbAccessModeNone
Definition: VimbaC.h:125


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