120 updater_.
broadcast(0,
"Starting device with IP:" + ip_str +
" or GUID:" + guid_str);
123 if (!ip_str.empty()) {
128 ROS_WARN(
"Camera pointer is empty. Returning...");
134 if (!guid_str.empty()) {
135 std::string cam_guid_str;
138 ROS_WARN(
"Camera pointer is empty. Returning...");
141 assert(cam_guid_str == guid_str);
144 diagnostic_msg_ =
"GUID " + cam_guid_str +
" matches for camera with IP: " + ip_str;
145 ROS_INFO_STREAM(
"GUID " << cam_guid_str <<
" matches for camera with IP: " << ip_str);
147 }
else if (!guid_str.empty()) {
156 diagnostic_msg_ =
"Can't connect to the camera: at least GUID or IP need to be set.";
157 ROS_ERROR(
"Can't connect to the camera: at least GUID or IP need to be set.");
170 std::string trigger_source;
174 if (trigger_source_int ==
Freerun ||
176 trigger_source_int ==
SyncIn1) {
183 std::string(TriggerMode[trigger_source_int]) +
186 TriggerMode[trigger_source_int] <<
187 " not implemented.");
202 <<
"]: Starting continuous image acquisition...(" <<
frame_id_ <<
")");
208 <<
"]: Could not start continuous image acquisition(" <<
frame_id_ <<
"). " 225 <<
"]: Acquisition stoppped... (" <<
frame_id_ <<
")");
231 <<
"]: Could not stop image acquisition (" <<
frame_id_ <<
")." 256 ROS_INFO_STREAM(
"Updating configuration for camera " << config.frame_id);
291 VimbaSystem& vimba_system(VimbaSystem::GetInstance());
297 ROS_WARN_STREAM(
"Could not get camera. Retrying every two seconds...");
302 <<
"]: Could not get camera " << id_str
313 ROS_WARN_STREAM(
"Could not open camera. Retrying every two seconds...");
318 <<
"]: Could not open camera " << id_str
325 std::string cam_id, cam_name, cam_model, cam_sn, cam_int_id;
328 camera->GetID(cam_id);
329 camera->GetName(cam_name);
330 camera->GetModel(cam_model);
331 camera->GetSerialNumber(cam_sn);
332 camera->GetInterfaceID(cam_int_id);
333 camera->GetInterfaceType(cam_int_type);
334 err = camera->GetPermittedAccess(accessMode);
338 <<
"\n\t\t * Name : " << cam_name
339 <<
"\n\t\t * Model : " << cam_model
340 <<
"\n\t\t * ID : " << cam_id
341 <<
"\n\t\t * S/N : " << cam_sn
342 <<
"\n\t\t * Itf. ID : " << cam_int_id
361 boost::thread thread_callback = boost::thread(
userFrameCallback, vimba_frame_ptr);
362 thread_callback.join();
376 return runCommand(
"GevTimestampControlReset");
380 double timestamp = -1.0;
385 timestamp = ((double)ticks)/((double)freq);
400 vimba_feature_ptr->IsReadable(readable);
402 vimba_feature_ptr->GetDataType(data_type);
404 std::cout <<
"[Could not get feature Data Type. Error code: " 405 << err <<
"]" << std::endl;
407 std::string strValue;
408 switch ( data_type ) {
411 err = vimba_feature_ptr->GetValue(bValue);
413 val =
static_cast<T
>(bValue);
418 err = vimba_feature_ptr->GetValue(fValue);
420 val =
static_cast<T
>(fValue);
425 err = vimba_feature_ptr->GetValue(nValue);
427 val =
static_cast<T
>(nValue);
439 <<
" is not readable.");
443 <<
"]: Could not get feature " << feature_str);
447 << feature_str <<
" with datatype " 448 << FeatureDataType[data_type]
449 <<
" and value " << val);
463 vimba_feature_ptr->IsReadable(readable);
465 vimba_feature_ptr->GetDataType(data_type);
467 std::cout <<
"[Could not get feature Data Type. Error code: " 468 << err <<
"]" << std::endl;
470 std::string strValue;
471 switch ( data_type ) {
473 err = vimba_feature_ptr->GetValue(strValue);
479 err = vimba_feature_ptr->GetValue(strValue);
493 <<
" is not readable.");
497 <<
"]: Could not get feature " << feature_str);
501 <<
" with datatype " << FeatureDataType[data_type]
502 <<
" and value " << val);
517 err = vimba_feature_ptr->IsWritable(writable);
521 ROS_INFO_STREAM(
"Setting feature " << feature_str <<
" value " << val);
523 err = vimba_feature_ptr->GetDataType(data_type);
527 err = vimba_feature_ptr->IsValueAvailable(val, available);
530 err = vimba_feature_ptr->SetValue(val);
533 <<
"]: Feature " << feature_str <<
" is available now.");
537 << feature_str <<
": value unavailable\n\tERROR " 541 err = vimba_feature_ptr->SetValue(val);
545 << feature_str <<
": Bad data type\n\tERROR " 551 <<
" is not writable.");
559 <<
"]: Could not get feature " << feature_str
571 err = feature_ptr->RunCommand();
573 bool is_command_done =
false;
575 err = feature_ptr->IsCommandDone(is_command_done);
581 << command_str.c_str() <<
"...");
583 }
while (
false == is_command_done );
600 switch ( interfaceType ) {
607 default:
return "Unknown";
614 s = std::string(
"Read and write access");
616 s = std::string(
"Only read access");
618 s = std::string(
"Device configuration access");
620 s = std::string(
"Device read/write access without feature access (only addresses)");
622 s = std::string(
"No access");
628 if (mode_str == TriggerMode[
Freerun]) {
630 }
else if (mode_str == TriggerMode[
FixedRate]) {
632 }
else if (mode_str == TriggerMode[
Software]) {
634 }
else if (mode_str == TriggerMode[
SyncIn1]) {
636 }
else if (mode_str == TriggerMode[
SyncIn2]) {
638 }
else if (mode_str == TriggerMode[
SyncIn3]) {
640 }
else if (mode_str == TriggerMode[
SyncIn4]) {
652 std::string strDisplayName;
653 std::string strTooltip;
654 std::string strDescription;
655 std::string strCategory;
656 std::string strSFNCNamespace;
662 std::string strValue;
664 std::stringstream strError;
667 err = camera->GetFeatures(features);
671 for ( FeaturePtrVector::const_iterator iter = features.begin();
672 features.end() != iter;
674 err = (*iter)->GetName(strName);
676 strError <<
"[Could not get feature Name. Error code: " << err <<
"]";
677 strName.assign(strError.str());
680 err = (*iter)->GetDisplayName(strDisplayName);
682 strError <<
"[Could not get feature Display Name. Error code: " 684 strDisplayName.assign(strError.str());
687 err = (*iter)->GetToolTip(strTooltip);
689 strError <<
"[Could not get feature Tooltip. Error code: " 691 strTooltip.assign(strError.str());
694 err = (*iter)->GetDescription(strDescription);
696 strError <<
"[Could not get feature Description. Error code: " 698 strDescription.assign(strError.str());
701 err = (*iter)->GetCategory(strCategory);
703 strError <<
"[Could not get feature Category. Error code: " 705 strCategory.assign(strError.str());
708 err = (*iter)->GetSFNCNamespace(strSFNCNamespace);
710 strError <<
"[Could not get feature SNFC Namespace. Error code: " 712 strSFNCNamespace.assign(strError.str());
715 err = (*iter)->GetUnit(strUnit);
717 strError <<
"[Could not get feature Unit. Error code: " << err <<
"]";
718 strUnit.assign(strError.str());
721 std::cout <<
"/// Feature Name: " << strName << std::endl;
722 std::cout <<
"/// Display Name: " << strDisplayName << std::endl;
723 std::cout <<
"/// Tooltip: " << strTooltip << std::endl;
724 std::cout <<
"/// Description: " << strDescription << std::endl;
725 std::cout <<
"/// SNFC Namespace: " << strSFNCNamespace << std::endl;
726 std::cout <<
"/// Unit: " << strUnit << std::endl;
727 std::cout <<
"/// Value: ";
729 err = (*iter)->GetDataType(eType);
731 std::cout <<
"[Could not get feature Data Type. Error code: " 732 << err <<
"]" << std::endl;
737 err = (*iter)->GetValue(bValue);
739 std::cout << bValue <<
" bool" << std::endl;
743 err = (*iter)->GetValue(strValue);
745 std::cout << strValue <<
" str Enum" << std::endl;
750 err = (*iter)->GetValue(fValue);
752 std::cout << fValue <<
" float" << std::endl;
756 err = (*iter)->GetValue(nValue);
758 std::cout << nValue <<
" int" << std::endl;
762 err = (*iter)->GetValue(strValue);
764 std::cout << strValue <<
" str" << std::endl;
769 std::cout <<
"[None]" << std::endl;
773 std::cout <<
"Could not get feature value. Error code: " 778 std::cout << std::endl;
787 bool changed =
false;
794 double acquisition_frame_rate_limit;
795 getFeatureValue(
"AcquisitionFrameRateLimit", acquisition_frame_rate_limit);
796 if (acquisition_frame_rate_limit < config.acquisition_rate) {
797 double rate = (double)floor(acquisition_frame_rate_limit);
798 ROS_WARN_STREAM(
"Max frame rate allowed: " << acquisition_frame_rate_limit
799 <<
". Setting " << rate <<
"...");
800 config.acquisition_rate = rate;
803 static_cast<float>(config.acquisition_rate));
817 if (config.trigger_activation !=
config_.trigger_activation ||
on_init_) {
819 setFeatureValue(
"TriggerActivation", config.trigger_activation.c_str());
826 ROS_INFO_STREAM(
"New Acquisition and Trigger config (" << config.frame_id <<
") : " 827 <<
"\n\tAcquisitionMode : " << config.acquisition_mode <<
" was " <<
config_.acquisition_mode
828 <<
"\n\tAcquisitionFrameRateAbs : " << config.acquisition_rate <<
" was " <<
config_.acquisition_rate
829 <<
"\n\tTriggerMode : " << config.trigger_mode <<
" was " <<
config_.trigger_mode
830 <<
"\n\tTriggerSource : " << config.trigger_source <<
" was " <<
config_.trigger_source
831 <<
"\n\tTriggerSelector : " << config.trigger_selector <<
" was " <<
config_.trigger_selector
832 <<
"\n\tTriggerActivation : " << config.trigger_activation <<
" was " <<
config_.trigger_activation
833 <<
"\n\tTriggerDelayAbs : " << config.trigger_delay <<
" was " <<
config_.trigger_delay);
839 bool changed =
false;
842 setFeatureValue(
"IrisAutoTarget", static_cast<float>(config.iris_auto_target));
853 if (config.iris_video_level_max !=
config_.iris_video_level_max ||
on_init_) {
855 setFeatureValue(
"IrisVideoLevelMax", static_cast<float>(config.iris_video_level_max));
857 if (config.iris_video_level_min !=
config_.iris_video_level_min ||
on_init_) {
860 static_cast<VmbInt64_t>(config.iris_video_level_min));
864 <<
"\n\tIrisAutoTarget : " << config.iris_auto_target <<
" was " <<
config_.iris_auto_target
876 bool changed =
false;
879 setFeatureValue(
"ExposureTimeAbs", static_cast<float>(config.exposure));
885 if (config.exposure_auto_alg !=
config_.exposure_auto_alg ||
on_init_) {
889 if (config.exposure_auto_tol !=
config_.exposure_auto_tol ||
on_init_) {
892 static_cast<VmbInt64_t>(config.exposure_auto_tol));
894 if (config.exposure_auto_max !=
config_.exposure_auto_max ||
on_init_) {
897 static_cast<VmbInt64_t>(config.exposure_auto_max));
899 if (config.exposure_auto_min !=
config_.exposure_auto_min ||
on_init_) {
902 static_cast<VmbInt64_t>(config.exposure_auto_min));
904 if (config.exposure_auto_outliers !=
config_.exposure_auto_outliers ||
on_init_) {
907 static_cast<VmbInt64_t>(config.exposure_auto_outliers));
909 if (config.exposure_auto_rate !=
config_.exposure_auto_rate ||
on_init_) {
912 static_cast<VmbInt64_t>(config.exposure_auto_rate));
914 if (config.exposure_auto_target !=
config_.exposure_auto_target ||
on_init_) {
917 static_cast<VmbInt64_t>(config.exposure_auto_target));
921 <<
"\n\tExposureTimeAbs : " << config.exposure <<
" was " <<
config_.exposure
922 <<
"\n\tExposureAuto : " << config.exposure_auto <<
" was " <<
config_.exposure_auto
923 <<
"\n\tExposureAutoAdjustTol : " << config.exposure_auto_tol <<
" was " <<
config_.exposure_auto_tol
924 <<
"\n\tExposureAutoMax : " << config.exposure_auto_max <<
" was " <<
config_.exposure_auto_max
925 <<
"\n\tExposureAutoMin : " << config.exposure_auto_min <<
" was " <<
config_.exposure_auto_min
926 <<
"\n\tExposureAutoOutliers : " << config.exposure_auto_outliers <<
" was " <<
config_.exposure_auto_outliers
927 <<
"\n\tExposureAutoRate : " << config.exposure_auto_rate <<
" was " <<
config_.exposure_auto_rate
928 <<
"\n\tExposureAutoTarget : " << config.exposure_auto_target <<
" was " <<
config_.exposure_auto_target);
934 bool changed =
false;
946 static_cast<VmbInt64_t>(config.gain_auto_tol));
950 setFeatureValue(
"GainAutoMax", static_cast<float>(config.gain_auto_max));
955 static_cast<VmbInt64_t>(config.gain_auto_min));
957 if (config.gain_auto_outliers !=
config_.gain_auto_outliers ||
on_init_) {
960 static_cast<VmbInt64_t>(config.gain_auto_outliers));
965 static_cast<VmbInt64_t>(config.gain_auto_rate));
969 setFeatureValue(
"GainAutoRate", static_cast<VmbInt64_t>(config.gain_auto_target));
973 <<
"\n\tGain : " << config.gain <<
" was " <<
config_.gain
974 <<
"\n\tGainAuto : " << config.gain_auto <<
" was " <<
config_.gain_auto
975 <<
"\n\tGainAutoAdjustTol : " << config.gain_auto_tol <<
" was " <<
config_.gain_auto_tol
976 <<
"\n\tGainAutoMax : " << config.gain_auto_max <<
" was " <<
config_.gain_auto_max
977 <<
"\n\tGainAutoMin : " << config.gain_auto_min <<
" was " <<
config_.gain_auto_min
978 <<
"\n\tGainAutoOutliers : " << config.gain_auto_outliers <<
" was " <<
config_.gain_auto_outliers
979 <<
"\n\tGainAutoRate : " << config.gain_auto_rate <<
" was " <<
config_.gain_auto_rate
980 <<
"\n\tGainAutoTarget : " << config.gain_auto_target <<
" was " <<
config_.gain_auto_target);
986 bool changed =
false;
987 if (config.balance_ratio_abs !=
config_.balance_ratio_abs ||
on_init_) {
989 setFeatureValue(
"BalanceRatioAbs", static_cast<float>(config.balance_ratio_abs));
991 if (config.balance_ratio_selector !=
config_.balance_ratio_selector ||
on_init_) {
993 setFeatureValue(
"BalanceRatioSelector", config.balance_ratio_selector.c_str());
995 if (config.whitebalance_auto !=
config_.whitebalance_auto ||
on_init_) {
999 if (config.whitebalance_auto_tol !=
config_.whitebalance_auto_tol ||
on_init_) {
1001 setFeatureValue(
"BalanceWhiteAutoAdjustTol", static_cast<VmbInt64_t>(config.whitebalance_auto_tol));
1003 if (config.whitebalance_auto_rate !=
config_.whitebalance_auto_rate ||
on_init_) {
1005 setFeatureValue(
"BalanceWhiteAutoRate", static_cast<VmbInt64_t>(config.whitebalance_auto_rate));
1008 ROS_INFO_STREAM(
"New White Balance config (" << config.frame_id <<
") : " 1009 <<
"\n\tBalanceRatioAbs : " << config.balance_ratio_abs <<
" was " <<
config_.balance_ratio_abs
1010 <<
"\n\tBalanceRatioSelector : " << config.balance_ratio_selector <<
" was " <<
config_.balance_ratio_selector
1011 <<
"\n\tBalanceWhiteAuto : " << config.whitebalance_auto <<
" was " <<
config_.whitebalance_auto
1012 <<
"\n\tBalanceWhiteAutoAdjustTol : " << config.whitebalance_auto_tol <<
" was " <<
config_.whitebalance_auto_tol
1013 <<
"\n\tBalanceWhiteAutoRate : " << config.whitebalance_auto_rate <<
" was " <<
config_.whitebalance_auto_rate);
1019 bool changed =
false;
1027 <<
"\n\tPtpMode : " << config.ptp_mode <<
" was " <<
config_.ptp_mode);
1033 bool changed =
false;
1037 static_cast<VmbInt64_t>(config.decimation_x));
1041 setFeatureValue(
"DecimationVertical", static_cast<VmbInt64_t>(config.decimation_y));
1045 setFeatureValue(
"BinningHorizontal", static_cast<VmbInt64_t>(config.binning_x));
1049 setFeatureValue(
"BinningVertical", static_cast<VmbInt64_t>(config.binning_y));
1052 ROS_INFO_STREAM(
"New Image Mode config (" << config.frame_id <<
") : " 1053 <<
"\n\tDecimationHorizontal : " << config.decimation_x <<
" was " <<
config_.decimation_x
1054 <<
"\n\tDecimationVertical : " << config.decimation_y <<
" was " <<
config_.decimation_y
1055 <<
"\n\tBinningHorizontal : " << config.binning_x <<
" was " <<
config_.binning_x
1056 <<
"\n\tBinningVertical : " << config.binning_y <<
" was " <<
config_.binning_y);
1062 bool changed =
false;
1067 int max_width, max_height;
1071 int binning_or_decimation_x = std::max(config.binning_x, config.decimation_x);
1072 int binning_or_decimation_y = std::max(config.binning_y, config.decimation_y);
1074 max_width *= binning_or_decimation_x;
1075 max_height *= binning_or_decimation_y;
1077 config.width = std::min(config.width, (
int)max_width);
1078 config.height = std::min(config.height, (
int)max_height);
1079 config.roi_offset_x = std::min(config.roi_offset_x, config.width - 1);
1080 config.roi_offset_y = std::min(config.roi_offset_y, config.height - 1);
1081 config.roi_width = std::min(config.roi_width, config.width - config.roi_offset_x);
1082 config.roi_height = std::min(config.roi_height, config.height - config.roi_offset_y);
1084 int width = config.roi_width ? config.roi_width : max_width - config.roi_offset_x;
1085 int height = config.roi_height ? config.roi_height : max_height - config.roi_offset_y;
1089 int offset_x = config.roi_offset_x;
1090 int offset_y = config.roi_offset_y;
1091 unsigned int right_x = (offset_x + width + binning_or_decimation_x - 1);
1092 unsigned int bottom_y = (offset_y + height + binning_or_decimation_y - 1);
1094 right_x = std::min(right_x, (
unsigned)(config.width));
1095 bottom_y = std::min(bottom_y, (
unsigned)(config.height));
1096 width = right_x - offset_x;
1097 height = bottom_y - offset_y;
1099 config.width = width/binning_or_decimation_x;
1100 config.height = height/binning_or_decimation_y;
1101 config.roi_offset_x = offset_x/binning_or_decimation_x;
1102 config.roi_offset_y = offset_y/binning_or_decimation_y;
1106 setFeatureValue(
"OffsetX", static_cast<VmbInt64_t>(config.roi_offset_x));
1110 setFeatureValue(
"OffsetY", static_cast<VmbInt64_t>(config.roi_offset_y));
1123 <<
"\n\tOffsetX : " << config.roi_offset_x <<
" was " <<
config_.roi_offset_x
1124 <<
"\n\tOffsetY : " << config.roi_offset_y <<
" was " <<
config_.roi_offset_y
1125 <<
"\n\tWidth : " << config.width <<
" was " <<
config_.width
1126 <<
"\n\tHeight : " << config.height <<
" was " <<
config_.height);
1132 bool changed =
false;
1133 if (config.stream_bytes_per_second
1137 static_cast<VmbInt64_t>(config.stream_bytes_per_second));
1141 <<
"\n\tStreamBytesPerSecond : " << config.stream_bytes_per_second <<
" was " <<
config_.stream_bytes_per_second);
1147 bool changed =
false;
1153 ROS_INFO_STREAM(
"New PixelFormat config (" << config.frame_id <<
") : " 1154 <<
"\n\tPixelFormat : " << config.pixel_format <<
" was " <<
config_.pixel_format);
1160 bool changed =
false;
1161 if (config.sync_in_selector
1166 if (config.sync_out_polarity
1171 if (config.sync_out_selector
1176 if (config.sync_out_source
1183 <<
"\n\tSyncInSelector : " << config.sync_in_selector <<
" was " <<
config_.sync_in_selector
1184 <<
"\n\tSyncOutPolarity : " << config.sync_out_polarity <<
" was " <<
config_.sync_out_polarity
1185 <<
"\n\tSyncOutSelector : " << config.sync_out_selector <<
" was " <<
config_.sync_out_selector
1186 <<
"\n\tSyncOutSource : " << config.sync_out_source <<
" was " <<
config_.sync_out_source);
1207 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Opening camera");
1210 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Camera is idle");
1213 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Camera is streaming");
1216 stat.
summaryf(diagnostic_msgs::DiagnosticStatus::ERROR,
"Cannot find requested camera %s",
guid_.c_str());
1220 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Problem retrieving frame");
1223 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Camera has encountered an error");
void updatePtpModeConfig(Config &config)
IMEXPORT VmbErrorType GetCameraByID(const char *pID, CameraPtr &pCamera)
std::string interfaceToString(VmbInterfaceType interfaceType)
static const char * State[]
void printAllCameraFeatures(const CameraPtr &camera)
void updateWhiteBalanceConfig(Config &config)
NetPointer< Frame, AVT::VmbAPINET::Frame > FramePtr
static volatile int keepRunning
static const char * FeatureDataType[]
void getCurrentState(diagnostic_updater::DiagnosticStatusWrapper &stat)
boost::mutex config_mutex_
void updateImageModeConfig(Config &config)
#define ROS_INFO_STREAM_THROTTLE(period, args)
void summary(unsigned char lvl, const std::string s)
FrameObserver * vimba_frame_observer_ptr_
void updatePixelFormatConfig(Config &config)
void setHardwareID(const std::string &hwid)
CameraPtr openCamera(std::string id_str)
bool resetTimestamp(void)
std::string getName(void *handle)
void updateIrisConfig(Config &config)
void add(const std::string &name, TaskFunction f)
void updateGPIOConfig(Config &config)
int getTriggerModeInt(std::string mode_str)
void summaryf(unsigned char lvl, const char *format,...)
void updateConfig(Config &config)
NetPointer< Feature, AVT::VmbAPINET::Feature > FeaturePtr
void updateROIConfig(Config &config)
void frameCallback(const FramePtr vimba_frame_ptr)
CameraPtr vimba_camera_ptr_
avt_vimba_camera::AvtVimbaCameraConfig Config
static const char * TriggerMode[]
void start(std::string ip_str, std::string guid_str, bool debug_prints=true)
NetPointer< Camera, AVT::VmbAPINET::Camera > CameraPtr
bool setFeatureValue(const std::string &feature_str, const T &val)
bool getFeatureValue(const std::string &feature_str, T &val)
void updateBandwidthConfig(Config &config)
static const char * AutoMode[]
void updateExposureConfig(Config &config)
double getDeviceTemp(void)
void updateGainConfig(Config &config)
frameCallbackFunc userFrameCallback
CameraState camera_state_
#define ROS_WARN_STREAM(args)
void intHandler(int dummy)
diagnostic_updater::Updater updater_
#define ROS_INFO_STREAM(args)
std::string diagnostic_msg_
void updateAcquisitionConfig(Config &config)
double getTimestamp(void)
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)
std::vector< FeaturePtr > FeaturePtrVector
static const char * BalanceRatioMode[]
std::string accessModeToString(VmbAccessModeType modeType)
bool runCommand(const std::string &command_str)