Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

only access camera with correct serial #202

Merged
merged 1 commit into from
Jul 26, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 0 additions & 10 deletions spinnaker_camera_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -65,16 +65,6 @@ message(STATUS "libSpinnaker include location: ${SPINNAKER_INCLUDE_DIRS}")

find_package(SPINNAKER REQUIRED)

# special case the older Spinnaker API
if(DEFINED ENV{ROS_DISTRO})
if($ENV{ROS_DISTRO} STREQUAL "foxy" OR
$ENV{ROS_DISTRO} STREQUAL "galactic")
add_definitions(-DUSE_OLD_SPINNAKER_API)
endif()
else()
message(FATAL_ERROR "ROS_DISTRO environment variable is not set!")
endif()

include_directories(SYSTEM
${SPINNAKER_INCLUDE_DIRS})

Expand Down
90 changes: 35 additions & 55 deletions spinnaker_camera_driver/src/spinnaker_wrapper_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,58 +105,10 @@ SpinnakerWrapperImpl::SpinnakerWrapperImpl()

void SpinnakerWrapperImpl::refreshCameraList()
{
#ifdef USE_OLD_SPINNAKER_API
cameraList_ = system_->GetCameras();
for (size_t cam_idx = 0; cam_idx < cameraList_.GetSize(); cam_idx++) {
const auto cam = cameraList_[cam_idx];
}
#else
cameraList_.Clear();

Spinnaker::InterfaceList interfaceList = system_->GetInterfaces();

for (size_t i = 0; i < interfaceList.GetSize(); i++) {
Spinnaker::InterfacePtr iface = interfaceList.GetByIndex(i);

Spinnaker::GenApi::INodeMap & nodeMapInterface = iface->GetTLNodeMap();

Spinnaker::GenApi::CEnumerationPtr ptrInterfaceType = nodeMapInterface.GetNode("InterfaceType");

if (IsAvailable(ptrInterfaceType) && IsReadable(ptrInterfaceType)) {
Spinnaker::GenApi::CStringPtr ptrInterfaceDisplayName =
nodeMapInterface.GetNode("InterfaceDisplayName");

if (IsAvailable(ptrInterfaceDisplayName) && IsReadable(ptrInterfaceDisplayName)) {
Spinnaker::GenICam::gcstring interfaceDisplayName = ptrInterfaceDisplayName->GetValue();

Spinnaker::CameraList camList = iface->GetCameras();

for (size_t cam_idx = 0; cam_idx < camList.GetSize(); cam_idx++) {
// try open the cameras in a specific interface
Spinnaker::CameraPtr ptrCam = camList.GetByIndex(cam_idx);
try {
ptrCam->Init();
ptrCam->DeInit();
} catch (Spinnaker::Exception & e) {
// erro while open the cameras in this interface
continue;
} // end try-catch ptrCam

// successfully open the camera in the interface
cameraList_.Add(ptrCam);

LOG_INFO_FMT(
"Found camera [serial: %s] from: [%s]", get_serial(ptrCam).c_str(),
interfaceDisplayName.c_str());
} // end for camList
} else {
LOG_ERROR("Unknown Interface (Display name not readable)");
}
}
}

interfaceList.Clear();
#endif
}

SpinnakerWrapperImpl::~SpinnakerWrapperImpl()
Expand Down Expand Up @@ -425,13 +377,41 @@ bool SpinnakerWrapperImpl::initCamera(const std::string & serialNumber)
if (camera_) {
return false;
}
for (size_t cam_idx = 0; cam_idx < cameraList_.GetSize(); cam_idx++) {
auto cam = cameraList_.GetByIndex(cam_idx);
const std::string sn = get_serial(cam);
if (sn == serialNumber) {
camera_ = cam;
camera_->Init();
break;
const auto interfaceList = system_->GetInterfaces();

for (size_t i = 0; i < interfaceList.GetSize(); i++) {
const auto iface = interfaceList.GetByIndex(i);
const auto & nodeMapInterface = iface->GetTLNodeMap();
const auto ptrInterfaceType = nodeMapInterface.GetNode("InterfaceType");

if (IsAvailable(ptrInterfaceType) && IsReadable(ptrInterfaceType)) {
const Spinnaker::GenApi::CStringPtr ptrInterfaceDisplayName =
nodeMapInterface.GetNode("InterfaceDisplayName");

if (IsAvailable(ptrInterfaceDisplayName) && IsReadable(ptrInterfaceDisplayName)) {
const auto interfaceDisplayName = ptrInterfaceDisplayName->GetValue();
const auto camList = iface->GetCameras();
for (size_t cam_idx = 0; cam_idx < camList.GetSize(); cam_idx++) {
// try open the cameras in a specific interface
Spinnaker::CameraPtr ptrCam = camList.GetByIndex(cam_idx);
const auto serial = get_serial(ptrCam);
if (serial == serialNumber) {
try {
ptrCam->Init();
LOG_INFO_FMT(
"Initialized camera [serial: %s] from: [%s]", serialNumber.c_str(),
interfaceDisplayName.c_str());
camera_ = ptrCam;
return (true);
} catch (Spinnaker::Exception & e) {
// error while open the cameras in this interface
ptrCam->DeInit();
}
}
}
} else {
LOG_ERROR("Unknown Interface (Display name not readable)");
}
}
}
return (camera_ != 0);
Expand Down
Loading