56 , system_(Spinnaker::System::GetInstance())
57 , camList_(system_->GetCameras())
58 , pCam_(static_cast<int>(NULL))
60 , camera_(static_cast<int>(NULL))
61 , captureRunning_(false)
63 unsigned int num_cameras =
camList_.GetSize();
81 std::lock_guard<std::mutex> scopedLock(
mutex_);
85 ROS_DEBUG(
"SpinnakerCamera::setNewConfiguration: Reconfigure Stop.");
89 camera_->setNewConfiguration(config, level);
90 if (capture_was_running)
95 camera_->setNewConfiguration(config, level);
108 return camera_->getHeightMax();
125 return camera_->readableProperty(property_name);
137 return camera_->readProperty(property_name);
152 const auto serial_string = std::to_string(
serial_);
158 catch (
const Spinnaker::Exception& e)
160 throw std::runtime_error(
"[SpinnakerCamera::connect] Could not find camera with serial number " +
161 serial_string +
". Is that camera plugged in? Error: " + std::string(e.what()));
171 catch (
const Spinnaker::Exception& e)
173 throw std::runtime_error(
"[SpinnakerCamera::connect] Failed to get first connected camera. Error: " +
174 std::string(e.what()));
179 throw std::runtime_error(
"[SpinnakerCamera::connect] Failed to obtain camera reference.");
185 Spinnaker::GenApi::INodeMap& genTLNodeMap =
pCam_->GetTLDeviceNodeMap();
189 Spinnaker::GenApi::CStringPtr serial_ptr =
190 static_cast<Spinnaker::GenApi::CStringPtr
>(genTLNodeMap.GetNode(
"DeviceID"));
191 if (IsAvailable(serial_ptr) && IsReadable(serial_ptr))
193 serial_ = atoi(serial_ptr->GetValue().c_str());
198 throw std::runtime_error(
"[SpinnakerCamera::connect]: Unable to determine serial number.");
202 Spinnaker::GenApi::CEnumerationPtr device_type_ptr =
203 static_cast<Spinnaker::GenApi::CEnumerationPtr
>(genTLNodeMap.GetNode(
"DeviceType"));
205 if (IsAvailable(device_type_ptr) && IsReadable(device_type_ptr))
207 ROS_INFO_STREAM(
"[SpinnakerCamera::connect]: Detected device type: " << device_type_ptr->ToString());
209 if (device_type_ptr->GetCurrentEntry() == device_type_ptr->GetEntryByName(
"U3V"))
211 Spinnaker::GenApi::CEnumerationPtr device_speed_ptr =
212 static_cast<Spinnaker::GenApi::CEnumerationPtr
>(genTLNodeMap.GetNode(
"DeviceCurrentSpeed"));
213 if (IsAvailable(device_speed_ptr) && IsReadable(device_speed_ptr))
215 if (device_speed_ptr->GetCurrentEntry() != device_speed_ptr->GetEntryByName(
"SuperSpeed"))
216 ROS_ERROR_STREAM(
"[SpinnakerCamera::connect]: U3V Device not running at Super-Speed. Check Cables! ");
222 catch (
const Spinnaker::Exception& e)
224 throw std::runtime_error(
"[SpinnakerCamera::connect] Failed to determine device info with error: " +
225 std::string(e.what()));
237 Spinnaker::GenApi::CStringPtr model_name =
node_map_->GetNode(
"DeviceModelName");
238 std::string model_name_str(model_name->ToString());
240 ROS_INFO(
"[SpinnakerCamera::connect]: Camera model name: %s", model_name_str.c_str());
241 if (model_name_str.find(
"Blackfly S") != std::string::npos)
243 else if (model_name_str.find(
"Chameleon3") != std::string::npos)
245 else if (model_name_str.find(
"Grasshopper3") != std::string::npos)
250 ROS_WARN(
"SpinnakerCamera::connect: Could not detect camera model name.");
256 catch (
const Spinnaker::Exception& e)
258 throw std::runtime_error(
"[SpinnakerCamera::connect] Failed to connect to camera. Error: " +
259 std::string(e.what()));
261 catch (
const std::runtime_error& e)
263 throw std::runtime_error(
"[SpinnakerCamera::connect] Failed to configure chunk data. Error: " +
264 std::string(e.what()));
279 std::lock_guard<std::mutex> scopedLock(
mutex_);
287 pCam_ =
static_cast<int>(NULL);
290 Spinnaker::CameraList temp_list =
system_->GetCameras();
293 catch (
const Spinnaker::Exception& e)
295 throw std::runtime_error(
"[SpinnakerCamera::disconnect] Failed to disconnect camera with error: " +
296 std::string(e.what()));
308 pCam_->BeginAcquisition();
312 catch (
const Spinnaker::Exception& e)
314 throw std::runtime_error(
"[SpinnakerCamera::start] Failed to start capture with error: " + std::string(e.what()));
326 pCam_->EndAcquisition();
328 catch (
const Spinnaker::Exception& e)
330 throw std::runtime_error(
"[SpinnakerCamera::stop] Failed to stop capture with error: " + std::string(e.what()));
337 std::lock_guard<std::mutex> scopedLock(
mutex_);
345 Spinnaker::ImagePtr image_ptr =
pCam_->GetNextImage(
timeout_);
352 while (image_ptr->IsIncomplete())
356 <<
" is incomplete. Trying again.");
361 image->header.stamp.sec = image_ptr->GetTimeStamp() * 1e-9;
362 image->header.stamp.nsec = image_ptr->GetTimeStamp();
365 size_t bitsPerPixel = image_ptr->GetBitsPerPixel();
371 Spinnaker::GenApi::CEnumerationPtr color_filter_ptr =
372 static_cast<Spinnaker::GenApi::CEnumerationPtr
>(
node_map_->GetNode(
"PixelColorFilter"));
374 Spinnaker::GenICam::gcstring color_filter_str = color_filter_ptr->ToString();
375 Spinnaker::GenICam::gcstring bayer_rg_str =
"BayerRG";
376 Spinnaker::GenICam::gcstring bayer_gr_str =
"BayerGR";
377 Spinnaker::GenICam::gcstring bayer_gb_str =
"BayerGB";
378 Spinnaker::GenICam::gcstring bayer_bg_str =
"BayerBG";
381 if (color_filter_ptr->GetCurrentEntry() != color_filter_ptr->GetEntryByName(
"None"))
383 if (bitsPerPixel == 16)
386 if (color_filter_str.compare(bayer_rg_str) == 0)
390 else if (color_filter_str.compare(bayer_gr_str) == 0)
394 else if (color_filter_str.compare(bayer_gb_str) == 0)
398 else if (color_filter_str.compare(bayer_bg_str) == 0)
404 throw std::runtime_error(
"[SpinnakerCamera::grabImage] Bayer format not recognized for 16-bit format.");
410 if (color_filter_str.compare(bayer_rg_str) == 0)
414 else if (color_filter_str.compare(bayer_gr_str) == 0)
418 else if (color_filter_str.compare(bayer_gb_str) == 0)
422 else if (color_filter_str.compare(bayer_bg_str) == 0)
428 throw std::runtime_error(
"[SpinnakerCamera::grabImage] Bayer format not recognized for 8-bit format.");
434 if (bitsPerPixel == 16)
438 else if (bitsPerPixel == 24)
448 int width = image_ptr->GetWidth();
449 int height = image_ptr->GetHeight();
450 int stride = image_ptr->GetStride();
453 fillImage(*image, imageEncoding, height, width, stride, image_ptr->GetData());
454 image->header.frame_id = frame_id;
456 catch (
const Spinnaker::Exception& e)
458 throw std::runtime_error(
"[SpinnakerCamera::grabImage] Failed to retrieve buffer with error: " +
459 std::string(e.what()));
465 "capturing frames first.");
469 throw std::runtime_error(
"[SpinnakerCamera::grabImage] Not connected to the camera.");
475 timeout_ =
static_cast<uint64_t
>(std::round(timeout * 1000));
494 Spinnaker::GenApi::CBooleanPtr ptrChunkModeActive = nodeMap.GetNode(
"ChunkModeActive");
495 if (!Spinnaker::GenApi::IsAvailable(ptrChunkModeActive) || !Spinnaker::GenApi::IsWritable(ptrChunkModeActive))
497 throw std::runtime_error(
"Unable to activate chunk mode. Aborting...");
499 ptrChunkModeActive->SetValue(
true);
515 Spinnaker::GenApi::NodeList_t entries;
517 Spinnaker::GenApi::CEnumerationPtr ptrChunkSelector = nodeMap.GetNode(
"ChunkSelector");
518 if (!Spinnaker::GenApi::IsAvailable(ptrChunkSelector) || !Spinnaker::GenApi::IsReadable(ptrChunkSelector))
520 throw std::runtime_error(
"Unable to retrieve chunk selector. Aborting...");
523 ptrChunkSelector->GetEntries(entries);
527 for (
unsigned int i = 0; i < entries.size(); i++)
530 Spinnaker::GenApi::CEnumEntryPtr ptrChunkSelectorEntry = entries.at(i);
532 if (!Spinnaker::GenApi::IsAvailable(ptrChunkSelectorEntry) ||
533 !Spinnaker::GenApi::IsReadable(ptrChunkSelectorEntry))
537 ptrChunkSelector->SetIntValue(ptrChunkSelectorEntry->GetValue());
541 Spinnaker::GenApi::CBooleanPtr ptrChunkEnable = nodeMap.GetNode(
"ChunkEnable");
543 if (!Spinnaker::GenApi::IsAvailable(ptrChunkEnable))
547 else if (ptrChunkEnable->GetValue())
551 else if (Spinnaker::GenApi::IsWritable(ptrChunkEnable))
553 ptrChunkEnable->SetValue(
true);
562 catch (
const Spinnaker::Exception& e)
564 throw std::runtime_error(e.what());