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" };
55 static const char*
FeatureDataType[] = {
"Unknown",
"int",
"float",
"enum",
"string",
"bool" };
57 static const char*
State[] = {
"Opening",
"Idle",
"Camera not found",
"Format error",
"Error",
"Ok" };
86 bool print_all_features)
92 updater_.
broadcast(0,
"Starting device with IP:" + ip_str +
" or GUID:" + guid_str);
102 ROS_WARN(
"Camera pointer is empty. Returning...");
108 if (!guid_str.empty())
110 std::string cam_guid_str;
114 ROS_WARN(
"Camera pointer is empty. Returning...");
117 assert(cam_guid_str == 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);
124 else if (!guid_str.empty())
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.");
193 ROS_WARN_STREAM(
"Start imaging called, but the camera is already imaging.");
220 ROS_WARN_STREAM(
"Stop imaging called, but the camera is already stopped.");
233 VimbaSystem& vimba_system(VimbaSystem::GetInstance());
236 sighandler_t oldHandler = signal(SIGINT,
intHandler);
244 ROS_WARN_STREAM(
"Could not find camera using " << id_str <<
". Retrying every two seconds ...");
262 ROS_WARN_STREAM(
"Could not open camera. Retrying every two seconds ...");
275 signal(SIGINT, oldHandler);
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);
284 if (print_all_features)
301 thread_callback.join();
308 double timestamp = -1.0;
314 timestamp =
static_cast<double>(ticks) / static_cast<double>(freq);
347 return sensor_height;
361 template <
typename T>
365 FeaturePtr vimba_feature_ptr;
366 err =
vimba_camera_ptr_->GetFeatureByName(feature_str.c_str(), vimba_feature_ptr);
370 err = vimba_feature_ptr->IsWritable(writable);
377 err = vimba_feature_ptr->GetDataType(data_type);
383 err = vimba_feature_ptr->IsValueAvailable(val, available);
388 err = vimba_feature_ptr->SetValue(val);
397 ROS_WARN_STREAM(
"Feature " << feature_str <<
": value unavailable\n\tERROR " 403 err = vimba_feature_ptr->SetValue(val);
423 ROS_WARN_STREAM(
"Could not get feature " << feature_str <<
", your camera probably doesn't support it.");
429 template <
typename T>
434 FeaturePtr vimba_feature_ptr;
436 err =
vimba_camera_ptr_->GetFeatureByName(feature_str.c_str(), vimba_feature_ptr);
440 vimba_feature_ptr->IsReadable(readable);
443 vimba_feature_ptr->GetDataType(data_type);
446 std::cout <<
"[Could not get feature Data Type. Error code: " << err <<
"]" << std::endl;
454 err = vimba_feature_ptr->GetValue(bValue);
457 val =
static_cast<T
>(bValue);
462 err = vimba_feature_ptr->GetValue(fValue);
465 val =
static_cast<T
>(fValue);
470 err = vimba_feature_ptr->GetValue(nValue);
473 val =
static_cast<T
>(nValue);
503 FeaturePtr vimba_feature_ptr;
505 err =
vimba_camera_ptr_->GetFeatureByName(feature_str.c_str(), vimba_feature_ptr);
509 vimba_feature_ptr->IsReadable(readable);
512 vimba_feature_ptr->GetDataType(data_type);
515 ROS_ERROR_STREAM(
"[Could not get feature Data Type. Error code: " << err <<
"]");
519 std::string strValue;
523 err = vimba_feature_ptr->GetValue(strValue);
530 err = vimba_feature_ptr->GetValue(strValue);
560 template <
typename Vimba_Type,
typename Std_Type>
563 Vimba_Type actual_value;
569 if (val_in == actual_value)
575 ROS_WARN_STREAM(
" - Tried to set " << feature_str <<
" to " << val_in <<
" but the camera used " << actual_value
577 val_out =
static_cast<Std_Type
>(actual_value);
582 val_out =
static_cast<Std_Type
>(val_in);
589 std::string actual_value;
595 if (val_in == actual_value)
601 ROS_WARN_STREAM(
" - Tried to set " << feature_str <<
" to " << val_in <<
" but the camera used " << actual_value
603 val_out = actual_value;
615 FeaturePtr feature_ptr;
619 err = feature_ptr->RunCommand();
622 bool is_command_done =
false;
625 err = feature_ptr->IsCommandDone(is_command_done);
631 }
while (
false == is_command_done);
655 std::string strDisplayName;
656 std::string strDescription;
657 std::string strCategory;
658 std::string strSFNCNamespace;
664 std::string strValue;
666 std::stringstream strError;
669 err = camera->GetFeatures(features);
674 for (FeaturePtrVector::const_iterator iter = features.begin(); features.end() != iter; ++iter)
676 err = (*iter)->GetName(strName);
679 strError <<
"[Could not get feature Name. Error code: " << err <<
"]";
680 strName.assign(strError.str());
683 err = (*iter)->GetDisplayName(strDisplayName);
686 strError <<
"[Could not get feature Display Name. Error code: " << err <<
"]";
687 strDisplayName.assign(strError.str());
690 err = (*iter)->GetDescription(strDescription);
693 strError <<
"[Could not get feature Description. Error code: " << err <<
"]";
694 strDescription.assign(strError.str());
697 err = (*iter)->GetCategory(strCategory);
700 strError <<
"[Could not get feature Category. Error code: " << err <<
"]";
701 strCategory.assign(strError.str());
704 err = (*iter)->GetSFNCNamespace(strSFNCNamespace);
707 strError <<
"[Could not get feature SNFC Namespace. Error code: " << err <<
"]";
708 strSFNCNamespace.assign(strError.str());
711 err = (*iter)->GetUnit(strUnit);
714 strError <<
"[Could not get feature Unit. Error code: " << err <<
"]";
715 strUnit.assign(strError.str());
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: ";
725 err = (*iter)->GetDataType(eType);
728 std::cout <<
"[Could not get feature Data Type. Error code: " << err <<
"]" << std::endl;
736 err = (*iter)->GetValue(bValue);
739 std::cout << bValue <<
" (bool)" << std::endl;
743 err = (*iter)->GetValue(strValue);
746 std::cout << strValue <<
" (string enum)" << std::endl;
751 err = (*iter)->GetValue(fValue);
753 std::cout << fValue <<
" (float)" << std::endl;
757 err = (*iter)->GetValue(nValue);
759 std::cout << nValue <<
" (int)" << std::endl;
763 err = (*iter)->GetValue(strValue);
765 std::cout << strValue <<
" (string)" << std::endl;
770 std::cout <<
"[None]" << std::endl;
775 std::cout <<
"Could not get feature value. Error code: " << err << std::endl;
779 std::cout << std::endl;
833 ROS_INFO(
"Updating Acquisition and Trigger config:");
838 configureFeature(
"AcquisitionMode", config.acquisition_mode, config.acquisition_mode);
840 if (config.acquisition_rate_enable !=
config_.acquisition_rate_enable ||
on_init_)
842 configureFeature(
"AcquisitionFrameRateEnable", static_cast<bool>(config.acquisition_rate_enable), config.acquisition_rate_enable);
846 configureFeature(
"AcquisitionFrameRateAbs", static_cast<float>(config.acquisition_rate), config.acquisition_rate);
847 configureFeature(
"AcquisitionFrameRate", static_cast<float>(config.acquisition_rate), config.acquisition_rate);
855 configureFeature(
"TriggerSelector", config.trigger_selector, config.trigger_selector);
859 configureFeature(
"TriggerSource", config.trigger_source, config.trigger_source);
861 if (config.trigger_activation !=
config_.trigger_activation ||
on_init_)
863 configureFeature(
"TriggerActivation", config.trigger_activation, config.trigger_activation);
867 configureFeature(
"TriggerDelayAbs", static_cast<float>(config.trigger_delay), config.trigger_delay);
871 configureFeature(
"ActionDeviceKey", static_cast<VmbInt64_t>(config.action_device_key), config.action_device_key);
875 configureFeature(
"ActionGroupKey", static_cast<VmbInt64_t>(config.action_group_key), config.action_group_key);
879 configureFeature(
"ActionGroupMask", static_cast<VmbInt64_t>(config.action_group_mask), config.action_group_mask);
893 configureFeature(
"IrisAutoTarget", static_cast<VmbInt64_t>(config.iris_auto_target), config.iris_auto_target);
899 if (config.iris_video_level_max !=
config_.iris_video_level_max ||
on_init_)
901 configureFeature(
"IrisVideoLevelMax", static_cast<VmbInt64_t>(config.iris_video_level_max),
902 config.iris_video_level_max);
904 if (config.iris_video_level_min !=
config_.iris_video_level_min ||
on_init_)
906 configureFeature(
"IrisVideoLevelMin", static_cast<VmbInt64_t>(config.iris_video_level_min),
907 config.iris_video_level_min);
916 ROS_INFO(
"Updating Exposure config:");
921 configureFeature(
"ExposureTimeAbs", static_cast<float>(config.exposure), config.exposure);
925 configureFeature(
"ExposureAuto", config.exposure_auto, config.exposure_auto);
929 configureFeature(
"ExposureAutoAlg", config.exposure_auto_alg, config.exposure_auto_alg);
933 configureFeature(
"ExposureAutoAdjustTol", static_cast<VmbInt64_t>(config.exposure_auto_tol),
934 config.exposure_auto_tol);
938 configureFeature(
"ExposureAutoMax", static_cast<VmbInt64_t>(config.exposure_auto_max), config.exposure_auto_max);
942 configureFeature(
"ExposureAutoMin", static_cast<VmbInt64_t>(config.exposure_auto_min), config.exposure_auto_min);
944 if (config.exposure_auto_outliers !=
config_.exposure_auto_outliers ||
on_init_)
946 configureFeature(
"ExposureAutoOutliers", static_cast<VmbInt64_t>(config.exposure_auto_outliers),
947 config.exposure_auto_outliers);
949 if (config.exposure_auto_rate !=
config_.exposure_auto_rate ||
on_init_)
951 configureFeature(
"ExposureAutoRate", static_cast<VmbInt64_t>(config.exposure_auto_rate), config.exposure_auto_rate);
953 if (config.exposure_auto_target !=
config_.exposure_auto_target ||
on_init_)
955 configureFeature(
"ExposureAutoTarget", static_cast<VmbInt64_t>(config.exposure_auto_target),
956 config.exposure_auto_target);
959 configureFeature(
"ExposureMode", config.exposure_mode ,config.exposure_mode);
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);
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);
967 if (config.exposure_threshold_PWL2 !=
config_.exposure_threshold_PWL2 ||
on_init_) {
969 static_cast<VmbInt64_t>(config.exposure_threshold_PWL2), config.exposure_threshold_PWL2);
971 if (config.exposure_threshold_PWL1 !=
config_.exposure_threshold_PWL1 ||
on_init_) {
973 static_cast<VmbInt64_t>(config.exposure_threshold_PWL1), config.exposure_threshold_PWL1);
995 ROS_INFO(
"Updating DSP-Subregion config:");
1000 configureFeature(
"DSPSubregionBottom", static_cast<VmbInt64_t>(config.subregion_bottom), config.subregion_bottom);
1004 configureFeature(
"DSPSubregionTop", static_cast<VmbInt64_t>(config.subregion_top), config.subregion_top);
1008 configureFeature(
"DSPSubregionLeft", static_cast<VmbInt64_t>(config.subregion_left), config.subregion_left);
1012 configureFeature(
"DSPSubregionRight", static_cast<VmbInt64_t>(config.subregion_right), config.subregion_right);
1032 if (config.gain_auto_adjust_tol !=
config_.gain_auto_adjust_tol ||
on_init_)
1034 configureFeature(
"GainAutoAdjustTol", static_cast<VmbInt64_t>(config.gain_auto_adjust_tol),
1035 config.gain_auto_adjust_tol);
1039 configureFeature(
"GainAutoMax", static_cast<float>(config.gain_auto_max), config.gain_auto_max);
1043 configureFeature(
"GainAutoMin", static_cast<float>(config.gain_auto_min), config.gain_auto_min);
1045 if (config.gain_auto_outliers !=
config_.gain_auto_outliers ||
on_init_)
1047 configureFeature(
"GainAutoOutliers", static_cast<VmbInt64_t>(config.gain_auto_outliers), config.gain_auto_outliers);
1051 configureFeature(
"GainAutoRate", static_cast<VmbInt64_t>(config.gain_auto_rate), config.gain_auto_rate);
1055 configureFeature(
"GainAutoTarget", static_cast<VmbInt64_t>(config.gain_auto_target), config.gain_auto_target);
1064 ROS_INFO(
"Updating White Balance config:");
1067 if (config.balance_ratio_abs !=
config_.balance_ratio_abs ||
on_init_)
1069 configureFeature(
"BalanceRatioAbs", static_cast<float>(config.balance_ratio_abs), config.balance_ratio_abs);
1071 if (config.balance_ratio_selector !=
config_.balance_ratio_selector ||
on_init_)
1073 configureFeature(
"BalanceRatioSelector", config.balance_ratio_selector, config.balance_ratio_selector);
1075 if (config.whitebalance_auto !=
config_.whitebalance_auto ||
on_init_)
1077 configureFeature(
"BalanceWhiteAuto", config.whitebalance_auto, config.whitebalance_auto);
1079 if (config.whitebalance_auto_tol !=
config_.whitebalance_auto_tol ||
on_init_)
1081 configureFeature(
"BalanceWhiteAutoAdjustTol", static_cast<VmbInt64_t>(config.whitebalance_auto_tol),
1082 config.whitebalance_auto_tol);
1084 if (config.whitebalance_auto_rate !=
config_.whitebalance_auto_rate ||
on_init_)
1086 configureFeature(
"BalanceWhiteAutoRate", static_cast<VmbInt64_t>(config.whitebalance_auto_rate),
1087 config.whitebalance_auto_rate);
1111 ROS_INFO(
"Updating Image Mode config:");
1116 configureFeature(
"DecimationHorizontal", static_cast<VmbInt64_t>(config.decimation_x), config.decimation_x);
1120 configureFeature(
"DecimationVertical", static_cast<VmbInt64_t>(config.decimation_y), config.decimation_y);
1124 configureFeature(
"BinningHorizontal", static_cast<VmbInt64_t>(config.binning_x), config.binning_x);
1128 configureFeature(
"BinningVertical", static_cast<VmbInt64_t>(config.binning_y), config.binning_y);
1132 configureFeature(
"ReverseX", static_cast<bool>(config.reverse_x), config.reverse_x);
1136 configureFeature(
"ReverseY", static_cast<bool>(config.reverse_y), config.reverse_y);
1150 configureFeature(
"Width", static_cast<VmbInt64_t>(config.width), config.width);
1154 configureFeature(
"Height", static_cast<VmbInt64_t>(config.height), config.height);
1158 configureFeature(
"OffsetX", static_cast<VmbInt64_t>(config.offset_x), config.offset_x);
1162 configureFeature(
"OffsetY", static_cast<VmbInt64_t>(config.offset_y), config.offset_y);
1171 ROS_INFO(
"Updating Bandwidth config:");
1174 if (config.stream_bytes_per_second !=
config_.stream_bytes_per_second ||
on_init_)
1176 configureFeature(
"StreamBytesPerSecond", static_cast<VmbInt64_t>(config.stream_bytes_per_second),
1177 config.stream_bytes_per_second);
1186 ROS_INFO(
"Updating PixelFormat config:");
1204 configureFeature(
"SyncInSelector", config.sync_in_selector, config.sync_in_selector);
1206 if (config.sync_out_polarity !=
config_.sync_out_polarity ||
on_init_)
1208 configureFeature(
"SyncOutPolarity", config.sync_out_polarity, config.sync_out_polarity);
1210 if (config.sync_out_selector !=
config_.sync_out_selector ||
on_init_)
1212 configureFeature(
"SyncOutSelector", config.sync_out_selector, config.sync_out_selector);
1216 configureFeature(
"SyncOutSource", config.sync_out_source, config.sync_out_source);
1225 ROS_INFO(
"Updating USB GPIO config:");
1229 configureFeature(
"LineSelector", config.line_selector, config.line_selector);
1246 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Opening camera");
1249 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Camera is idle");
1252 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Camera is streaming");
1255 stat.
summaryf(diagnostic_msgs::DiagnosticStatus::ERROR,
"Cannot find requested camera %s",
guid_.c_str());
1258 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Problem retrieving frame");
1261 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Camera has encountered an error");
1264 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Camera is in unknown state");
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)
void updateImageModeConfig(Config &config)
void summary(unsigned char lvl, const std::string s)
void updatePixelFormatConfig(Config &config)
void setHardwareID(const std::string &hwid)
void updateUSBGPIOConfig(Config &config)
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
void updateIrisConfig(Config &config)
void add(const std::string &name, TaskFunction f)
void updateGPIOConfig(Config &config)
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
static const char * PixelFormatMode[]
double getTimestampRealTime(VmbUint64_t timestamp_ticks)
void summaryf(unsigned char lvl, const char *format,...)
void updateConfig(Config &config)
void updateROIConfig(Config &config)
void frameCallback(const FramePtr vimba_frame_ptr)
CameraPtr vimba_camera_ptr_
avt_vimba_camera::AvtVimbaCameraConfig Config
static const char * TriggerMode[]
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)
void updateGainConfig(Config &config)
#define SP_SET(sp, rawPtr)
frameCallbackFunc userFrameCallback
CameraState camera_state_
#define ROS_WARN_STREAM(args)
#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)
std::string diagnostic_msg_
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)
#define ROS_ERROR_STREAM(args)
std::string errorCodeToMessage(VmbErrorType error)
static const char * AcquisitionMode[]
std::vector< FeaturePtr > FeaturePtrVector
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[]
VmbInt64_t vimba_timestamp_tick_freq_
bool runCommand(const std::string &command_str)