avt_vimba_camera.cpp
Go to the documentation of this file.
1 
35 
36 #include <ros/ros.h>
37 
38 #include <signal.h>
39 #include <thread>
40 
41 namespace avt_vimba_camera
42 {
43 static const char* AutoMode[] = { "Off", "Once", "Continuous" };
44 static const char* TriggerMode[] = { "Invalid", "Freerun", "FixedRate", "Software", "Line0", "Line1",
45  "Line2", "Line3", "Line4", "Action0", "Action1" };
46 static const char* AcquisitionMode[] = { "Continuous", "SingleFrame", "MultiFrame", "Recorder" };
47 static const char* PixelFormatMode[] = { "Mono8", "Mono10", "Mono10Packed", "Mono12",
48  "Mono12Packed", "BayerGR8", "BayerRG8", "BayerGB8",
49  "BayerBG8", "BayerGR10", "BayerRG10", "BayerGB10",
50  "BayerBG10", "BayerGR12", "BayerRG12", "BayerGB12",
51  "BayerBG12", "BayerGR10Packed", "BayerRG10Packed", "BayerGB10Packed",
52  "BayerBG10Packed", "BayerGR12Packed", "BayerRG12Packed", "BayerGB12Packed",
53  "BayerBG12Packed", "RGB8Packed", "BGR8Packed" };
54 static const char* BalanceRatioMode[] = { "Red", "Blue" };
55 static const char* FeatureDataType[] = { "Unknown", "int", "float", "enum", "string", "bool" };
56 
57 static const char* State[] = { "Opening", "Idle", "Camera not found", "Format error", "Error", "Ok" };
58 
59 static volatile int keepRunning = 1;
60 
61 void intHandler(int dummy)
62 {
63  keepRunning = 0;
64 }
65 
67 {
68 }
69 
70 AvtVimbaCamera::AvtVimbaCamera(const std::string& name)
71 {
72  // Init global variables
73  opened_ = false; // camera connected to the api
74  streaming_ = false; // capturing frames
75  on_init_ = true; // on initialization phase
76  name_ = name;
77 
79 
80  updater_.setHardwareID("unknown");
82  updater_.update();
83 }
84 
85 void AvtVimbaCamera::start(const std::string& ip_str, const std::string& guid_str, const std::string& frame_id,
86  bool print_all_features)
87 {
88  if (opened_)
89  return;
90 
91  frame_id_ = frame_id;
92  updater_.broadcast(0, "Starting device with IP:" + ip_str + " or GUID:" + guid_str);
93 
94  // Determine which camera to use. Try IP first
95  if (!ip_str.empty())
96  {
97  diagnostic_msg_ = "Trying to open camera by IP: " + ip_str;
98  ROS_INFO_STREAM("Trying to open camera by IP: " << ip_str);
99  vimba_camera_ptr_ = openCamera(ip_str, print_all_features);
100  if (!vimba_camera_ptr_)
101  {
102  ROS_WARN("Camera pointer is empty. Returning...");
103  return;
104  }
105  updater_.setHardwareID(ip_str);
106  guid_ = ip_str;
107  // If both guid and IP are available, open by IP and check guid
108  if (!guid_str.empty())
109  {
110  std::string cam_guid_str;
111  vimba_camera_ptr_->GetSerialNumber(cam_guid_str);
112  if (!vimba_camera_ptr_)
113  {
114  ROS_WARN("Camera pointer is empty. Returning...");
115  return;
116  }
117  assert(cam_guid_str == guid_str);
118  updater_.setHardwareID(guid_str);
119  guid_ = guid_str;
120  diagnostic_msg_ = "GUID " + cam_guid_str + " matches for camera with IP: " + ip_str;
121  ROS_INFO_STREAM("GUID " << cam_guid_str << " matches for camera with IP: " << ip_str);
122  }
123  }
124  else if (!guid_str.empty())
125  {
126  // Only guid available
127  diagnostic_msg_ = "Trying to open camera by ID: " + guid_str;
128  ROS_INFO_STREAM("Trying to open camera by ID: " << guid_str);
129  vimba_camera_ptr_ = openCamera(guid_str, print_all_features);
130  updater_.setHardwareID(guid_str);
131  guid_ = guid_str;
132  }
133  else
134  {
135  // No identifying info (GUID and IP) are available
136  diagnostic_msg_ = "Can't connect to the camera: at least GUID or IP need to be set.";
137  ROS_ERROR("Can't connect to the camera: at least GUID or IP need to be set.");
139  }
140  updater_.update();
141 
142  getFeatureValue("GevTimestampTickFrequency", vimba_timestamp_tick_freq_);
143 
144  // From the SynchronousGrab API example:
145  // TODO Set the GeV packet size to the highest possible value
146  VmbInterfaceType cam_int_type;
147  vimba_camera_ptr_->GetInterfaceType(cam_int_type);
148  if (cam_int_type == VmbInterfaceEthernet)
149  {
150  runCommand("GVSPAdjustPacketSize");
151  }
152 
153  // Create a frame observer for this camera
154  SP_SET(frame_obs_ptr_,
156  std::bind(&avt_vimba_camera::AvtVimbaCamera::frameCallback, this, std::placeholders::_1)));
158 
159  updater_.update();
160 }
161 
163 {
164  if (!opened_)
165  return;
166  vimba_camera_ptr_->Close();
167  opened_ = false;
168 }
169 
171 {
172  if (!streaming_)
173  {
174  // Start streaming
175  VmbErrorType err = vimba_camera_ptr_->StartContinuousImageAcquisition(3, IFrameObserverPtr(frame_obs_ptr_));
176  if (err == VmbErrorSuccess)
177  {
178  diagnostic_msg_ = "Starting continuous image acquisition";
179  ROS_INFO_STREAM("Starting continuous image acquisition ...");
180  streaming_ = true;
181  camera_state_ = OK;
182  }
183  else
184  {
185  diagnostic_msg_ = "Could not start continuous image acquisition. Error: " + api_.errorCodeToMessage(err);
186  ROS_ERROR_STREAM("Could not start continuous image acquisition. "
187  << "\n Error: " << api_.errorCodeToMessage(err));
189  }
190  }
191  else
192  {
193  ROS_WARN_STREAM("Start imaging called, but the camera is already imaging.");
194  }
195  updater_.update();
196 }
197 
199 {
200  if (streaming_ || on_init_)
201  {
202  VmbErrorType err = vimba_camera_ptr_->StopContinuousImageAcquisition();
203  if (err == VmbErrorSuccess)
204  {
205  diagnostic_msg_ = "Acquisition stopped";
206  ROS_INFO_STREAM("Acquisition stoppped ...");
207  streaming_ = false;
209  }
210  else
211  {
212  diagnostic_msg_ = "Could not stop image acquisition. Error: " + api_.errorCodeToMessage(err);
213  ROS_ERROR_STREAM("Could not stop image acquisition."
214  << "\n Error: " << api_.errorCodeToMessage(err));
216  }
217  }
218  else
219  {
220  ROS_WARN_STREAM("Stop imaging called, but the camera is already stopped.");
221  }
222  updater_.update();
223 }
224 
225 CameraPtr AvtVimbaCamera::openCamera(const std::string& id_str, bool print_all_features)
226 {
227  // Details: The ID might be one of the following:
228  // "IP:169.254.12.13",
229  // "MAC:000f31000001",
230  // or a plain serial number: "1234567890".
231 
232  CameraPtr camera;
233  VimbaSystem& vimba_system(VimbaSystem::GetInstance());
234 
235  // set handler to catch ctrl+c presses
236  sighandler_t oldHandler = signal(SIGINT, intHandler);
237 
238  // get camera
239  VmbErrorType err = vimba_system.GetCameraByID(id_str.c_str(), camera);
240  while (err != VmbErrorSuccess)
241  {
242  if (keepRunning)
243  {
244  ROS_WARN_STREAM("Could not find camera using " << id_str << ". Retrying every two seconds ...");
245  ros::Duration(2.0).sleep();
246  err = vimba_system.GetCameraByID(id_str.c_str(), camera);
247  }
248  else
249  {
250  ROS_ERROR_STREAM("Could not find camera using " << id_str << "\n Error: " << api_.errorCodeToMessage(err));
252  return camera;
253  }
254  }
255 
256  // open camera
257  err = camera->Open(VmbAccessModeFull);
258  while (err != VmbErrorSuccess && keepRunning)
259  {
260  if (keepRunning)
261  {
262  ROS_WARN_STREAM("Could not open camera. Retrying every two seconds ...");
263  err = camera->Open(VmbAccessModeFull);
264  ros::Duration(2.0).sleep();
265  }
266  else
267  {
268  ROS_ERROR_STREAM("Could not open camera " << id_str << "\n Error: " << api_.errorCodeToMessage(err));
270  return camera;
271  }
272  }
273 
274  // set previous handler back
275  signal(SIGINT, oldHandler);
276 
277  std::string cam_id, cam_name;
278  camera->GetID(cam_id);
279  camera->GetName(cam_name);
280  ROS_INFO_STREAM("Opened connection to camera named " << cam_name << " with ID " << cam_id);
281 
282  ros::Duration(2.0).sleep();
283 
284  if (print_all_features)
285  {
286  printAllCameraFeatures(camera);
287  }
288  opened_ = true;
290  return camera;
291 }
292 
293 void AvtVimbaCamera::frameCallback(const FramePtr vimba_frame_ptr)
294 {
295  std::unique_lock<std::mutex> lock(config_mutex_);
296  camera_state_ = OK;
297  diagnostic_msg_ = "Camera operating normally";
298 
299  // Call the callback implemented by other classes
300  std::thread thread_callback = std::thread(userFrameCallback, vimba_frame_ptr);
301  thread_callback.join();
302 
303  updater_.update();
304 }
305 
307 {
308  double timestamp = -1.0;
309  if (runCommand("GevTimestampControlLatch"))
310  {
311  VmbInt64_t freq, ticks;
312  getFeatureValue("GevTimestampTickFrequency", freq);
313  getFeatureValue("GevTimestampValue", ticks);
314  timestamp = static_cast<double>(ticks) / static_cast<double>(freq);
315  }
316  return timestamp;
317 }
318 
320 {
321  double temp = -1.0;
322  if (setFeatureValue("DeviceTemperatureSelector", "Main") == VmbErrorSuccess)
323  {
324  getFeatureValue("DeviceTemperature", temp);
325  }
326  return temp;
327 }
328 
330 {
331  int sensor_width;
332  if (getFeatureValue("SensorWidth", sensor_width))
333  {
334  return sensor_width;
335  }
336  else
337  {
338  return -1;
339  }
340 }
341 
343 {
344  int sensor_height;
345  if (getFeatureValue("SensorHeight", sensor_height))
346  {
347  return sensor_height;
348  }
349  else
350  {
351  return -1;
352  }
353 }
354 
356 {
357  return (static_cast<double>(timestamp_ticks)) / (static_cast<double>(vimba_timestamp_tick_freq_));
358 }
359 
360 // Template function to SET a feature value from the camera
361 template <typename T>
362 VmbErrorType AvtVimbaCamera::setFeatureValue(const std::string& feature_str, const T& val)
363 {
364  VmbErrorType err;
365  FeaturePtr vimba_feature_ptr;
366  err = vimba_camera_ptr_->GetFeatureByName(feature_str.c_str(), vimba_feature_ptr);
367  if (err == VmbErrorSuccess)
368  {
369  bool writable;
370  err = vimba_feature_ptr->IsWritable(writable);
371  if (err == VmbErrorSuccess)
372  {
373  if (writable)
374  {
375  ROS_DEBUG_STREAM("Setting feature " << feature_str << " value " << val);
376  VmbFeatureDataType data_type;
377  err = vimba_feature_ptr->GetDataType(data_type);
378  if (err == VmbErrorSuccess)
379  {
380  if (data_type == VmbFeatureDataEnum)
381  {
382  bool available;
383  err = vimba_feature_ptr->IsValueAvailable(val, available);
384  if (err == VmbErrorSuccess)
385  {
386  if (available)
387  {
388  err = vimba_feature_ptr->SetValue(val);
389  }
390  else
391  {
392  ROS_WARN_STREAM("Feature " << feature_str << " is available now.");
393  }
394  }
395  else
396  {
397  ROS_WARN_STREAM("Feature " << feature_str << ": value unavailable\n\tERROR "
398  << api_.errorCodeToMessage(err));
399  }
400  }
401  else
402  {
403  err = vimba_feature_ptr->SetValue(val);
404  }
405  }
406  else
407  {
408  ROS_WARN_STREAM("Feature " << feature_str << ": Bad data type\n\tERROR " << api_.errorCodeToMessage(err));
409  }
410  }
411  else
412  {
413  ROS_WARN_STREAM("Feature " << feature_str << " is not writable.");
414  }
415  }
416  else
417  {
418  ROS_WARN_STREAM("Feature " << feature_str << ": ERROR " << api_.errorCodeToMessage(err));
419  }
420  }
421  else
422  {
423  ROS_WARN_STREAM("Could not get feature " << feature_str << ", your camera probably doesn't support it.");
424  }
425  return err;
426 }
427 
428 // Template function to GET a feature value from the camera
429 template <typename T>
430 bool AvtVimbaCamera::getFeatureValue(const std::string& feature_str, T& val)
431 {
432  ROS_DEBUG_STREAM("Asking for feature " << feature_str);
433  VmbErrorType err;
434  FeaturePtr vimba_feature_ptr;
435  VmbFeatureDataType data_type;
436  err = vimba_camera_ptr_->GetFeatureByName(feature_str.c_str(), vimba_feature_ptr);
437  if (err == VmbErrorSuccess)
438  {
439  bool readable;
440  vimba_feature_ptr->IsReadable(readable);
441  if (readable)
442  {
443  vimba_feature_ptr->GetDataType(data_type);
444  if (err != VmbErrorSuccess)
445  {
446  std::cout << "[Could not get feature Data Type. Error code: " << err << "]" << std::endl;
447  }
448  else
449  {
450  switch (data_type)
451  {
452  case VmbFeatureDataBool:
453  bool bValue;
454  err = vimba_feature_ptr->GetValue(bValue);
455  if (err == VmbErrorSuccess)
456  {
457  val = static_cast<T>(bValue);
458  }
459  break;
460  case VmbFeatureDataFloat:
461  double fValue;
462  err = vimba_feature_ptr->GetValue(fValue);
463  if (err == VmbErrorSuccess)
464  {
465  val = static_cast<T>(fValue);
466  }
467  break;
468  case VmbFeatureDataInt:
469  VmbInt64_t nValue;
470  err = vimba_feature_ptr->GetValue(nValue);
471  if (err == VmbErrorSuccess)
472  {
473  val = static_cast<T>(nValue);
474  }
475  break;
476  default:
477  err = VmbErrorNotFound;
478  break;
479  }
480  if (err != VmbErrorSuccess)
481  {
482  ROS_WARN_STREAM("Could not get feature value. Error code: " << api_.errorCodeToMessage(err));
483  }
484  }
485  }
486  else
487  {
488  ROS_WARN_STREAM("Feature " << feature_str << " is not readable.");
489  }
490  }
491  else
492  {
493  ROS_WARN_STREAM("Could not get feature " << feature_str);
494  }
495  return (err == VmbErrorSuccess);
496 }
497 
498 // Function to GET a feature value from the camera, overloaded to strings
499 bool AvtVimbaCamera::getFeatureValue(const std::string& feature_str, std::string& val)
500 {
501  ROS_DEBUG_STREAM("Asking for feature " << feature_str);
502  VmbErrorType err;
503  FeaturePtr vimba_feature_ptr;
504  VmbFeatureDataType data_type;
505  err = vimba_camera_ptr_->GetFeatureByName(feature_str.c_str(), vimba_feature_ptr);
506  if (err == VmbErrorSuccess)
507  {
508  bool readable;
509  vimba_feature_ptr->IsReadable(readable);
510  if (readable)
511  {
512  vimba_feature_ptr->GetDataType(data_type);
513  if (err != VmbErrorSuccess)
514  {
515  ROS_ERROR_STREAM("[Could not get feature Data Type. Error code: " << err << "]");
516  }
517  else
518  {
519  std::string strValue;
520  switch (data_type)
521  {
522  case VmbFeatureDataEnum:
523  err = vimba_feature_ptr->GetValue(strValue);
524  if (err == VmbErrorSuccess)
525  {
526  val = strValue;
527  }
528  break;
530  err = vimba_feature_ptr->GetValue(strValue);
531  if (err == VmbErrorSuccess)
532  {
533  val = strValue;
534  }
535  break;
536  default:
537  err = VmbErrorNotFound;
538  break;
539  }
540  if (err != VmbErrorSuccess)
541  {
542  ROS_WARN_STREAM("Could not get feature value. Error code: " << api_.errorCodeToMessage(err));
543  }
544  }
545  }
546  else
547  {
548  ROS_WARN_STREAM("Feature " << feature_str << " is not readable.");
549  }
550  }
551  else
552  {
553  ROS_WARN_STREAM("Could not get feature " << feature_str);
554  }
555  return (err == VmbErrorSuccess);
556 }
557 
558 // Tries to configure a camera feature.
559 // Updates the config value passed in if a different config is in use by the camera.
560 template <typename Vimba_Type, typename Std_Type>
561 void AvtVimbaCamera::configureFeature(const std::string& feature_str, const Vimba_Type& val_in, Std_Type& val_out)
562 {
563  Vimba_Type actual_value;
564 
565  VmbErrorType return_value = setFeatureValue(feature_str, val_in);
566  if (return_value == VmbErrorSuccess || return_value == VmbErrorInvalidValue)
567  {
568  getFeatureValue(feature_str, actual_value);
569  if (val_in == actual_value)
570  {
571  ROS_INFO_STREAM(" - " << feature_str << " set to " << actual_value);
572  }
573  else
574  {
575  ROS_WARN_STREAM(" - Tried to set " << feature_str << " to " << val_in << " but the camera used " << actual_value
576  << " instead");
577  val_out = static_cast<Std_Type>(actual_value);
578  }
579  }
580  else
581  {
582  val_out = static_cast<Std_Type>(val_in);
583  }
584 }
585 
586 // Overloaded for strings, template specialization doesn't currently compile with GCC
587 void AvtVimbaCamera::configureFeature(const std::string& feature_str, const std::string& val_in, std::string& val_out)
588 {
589  std::string actual_value;
590 
591  VmbErrorType return_value = setFeatureValue(feature_str, val_in.c_str());
592  if (return_value == VmbErrorSuccess || return_value == VmbErrorInvalidValue)
593  {
594  getFeatureValue(feature_str, actual_value);
595  if (val_in == actual_value)
596  {
597  ROS_INFO_STREAM(" - " << feature_str << " set to " << actual_value);
598  }
599  else
600  {
601  ROS_WARN_STREAM(" - Tried to set " << feature_str << " to " << val_in << " but the camera used " << actual_value
602  << " instead");
603  val_out = actual_value;
604  }
605  }
606  else
607  {
608  val_out = val_in;
609  }
610 }
611 
612 // Template function to RUN a command
613 bool AvtVimbaCamera::runCommand(const std::string& command_str)
614 {
615  FeaturePtr feature_ptr;
616  VmbErrorType err = vimba_camera_ptr_->GetFeatureByName(command_str.c_str(), feature_ptr);
617  if (err == VmbErrorSuccess)
618  {
619  err = feature_ptr->RunCommand();
620  if (err == VmbErrorSuccess)
621  {
622  bool is_command_done = false;
623  do
624  {
625  err = feature_ptr->IsCommandDone(is_command_done);
626  if (err != VmbErrorSuccess)
627  {
628  break;
629  }
630  ROS_DEBUG_STREAM_THROTTLE(1, "Waiting for command " << command_str.c_str() << "...");
631  } while (false == is_command_done);
632  ROS_DEBUG_STREAM("Command " << command_str.c_str() << " done!");
633  return true;
634  }
635  else
636  {
637  ROS_WARN_STREAM("Could not run command " << command_str << ". Error: " << api_.errorCodeToMessage(err));
638  return false;
639  }
640  }
641  else
642  {
643  ROS_WARN_STREAM("Could not get feature command " << command_str << ". Error: " << api_.errorCodeToMessage(err));
644  return false;
645  }
646 }
647 
648 void AvtVimbaCamera::printAllCameraFeatures(const CameraPtr& camera)
649 {
650  VmbErrorType err;
651  FeaturePtrVector features;
652 
653  // The static details of a feature
654  std::string strName; // The name of the feature
655  std::string strDisplayName; // The display name of the feature
656  std::string strDescription; // A long description of the feature
657  std::string strCategory; // A category to group features
658  std::string strSFNCNamespace; // The Std Feature Naming Convention namespace
659  std::string strUnit; // The measurement unit of the value
660  VmbFeatureDataType eType; // The data type of the feature
661 
662  // The changeable value of a feature
663  VmbInt64_t nValue;
664  std::string strValue;
665 
666  std::stringstream strError;
667 
668  // Fetch all features of our cam
669  err = camera->GetFeatures(features);
670  if (err == VmbErrorSuccess)
671  {
672  // Query all static details as well as the value of
673  // all fetched features and print them out.
674  for (FeaturePtrVector::const_iterator iter = features.begin(); features.end() != iter; ++iter)
675  {
676  err = (*iter)->GetName(strName);
677  if (err != VmbErrorSuccess)
678  {
679  strError << "[Could not get feature Name. Error code: " << err << "]";
680  strName.assign(strError.str());
681  }
682 
683  err = (*iter)->GetDisplayName(strDisplayName);
684  if (err != VmbErrorSuccess)
685  {
686  strError << "[Could not get feature Display Name. Error code: " << err << "]";
687  strDisplayName.assign(strError.str());
688  }
689 
690  err = (*iter)->GetDescription(strDescription);
691  if (err != VmbErrorSuccess)
692  {
693  strError << "[Could not get feature Description. Error code: " << err << "]";
694  strDescription.assign(strError.str());
695  }
696 
697  err = (*iter)->GetCategory(strCategory);
698  if (err != VmbErrorSuccess)
699  {
700  strError << "[Could not get feature Category. Error code: " << err << "]";
701  strCategory.assign(strError.str());
702  }
703 
704  err = (*iter)->GetSFNCNamespace(strSFNCNamespace);
705  if (err != VmbErrorSuccess)
706  {
707  strError << "[Could not get feature SNFC Namespace. Error code: " << err << "]";
708  strSFNCNamespace.assign(strError.str());
709  }
710 
711  err = (*iter)->GetUnit(strUnit);
712  if (err != VmbErrorSuccess)
713  {
714  strError << "[Could not get feature Unit. Error code: " << err << "]";
715  strUnit.assign(strError.str());
716  }
717 
718  std::cout << "/// Feature Name: " << strName << std::endl;
719  std::cout << "/// Display Name: " << strDisplayName << std::endl;
720  std::cout << "/// Description: " << strDescription << std::endl;
721  std::cout << "/// SNFC Namespace: " << strSFNCNamespace << std::endl;
722  std::cout << "/// Unit: " << strUnit << std::endl;
723  std::cout << "/// Value: ";
724 
725  err = (*iter)->GetDataType(eType);
726  if (err != VmbErrorSuccess)
727  {
728  std::cout << "[Could not get feature Data Type. Error code: " << err << "]" << std::endl;
729  }
730  else
731  {
732  switch (eType)
733  {
734  case VmbFeatureDataBool:
735  bool bValue;
736  err = (*iter)->GetValue(bValue);
737  if (err == VmbErrorSuccess)
738  {
739  std::cout << bValue << " (bool)" << std::endl;
740  }
741  break;
742  case VmbFeatureDataEnum:
743  err = (*iter)->GetValue(strValue);
744  if (err == VmbErrorSuccess)
745  {
746  std::cout << strValue << " (string enum)" << std::endl;
747  }
748  break;
749  case VmbFeatureDataFloat:
750  double fValue;
751  err = (*iter)->GetValue(fValue);
752  {
753  std::cout << fValue << " (float)" << std::endl;
754  }
755  break;
756  case VmbFeatureDataInt:
757  err = (*iter)->GetValue(nValue);
758  {
759  std::cout << nValue << " (int)" << std::endl;
760  }
761  break;
763  err = (*iter)->GetValue(strValue);
764  {
765  std::cout << strValue << " (string)" << std::endl;
766  }
767  break;
769  default:
770  std::cout << "[None]" << std::endl;
771  break;
772  }
773  if (err != VmbErrorSuccess)
774  {
775  std::cout << "Could not get feature value. Error code: " << err << std::endl;
776  }
777  }
778 
779  std::cout << std::endl;
780  }
781  }
782  else
783  {
784  std::cout << "Could not get features. Error code: " << api_.errorCodeToMessage(err) << std::endl;
785  }
786 }
787 
789 {
790  std::unique_lock<std::mutex> lock(config_mutex_);
791 
792  if (streaming_)
793  {
794  stopImaging();
795  ros::Duration(0.5).sleep(); // sleep for half a second
796  }
797 
798  if (on_init_)
799  {
800  config_ = config;
801  }
802  diagnostic_msg_ = "Updating configuration";
803 
804  updateExposureConfig(config);
805  updateGammaConfig(config);
806  updateDspsubregionConfig(config);
807  updateGainConfig(config);
808  updateWhiteBalanceConfig(config);
809  updateImageModeConfig(config);
810  updateROIConfig(config);
811  updateBandwidthConfig(config);
812  updateGPIOConfig(config);
813  updateUSBGPIOConfig(config);
814  updatePtpModeConfig(config);
815  updatePixelFormatConfig(config);
816  updateAcquisitionConfig(config);
817  updateIrisConfig(config);
818  config_ = config;
819 
820  if (on_init_)
821  {
822  on_init_ = false;
823  }
824 
825  startImaging();
826 }
827 
830 {
831  if (on_init_)
832  {
833  ROS_INFO("Updating Acquisition and Trigger config:");
834  }
835 
836  if (config.acquisition_mode != config_.acquisition_mode || on_init_)
837  {
838  configureFeature("AcquisitionMode", config.acquisition_mode, config.acquisition_mode);
839  }
840  if (config.acquisition_rate_enable != config_.acquisition_rate_enable || on_init_)
841  {
842  configureFeature("AcquisitionFrameRateEnable", static_cast<bool>(config.acquisition_rate_enable), config.acquisition_rate_enable);
843  }
844  if (config.acquisition_rate != config_.acquisition_rate || on_init_)
845  {
846  configureFeature("AcquisitionFrameRateAbs", static_cast<float>(config.acquisition_rate), config.acquisition_rate);
847  configureFeature("AcquisitionFrameRate", static_cast<float>(config.acquisition_rate), config.acquisition_rate); // NEW CAMERAS USE THIS PARAMETER
848  }
849  if (config.trigger_mode != config_.trigger_mode || on_init_)
850  {
851  configureFeature("TriggerMode", config.trigger_mode, config.trigger_mode);
852  }
853  if (config.trigger_selector != config_.trigger_selector || on_init_)
854  {
855  configureFeature("TriggerSelector", config.trigger_selector, config.trigger_selector);
856  }
857  if (config.trigger_source != config_.trigger_source || on_init_)
858  {
859  configureFeature("TriggerSource", config.trigger_source, config.trigger_source);
860  }
861  if (config.trigger_activation != config_.trigger_activation || on_init_)
862  {
863  configureFeature("TriggerActivation", config.trigger_activation, config.trigger_activation);
864  }
865  if (config.trigger_delay != config_.trigger_delay || on_init_)
866  {
867  configureFeature("TriggerDelayAbs", static_cast<float>(config.trigger_delay), config.trigger_delay);
868  }
869  if (config.action_device_key != config_.action_device_key || on_init_)
870  {
871  configureFeature("ActionDeviceKey", static_cast<VmbInt64_t>(config.action_device_key), config.action_device_key);
872  }
873  if (config.action_group_key != config_.action_group_key || on_init_)
874  {
875  configureFeature("ActionGroupKey", static_cast<VmbInt64_t>(config.action_group_key), config.action_group_key);
876  }
877  if (config.action_group_mask != config_.action_group_mask || on_init_)
878  {
879  configureFeature("ActionGroupMask", static_cast<VmbInt64_t>(config.action_group_mask), config.action_group_mask);
880  }
881 }
882 
883 /* Update the Iris config */
885 {
886  if (on_init_)
887  {
888  ROS_INFO("Updating Iris config:");
889  }
890 
891  if (config.iris_auto_target != config_.iris_auto_target || on_init_)
892  {
893  configureFeature("IrisAutoTarget", static_cast<VmbInt64_t>(config.iris_auto_target), config.iris_auto_target);
894  }
895  if (config.iris_mode != config_.iris_mode || on_init_)
896  {
897  configureFeature("IrisMode", config.iris_mode, config.iris_mode);
898  }
899  if (config.iris_video_level_max != config_.iris_video_level_max || on_init_)
900  {
901  configureFeature("IrisVideoLevelMax", static_cast<VmbInt64_t>(config.iris_video_level_max),
902  config.iris_video_level_max);
903  }
904  if (config.iris_video_level_min != config_.iris_video_level_min || on_init_)
905  {
906  configureFeature("IrisVideoLevelMin", static_cast<VmbInt64_t>(config.iris_video_level_min),
907  config.iris_video_level_min);
908  }
909 }
910 
913 {
914  if (on_init_)
915  {
916  ROS_INFO("Updating Exposure config:");
917  }
918 
919  if (config.exposure != config_.exposure || on_init_)
920  {
921  configureFeature("ExposureTimeAbs", static_cast<float>(config.exposure), config.exposure);
922  }
923  if (config.exposure_auto != config_.exposure_auto || on_init_)
924  {
925  configureFeature("ExposureAuto", config.exposure_auto, config.exposure_auto);
926  }
927  if (config.exposure_auto_alg != config_.exposure_auto_alg || on_init_)
928  {
929  configureFeature("ExposureAutoAlg", config.exposure_auto_alg, config.exposure_auto_alg);
930  }
931  if (config.exposure_auto_tol != config_.exposure_auto_tol || on_init_)
932  {
933  configureFeature("ExposureAutoAdjustTol", static_cast<VmbInt64_t>(config.exposure_auto_tol),
934  config.exposure_auto_tol);
935  }
936  if (config.exposure_auto_max != config_.exposure_auto_max || on_init_)
937  {
938  configureFeature("ExposureAutoMax", static_cast<VmbInt64_t>(config.exposure_auto_max), config.exposure_auto_max);
939  }
940  if (config.exposure_auto_min != config_.exposure_auto_min || on_init_)
941  {
942  configureFeature("ExposureAutoMin", static_cast<VmbInt64_t>(config.exposure_auto_min), config.exposure_auto_min);
943  }
944  if (config.exposure_auto_outliers != config_.exposure_auto_outliers || on_init_)
945  {
946  configureFeature("ExposureAutoOutliers", static_cast<VmbInt64_t>(config.exposure_auto_outliers),
947  config.exposure_auto_outliers);
948  }
949  if (config.exposure_auto_rate != config_.exposure_auto_rate || on_init_)
950  {
951  configureFeature("ExposureAutoRate", static_cast<VmbInt64_t>(config.exposure_auto_rate), config.exposure_auto_rate);
952  }
953  if (config.exposure_auto_target != config_.exposure_auto_target || on_init_)
954  {
955  configureFeature("ExposureAutoTarget", static_cast<VmbInt64_t>(config.exposure_auto_target),
956  config.exposure_auto_target);
957  }
958  if (config.exposure_mode != config_.exposure_mode || on_init_) {
959  configureFeature("ExposureMode", config.exposure_mode ,config.exposure_mode);
960  }
961  if (config.exposure_time_PWL1 != config_.exposure_time_PWL1 || on_init_) {
962  configureFeature("ExposureTimePWL1", static_cast<float>(config.exposure_time_PWL1), config.exposure_time_PWL1);
963  }
964  if (config.exposure_time_PWL2 != config_.exposure_time_PWL2 || on_init_) {
965  configureFeature("ExposureTimePWL2", static_cast<float>(config.exposure_time_PWL2), config.exposure_time_PWL2);
966  }
967  if (config.exposure_threshold_PWL2 != config_.exposure_threshold_PWL2 || on_init_) {
968  configureFeature("ThresholdPWL2",
969  static_cast<VmbInt64_t>(config.exposure_threshold_PWL2), config.exposure_threshold_PWL2);
970  }
971  if (config.exposure_threshold_PWL1 != config_.exposure_threshold_PWL1 || on_init_) {
972  configureFeature("ThresholdPWL1",
973  static_cast<VmbInt64_t>(config.exposure_threshold_PWL1), config.exposure_threshold_PWL1);
974  }
975 }
976 
979 {
980  if (on_init_)
981  {
982  ROS_INFO("Updating Gamma config:");
983  }
984  if (config.gamma != config_.gamma || on_init_)
985  {
986  configureFeature("Gamma", static_cast<float>(config.gamma), config.gamma);
987  }
988 }
989 
992 {
993  if (on_init_)
994  {
995  ROS_INFO("Updating DSP-Subregion config:");
996  }
997 
998  if (config.subregion_bottom != config_.subregion_bottom || on_init_)
999  {
1000  configureFeature("DSPSubregionBottom", static_cast<VmbInt64_t>(config.subregion_bottom), config.subregion_bottom);
1001  }
1002  if (config.subregion_top != config_.subregion_top || on_init_)
1003  {
1004  configureFeature("DSPSubregionTop", static_cast<VmbInt64_t>(config.subregion_top), config.subregion_top);
1005  }
1006  if (config.subregion_left != config_.subregion_left || on_init_)
1007  {
1008  configureFeature("DSPSubregionLeft", static_cast<VmbInt64_t>(config.subregion_left), config.subregion_left);
1009  }
1010  if (config.subregion_right != config_.subregion_right || on_init_)
1011  {
1012  configureFeature("DSPSubregionRight", static_cast<VmbInt64_t>(config.subregion_right), config.subregion_right);
1013  }
1014 }
1015 
1018 {
1019  if (on_init_)
1020  {
1021  ROS_INFO("Updating Gain config:");
1022  }
1023 
1024  if (config.gain != config_.gain || on_init_)
1025  {
1026  configureFeature("Gain", static_cast<float>(config.gain), config.gain);
1027  }
1028  if (config.gain_auto != config_.gain_auto || on_init_)
1029  {
1030  configureFeature("GainAuto", config.gain_auto, config.gain_auto);
1031  }
1032  if (config.gain_auto_adjust_tol != config_.gain_auto_adjust_tol || on_init_)
1033  {
1034  configureFeature("GainAutoAdjustTol", static_cast<VmbInt64_t>(config.gain_auto_adjust_tol),
1035  config.gain_auto_adjust_tol);
1036  }
1037  if (config.gain_auto_max != config_.gain_auto_max || on_init_)
1038  {
1039  configureFeature("GainAutoMax", static_cast<float>(config.gain_auto_max), config.gain_auto_max);
1040  }
1041  if (config.gain_auto_min != config_.gain_auto_min || on_init_)
1042  {
1043  configureFeature("GainAutoMin", static_cast<float>(config.gain_auto_min), config.gain_auto_min);
1044  }
1045  if (config.gain_auto_outliers != config_.gain_auto_outliers || on_init_)
1046  {
1047  configureFeature("GainAutoOutliers", static_cast<VmbInt64_t>(config.gain_auto_outliers), config.gain_auto_outliers);
1048  }
1049  if (config.gain_auto_rate != config_.gain_auto_rate || on_init_)
1050  {
1051  configureFeature("GainAutoRate", static_cast<VmbInt64_t>(config.gain_auto_rate), config.gain_auto_rate);
1052  }
1053  if (config.gain_auto_target != config_.gain_auto_target || on_init_)
1054  {
1055  configureFeature("GainAutoTarget", static_cast<VmbInt64_t>(config.gain_auto_target), config.gain_auto_target);
1056  }
1057 }
1058 
1061 {
1062  if (on_init_)
1063  {
1064  ROS_INFO("Updating White Balance config:");
1065  }
1066 
1067  if (config.balance_ratio_abs != config_.balance_ratio_abs || on_init_)
1068  {
1069  configureFeature("BalanceRatioAbs", static_cast<float>(config.balance_ratio_abs), config.balance_ratio_abs);
1070  }
1071  if (config.balance_ratio_selector != config_.balance_ratio_selector || on_init_)
1072  {
1073  configureFeature("BalanceRatioSelector", config.balance_ratio_selector, config.balance_ratio_selector);
1074  }
1075  if (config.whitebalance_auto != config_.whitebalance_auto || on_init_)
1076  {
1077  configureFeature("BalanceWhiteAuto", config.whitebalance_auto, config.whitebalance_auto);
1078  }
1079  if (config.whitebalance_auto_tol != config_.whitebalance_auto_tol || on_init_)
1080  {
1081  configureFeature("BalanceWhiteAutoAdjustTol", static_cast<VmbInt64_t>(config.whitebalance_auto_tol),
1082  config.whitebalance_auto_tol);
1083  }
1084  if (config.whitebalance_auto_rate != config_.whitebalance_auto_rate || on_init_)
1085  {
1086  configureFeature("BalanceWhiteAutoRate", static_cast<VmbInt64_t>(config.whitebalance_auto_rate),
1087  config.whitebalance_auto_rate);
1088  }
1089 }
1090 
1093 {
1094  if (on_init_)
1095  {
1096  ROS_INFO("Updating PTP config:");
1097  }
1098 
1099  if (config.ptp_mode != config_.ptp_mode || on_init_)
1100  {
1101  // configureFeature("PtpMode", config.ptp_mode, config.ptp_mode);
1102  configureFeature("PtpMode", config.ptp_mode, config.ptp_mode);
1103  }
1104 }
1105 
1108 {
1109  if (on_init_)
1110  {
1111  ROS_INFO("Updating Image Mode config:");
1112  }
1113 
1114  if (config.decimation_x != config_.decimation_x || on_init_)
1115  {
1116  configureFeature("DecimationHorizontal", static_cast<VmbInt64_t>(config.decimation_x), config.decimation_x);
1117  }
1118  if (config.decimation_y != config_.decimation_y || on_init_)
1119  {
1120  configureFeature("DecimationVertical", static_cast<VmbInt64_t>(config.decimation_y), config.decimation_y);
1121  }
1122  if (config.binning_x != config_.binning_x || on_init_)
1123  {
1124  configureFeature("BinningHorizontal", static_cast<VmbInt64_t>(config.binning_x), config.binning_x);
1125  }
1126  if (config.binning_y != config_.binning_y || on_init_)
1127  {
1128  configureFeature("BinningVertical", static_cast<VmbInt64_t>(config.binning_y), config.binning_y);
1129  }
1130  if (config.reverse_x != config_.reverse_x || on_init_)
1131  {
1132  configureFeature("ReverseX", static_cast<bool>(config.reverse_x), config.reverse_x);
1133  }
1134  if (config.reverse_y != config_.reverse_y || on_init_)
1135  {
1136  configureFeature("ReverseY", static_cast<bool>(config.reverse_y), config.reverse_y);
1137  }
1138 }
1139 
1142 {
1143  if (on_init_)
1144  {
1145  ROS_INFO("Updating ROI config:");
1146  }
1147 
1148  if (config.width != config_.width || on_init_)
1149  {
1150  configureFeature("Width", static_cast<VmbInt64_t>(config.width), config.width);
1151  }
1152  if (config.height != config_.height || on_init_)
1153  {
1154  configureFeature("Height", static_cast<VmbInt64_t>(config.height), config.height);
1155  }
1156  if (config.offset_x != config_.offset_x || on_init_)
1157  {
1158  configureFeature("OffsetX", static_cast<VmbInt64_t>(config.offset_x), config.offset_x);
1159  }
1160  if (config.offset_y != config_.offset_y || on_init_)
1161  {
1162  configureFeature("OffsetY", static_cast<VmbInt64_t>(config.offset_y), config.offset_y);
1163  }
1164 }
1165 
1168 {
1169  if (on_init_)
1170  {
1171  ROS_INFO("Updating Bandwidth config:");
1172  }
1173 
1174  if (config.stream_bytes_per_second != config_.stream_bytes_per_second || on_init_)
1175  {
1176  configureFeature("StreamBytesPerSecond", static_cast<VmbInt64_t>(config.stream_bytes_per_second),
1177  config.stream_bytes_per_second);
1178  }
1179 }
1180 
1183 {
1184  if (on_init_)
1185  {
1186  ROS_INFO("Updating PixelFormat config:");
1187  }
1188 
1189  if (config.pixel_format != config_.pixel_format || on_init_)
1190  {
1191  configureFeature("PixelFormat", config.pixel_format, config.pixel_format);
1192  }
1193 }
1194 
1197 {
1198  if (on_init_)
1199  {
1200  ROS_INFO("Updating GPIO config:");
1201  }
1202  if (config.sync_in_selector != config_.sync_in_selector || on_init_)
1203  {
1204  configureFeature("SyncInSelector", config.sync_in_selector, config.sync_in_selector);
1205  }
1206  if (config.sync_out_polarity != config_.sync_out_polarity || on_init_)
1207  {
1208  configureFeature("SyncOutPolarity", config.sync_out_polarity, config.sync_out_polarity);
1209  }
1210  if (config.sync_out_selector != config_.sync_out_selector || on_init_)
1211  {
1212  configureFeature("SyncOutSelector", config.sync_out_selector, config.sync_out_selector);
1213  }
1214  if (config.sync_out_source != config_.sync_out_source || on_init_)
1215  {
1216  configureFeature("SyncOutSource", config.sync_out_source, config.sync_out_source);
1217  }
1218 }
1219 
1222 {
1223  if (on_init_)
1224  {
1225  ROS_INFO("Updating USB GPIO config:");
1226  }
1227  if (config.line_selector != config_.line_selector || on_init_)
1228  {
1229  configureFeature("LineSelector", config.line_selector, config.line_selector);
1230  }
1231  if (config.line_mode != config_.line_mode || on_init_)
1232  {
1233  configureFeature("LineMode", config.line_mode, config.line_mode);
1234  }
1235 }
1236 
1238 {
1239  stat.add("ID", guid_);
1240  stat.add("Info", diagnostic_msg_);
1241  stat.add("Temperature", getDeviceTemp());
1242 
1243  switch (camera_state_)
1244  {
1245  case OPENING:
1246  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Opening camera");
1247  break;
1248  case IDLE:
1249  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Camera is idle");
1250  break;
1251  case OK:
1252  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Camera is streaming");
1253  break;
1254  case CAMERA_NOT_FOUND:
1255  stat.summaryf(diagnostic_msgs::DiagnosticStatus::ERROR, "Cannot find requested camera %s", guid_.c_str());
1256  break;
1257  case FORMAT_ERROR:
1258  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Problem retrieving frame");
1259  break;
1260  case ERROR:
1261  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Camera has encountered an error");
1262  break;
1263  default:
1264  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Camera is in unknown state");
1265  break;
1266  }
1267 }
1268 } // namespace avt_vimba_camera
void updatePtpModeConfig(Config &config)
IMEXPORT VmbErrorType GetCameraByID(const char *pID, CameraPtr &pCamera)
static const char * State[]
void printAllCameraFeatures(const CameraPtr &camera)
void updateWhiteBalanceConfig(Config &config)
static volatile int keepRunning
static const char * FeatureDataType[]
void getCurrentState(diagnostic_updater::DiagnosticStatusWrapper &stat)
long long VmbInt64_t
void updateImageModeConfig(Config &config)
void summary(unsigned char lvl, const std::string s)
void updatePixelFormatConfig(Config &config)
void setHardwareID(const std::string &hwid)
VmbFeatureDataType
Definition: VimbaC.h:163
void updateUSBGPIOConfig(Config &config)
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
void add(const std::string &name, TaskFunction f)
#define ROS_WARN(...)
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
static const char * PixelFormatMode[]
double getTimestampRealTime(VmbUint64_t timestamp_ticks)
VmbErrorType
void summaryf(unsigned char lvl, const char *format,...)
void frameCallback(const FramePtr vimba_frame_ptr)
avt_vimba_camera::AvtVimbaCameraConfig Config
static const char * TriggerMode[]
#define ROS_INFO(...)
unsigned long long VmbUint64_t
bool getFeatureValue(const std::string &feature_str, T &val)
void updateBandwidthConfig(Config &config)
static const char * AutoMode[]
void updateExposureConfig(Config &config)
VmbErrorType setFeatureValue(const std::string &feature_str, const T &val)
#define SP_SET(sp, rawPtr)
#define ROS_WARN_STREAM(args)
VmbInterfaceType
Definition: VimbaC.h:107
#define ROS_DEBUG_STREAM(args)
CameraPtr openCamera(const std::string &id_str, bool print_all_features)
void intHandler(int dummy)
void configureFeature(const std::string &feature_str, const Vimba_Type &val_in, Std_Type &val_out)
void updateDspsubregionConfig(Config &config)
diagnostic_updater::Updater updater_
#define ROS_INFO_STREAM(args)
void updateGammaConfig(Config &config)
void updateAcquisitionConfig(Config &config)
void add(const std::string &key, const T &val)
void broadcast(int lvl, const std::string msg)
bool sleep() const
#define ROS_ERROR_STREAM(args)
std::string errorCodeToMessage(VmbErrorType error)
Definition: avt_vimba_api.h:79
static const char * AcquisitionMode[]
std::vector< FeaturePtr > FeaturePtrVector
Definition: Feature.h:46
#define ROS_ERROR(...)
void start(const std::string &ip_str, const std::string &guid_str, const std::string &frame_id, bool print_all_features=false)
static const char * BalanceRatioMode[]
bool runCommand(const std::string &command_str)


avt_vimba_camera
Author(s): Allied Vision Technologies, Miquel Massot
autogenerated on Fri Jun 2 2023 02:21:10