SpinnakerCamera.cpp
Go to the documentation of this file.
1 /*
2 This code was developed by the National Robotics Engineering Center (NREC), part of the Robotics Institute at Carnegie
3 Mellon University.
4 Its development was funded by DARPA under the LS3 program and submitted for public release on June 7th, 2012.
5 Release was granted on August, 21st 2012 with Distribution Statement "A" (Approved for Public Release, Distribution
6 Unlimited).
7 
8 This software is released under a BSD license:
9 
10 Copyright (c) 2012, Carnegie Mellon University. All rights reserved.
11 Copyright (c) 2018, Clearpath Robotics, Inc., All rights reserved.
12 
13 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
14 following conditions are met:
15 
16 Redistributions of source code must retain the above copyright notice, this list of conditions and the following
17 disclaimer.
18 Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following
19 disclaimer in the documentation and/or other materials provided with the distribution.
20 Neither the name of the Carnegie Mellon University nor the names of its contributors may be used to endorse or promote
21 products derived from this software without specific prior written permission.
22 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
23 INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
25 SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
27 WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
28 THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29 */
30 
31 /*-*-C++-*-*/
44 
45 #include <iostream>
46 #include <sstream>
47 #include <typeinfo>
48 #include <string>
49 
50 #include <ros/ros.h>
51 
53 {
55  : serial_(0)
56  , system_(Spinnaker::System::GetInstance())
57  , camList_(system_->GetCameras())
58  , pCam_(static_cast<int>(NULL)) // Hack to suppress compiler warning. Spinnaker has only one contructor which takes
59  // an int
60  , camera_(static_cast<int>(NULL))
61  , captureRunning_(false)
62 {
63  unsigned int num_cameras = camList_.GetSize();
64  ROS_INFO_STREAM_ONCE("[SpinnakerCamera]: Number of cameras detected: " << num_cameras);
65 }
66 
68 {
69  // @note ebretl Destructors of camList_ and system_ handle teardown
70 }
71 
72 void SpinnakerCamera::setNewConfiguration(const spinnaker_camera_driver::SpinnakerConfig& config, const uint32_t& level)
73 {
74  // Check if camera is connected
75  if (!pCam_)
76  {
78  }
79 
80  // Activate mutex to prevent us from grabbing images during this time
81  std::lock_guard<std::mutex> scopedLock(mutex_);
82 
83  if (level >= LEVEL_RECONFIGURE_STOP)
84  {
85  ROS_DEBUG("SpinnakerCamera::setNewConfiguration: Reconfigure Stop.");
86  bool capture_was_running = captureRunning_;
87  start(); // For some reason some params only work after aquisition has be started once.
88  stop();
89  camera_->setNewConfiguration(config, level);
90  if (capture_was_running)
91  start();
92  }
93  else
94  {
95  camera_->setNewConfiguration(config, level);
96  }
97 } // end setNewConfiguration
98 
99 void SpinnakerCamera::setGain(const float& gain)
100 {
101  if (camera_)
102  camera_->setGain(gain);
103 }
104 
106 {
107  if (camera_)
108  return camera_->getHeightMax();
109  else
110  return 0;
111 }
112 
114 {
115  if (camera_)
116  return camera_->getWidthMax();
117  else
118  return 0;
119 }
120 
121 bool SpinnakerCamera::readableProperty(const Spinnaker::GenICam::gcstring property_name)
122 {
123  if (camera_)
124  {
125  return camera_->readableProperty(property_name);
126  }
127  else
128  {
129  return 0;
130  }
131 }
132 
133 Spinnaker::GenApi::CNodePtr SpinnakerCamera::readProperty(const Spinnaker::GenICam::gcstring property_name)
134 {
135  if (camera_)
136  {
137  return camera_->readProperty(property_name);
138  }
139  else
140  {
141  return 0;
142  }
143 }
144 
146 {
147  if (!pCam_)
148  {
149  // If we have a specific camera to connect to (specified by a serial number)
150  if (serial_ != 0)
151  {
152  const auto serial_string = std::to_string(serial_);
153 
154  try
155  {
156  pCam_ = camList_.GetBySerial(serial_string);
157  }
158  catch (const Spinnaker::Exception& e)
159  {
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()));
162  }
163  }
164  else
165  {
166  // Connect to any camera (the first)
167  try
168  {
169  pCam_ = camList_.GetByIndex(0);
170  }
171  catch (const Spinnaker::Exception& e)
172  {
173  throw std::runtime_error("[SpinnakerCamera::connect] Failed to get first connected camera. Error: " +
174  std::string(e.what()));
175  }
176  }
177  if (!pCam_ || !pCam_->IsValid())
178  {
179  throw std::runtime_error("[SpinnakerCamera::connect] Failed to obtain camera reference.");
180  }
181 
182  try
183  {
184  // Check Device type and save serial for reconnecting
185  Spinnaker::GenApi::INodeMap& genTLNodeMap = pCam_->GetTLDeviceNodeMap();
186 
187  if (serial_ == 0)
188  {
189  Spinnaker::GenApi::CStringPtr serial_ptr =
190  static_cast<Spinnaker::GenApi::CStringPtr>(genTLNodeMap.GetNode("DeviceID"));
191  if (IsAvailable(serial_ptr) && IsReadable(serial_ptr))
192  {
193  serial_ = atoi(serial_ptr->GetValue().c_str());
194  ROS_INFO("[SpinnakerCamera::connect]: Using Serial: %i", serial_);
195  }
196  else
197  {
198  throw std::runtime_error("[SpinnakerCamera::connect]: Unable to determine serial number.");
199  }
200  }
201 
202  Spinnaker::GenApi::CEnumerationPtr device_type_ptr =
203  static_cast<Spinnaker::GenApi::CEnumerationPtr>(genTLNodeMap.GetNode("DeviceType"));
204 
205  if (IsAvailable(device_type_ptr) && IsReadable(device_type_ptr))
206  {
207  ROS_INFO_STREAM("[SpinnakerCamera::connect]: Detected device type: " << device_type_ptr->ToString());
208 
209  if (device_type_ptr->GetCurrentEntry() == device_type_ptr->GetEntryByName("U3V"))
210  {
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))
214  {
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! ");
217  }
218  }
219  // TODO(mhosmar): - check if interface is GigE and connect to GigE cam
220  }
221  }
222  catch (const Spinnaker::Exception& e)
223  {
224  throw std::runtime_error("[SpinnakerCamera::connect] Failed to determine device info with error: " +
225  std::string(e.what()));
226  }
227 
228  try
229  {
230  // Initialize Camera
231  pCam_->Init();
232 
233  // Retrieve GenICam nodemap
234  node_map_ = &pCam_->GetNodeMap();
235 
236  // detect model and set camera_ accordingly;
237  Spinnaker::GenApi::CStringPtr model_name = node_map_->GetNode("DeviceModelName");
238  std::string model_name_str(model_name->ToString());
239 
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)
242  camera_.reset(new Camera(node_map_));
243  else if (model_name_str.find("Chameleon3") != std::string::npos)
244  camera_.reset(new Cm3(node_map_));
245  else if (model_name_str.find("Grasshopper3") != std::string::npos)
246  camera_.reset(new Gh3(node_map_));
247  else
248  {
249  camera_.reset(new Camera(node_map_));
250  ROS_WARN("SpinnakerCamera::connect: Could not detect camera model name.");
251  }
252 
253  // Configure chunk data - Enable Metadata
254  // SpinnakerCamera::ConfigureChunkData(*node_map_);
255  }
256  catch (const Spinnaker::Exception& e)
257  {
258  throw std::runtime_error("[SpinnakerCamera::connect] Failed to connect to camera. Error: " +
259  std::string(e.what()));
260  }
261  catch (const std::runtime_error& e)
262  {
263  throw std::runtime_error("[SpinnakerCamera::connect] Failed to configure chunk data. Error: " +
264  std::string(e.what()));
265  }
266  }
267 
268  // TODO(mhosmar): Get camera info to check if camera is running in color or mono mode
269  /*
270  CameraInfo cInfo;
271  error = cam_.GetCameraInfo(&cInfo);
272  SpinnakerCamera::handleError("SpinnakerCamera::connect Failed to get camera info.", error);
273  isColor_ = cInfo.isColorCamera;
274  */
275 }
276 
278 {
279  std::lock_guard<std::mutex> scopedLock(mutex_);
280  captureRunning_ = false;
281  try
282  {
283  // Check if camera is connected
284  if (pCam_)
285  {
286  pCam_->DeInit();
287  pCam_ = static_cast<int>(NULL);
288  camList_.RemoveBySerial(std::to_string(serial_));
289  }
290  Spinnaker::CameraList temp_list = system_->GetCameras();
291  camList_.Append(temp_list);
292  }
293  catch (const Spinnaker::Exception& e)
294  {
295  throw std::runtime_error("[SpinnakerCamera::disconnect] Failed to disconnect camera with error: " +
296  std::string(e.what()));
297  }
298 }
299 
301 {
302  try
303  {
304  // Check if camera is connected
305  if (pCam_ && !captureRunning_)
306  {
307  // Start capturing images
308  pCam_->BeginAcquisition();
309  captureRunning_ = true;
310  }
311  }
312  catch (const Spinnaker::Exception& e)
313  {
314  throw std::runtime_error("[SpinnakerCamera::start] Failed to start capture with error: " + std::string(e.what()));
315  }
316 }
317 
319 {
320  if (pCam_ && captureRunning_)
321  {
322  // Stop capturing images
323  try
324  {
325  captureRunning_ = false;
326  pCam_->EndAcquisition();
327  }
328  catch (const Spinnaker::Exception& e)
329  {
330  throw std::runtime_error("[SpinnakerCamera::stop] Failed to stop capture with error: " + std::string(e.what()));
331  }
332  }
333 }
334 
335 void SpinnakerCamera::grabImage(sensor_msgs::Image* image, const std::string& frame_id)
336 {
337  std::lock_guard<std::mutex> scopedLock(mutex_);
338 
339  // Check if Camera is connected and Running
340  if (pCam_ && captureRunning_)
341  {
342  // Handle "Image Retrieval" Exception
343  try
344  {
345  Spinnaker::ImagePtr image_ptr = pCam_->GetNextImage(timeout_);
346  // std::string format(image_ptr->GetPixelFormatName());
347  // std::printf("\033[100m format: %s \n", format.c_str());
348 
349  // throw std::runtime_error("[SpinnakerCamera::grabImage] Image received from camera "
350  // + std::to_string(serial_)
351  // + " is incomplete.");
352  while (image_ptr->IsIncomplete())
353  {
354  ROS_WARN_STREAM_ONCE("[SpinnakerCamera::grabImage] Image received from camera "
355  << std::to_string(serial_)
356  << " is incomplete. Trying again.");
357  image_ptr = pCam_->GetNextImage(timeout_);
358  }
359 
360  // Set Image Time Stamp
361  image->header.stamp.sec = image_ptr->GetTimeStamp() * 1e-9;
362  image->header.stamp.nsec = image_ptr->GetTimeStamp();
363 
364  // Check the bits per pixel.
365  size_t bitsPerPixel = image_ptr->GetBitsPerPixel();
366 
367  // --------------------------------------------------
368  // Set the image encoding
369  std::string imageEncoding = sensor_msgs::image_encodings::MONO8;
370 
371  Spinnaker::GenApi::CEnumerationPtr color_filter_ptr =
372  static_cast<Spinnaker::GenApi::CEnumerationPtr>(node_map_->GetNode("PixelColorFilter"));
373 
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";
379 
380  // if(isColor_ && bayer_format != NONE)
381  if (color_filter_ptr->GetCurrentEntry() != color_filter_ptr->GetEntryByName("None"))
382  {
383  if (bitsPerPixel == 16)
384  {
385  // 16 Bits per Pixel
386  if (color_filter_str.compare(bayer_rg_str) == 0)
387  {
389  }
390  else if (color_filter_str.compare(bayer_gr_str) == 0)
391  {
393  }
394  else if (color_filter_str.compare(bayer_gb_str) == 0)
395  {
397  }
398  else if (color_filter_str.compare(bayer_bg_str) == 0)
399  {
401  }
402  else
403  {
404  throw std::runtime_error("[SpinnakerCamera::grabImage] Bayer format not recognized for 16-bit format.");
405  }
406  }
407  else
408  {
409  // 8 Bits per Pixel
410  if (color_filter_str.compare(bayer_rg_str) == 0)
411  {
413  }
414  else if (color_filter_str.compare(bayer_gr_str) == 0)
415  {
417  }
418  else if (color_filter_str.compare(bayer_gb_str) == 0)
419  {
421  }
422  else if (color_filter_str.compare(bayer_bg_str) == 0)
423  {
425  }
426  else
427  {
428  throw std::runtime_error("[SpinnakerCamera::grabImage] Bayer format not recognized for 8-bit format.");
429  }
430  }
431  }
432  else // Mono camera or in pixel binned mode.
433  {
434  if (bitsPerPixel == 16)
435  {
436  imageEncoding = sensor_msgs::image_encodings::MONO16;
437  }
438  else if (bitsPerPixel == 24)
439  {
440  imageEncoding = sensor_msgs::image_encodings::RGB8;
441  }
442  else
443  {
444  imageEncoding = sensor_msgs::image_encodings::MONO8;
445  }
446  }
447 
448  int width = image_ptr->GetWidth();
449  int height = image_ptr->GetHeight();
450  int stride = image_ptr->GetStride();
451 
452  // ROS_INFO_ONCE("\033[93m wxh: (%d, %d), stride: %d \n", width, height, stride);
453  fillImage(*image, imageEncoding, height, width, stride, image_ptr->GetData());
454  image->header.frame_id = frame_id;
455  }
456  catch (const Spinnaker::Exception& e)
457  {
458  throw std::runtime_error("[SpinnakerCamera::grabImage] Failed to retrieve buffer with error: " +
459  std::string(e.what()));
460  }
461  }
462  else if (pCam_)
463  {
464  throw CameraNotRunningException("[SpinnakerCamera::grabImage] Camera is currently not running. Please start "
465  "capturing frames first.");
466  }
467  else
468  {
469  throw std::runtime_error("[SpinnakerCamera::grabImage] Not connected to the camera.");
470  }
471 } // end grabImage
472 
473 void SpinnakerCamera::setTimeout(const double& timeout)
474 {
475  timeout_ = static_cast<uint64_t>(std::round(timeout * 1000));
476 }
477 void SpinnakerCamera::setDesiredCamera(const uint32_t& id)
478 {
479  serial_ = id;
480 }
481 
482 void SpinnakerCamera::ConfigureChunkData(const Spinnaker::GenApi::INodeMap& nodeMap)
483 {
484  ROS_INFO_STREAM("*** CONFIGURING CHUNK DATA ***");
485  try
486  {
487  // Activate chunk mode
488  //
489  // *** NOTES ***
490  // Once enabled, chunk data will be available at the end of the payload
491  // of every image captured until it is disabled. Chunk data can also be
492  // retrieved from the nodemap.
493  //
494  Spinnaker::GenApi::CBooleanPtr ptrChunkModeActive = nodeMap.GetNode("ChunkModeActive");
495  if (!Spinnaker::GenApi::IsAvailable(ptrChunkModeActive) || !Spinnaker::GenApi::IsWritable(ptrChunkModeActive))
496  {
497  throw std::runtime_error("Unable to activate chunk mode. Aborting...");
498  }
499  ptrChunkModeActive->SetValue(true);
500  ROS_INFO_STREAM_ONCE("Chunk mode activated...");
501 
502  // Enable all types of chunk data
503  //
504  // *** NOTES ***
505  // Enabling chunk data requires working with nodes: "ChunkSelector"
506  // is an enumeration selector node and "ChunkEnable" is a boolean. It
507  // requires retrieving the selector node (which is of enumeration node
508  // type), selecting the entry of the chunk data to be enabled, retrieving
509  // the corresponding boolean, and setting it to true.
510  //
511  // In this example, all chunk data is enabled, so these steps are
512  // performed in a loop. Once this is complete, chunk mode still needs to
513  // be activated.
514  //
515  Spinnaker::GenApi::NodeList_t entries;
516  // Retrieve the selector node
517  Spinnaker::GenApi::CEnumerationPtr ptrChunkSelector = nodeMap.GetNode("ChunkSelector");
518  if (!Spinnaker::GenApi::IsAvailable(ptrChunkSelector) || !Spinnaker::GenApi::IsReadable(ptrChunkSelector))
519  {
520  throw std::runtime_error("Unable to retrieve chunk selector. Aborting...");
521  }
522  // Retrieve entries
523  ptrChunkSelector->GetEntries(entries);
524 
525  ROS_INFO_STREAM("Enabling entries...");
526 
527  for (unsigned int i = 0; i < entries.size(); i++)
528  {
529  // Select entry to be enabled
530  Spinnaker::GenApi::CEnumEntryPtr ptrChunkSelectorEntry = entries.at(i);
531  // Go to next node if problem occurs
532  if (!Spinnaker::GenApi::IsAvailable(ptrChunkSelectorEntry) ||
533  !Spinnaker::GenApi::IsReadable(ptrChunkSelectorEntry))
534  {
535  continue;
536  }
537  ptrChunkSelector->SetIntValue(ptrChunkSelectorEntry->GetValue());
538 
539  ROS_INFO_STREAM("\t" << ptrChunkSelectorEntry->GetSymbolic() << ": ");
540  // Retrieve corresponding boolean
541  Spinnaker::GenApi::CBooleanPtr ptrChunkEnable = nodeMap.GetNode("ChunkEnable");
542  // Enable the boolean, thus enabling the corresponding chunk data
543  if (!Spinnaker::GenApi::IsAvailable(ptrChunkEnable))
544  {
545  ROS_INFO("Node not available");
546  }
547  else if (ptrChunkEnable->GetValue())
548  {
549  ROS_INFO("Enabled");
550  }
551  else if (Spinnaker::GenApi::IsWritable(ptrChunkEnable))
552  {
553  ptrChunkEnable->SetValue(true);
554  ROS_INFO("Enabled");
555  }
556  else
557  {
558  ROS_INFO("Node not writable");
559  }
560  }
561  }
562  catch (const Spinnaker::Exception& e)
563  {
564  throw std::runtime_error(e.what());
565  }
566 }
567 } // namespace spinnaker_camera_driver
spinnaker_camera_driver::SpinnakerCamera::pCam_
Spinnaker::CameraPtr pCam_
Definition: SpinnakerCamera.h:179
spinnaker_camera_driver::SpinnakerCamera::connect
void connect()
Function that connects to a specified camera.
Definition: SpinnakerCamera.cpp:145
spinnaker_camera_driver::SpinnakerCamera::serial_
uint32_t serial_
A variable to hold the serial number of the desired camera.
Definition: SpinnakerCamera.h:175
sensor_msgs::image_encodings::BAYER_RGGB8
const std::string BAYER_RGGB8
spinnaker_camera_driver::SpinnakerCamera::grabImage
void grabImage(sensor_msgs::Image *image, const std::string &frame_id)
Loads the raw data from the cameras buffer.
Definition: SpinnakerCamera.cpp:335
spinnaker_camera_driver::SpinnakerCamera::getHeightMax
int getHeightMax()
Definition: SpinnakerCamera.cpp:105
spinnaker_camera_driver::SpinnakerCamera::setGain
void setGain(const float &gain)
Definition: SpinnakerCamera.cpp:99
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
spinnaker_camera_driver::SpinnakerCamera::setTimeout
void setTimeout(const double &timeout)
Will set grabImage timeout for the camera.
Definition: SpinnakerCamera.cpp:473
ros.h
sensor_msgs::image_encodings::BAYER_GBRG8
const std::string BAYER_GBRG8
spinnaker_camera_driver::SpinnakerCamera::setNewConfiguration
void setNewConfiguration(const spinnaker_camera_driver::SpinnakerConfig &config, const uint32_t &level)
Function that allows reconfiguration of the camera.
Definition: SpinnakerCamera.cpp:72
spinnaker_camera_driver::SpinnakerCamera::ConfigureChunkData
void ConfigureChunkData(const Spinnaker::GenApi::INodeMap &nodeMap)
Definition: SpinnakerCamera.cpp:482
spinnaker_camera_driver::Gh3
Definition: gh3.h:31
sensor_msgs::image_encodings::RGB8
const std::string RGB8
spinnaker_camera_driver::SpinnakerCamera::captureRunning_
volatile bool captureRunning_
Definition: SpinnakerCamera.h:188
spinnaker_camera_driver::SpinnakerCamera::mutex_
std::mutex mutex_
A mutex to make sure that we don't try to grabImages while reconfiguring or vice versa.
Definition: SpinnakerCamera.h:187
spinnaker_camera_driver::Cm3
Definition: cm3.h:31
ROS_WARN_STREAM_ONCE
#define ROS_WARN_STREAM_ONCE(args)
spinnaker_camera_driver::SpinnakerCamera::start
void start()
Starts the camera loading data into its buffer.
Definition: SpinnakerCamera.cpp:300
spinnaker_camera_driver::SpinnakerCamera::readableProperty
bool readableProperty(const Spinnaker::GenICam::gcstring property_name)
Definition: SpinnakerCamera.cpp:121
spinnaker_camera_driver::SpinnakerCamera::setDesiredCamera
void setDesiredCamera(const uint32_t &id)
Used to set the serial number for the camera you wish to connect to.
Definition: SpinnakerCamera.cpp:477
spinnaker_camera_driver
Definition: camera.h:45
ROS_DEBUG
#define ROS_DEBUG(...)
ROS_INFO_STREAM_ONCE
#define ROS_INFO_STREAM_ONCE(args)
spinnaker_camera_driver::SpinnakerCamera::LEVEL_RECONFIGURE_STOP
static const uint8_t LEVEL_RECONFIGURE_STOP
Definition: SpinnakerCamera.h:95
sensor_msgs::image_encodings::BAYER_BGGR8
const std::string BAYER_BGGR8
spinnaker_camera_driver::SpinnakerCamera::getWidthMax
int getWidthMax()
Definition: SpinnakerCamera.cpp:113
spinnaker_camera_driver::SpinnakerCamera::timeout_
uint64_t timeout_
Definition: SpinnakerCamera.h:202
ROS_WARN
#define ROS_WARN(...)
CameraNotRunningException
Definition: camera_exceptions.h:60
spinnaker_camera_driver::SpinnakerCamera::camList_
Spinnaker::CameraList camList_
Definition: SpinnakerCamera.h:178
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
sensor_msgs::image_encodings::BAYER_BGGR16
const std::string BAYER_BGGR16
spinnaker_camera_driver::Camera
Definition: camera.h:47
sensor_msgs::image_encodings::BAYER_GBRG16
const std::string BAYER_GBRG16
sensor_msgs::image_encodings::MONO8
const std::string MONO8
spinnaker_camera_driver::SpinnakerCamera::SpinnakerCamera
SpinnakerCamera()
Definition: SpinnakerCamera.cpp:54
sensor_msgs::image_encodings::MONO16
const std::string MONO16
spinnaker_camera_driver::SpinnakerCamera::system_
Spinnaker::SystemPtr system_
Definition: SpinnakerCamera.h:177
spinnaker_camera_driver::SpinnakerCamera::node_map_
Spinnaker::GenApi::INodeMap * node_map_
Definition: SpinnakerCamera.h:182
sensor_msgs::image_encodings::BAYER_GRBG8
const std::string BAYER_GRBG8
spinnaker_camera_driver::SpinnakerCamera::camera_
std::shared_ptr< Camera > camera_
Definition: SpinnakerCamera.h:183
ROS_INFO
#define ROS_INFO(...)
spinnaker_camera_driver::SpinnakerCamera::disconnect
void disconnect()
Disconnects from the camera.
Definition: SpinnakerCamera.cpp:277
spinnaker_camera_driver::SpinnakerCamera::~SpinnakerCamera
~SpinnakerCamera()
Definition: SpinnakerCamera.cpp:67
sensor_msgs::image_encodings::BAYER_GRBG16
const std::string BAYER_GRBG16
SpinnakerCamera.h
Interface to Point Grey cameras.
spinnaker_camera_driver::SpinnakerCamera::stop
void stop()
Stops the camera loading data into its buffer.
Definition: SpinnakerCamera.cpp:318
spinnaker_camera_driver::SpinnakerCamera::readProperty
Spinnaker::GenApi::CNodePtr readProperty(const Spinnaker::GenICam::gcstring property_name)
Definition: SpinnakerCamera.cpp:133
sensor_msgs::image_encodings::BAYER_RGGB16
const std::string BAYER_RGGB16


spinnaker_camera_driver
Author(s): Chad Rockey
autogenerated on Mon Sep 25 2023 02:56:14