00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #include <avt_vimba_camera/avt_vimba_camera.h>
00034 #include <avt_vimba_camera/avt_vimba_api.h>
00035
00036 #include <ros/ros.h>
00037 #include <ros/console.h>
00038
00039 namespace avt_vimba_camera {
00040
00041 static const char* AutoMode[] = {
00042 "Off",
00043 "Once",
00044 "Continuous"};
00045 static const char* TriggerMode[] = {
00046 "Freerun",
00047 "FixedRate",
00048 "Software",
00049 "Line1",
00050 "Line2",
00051 "Line3",
00052 "Line4" };
00053 static const char* AcquisitionMode[] = {
00054 "Continuous",
00055 "SingleFrame",
00056 "MultiFrame",
00057 "Recorder"};
00058 static const char* PixelFormatMode[] = {
00059 "Mono8",
00060 "Mono12",
00061 "Mono12Packed",
00062 "BayerRG8",
00063 "BayerRG12Packed",
00064 "BayerRG12",
00065 "RGB8Packed",
00066 "BGR8Packed"};
00067 static const char* BalanceRatioMode[] = {
00068 "Red",
00069 "Blue"};
00070 static const char* FeatureDataType[] = {
00071 "Unknown",
00072 "int",
00073 "float",
00074 "enum",
00075 "string",
00076 "bool"};
00077
00078 static const char* State[] = {
00079 "Opening",
00080 "Idle",
00081 "Camera not found",
00082 "Format error",
00083 "Error",
00084 "Ok"};
00085
00086
00087 AvtVimbaCamera::AvtVimbaCamera() : AvtVimbaCamera(ros::this_node::getName().c_str()) {
00088
00089 }
00090
00091 AvtVimbaCamera::AvtVimbaCamera(std::string name) {
00092
00093 opened_ = false;
00094 streaming_ = false;
00095 on_init_ = true;
00096 show_debug_prints_ = false;
00097 name_ = name;
00098
00099 camera_state_ = OPENING;
00100
00101 updater_.setHardwareID("unknown");
00102 updater_.add(name_, this, &AvtVimbaCamera::getCurrentState);
00103 updater_.update();
00104 }
00105
00106 void AvtVimbaCamera::start(std::string ip_str, std::string guid_str, bool debug_prints) {
00107 if (opened_) return;
00108
00109 show_debug_prints_ = debug_prints;
00110 updater_.broadcast(0, "Starting device with IP:" + ip_str + " or GUID:" + guid_str);
00111
00112
00113 if (!ip_str.empty()) {
00114 diagnostic_msg_ = "Trying to open camera by IP: " + ip_str;
00115 ROS_INFO_STREAM("Trying to open camera by IP: " << ip_str);
00116 vimba_camera_ptr_ = openCamera(ip_str);
00117 updater_.setHardwareID(ip_str);
00118 guid_ = ip_str;
00119
00120 if (!guid_str.empty()) {
00121 std::string cam_guid_str;
00122 vimba_camera_ptr_->GetSerialNumber(cam_guid_str);
00123 assert(cam_guid_str == guid_str);
00124 updater_.setHardwareID(guid_str);
00125 guid_ = guid_str;
00126 diagnostic_msg_ = "GUID " + cam_guid_str + " matches for camera with IP: " + ip_str;
00127 ROS_INFO_STREAM("GUID " << cam_guid_str << " matches for camera with IP: " << ip_str);
00128 }
00129 } else if (!guid_str.empty()) {
00130
00131 diagnostic_msg_ = "Trying to open camera by ID: " + guid_str;
00132 ROS_INFO_STREAM("Trying to open camera by ID: " << guid_str);
00133 vimba_camera_ptr_ = openCamera(guid_str);
00134 updater_.setHardwareID(guid_str);
00135 guid_ = guid_str;
00136 } else {
00137
00138 diagnostic_msg_ = "Can't connect to the camera: at least GUID or IP need to be set.";
00139 ROS_ERROR("Can't connect to the camera: at least GUID or IP need to be set.");
00140 camera_state_ = ERROR;
00141 }
00142 updater_.update();
00143
00144
00145
00146 VmbInterfaceType cam_int_type;
00147 vimba_camera_ptr_->GetInterfaceType(cam_int_type);
00148 if ( cam_int_type == VmbInterfaceEthernet ){
00149 runCommand("GVSPAdjustPacketSize");
00150 }
00151
00152 std::string trigger_source;
00153 getFeatureValue("TriggerSource", trigger_source);
00154 int trigger_source_int = getTriggerModeInt(trigger_source);
00155
00156 if (trigger_source_int == Freerun ||
00157 trigger_source_int == FixedRate ||
00158 trigger_source_int == SyncIn1) {
00159
00160 vimba_frame_observer_ptr_ = new FrameObserver(vimba_camera_ptr_,
00161 boost::bind(&avt_vimba_camera::AvtVimbaCamera::frameCallback, this, _1));
00162 camera_state_ = IDLE;
00163 } else {
00164 diagnostic_msg_ = "Trigger mode " +
00165 std::string(TriggerMode[trigger_source_int]) +
00166 " not implemented.";
00167 ROS_ERROR_STREAM("Trigger mode " <<
00168 TriggerMode[trigger_source_int] <<
00169 " not implemented.");
00170 camera_state_ = ERROR;
00171 }
00172 updater_.update();
00173 }
00174
00175 void AvtVimbaCamera::startImaging(void) {
00176 if (!streaming_) {
00177
00178 VmbErrorType err =
00179 vimba_camera_ptr_->StartContinuousImageAcquisition(1,
00180 IFrameObserverPtr(vimba_frame_observer_ptr_));
00181 if (VmbErrorSuccess == err) {
00182 diagnostic_msg_ = "Starting continuous image acquisition";
00183 ROS_INFO_STREAM("[" << name_
00184 << "]: Starting continuous image acquisition...(" << frame_id_ << ")");
00185 streaming_ = true;
00186 camera_state_ = OK;
00187 } else {
00188 diagnostic_msg_ = "Could not start continuous image acquisition. Error: " + api_.errorCodeToMessage(err);
00189 ROS_ERROR_STREAM("[" << name_
00190 << "]: Could not start continuous image acquisition(" << frame_id_ << "). "
00191 << "\n Error: " << api_.errorCodeToMessage(err));
00192 camera_state_ = ERROR;
00193 }
00194 } else {
00195 ROS_WARN_STREAM("Start imaging called, but the camera is already imaging(" << frame_id_ << ").");
00196 }
00197 updater_.update();
00198 }
00199
00200 void AvtVimbaCamera::stopImaging(void) {
00201 if (streaming_ || on_init_) {
00202 VmbErrorType err =
00203 vimba_camera_ptr_->StopContinuousImageAcquisition();
00204 if (VmbErrorSuccess == err) {
00205 diagnostic_msg_ = "Acquisition stopped";
00206 ROS_INFO_STREAM("[" << name_
00207 << "]: Acquisition stoppped... (" << frame_id_ << ")");
00208 streaming_ = false;
00209 camera_state_ = IDLE;
00210 } else {
00211 diagnostic_msg_ = "Could not stop image acquisition. Error: " + api_.errorCodeToMessage(err);
00212 ROS_ERROR_STREAM("[" << name_
00213 << "]: Could not stop image acquisition (" << frame_id_ << ")."
00214 << "\n Error: " << api_.errorCodeToMessage(err));
00215 camera_state_ = ERROR;
00216 }
00217 } else {
00218 ROS_WARN_STREAM("Stop imaging called, but the camera is already stopped (" << frame_id_ << ").");
00219 }
00220 updater_.update();
00221 }
00222
00223 void AvtVimbaCamera::updateConfig(Config& config) {
00224 boost::mutex::scoped_lock lock(config_mutex_);
00225
00226 frame_id_ = config.frame_id;
00227
00228 if (streaming_) {
00229 stopImaging();
00230 ros::Duration(0.5).sleep();
00231 }
00232
00233 if (on_init_) {
00234 config_ = config;
00235 }
00236 diagnostic_msg_ = "Updating configuration";
00237 if(show_debug_prints_)
00238 ROS_INFO_STREAM("Updating configuration for camera " << config.frame_id);
00239 updateExposureConfig(config);
00240 updateGainConfig(config);
00241 updateWhiteBalanceConfig(config);
00242 updateImageModeConfig(config);
00243 updateROIConfig(config);
00244 updateBandwidthConfig(config);
00245 updateGPIOConfig(config);
00246 updatePtpModeConfig(config);
00247 updatePixelFormatConfig(config);
00248 updateAcquisitionConfig(config);
00249 config_ = config;
00250
00251 if (on_init_) {
00252 on_init_ = false;
00253
00254 }
00255
00256 startImaging();
00257 }
00258
00259 void AvtVimbaCamera::stop() {
00260 if (!opened_) return;
00261 vimba_camera_ptr_->Close();
00262 opened_ = false;
00263 }
00264
00265 CameraPtr AvtVimbaCamera::openCamera(std::string id_str) {
00266
00267
00268
00269
00270
00271 CameraPtr camera;
00272 VimbaSystem& vimba_system(VimbaSystem::GetInstance());
00273 VmbErrorType err = vimba_system.GetCameraByID(id_str.c_str(), camera);
00274 if (VmbErrorSuccess == err) {
00275 std::string cam_id, cam_name, cam_model, cam_sn, cam_int_id;
00276 VmbInterfaceType cam_int_type;
00277 VmbAccessModeType accessMode;
00278 camera->GetID(cam_id);
00279 camera->GetName(cam_name);
00280 camera->GetModel(cam_model);
00281 camera->GetSerialNumber(cam_sn);
00282 camera->GetInterfaceID(cam_int_id);
00283 camera->GetInterfaceType(cam_int_type);
00284 err = camera->GetPermittedAccess(accessMode);
00285
00286 if(show_debug_prints_) {
00287 ROS_INFO_STREAM("[" << name_ << "]: Opened camera with"
00288 << "\n\t\t * Name : " << cam_name
00289 << "\n\t\t * Model : " << cam_model
00290 << "\n\t\t * ID : " << cam_id
00291 << "\n\t\t * S/N : " << cam_sn
00292 << "\n\t\t * Itf. ID : " << cam_int_id
00293 << "\n\t\t * Itf. Type: " << interfaceToString(cam_int_type)
00294 << "\n\t\t * Access : " << accessModeToString(accessMode));
00295 }
00296
00297 err = camera->Open(VmbAccessModeFull);
00298 if (VmbErrorSuccess == err) {
00299
00300 opened_ = true;
00301 camera_state_ = IDLE;
00302 } else {
00303 ROS_ERROR_STREAM("[" << name_
00304 << "]: Could not get camera " << id_str
00305 << "\n Error: " << api_.errorCodeToMessage(err));
00306 camera_state_ = CAMERA_NOT_FOUND;
00307 }
00308 } else {
00309 ROS_ERROR_STREAM("[" << name_
00310 << "]: Could not get camera " << id_str
00311 << "\n Error: " << api_.errorCodeToMessage(err));
00312 camera_state_ = CAMERA_NOT_FOUND;
00313 }
00314 return camera;
00315 }
00316
00317 void AvtVimbaCamera::frameCallback(const FramePtr vimba_frame_ptr) {
00318 boost::mutex::scoped_lock lock(config_mutex_);
00319 camera_state_ = OK;
00320 diagnostic_msg_ = "Camera operating normally";
00321
00322
00323 thread_callback_ = boost::thread(userFrameCallback, vimba_frame_ptr);
00324 thread_callback_.join();
00325
00326
00327 vimba_camera_ptr_->QueueFrame(vimba_frame_ptr);
00328 updater_.update();
00329 }
00330
00331 double AvtVimbaCamera::getDeviceTemp(void) {
00332 double temp = -1.0;
00333 if (setFeatureValue("DeviceTemperatureSelector", "Main")) {
00334 getFeatureValue("DeviceTemperature", temp);
00335 }
00336 return temp;
00337 }
00338
00339 bool AvtVimbaCamera::resetTimestamp(void) {
00340 return runCommand("GevTimestampControlReset");
00341 }
00342
00343 double AvtVimbaCamera::getTimestamp(void) {
00344 double timestamp = -1.0;
00345 if (runCommand("GevTimestampControlLatch")) {
00346 VmbInt64_t freq, ticks;
00347 getFeatureValue("GevTimestampTickFrequency", freq);
00348 getFeatureValue("GevTimestampValue", ticks);
00349 timestamp = ((double)ticks)/((double)freq);
00350 }
00351 return timestamp;
00352 }
00353
00354
00355 template<typename T>
00356 bool AvtVimbaCamera::getFeatureValue(const std::string& feature_str, T& val) {
00357 VmbErrorType err;
00358 FeaturePtr vimba_feature_ptr;
00359 VmbFeatureDataType data_type;
00360 err = vimba_camera_ptr_->GetFeatureByName(feature_str.c_str(),
00361 vimba_feature_ptr);
00362 if (VmbErrorSuccess == err) {
00363 bool readable;
00364 vimba_feature_ptr->IsReadable(readable);
00365 if (readable) {
00366 vimba_feature_ptr->GetDataType(data_type);
00367 if ( VmbErrorSuccess != err ) {
00368 std::cout << "[Could not get feature Data Type. Error code: "
00369 << err << "]" << std::endl;
00370 } else {
00371 std::string strValue;
00372 switch ( data_type ) {
00373 case VmbFeatureDataBool:
00374 bool bValue;
00375 err = vimba_feature_ptr->GetValue(bValue);
00376 if (VmbErrorSuccess == err) {
00377 val = static_cast<T>(bValue);
00378 }
00379 break;
00380 case VmbFeatureDataFloat:
00381 double fValue;
00382 err = vimba_feature_ptr->GetValue(fValue);
00383 if (VmbErrorSuccess == err) {
00384 val = static_cast<T>(fValue);
00385 }
00386 break;
00387 case VmbFeatureDataInt:
00388 VmbInt64_t nValue;
00389 err = vimba_feature_ptr->GetValue(nValue);
00390 if (VmbErrorSuccess == err) {
00391 val = static_cast<T>(nValue);
00392 }
00393 break;
00394 }
00395 if (VmbErrorSuccess != err) {
00396 ROS_WARN_STREAM("Could not get feature value. Error code: "
00397 << api_.errorCodeToMessage(err));
00398 }
00399 }
00400 } else {
00401 ROS_WARN_STREAM("[" << name_ << "]: Feature "
00402 << feature_str
00403 << " is not readable.");
00404 }
00405 } else {
00406 ROS_WARN_STREAM("[" << name_
00407 << "]: Could not get feature " << feature_str);
00408 }
00409 if (show_debug_prints_)
00410 ROS_INFO_STREAM("Asking for feature "
00411 << feature_str << " with datatype "
00412 << FeatureDataType[data_type]
00413 << " and value " << val);
00414 return (VmbErrorSuccess == err);
00415 }
00416
00417
00418 bool AvtVimbaCamera::getFeatureValue(const std::string& feature_str,
00419 std::string& val) {
00420 VmbErrorType err;
00421 FeaturePtr vimba_feature_ptr;
00422 VmbFeatureDataType data_type;
00423 err = vimba_camera_ptr_->GetFeatureByName(feature_str.c_str(),
00424 vimba_feature_ptr);
00425 if (VmbErrorSuccess == err) {
00426 bool readable;
00427 vimba_feature_ptr->IsReadable(readable);
00428 if (readable) {
00429 vimba_feature_ptr->GetDataType(data_type);
00430 if ( VmbErrorSuccess != err ) {
00431 std::cout << "[Could not get feature Data Type. Error code: "
00432 << err << "]" << std::endl;
00433 } else {
00434 std::string strValue;
00435 switch ( data_type ) {
00436 case VmbFeatureDataEnum:
00437 err = vimba_feature_ptr->GetValue(strValue);
00438 if (VmbErrorSuccess == err) {
00439 val = strValue;
00440 }
00441 break;
00442 case VmbFeatureDataString:
00443 err = vimba_feature_ptr->GetValue(strValue);
00444 if (VmbErrorSuccess == err) {
00445 val = strValue;
00446 }
00447 break;
00448 }
00449 if (VmbErrorSuccess != err) {
00450 ROS_WARN_STREAM("Could not get feature value. Error code: "
00451 << api_.errorCodeToMessage(err));
00452 }
00453 }
00454 } else {
00455 ROS_WARN_STREAM("[" << name_ << "]: Feature "
00456 << feature_str
00457 << " is not readable.");
00458 }
00459 } else {
00460 ROS_WARN_STREAM("[" << name_
00461 << "]: Could not get feature " << feature_str);
00462 }
00463 if(show_debug_prints_) {
00464 ROS_INFO_STREAM("Asking for feature " << feature_str
00465 << " with datatype " << FeatureDataType[data_type]
00466 << " and value " << val);
00467 }
00468 return (VmbErrorSuccess == err);
00469 }
00470
00471
00472 template<typename T>
00473 bool AvtVimbaCamera::setFeatureValue(const std::string& feature_str,
00474 const T& val) {
00475 VmbErrorType err;
00476 FeaturePtr vimba_feature_ptr;
00477 err = vimba_camera_ptr_->GetFeatureByName(feature_str.c_str(),
00478 vimba_feature_ptr);
00479 if (VmbErrorSuccess == err) {
00480 bool writable;
00481 err = vimba_feature_ptr->IsWritable(writable);
00482 if (VmbErrorSuccess == err) {
00483 if (writable) {
00484 if(show_debug_prints_)
00485 ROS_INFO_STREAM("Setting feature " << feature_str << " value " << val);
00486 VmbFeatureDataType data_type;
00487 err = vimba_feature_ptr->GetDataType(data_type);
00488 if (VmbErrorSuccess == err) {
00489 if (data_type == VmbFeatureDataEnum) {
00490 bool available;
00491 err = vimba_feature_ptr->IsValueAvailable(val, available);
00492 if (VmbErrorSuccess == err) {
00493 if (available) {
00494 err = vimba_feature_ptr->SetValue(val);
00495 } else {
00496 ROS_WARN_STREAM("[" << name_
00497 << "]: Feature " << feature_str << " is available now.");
00498 }
00499 } else {
00500 ROS_WARN_STREAM("[" << name_ << "]: Feature "
00501 << feature_str << ": value unavailable\n\tERROR "
00502 << api_.errorCodeToMessage(err));
00503 }
00504 } else {
00505 err = vimba_feature_ptr->SetValue(val);
00506 }
00507 } else {
00508 ROS_WARN_STREAM("[" << name_ << "]: Feature "
00509 << feature_str << ": Bad data type\n\tERROR "
00510 << api_.errorCodeToMessage(err));
00511 }
00512 } else {
00513 ROS_WARN_STREAM("[" << name_ << "]: Feature "
00514 << feature_str
00515 << " is not writable.");
00516 }
00517 } else {
00518 ROS_WARN_STREAM("[" << name_ << "]: Feature "
00519 << feature_str << ": ERROR " << api_.errorCodeToMessage(err));
00520 }
00521 } else {
00522 ROS_WARN_STREAM("[" << name_
00523 << "]: Could not get feature " << feature_str
00524 << "\n Error: " << api_.errorCodeToMessage(err));
00525 }
00526 return (VmbErrorSuccess == err);
00527 }
00528
00529
00530
00531 bool AvtVimbaCamera::runCommand(const std::string& command_str) {
00532 FeaturePtr feature_ptr;
00533 VmbErrorType err = vimba_camera_ptr_->GetFeatureByName(command_str.c_str(), feature_ptr);
00534 if (VmbErrorSuccess == err ) {
00535 err = feature_ptr->RunCommand();
00536 if ( VmbErrorSuccess == err ) {
00537 bool is_command_done = false;
00538 do {
00539 err = feature_ptr->IsCommandDone(is_command_done);
00540 if ( VmbErrorSuccess != err ) {
00541 break;
00542 }
00543 if(show_debug_prints_) {
00544 ROS_INFO_STREAM_THROTTLE(1, "Waiting for command "
00545 << command_str.c_str() << "...");
00546 }
00547 } while ( false == is_command_done );
00548 if(show_debug_prints_)
00549 ROS_INFO_STREAM("Command " << command_str.c_str() << " done!");
00550 return true;
00551 } else {
00552 ROS_WARN_STREAM("[" << name_
00553 << "]: Could not run command " << command_str << ". Error: " << api_.errorCodeToMessage(err));
00554 return false;
00555 }
00556 } else {
00557 ROS_WARN_STREAM("[" << name_
00558 << "]: Could not get feature command " << command_str << ". Error: " << api_.errorCodeToMessage(err));
00559 return false;
00560 }
00561 }
00562
00563 std::string AvtVimbaCamera::interfaceToString(VmbInterfaceType interfaceType) {
00564 switch ( interfaceType ) {
00565 case VmbInterfaceFirewire: return "FireWire";
00566 break;
00567 case VmbInterfaceEthernet: return "GigE";
00568 break;
00569 case VmbInterfaceUsb: return "USB";
00570 break;
00571 default: return "Unknown";
00572 }
00573 }
00574
00575 std::string AvtVimbaCamera::accessModeToString(VmbAccessModeType modeType) {
00576 std::string s;
00577 if (modeType & VmbAccessModeFull)
00578 s = std::string("Read and write access");
00579 else if (modeType & VmbAccessModeRead)
00580 s = std::string("Only read access");
00581 else if (modeType & VmbAccessModeConfig)
00582 s = std::string("Device configuration access");
00583 else if (modeType & VmbAccessModeLite)
00584 s = std::string("Device read/write access without feature access (only addresses)");
00585 else if (modeType & VmbAccessModeNone)
00586 s = std::string("No access");
00587 return s;
00588 }
00589
00590 int AvtVimbaCamera::getTriggerModeInt(std::string mode_str) {
00591 int mode;
00592 if (mode_str == TriggerMode[Freerun]) {
00593 mode = Freerun;
00594 } else if (mode_str == TriggerMode[FixedRate]) {
00595 mode = FixedRate;
00596 } else if (mode_str == TriggerMode[Software]) {
00597 mode = Software;
00598 } else if (mode_str == TriggerMode[SyncIn1]) {
00599 mode = SyncIn1;
00600 } else if (mode_str == TriggerMode[SyncIn2]) {
00601 mode = SyncIn2;
00602 } else if (mode_str == TriggerMode[SyncIn3]) {
00603 mode = SyncIn3;
00604 } else if (mode_str == TriggerMode[SyncIn4]) {
00605 mode = SyncIn4;
00606 }
00607 return mode;
00608 }
00609
00610 void AvtVimbaCamera::printAllCameraFeatures(CameraPtr camera) {
00611 VmbErrorType err;
00612 FeaturePtrVector features;
00613
00614
00615 std::string strName;
00616 std::string strDisplayName;
00617 std::string strTooltip;
00618 std::string strDescription;
00619 std::string strCategory;
00620 std::string strSFNCNamespace;
00621 std::string strUnit;
00622 VmbFeatureDataType eType;
00623
00624
00625 VmbInt64_t nValue;
00626 std::string strValue;
00627
00628 std::stringstream strError;
00629
00630
00631 err = camera->GetFeatures(features);
00632 if ( VmbErrorSuccess == err ) {
00633
00634
00635 for ( FeaturePtrVector::const_iterator iter = features.begin();
00636 features.end() != iter;
00637 ++iter ) {
00638 err = (*iter)->GetName(strName);
00639 if (VmbErrorSuccess != err) {
00640 strError << "[Could not get feature Name. Error code: " << err << "]";
00641 strName.assign(strError.str());
00642 }
00643
00644 err = (*iter)->GetDisplayName(strDisplayName);
00645 if (VmbErrorSuccess != err) {
00646 strError << "[Could not get feature Display Name. Error code: "
00647 << err << "]";
00648 strDisplayName.assign(strError.str());
00649 }
00650
00651 err = (*iter)->GetToolTip(strTooltip);
00652 if (VmbErrorSuccess != err) {
00653 strError << "[Could not get feature Tooltip. Error code: "
00654 << err << "]";
00655 strTooltip.assign(strError.str());
00656 }
00657
00658 err = (*iter)->GetDescription(strDescription);
00659 if (VmbErrorSuccess != err) {
00660 strError << "[Could not get feature Description. Error code: "
00661 << err << "]";
00662 strDescription.assign(strError.str());
00663 }
00664
00665 err = (*iter)->GetCategory(strCategory);
00666 if (VmbErrorSuccess != err) {
00667 strError << "[Could not get feature Category. Error code: "
00668 << err << "]";
00669 strCategory.assign(strError.str());
00670 }
00671
00672 err = (*iter)->GetSFNCNamespace(strSFNCNamespace);
00673 if (VmbErrorSuccess != err) {
00674 strError << "[Could not get feature SNFC Namespace. Error code: "
00675 << err << "]";
00676 strSFNCNamespace.assign(strError.str());
00677 }
00678
00679 err = (*iter)->GetUnit(strUnit);
00680 if (VmbErrorSuccess != err) {
00681 strError << "[Could not get feature Unit. Error code: " << err << "]";
00682 strUnit.assign(strError.str());
00683 }
00684
00685 std::cout << "/// Feature Name: " << strName << std::endl;
00686 std::cout << "/// Display Name: " << strDisplayName << std::endl;
00687 std::cout << "/// Tooltip: " << strTooltip << std::endl;
00688 std::cout << "/// Description: " << strDescription << std::endl;
00689 std::cout << "/// SNFC Namespace: " << strSFNCNamespace << std::endl;
00690 std::cout << "/// Unit: " << strUnit << std::endl;
00691 std::cout << "/// Value: ";
00692
00693 err = (*iter)->GetDataType(eType);
00694 if ( VmbErrorSuccess != err ) {
00695 std::cout << "[Could not get feature Data Type. Error code: "
00696 << err << "]" << std::endl;
00697 } else {
00698 switch ( eType ) {
00699 case VmbFeatureDataBool:
00700 bool bValue;
00701 err = (*iter)->GetValue(bValue);
00702 if (VmbErrorSuccess == err) {
00703 std::cout << bValue << " bool" << std::endl;
00704 }
00705 break;
00706 case VmbFeatureDataEnum:
00707 err = (*iter)->GetValue(strValue);
00708 if (VmbErrorSuccess == err) {
00709 std::cout << strValue << " str Enum" << std::endl;
00710 }
00711 break;
00712 case VmbFeatureDataFloat:
00713 double fValue;
00714 err = (*iter)->GetValue(fValue);
00715 {
00716 std::cout << fValue << " float" << std::endl;
00717 }
00718 break;
00719 case VmbFeatureDataInt:
00720 err = (*iter)->GetValue(nValue);
00721 {
00722 std::cout << nValue << " int" << std::endl;
00723 }
00724 break;
00725 case VmbFeatureDataString:
00726 err = (*iter)->GetValue(strValue);
00727 {
00728 std::cout << strValue << " str" << std::endl;
00729 }
00730 break;
00731 case VmbFeatureDataCommand:
00732 default:
00733 std::cout << "[None]" << std::endl;
00734 break;
00735 }
00736 if (VmbErrorSuccess != err) {
00737 std::cout << "Could not get feature value. Error code: "
00738 << err << std::endl;
00739 }
00740 }
00741
00742 std::cout << std::endl;
00743 }
00744 } else {
00745 std::cout << "Could not get features. Error code: " << err << std::endl;
00746 }
00747 }
00748
00750 void AvtVimbaCamera::updateAcquisitionConfig(Config& config) {
00751 bool changed = false;
00752 if (config.acquisition_mode != config_.acquisition_mode || on_init_) {
00753 changed = true;
00754 setFeatureValue("AcquisitionMode", config.acquisition_mode.c_str());
00755 }
00756 if (config.acquisition_rate != config_.acquisition_rate || on_init_) {
00757 changed = true;
00758 double acquisition_frame_rate_limit;
00759 getFeatureValue("AcquisitionFrameRateLimit", acquisition_frame_rate_limit);
00760 if (acquisition_frame_rate_limit < config.acquisition_rate) {
00761 double rate = (double)floor(acquisition_frame_rate_limit);
00762 ROS_WARN_STREAM("Max frame rate allowed: " << acquisition_frame_rate_limit
00763 << ". Setting " << rate << "...");
00764 config.acquisition_rate = rate;
00765 }
00766 setFeatureValue("AcquisitionFrameRateAbs",
00767 static_cast<float>(config.acquisition_rate));
00768 }
00769 if (config.trigger_mode != config_.trigger_mode || on_init_) {
00770 changed = true;
00771 setFeatureValue("TriggerMode", config.trigger_mode.c_str());
00772 }
00773 if (config.trigger_selector != config_.trigger_selector || on_init_) {
00774 changed = true;
00775 setFeatureValue("TriggerSelector", config.trigger_selector.c_str());
00776 }
00777 if (config.trigger_source != config_.trigger_source || on_init_) {
00778 changed = true;
00779 setFeatureValue("TriggerSource", config.trigger_source.c_str());
00780 }
00781 if (config.trigger_activation != config_.trigger_activation || on_init_) {
00782 changed = true;
00783 setFeatureValue("TriggerActivation", config.trigger_activation.c_str());
00784 }
00785 if (config.trigger_delay != config_.trigger_delay || on_init_) {
00786 changed = true;
00787 setFeatureValue("TriggerDelayAbs", config.trigger_delay);
00788 }
00789 if(changed && show_debug_prints_){
00790 ROS_INFO_STREAM("New Acquisition and Trigger config (" << config.frame_id << ") : "
00791 << "\n\tAcquisitionMode : " << config.acquisition_mode << " was " << config_.acquisition_mode
00792 << "\n\tAcquisitionFrameRateAbs : " << config.acquisition_rate << " was " << config_.acquisition_rate
00793 << "\n\tTriggerMode : " << config.trigger_mode << " was " << config_.trigger_mode
00794 << "\n\tTriggerSource : " << config.trigger_source << " was " << config_.trigger_source
00795 << "\n\tTriggerSelector : " << config.trigger_selector << " was " << config_.trigger_selector
00796 << "\n\tTriggerActivation : " << config.trigger_activation << " was " << config_.trigger_activation
00797 << "\n\tTriggerDelayAbs : " << config.trigger_delay << " was " << config_.trigger_delay);
00798 }
00799 }
00800
00802 void AvtVimbaCamera::updateExposureConfig(Config& config) {
00803 bool changed = false;
00804 if (config.exposure != config_.exposure || on_init_) {
00805 changed = true;
00806 setFeatureValue("ExposureTimeAbs", static_cast<float>(config.exposure));
00807 }
00808 if (config.exposure_auto != config_.exposure_auto || on_init_) {
00809 changed = true;
00810 setFeatureValue("ExposureAuto", config.exposure_auto.c_str());
00811 }
00812 if (config.exposure_auto_alg != config_.exposure_auto_alg || on_init_) {
00813 changed = true;
00814 setFeatureValue("ExposureAutoAlg", config.exposure_auto_alg.c_str());
00815 }
00816 if (config.exposure_auto_tol != config_.exposure_auto_tol || on_init_) {
00817 changed = true;
00818 setFeatureValue("ExposureAutoAdjustTol",
00819 static_cast<VmbInt64_t>(config.exposure_auto_tol));
00820 }
00821 if (config.exposure_auto_max != config_.exposure_auto_max || on_init_) {
00822 changed = true;
00823 setFeatureValue("ExposureAutoMax",
00824 static_cast<VmbInt64_t>(config.exposure_auto_max));
00825 }
00826 if (config.exposure_auto_min != config_.exposure_auto_min || on_init_) {
00827 changed = true;
00828 setFeatureValue("ExposureAutoMin",
00829 static_cast<VmbInt64_t>(config.exposure_auto_min));
00830 }
00831 if (config.exposure_auto_outliers != config_.exposure_auto_outliers || on_init_) {
00832 changed = true;
00833 setFeatureValue("ExposureAutoOutliers",
00834 static_cast<VmbInt64_t>(config.exposure_auto_outliers));
00835 }
00836 if (config.exposure_auto_rate != config_.exposure_auto_rate || on_init_) {
00837 changed = true;
00838 setFeatureValue("ExposureAutoRate",
00839 static_cast<VmbInt64_t>(config.exposure_auto_rate));
00840 }
00841 if (config.exposure_auto_target != config_.exposure_auto_target || on_init_) {
00842 changed = true;
00843 setFeatureValue("ExposureAutoTarget",
00844 static_cast<VmbInt64_t>(config.exposure_auto_target));
00845 }
00846 if(changed && show_debug_prints_){
00847 ROS_INFO_STREAM("New Exposure config (" << config.frame_id << ") : "
00848 << "\n\tExposureTimeAbs : " << config.exposure << " was " << config_.exposure
00849 << "\n\tExposureAuto : " << config.exposure_auto << " was " << config_.exposure_auto
00850 << "\n\tExposureAutoAdjustTol : " << config.exposure_auto_tol << " was " << config_.exposure_auto_tol
00851 << "\n\tExposureAutoMax : " << config.exposure_auto_max << " was " << config_.exposure_auto_max
00852 << "\n\tExposureAutoMin : " << config.exposure_auto_min << " was " << config_.exposure_auto_min
00853 << "\n\tExposureAutoOutliers : " << config.exposure_auto_outliers << " was " << config_.exposure_auto_outliers
00854 << "\n\tExposureAutoRate : " << config.exposure_auto_rate << " was " << config_.exposure_auto_rate
00855 << "\n\tExposureAutoTarget : " << config.exposure_auto_target << " was " << config_.exposure_auto_target);
00856 }
00857 }
00858
00860 void AvtVimbaCamera::updateGainConfig(Config& config) {
00861 bool changed = false;
00862 if (config.gain != config_.gain || on_init_) {
00863 changed = true;
00864 setFeatureValue("Gain", static_cast<float>(config.gain));
00865 }
00866 if (config.gain_auto != config_.gain_auto || on_init_) {
00867 changed = true;
00868 setFeatureValue("GainAuto", config.gain_auto.c_str());
00869 }
00870 if (config.gain_auto_tol != config_.gain_auto_tol || on_init_) {
00871 changed = true;
00872 setFeatureValue("GainAutoAdjustTol",
00873 static_cast<VmbInt64_t>(config.gain_auto_tol));
00874 }
00875 if (config.gain_auto_max != config_.gain_auto_max || on_init_) {
00876 changed = true;
00877 setFeatureValue("GainAutoMax", static_cast<float>(config.gain_auto_max));
00878 }
00879 if (config.gain_auto_min != config_.gain_auto_min || on_init_) {
00880 changed = true;
00881 setFeatureValue("GainAutoMin",
00882 static_cast<VmbInt64_t>(config.gain_auto_min));
00883 }
00884 if (config.gain_auto_outliers != config_.gain_auto_outliers || on_init_) {
00885 changed = true;
00886 setFeatureValue("GainAutoMin",
00887 static_cast<VmbInt64_t>(config.gain_auto_outliers));
00888 }
00889 if (config.gain_auto_rate != config_.gain_auto_rate || on_init_) {
00890 changed = true;
00891 setFeatureValue("GainAutoOutliers",
00892 static_cast<VmbInt64_t>(config.gain_auto_rate));
00893 }
00894 if (config.gain_auto_target != config_.gain_auto_target || on_init_) {
00895 changed = true;
00896 setFeatureValue("GainAutoRate", static_cast<VmbInt64_t>(config.gain_auto_target));
00897 }
00898 if(changed && show_debug_prints_){
00899 ROS_INFO_STREAM("New Gain config (" << config.frame_id << ") : "
00900 << "\n\tGain : " << config.gain << " was " << config_.gain
00901 << "\n\tGainAuto : " << config.gain_auto << " was " << config_.gain_auto
00902 << "\n\tGainAutoAdjustTol : " << config.gain_auto_tol << " was " << config_.gain_auto_tol
00903 << "\n\tGainAutoMax : " << config.gain_auto_max << " was " << config_.gain_auto_max
00904 << "\n\tGainAutoMin : " << config.gain_auto_min << " was " << config_.gain_auto_min
00905 << "\n\tGainAutoOutliers : " << config.gain_auto_outliers << " was " << config_.gain_auto_outliers
00906 << "\n\tGainAutoRate : " << config.gain_auto_rate << " was " << config_.gain_auto_rate
00907 << "\n\tGainAutoTarget : " << config.gain_auto_target << " was " << config_.gain_auto_target);
00908 }
00909 }
00910
00912 void AvtVimbaCamera::updateWhiteBalanceConfig(Config& config){
00913 bool changed = false;
00914 if (config.balance_ratio_abs != config_.balance_ratio_abs || on_init_) {
00915 changed = true;
00916 setFeatureValue("BalanceRatioAbs", static_cast<float>(config.balance_ratio_abs));
00917 }
00918 if (config.balance_ratio_selector != config_.balance_ratio_selector || on_init_) {
00919 changed = true;
00920 setFeatureValue("BalanceRatioSelector", config.balance_ratio_selector.c_str());
00921 }
00922 if (config.whitebalance_auto != config_.whitebalance_auto || on_init_) {
00923 changed = true;
00924 setFeatureValue("BalanceWhiteAuto", config.whitebalance_auto.c_str());
00925 }
00926 if (config.whitebalance_auto_tol != config_.whitebalance_auto_tol || on_init_) {
00927 changed = true;
00928 setFeatureValue("BalanceWhiteAutoAdjustTol", static_cast<VmbInt64_t>(config.whitebalance_auto_tol));
00929 }
00930 if (config.whitebalance_auto_rate != config_.whitebalance_auto_rate || on_init_) {
00931 changed = true;
00932 setFeatureValue("BalanceWhiteAutoRate", static_cast<VmbInt64_t>(config.whitebalance_auto_rate));
00933 }
00934 if(changed && show_debug_prints_){
00935 ROS_INFO_STREAM("New White Balance config (" << config.frame_id << ") : "
00936 << "\n\tBalanceRatioAbs : " << config.balance_ratio_abs << " was " << config_.balance_ratio_abs
00937 << "\n\tBalanceRatioSelector : " << config.balance_ratio_selector << " was " << config_.balance_ratio_selector
00938 << "\n\tBalanceWhiteAuto : " << config.whitebalance_auto << " was " << config_.whitebalance_auto
00939 << "\n\tBalanceWhiteAutoAdjustTol : " << config.whitebalance_auto_tol << " was " << config_.whitebalance_auto_tol
00940 << "\n\tBalanceWhiteAutoRate : " << config.whitebalance_auto_rate << " was " << config_.whitebalance_auto_rate);
00941 }
00942 }
00943
00945 void AvtVimbaCamera::updatePtpModeConfig(Config& config) {
00946 bool changed = false;
00947 if (config.ptp_mode != config_.ptp_mode || on_init_) {
00948 changed = true;
00949 setFeatureValue("PtpMode", config.ptp_mode.c_str());
00950 }
00951
00952 if(changed && show_debug_prints_){
00953 ROS_INFO_STREAM("New PTP config (" << config.frame_id << ") : "
00954 << "\n\tPtpMode : " << config.ptp_mode << " was " << config_.ptp_mode);
00955 }
00956 }
00957
00959 void AvtVimbaCamera::updateImageModeConfig(Config& config) {
00960 bool changed = false;
00961 if (config.decimation_x != config_.decimation_x || on_init_) {
00962 changed = true;
00963 setFeatureValue("DecimationHorizontal",
00964 static_cast<VmbInt64_t>(config.decimation_x));
00965 }
00966 if (config.decimation_y != config_.decimation_y || on_init_) {
00967 changed = true;
00968 setFeatureValue("DecimationVertical", static_cast<VmbInt64_t>(config.decimation_y));
00969 }
00970 if (config.binning_x != config_.binning_x || on_init_) {
00971 changed = true;
00972 setFeatureValue("BinningHorizontal", static_cast<VmbInt64_t>(config.binning_x));
00973 }
00974 if (config.binning_y != config_.binning_y || on_init_) {
00975 changed = true;
00976 setFeatureValue("BinningVertical", static_cast<VmbInt64_t>(config.binning_y));
00977 }
00978 if(changed && show_debug_prints_){
00979 ROS_INFO_STREAM("New Image Mode config (" << config.frame_id << ") : "
00980 << "\n\tDecimationHorizontal : " << config.decimation_x << " was " << config_.decimation_x
00981 << "\n\tDecimationVertical : " << config.decimation_y << " was " << config_.decimation_y
00982 << "\n\tBinningHorizontal : " << config.binning_x << " was " << config_.binning_x
00983 << "\n\tBinningVertical : " << config.binning_y << " was " << config_.binning_y);
00984 }
00985 }
00986
00988 void AvtVimbaCamera::updateROIConfig(Config& config) {
00989 bool changed = false;
00990
00991
00992
00993
00994 int max_width, max_height;
00995 getFeatureValue("WidthMax", max_width);
00996 getFeatureValue("HeightMax", max_height);
00997
00998 int binning_or_decimation_x = std::max(config.binning_x, config.decimation_x);
00999 int binning_or_decimation_y = std::max(config.binning_y, config.decimation_y);
01000
01001 max_width *= binning_or_decimation_x;
01002 max_height *= binning_or_decimation_y;
01003
01004 config.width = std::min(config.width, (int)max_width);
01005 config.height = std::min(config.height, (int)max_height);
01006 config.roi_offset_x = std::min(config.roi_offset_x, config.width - 1);
01007 config.roi_offset_y = std::min(config.roi_offset_y, config.height - 1);
01008 config.roi_width = std::min(config.roi_width, config.width - config.roi_offset_x);
01009 config.roi_height = std::min(config.roi_height, config.height - config.roi_offset_y);
01010
01011 int width = config.roi_width ? config.roi_width : max_width - config.roi_offset_x;
01012 int height = config.roi_height ? config.roi_height : max_height - config.roi_offset_y;
01013
01014
01016 int offset_x = config.roi_offset_x;
01017 int offset_y = config.roi_offset_y;
01018 unsigned int right_x = (offset_x + width + binning_or_decimation_x - 1);
01019 unsigned int bottom_y = (offset_y + height + binning_or_decimation_y - 1);
01020
01021 right_x = std::min(right_x, (unsigned)(config.width));
01022 bottom_y = std::min(bottom_y, (unsigned)(config.height));
01023 width = right_x - offset_x;
01024 height = bottom_y - offset_y;
01025
01026 config.width = width/binning_or_decimation_x;
01027 config.height = height/binning_or_decimation_y;
01028 config.roi_offset_x = offset_x/binning_or_decimation_x;
01029 config.roi_offset_y = offset_y/binning_or_decimation_y;
01030
01031 if (config.roi_offset_x != config_.roi_offset_x || on_init_) {
01032 changed = true;
01033 setFeatureValue("OffsetX", static_cast<VmbInt64_t>(config.roi_offset_x));
01034 }
01035 if (config.roi_offset_y != config_.roi_offset_y || on_init_) {
01036 changed = true;
01037 setFeatureValue("OffsetY", static_cast<VmbInt64_t>(config.roi_offset_y));
01038 }
01039 if (config.width != config_.width || on_init_) {
01040 changed = true;
01041 setFeatureValue("Width", static_cast<VmbInt64_t>(config.width));
01042 }
01043 if (config.height != config_.height || on_init_) {
01044 changed = true;
01045 setFeatureValue("Height", static_cast<VmbInt64_t>(config.height));
01046 }
01047
01048 if(changed && show_debug_prints_){
01049 ROS_INFO_STREAM("New ROI config (" << config.frame_id << ") : "
01050 << "\n\tOffsetX : " << config.roi_offset_x << " was " << config_.roi_offset_x
01051 << "\n\tOffsetY : " << config.roi_offset_y << " was " << config_.roi_offset_y
01052 << "\n\tWidth : " << config.width << " was " << config_.width
01053 << "\n\tHeight : " << config.height << " was " << config_.height);
01054 }
01055 }
01056
01058 void AvtVimbaCamera::updateBandwidthConfig(Config& config) {
01059 bool changed = false;
01060 if (config.stream_bytes_per_second
01061 != config_.stream_bytes_per_second || on_init_) {
01062 changed = true;
01063 setFeatureValue("StreamBytesPerSecond",
01064 static_cast<VmbInt64_t>(config.stream_bytes_per_second));
01065 }
01066 if(changed && show_debug_prints_){
01067 ROS_INFO_STREAM("New Bandwidth config (" << config.frame_id << ") : "
01068 << "\n\tStreamBytesPerSecond : " << config.stream_bytes_per_second << " was " << config_.stream_bytes_per_second);
01069 }
01070 }
01071
01073 void AvtVimbaCamera::updatePixelFormatConfig(Config& config) {
01074 bool changed = false;
01075 if (config.pixel_format != config_.pixel_format || on_init_) {
01076 changed = true;
01077 setFeatureValue("PixelFormat", config.pixel_format.c_str());
01078 }
01079 if(changed && show_debug_prints_){
01080 ROS_INFO_STREAM("New PixelFormat config (" << config.frame_id << ") : "
01081 << "\n\tPixelFormat : " << config.pixel_format << " was " << config_.pixel_format);
01082 }
01083 }
01084
01086 void AvtVimbaCamera::updateGPIOConfig(Config& config) {
01087 bool changed = false;
01088 if (config.sync_in_selector
01089 != config_.sync_in_selector || on_init_) {
01090 changed = true;
01091 setFeatureValue("SyncInSelector", config.sync_in_selector.c_str());
01092 }
01093 if (config.sync_out_polarity
01094 != config_.sync_out_polarity || on_init_) {
01095 changed = true;
01096 setFeatureValue("SyncOutPolarity", config.sync_out_polarity.c_str());
01097 }
01098 if (config.sync_out_selector
01099 != config_.sync_out_selector || on_init_) {
01100 changed = true;
01101 setFeatureValue("SyncOutSelector", config.sync_out_selector.c_str());
01102 }
01103 if (config.sync_out_source
01104 != config_.sync_out_source || on_init_) {
01105 changed = true;
01106 setFeatureValue("SyncOutSource", config.sync_out_source.c_str());
01107 }
01108 if(changed && show_debug_prints_){
01109 ROS_INFO_STREAM("New GPIO config (" << config.frame_id << ") : "
01110 << "\n\tSyncInSelector : " << config.sync_in_selector << " was " << config_.sync_in_selector
01111 << "\n\tSyncOutPolarity : " << config.sync_out_polarity << " was " << config_.sync_out_polarity
01112 << "\n\tSyncOutSelector : " << config.sync_out_selector << " was " << config_.sync_out_selector
01113 << "\n\tSyncOutSource : " << config.sync_out_source << " was " << config_.sync_out_source);
01114 }
01115 }
01116
01117 void AvtVimbaCamera::getCurrentState(diagnostic_updater::DiagnosticStatusWrapper &stat) {
01118 stat.add("Serial", guid_);
01119 stat.add("Info", diagnostic_msg_);
01120
01121
01122
01123
01124
01125
01126
01127
01128
01129
01130
01131
01132 switch (camera_state_) {
01133 case OPENING:
01134 stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Opening camera");
01135 break;
01136 case IDLE:
01137 stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Camera is idle");
01138 break;
01139 case OK:
01140 stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Camera is streaming");
01141 break;
01142 case CAMERA_NOT_FOUND:
01143 stat.summaryf(diagnostic_msgs::DiagnosticStatus::ERROR, "Cannot find requested camera %s", guid_.c_str());
01144
01145 break;
01146 case FORMAT_ERROR:
01147 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Problem retrieving frame");
01148 break;
01149 case ERROR:
01150 stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Camera has encountered an error");
01151 break;
01152 default:
01153 break;
01154 }
01155 }
01156 }