nodelet.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 
49 // ROS and associated nodelet interface and PLUGINLIB declaration header
50 #include "ros/ros.h"
52 #include <nodelet/nodelet.h>
53 
54 #include "spinnaker_camera_driver/SpinnakerCamera.h" // The actual standalone library for the Spinnakers
56 
57 #include <image_transport/image_transport.h> // ROS library that allows sending compressed images
58 #include <camera_info_manager/camera_info_manager.h> // ROS library that publishes CameraInfo topics
59 #include <sensor_msgs/CameraInfo.h> // ROS message header for CameraInfo
60 
61 #include <wfov_camera_msgs/WFOVImage.h>
62 #include <image_exposure_msgs/ExposureSequence.h> // Message type for configuring gain and white balance.
63 
64 #include <diagnostic_updater/diagnostic_updater.h> // Headers for publishing diagnostic messages.
66 
67 #include <boost/thread.hpp> // Needed for the nodelet to launch the reading thread.
68 
69 #include <dynamic_reconfigure/server.h> // Needed for the dynamic_reconfigure gui service to run
70 
71 #include <fstream>
72 #include <memory>
73 #include <string>
74 #include <utility>
75 
77 {
79 {
80 public:
82  {
83  }
84 
86  {
87  std::lock_guard<std::mutex> scopedLock(connect_mutex_);
88 
89  if (diagThread_)
90  {
91  diagThread_->interrupt();
92  diagThread_->join();
93  }
94 
95  if (pubThread_)
96  {
97  pubThread_->interrupt();
98  pubThread_->join();
99 
100  try
101  {
102  NODELET_DEBUG_ONCE("Stopping camera capture.");
103  spinnaker_.stop();
104  NODELET_DEBUG_ONCE("Disconnecting from camera.");
106  }
107  catch (const std::runtime_error& e)
108  {
109  NODELET_ERROR("%s", e.what());
110  }
111  }
112  }
113 
114 private:
125  void paramCallback(const spinnaker_camera_driver::SpinnakerConfig& config, uint32_t level)
126  {
127  config_ = config;
128 
129  try
130  {
131  NODELET_DEBUG_ONCE("Dynamic reconfigure callback with level: %u", level);
132  spinnaker_.setNewConfiguration(config, level);
133 
134  // Store needed parameters for the metadata message
135  gain_ = config.gain;
136  wb_blue_ = config.white_balance_blue_ratio;
137  wb_red_ = config.white_balance_red_ratio;
138 
139  // No separate param in CameraInfo for binning/decimation
140  binning_x_ = config.image_format_x_binning * config.image_format_x_decimation;
141  binning_y_ = config.image_format_y_binning * config.image_format_y_decimation;
142 
143  // Store CameraInfo RegionOfInterest information
144  // TODO(mhosmar): Not compliant with CameraInfo message: "A particular ROI always denotes the
145  // same window of pixels on the camera sensor, regardless of binning settings."
146  // These values are in the post binned frame.
147  if ((config.image_format_roi_width + config.image_format_roi_height) > 0 &&
148  (config.image_format_roi_width < spinnaker_.getWidthMax() ||
149  config.image_format_roi_height < spinnaker_.getHeightMax()))
150  {
151  roi_x_offset_ = config.image_format_x_offset;
152  roi_y_offset_ = config.image_format_y_offset;
153  roi_width_ = config.image_format_roi_width;
154  roi_height_ = config.image_format_roi_height;
155  do_rectify_ = true; // Set to true if an ROI is used.
156  }
157  else
158  {
159  // Zeros mean the full resolution was captured.
160  roi_x_offset_ = 0;
161  roi_y_offset_ = 0;
162  roi_height_ = 0;
163  roi_width_ = 0;
164  do_rectify_ = false; // Set to false if the whole image is captured.
165  }
166  }
167  catch (std::runtime_error& e)
168  {
169  NODELET_ERROR("Reconfigure Callback failed with error: %s", e.what());
170  }
171  }
172 
173  void diagCb()
174  {
175  if (!diagThread_) // We need to connect
176  {
177  // Start the thread to loop through and publish messages
178  diagThread_.reset(
179  new boost::thread(boost::bind(&spinnaker_camera_driver::SpinnakerCameraNodelet::diagPoll, this)));
180  }
181  }
182 
188  void connectCb()
189  {
190  if (!pubThread_) // We need to connect
191  {
192  // Start the thread to loop through and publish messages
193  pubThread_.reset(
194  new boost::thread(boost::bind(&spinnaker_camera_driver::SpinnakerCameraNodelet::devicePoll, this)));
195  }
196 
197  // @tthomas - removing subscriber check and logic below as it's leading to mutex locks and crashes currently
198  /*
199  NODELET_DEBUG_ONCE("Connect callback!");
200  std::lock_guard<std::mutex> scopedLock(connect_mutex_); // Grab the mutex. Wait until we're done initializing
201  before letting this function through.
202  // Check if we should disconnect (there are 0 subscribers to our data)
203  if(it_pub_.getNumSubscribers() == 0 && pub_->getPublisher().getNumSubscribers() == 0)
204  {
205  if (pubThread_)
206  {
207  NODELET_DEBUG_ONCE("Disconnecting.");
208  pubThread_->interrupt();
209  scopedLock.unlock();
210  pubThread_->join();
211  scopedLock.lock();
212  pubThread_.reset();
213  sub_.shutdown();
214 
215  try
216  {
217  NODELET_DEBUG_ONCE("Stopping camera capture.");
218  spinnaker_.stop();
219  }
220  catch(std::runtime_error& e)
221  {
222  NODELET_ERROR("%s", e.what());
223  }
224 
225  try
226  {
227  NODELET_DEBUG_ONCE("Disconnecting from camera.");
228  spinnaker_.disconnect();
229  }
230  catch(std::runtime_error& e)
231  {
232  NODELET_ERROR("%s", e.what());
233  }
234  }
235  }
236  else if(!pubThread_) // We need to connect
237  {
238  // Start the thread to loop through and publish messages
239  pubThread_.reset(new boost::thread(boost::bind(&spinnaker_camera_driver::SpinnakerCameraNodelet::devicePoll,
240  this)));
241  }
242  else
243  {
244  NODELET_DEBUG_ONCE("Do nothing in callback.");
245  }
246  */
247  }
248 
255  void onInit()
256  {
257  // Get nodeHandles
260 
261  // Get a serial number through ros
262  int serial = 0;
263 
264  XmlRpc::XmlRpcValue serial_xmlrpc;
265  pnh.getParam("serial", serial_xmlrpc);
266  if (serial_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeInt)
267  {
268  pnh.param<int>("serial", serial, 0);
269  }
270  else if (serial_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeString)
271  {
272  std::string serial_str;
273  pnh.param<std::string>("serial", serial_str, "0");
274  std::istringstream(serial_str) >> serial;
275  }
276  else
277  {
278  NODELET_DEBUG_ONCE("Serial XMLRPC type.");
279  serial = 0;
280  }
281 
282  std::string camera_serial_path;
283  pnh.param<std::string>("camera_serial_path", camera_serial_path, "");
284  NODELET_DEBUG_ONCE("Camera serial path %s", camera_serial_path.c_str());
285  // If serial has been provided directly as a param, ignore the path
286  // to read in the serial from.
287  while (serial == 0 && !camera_serial_path.empty())
288  {
289  serial = readSerialAsHexFromFile(camera_serial_path);
290  if (serial == 0)
291  {
292  NODELET_WARN_ONCE("Waiting for camera serial path to become available");
293  ros::Duration(1.0).sleep(); // Sleep for 1 second, wait for serial device path to become available
294  }
295  }
296 
297  NODELET_DEBUG_ONCE("Using camera serial %d", serial);
298 
299  spinnaker_.setDesiredCamera((uint32_t)serial);
300 
301  // Get GigE camera parameters:
302  pnh.param<int>("packet_size", packet_size_, 1400);
303  pnh.param<bool>("auto_packet_size", auto_packet_size_, true);
304  pnh.param<int>("packet_delay", packet_delay_, 4000);
305 
306  // TODO(mhosmar): Set GigE parameters:
307  // spinnaker_.setGigEParameters(auto_packet_size_, packet_size_, packet_delay_);
308 
309  // Get the location of our camera config yaml
310  std::string camera_info_url;
311  pnh.param<std::string>("camera_info_url", camera_info_url, "");
312  // Get the desired frame_id, set to 'camera' if not found
313  pnh.param<std::string>("frame_id", frame_id_, "camera");
314  // Do not call the connectCb function until after we are done initializing.
315  std::lock_guard<std::mutex> scopedLock(connect_mutex_);
316 
317  // Start up the dynamic_reconfigure service, note that this needs to stick around after this function ends
318  srv_ = std::make_shared<dynamic_reconfigure::Server<spinnaker_camera_driver::SpinnakerConfig> >(pnh);
319  dynamic_reconfigure::Server<spinnaker_camera_driver::SpinnakerConfig>::CallbackType f =
321 
322  srv_->setCallback(f);
323 
324  // queue size of ros publisher
325  int queue_size;
326  pnh.param<int>("queue_size", queue_size, 5);
327 
328  // Start the camera info manager and attempt to load any configurations
329  std::stringstream cinfo_name;
330  cinfo_name << serial;
331  cinfo_.reset(new camera_info_manager::CameraInfoManager(nh, cinfo_name.str(), camera_info_url));
332 
333  // Publish topics using ImageTransport through camera_info_manager (gives cool things like compression)
334  it_.reset(new image_transport::ImageTransport(nh));
336  it_pub_ = it_->advertiseCamera("image_raw", queue_size, cb, cb);
337 
338  // Set up diagnostics
339  updater_.setHardwareID("spinnaker_camera " + cinfo_name.str());
340 
341  // Set up a diagnosed publisher
342  double desired_freq;
343  std::string device_type;
344  pnh.param<std::string>("device_type", device_type, "USB3");
345  pnh.param<double>("desired_freq", desired_freq, 30.0);
346  pnh.param<double>("min_freq", min_freq_, desired_freq);
347  pnh.param<double>("max_freq", max_freq_, desired_freq);
348  double freq_tolerance; // Tolerance before stating error on publish frequency, fractional percent of desired
349  // frequencies.
350  pnh.param<double>("freq_tolerance", freq_tolerance, 0.1);
351  int window_size; // Number of samples to consider in frequency
352  pnh.param<int>("window_size", window_size, 30);
353  double min_acceptable; // The minimum publishing delay (in seconds) before warning. Negative values mean future
354  // dated messages.
355  pnh.param<double>("min_acceptable_delay", min_acceptable, 0.0);
356  double max_acceptable; // The maximum publishing delay (in seconds) before warning.
357  pnh.param<double>("max_acceptable_delay", max_acceptable, 0.2);
360  nh.advertise<wfov_camera_msgs::WFOVImage>("image", queue_size, cb2, cb2),
361  updater_,
363  &max_freq_,
364  freq_tolerance,
365  window_size),
367  max_acceptable)));
368 
369  // Set up diagnostics aggregator publisher and diagnostics manager
372  nh.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1, diag_cb, diag_cb)));
373 
374  diag_man = std::unique_ptr<DiagnosticsManager>(new DiagnosticsManager(
375  frame_id_, std::to_string(spinnaker_.getSerial()), diagnostics_pub_, nh));
376  diag_man->addDiagnostic("DeviceTemperature", true, std::make_pair(0.0f, 90.0f), -10.0f, 95.0f);
377  diag_man->addDiagnostic("AcquisitionResultingFrameRate", true, std::make_pair(10.0f, 60.0f), 5.0f, 90.0f);
378  diag_man->addDiagnostic("PowerSupplyVoltage", true, std::make_pair(4.5f, 5.2f), 4.4f, 5.3f);
379  diag_man->addDiagnostic("PowerSupplyCurrent", true, std::make_pair(0.4f, 0.6f), 0.3f, 1.0f);
380  diag_man->addDiagnostic<int>("DeviceUptime");
381  if (device_type.compare("USB3") == 0 )
382  {
383  diag_man->addDiagnostic<int>("U3VMessageChannelID");
384  }
385  }
386 
394  int readSerialAsHexFromFile(std::string camera_serial_path)
395  {
396  NODELET_DEBUG_ONCE("Reading camera serial file from: %s", camera_serial_path.c_str());
397 
398  std::ifstream serial_file(camera_serial_path.c_str());
399  std::stringstream buffer;
400  int serial = 0;
401 
402  if (serial_file.is_open())
403  {
404  std::string serial_str((std::istreambuf_iterator<char>(serial_file)), std::istreambuf_iterator<char>());
405  NODELET_DEBUG_ONCE("Serial file contents: %s", serial_str.c_str());
406  buffer << std::hex << serial_str;
407  buffer >> serial;
408  NODELET_DEBUG_ONCE("Serial discovered %d", serial);
409 
410  return serial;
411  }
412 
413  NODELET_WARN_ONCE("Unable to open serial path: %s", camera_serial_path.c_str());
414  return 0;
415  }
416 
417  void diagPoll()
418  {
419  diag_man->addAnalyzers();
420  while (!boost::this_thread::interruption_requested()) // Block until we need
421  // to stop this
422  // thread.
423  {
424  diag_man->processDiagnostics(&spinnaker_);
425  }
426  }
427 
434  void devicePoll()
435  {
436  ROS_INFO_ONCE("devicePoll");
437 
438  enum State
439  {
440  NONE,
441  ERROR,
442  STOPPED,
443  DISCONNECTED,
444  CONNECTED,
445  STARTED
446  };
447 
448  State state = DISCONNECTED;
449  State previous_state = NONE;
450 
451  while (!boost::this_thread::interruption_requested()) // Block until we need to stop this thread.
452  {
453  bool state_changed = state != previous_state;
454 
455  previous_state = state;
456 
457  switch (state)
458  {
459  case ERROR:
460 // Generally there's no need to stop before disconnecting after an
461 // error. Indeed, stop will usually fail.
462 #if STOP_ON_ERROR
463  // Try stopping the camera
464  {
465  std::lock_guard<std::mutex> scopedLock(connect_mutex_);
466  sub_.shutdown();
467  }
468 
469  try
470  {
471  NODELET_DEBUG_ONCE("Stopping camera.");
472  spinnaker_.stop();
473  NODELET_DEBUG_ONCE("Stopped camera.");
474 
475  state = STOPPED;
476  }
477  catch (std::runtime_error& e)
478  {
479  if (state_changed)
480  {
481  NODELET_ERROR("Failed to stop with error: %s", e.what());
482  ros::Duration(1.0).sleep(); // sleep for one second each time
483  }
484  state = ERROR;
485  }
486 
487  break;
488 #endif
489  case STOPPED:
490  // Try disconnecting from the camera
491  try
492  {
493  NODELET_DEBUG("Disconnecting from camera.");
495  NODELET_DEBUG("Disconnected from camera.");
496 
497  state = DISCONNECTED;
498  }
499  catch (std::runtime_error& e)
500  {
501  if (state_changed)
502  {
503  NODELET_ERROR("Failed to disconnect with error: %s", e.what());
504  ros::Duration(1.0).sleep(); // sleep for one second each time
505  }
506  state = ERROR;
507  }
508 
509  break;
510  case DISCONNECTED:
511  // Try connecting to the camera
512  try
513  {
514  NODELET_DEBUG("Connecting to camera.");
515 
517 
518  NODELET_DEBUG("Connected to camera.");
519 
520  // Set last configuration, forcing the reconfigure level to stop
522 
523  // Set the timeout for grabbing images.
524  try
525  {
526  double timeout;
527  getMTPrivateNodeHandle().param("timeout", timeout, 1.0);
528 
529  NODELET_DEBUG_ONCE("Setting timeout to: %f.", timeout);
530  spinnaker_.setTimeout(timeout);
531  }
532  catch (const std::runtime_error& e)
533  {
534  NODELET_ERROR("%s", e.what());
535  }
536 
537  // Subscribe to gain and white balance changes
538  {
539  std::lock_guard<std::mutex> scopedLock(connect_mutex_);
540  sub_ =
541  getMTNodeHandle().subscribe("image_exposure_sequence", 10,
543  }
544  state = CONNECTED;
545  }
546  catch (const std::runtime_error& e)
547  {
548  if (state_changed)
549  {
550  NODELET_ERROR("Failed to connect with error: %s", e.what());
551  ros::Duration(1.0).sleep(); // sleep for one second each time
552  }
553  state = ERROR;
554  }
555 
556  break;
557  case CONNECTED:
558  // Try starting the camera
559  try
560  {
561  NODELET_DEBUG("Starting camera.");
562  spinnaker_.start();
563  NODELET_DEBUG("Started camera.");
564  NODELET_DEBUG("Attention: if nothing subscribes to the camera topic, the camera_info is not published "
565  "on the correspondent topic.");
566  state = STARTED;
567  }
568  catch (std::runtime_error& e)
569  {
570  if (state_changed)
571  {
572  NODELET_ERROR("Failed to start with error: %s", e.what());
573  ros::Duration(1.0).sleep(); // sleep for one second each time
574  }
575  state = ERROR;
576  }
577 
578  break;
579  case STARTED:
580  try
581  {
582  wfov_camera_msgs::WFOVImagePtr wfov_image(new wfov_camera_msgs::WFOVImage);
583  // Get the image from the camera library
584  NODELET_DEBUG_ONCE("Starting a new grab from camera with serial {%d}.", spinnaker_.getSerial());
585  spinnaker_.grabImage(&wfov_image->image, frame_id_);
586 
587  // Set other values
588  wfov_image->header.frame_id = frame_id_;
589 
590  wfov_image->gain = gain_;
591  wfov_image->white_balance_blue = wb_blue_;
592  wfov_image->white_balance_red = wb_red_;
593 
594  // wfov_image->temperature = spinnaker_.getCameraTemperature();
595 
596  ros::Time time = ros::Time::now() + ros::Duration(config_.time_offset);
597  wfov_image->header.stamp = time;
598  wfov_image->image.header.stamp = time;
599 
600  // Set the CameraInfo message
601  ci_.reset(new sensor_msgs::CameraInfo(cinfo_->getCameraInfo()));
602  ci_->header.stamp = wfov_image->image.header.stamp;
603  ci_->header.frame_id = wfov_image->header.frame_id;
604  // The height, width, distortion model, and parameters are all filled in by camera info manager.
605  ci_->binning_x = binning_x_;
606  ci_->binning_y = binning_y_;
607  ci_->roi.x_offset = roi_x_offset_;
608  ci_->roi.y_offset = roi_y_offset_;
609  ci_->roi.height = roi_height_;
610  ci_->roi.width = roi_width_;
611  ci_->roi.do_rectify = do_rectify_;
612 
613  wfov_image->info = *ci_;
614 
615  // Publish the full message
616  pub_->publish(wfov_image);
617 
618  // Publish the message using standard image transport
619  if (it_pub_.getNumSubscribers() > 0)
620  {
621  sensor_msgs::ImagePtr image(new sensor_msgs::Image(wfov_image->image));
622  it_pub_.publish(image, ci_);
623  }
624  }
625  catch (CameraTimeoutException& e)
626  {
627  NODELET_WARN("%s", e.what());
628  }
629 
630  catch (std::runtime_error& e)
631  {
632  NODELET_ERROR("%s", e.what());
633  state = ERROR;
634  }
635 
636  break;
637  default:
638  NODELET_ERROR("Unknown camera state %d!", state);
639  }
640 
641  // Update diagnostics
642  updater_.update();
643  }
644  NODELET_DEBUG_ONCE("Leaving thread.");
645  }
646 
647  void gainWBCallback(const image_exposure_msgs::ExposureSequence& msg)
648  {
649  try
650  {
651  NODELET_DEBUG_ONCE("Gain callback: Setting gain to %f and white balances to %u, %u", msg.gain,
652  msg.white_balance_blue, msg.white_balance_red);
653  gain_ = msg.gain;
654 
655  spinnaker_.setGain(static_cast<float>(gain_));
656  wb_blue_ = msg.white_balance_blue;
657  wb_red_ = msg.white_balance_red;
658 
659  // TODO(mhosmar):
660  // spinnaker_.setBRWhiteBalance(false, wb_blue_, wb_red_);
661  }
662  catch (std::runtime_error& e)
663  {
664  NODELET_ERROR("gainWBCallback failed with error: %s", e.what());
665  }
666  }
667 
668  /* Class Fields */
669  std::shared_ptr<dynamic_reconfigure::Server<spinnaker_camera_driver::SpinnakerConfig> > srv_;
670  std::shared_ptr<image_transport::ImageTransport> it_;
675  std::shared_ptr<camera_info_manager::CameraInfoManager> cinfo_;
679  std::shared_ptr<diagnostic_updater::DiagnosedPublisher<wfov_camera_msgs::WFOVImage> > pub_;
680  std::shared_ptr<ros::Publisher> diagnostics_pub_;
686 
687  std::mutex connect_mutex_;
688 
690  double min_freq_;
691  double max_freq_;
692 
694  sensor_msgs::CameraInfoPtr ci_;
695  std::string frame_id_;
696  std::shared_ptr<boost::thread> pubThread_;
697  std::shared_ptr<boost::thread> diagThread_;
698 
699  std::unique_ptr<DiagnosticsManager> diag_man;
700 
701  double gain_;
702  uint16_t wb_blue_;
703  uint16_t wb_red_;
704 
705  // Parameters for cameraInfo
706  size_t binning_x_;
707  size_t binning_y_;
708  size_t roi_x_offset_;
709  size_t roi_y_offset_;
710  size_t roi_height_;
711  size_t roi_width_;
712  bool do_rectify_;
713 
715  // For GigE cameras:
722 
724  spinnaker_camera_driver::SpinnakerConfig config_;
725 };
726 
728  nodelet::Nodelet) // Needed for Nodelet declaration
729 } // namespace spinnaker_camera_driver
spinnaker_camera_driver::DiagnosticsManager
Definition: diagnostics.h:59
spinnaker_camera_driver::SpinnakerCamera::getSerial
uint32_t getSerial()
Definition: SpinnakerCamera.h:169
spinnaker_camera_driver::SpinnakerCameraNodelet::frame_id_
std::string frame_id_
Frame id for the camera messages, defaults to 'camera'.
Definition: nodelet.cpp:695
spinnaker_camera_driver::SpinnakerCamera::connect
void connect()
Function that connects to a specified camera.
Definition: SpinnakerCamera.cpp:145
spinnaker_camera_driver::SpinnakerCameraNodelet::binning_x_
size_t binning_x_
Camera Info pixel binning along the image x axis.
Definition: nodelet.cpp:706
spinnaker_camera_driver::SpinnakerCameraNodelet::spinnaker_
SpinnakerCamera spinnaker_
Instance of the SpinnakerCamera library, used to interface with the hardware.
Definition: nodelet.cpp:693
spinnaker_camera_driver::SpinnakerCameraNodelet::max_freq_
double max_freq_
Definition: nodelet.cpp:691
NODELET_ERROR
#define NODELET_ERROR(...)
spinnaker_camera_driver::SpinnakerCameraNodelet::gain_
double gain_
Definition: nodelet.cpp:701
spinnaker_camera_driver::SpinnakerCameraNodelet::roi_height_
size_t roi_height_
Camera Info ROI height.
Definition: nodelet.cpp:710
msg
msg
ros::Publisher
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
image_transport::ImageTransport
spinnaker_camera_driver::SpinnakerCamera::getHeightMax
int getHeightMax()
Definition: SpinnakerCamera.cpp:105
spinnaker_camera_driver::SpinnakerCameraNodelet::packet_delay_
int packet_delay_
GigE packet delay:
Definition: nodelet.cpp:721
spinnaker_camera_driver::SpinnakerCamera::setGain
void setGain(const float &gain)
Definition: SpinnakerCamera.cpp:99
spinnaker_camera_driver::SpinnakerCameraNodelet::do_rectify_
bool do_rectify_
Definition: nodelet.cpp:712
diagnostic_updater::TimeStampStatusParam
image_transport::CameraPublisher::getNumSubscribers
uint32_t getNumSubscribers() const
ERROR
ERROR
spinnaker_camera_driver::SpinnakerCameraNodelet::it_pub_
image_transport::CameraPublisher it_pub_
CameraInfoManager ROS publisher.
Definition: nodelet.cpp:678
spinnaker_camera_driver::SpinnakerCamera::setTimeout
void setTimeout(const double &timeout)
Will set grabImage timeout for the camera.
Definition: SpinnakerCamera.cpp:473
spinnaker_camera_driver::SpinnakerCamera
Definition: SpinnakerCamera.h:69
spinnaker_camera_driver::SpinnakerCameraNodelet::devicePoll
void devicePoll()
Function for the boost::thread to grabImages and publish them.
Definition: nodelet.cpp:434
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
spinnaker_camera_driver::SpinnakerCameraNodelet::min_freq_
double min_freq_
Definition: nodelet.cpp:690
ros.h
NONE
NONE
camera_info_manager.h
spinnaker_camera_driver::SpinnakerCameraNodelet::wb_red_
uint16_t wb_red_
Definition: nodelet.cpp:703
diagnostic_updater::Updater
XmlRpc::XmlRpcValue::TypeInt
TypeInt
nodelet::Nodelet::getMTPrivateNodeHandle
ros::NodeHandle & getMTPrivateNodeHandle() const
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
NODELET_WARN
#define NODELET_WARN(...)
image_transport::CameraPublisher::publish
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
spinnaker_camera_driver::SpinnakerCameraNodelet::sub_
ros::Subscriber sub_
Subscriber for gain and white balance changes.
Definition: nodelet.cpp:685
spinnaker_camera_driver::SpinnakerCameraNodelet::diagnostics_pub_
std::shared_ptr< ros::Publisher > diagnostics_pub_
Definition: nodelet.cpp:680
CameraTimeoutException
Definition: camera_exceptions.h:49
ros::Subscriber::shutdown
void shutdown()
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
spinnaker_camera_driver::SpinnakerCameraNodelet::diag_man
std::unique_ptr< DiagnosticsManager > diag_man
Definition: nodelet.cpp:699
spinnaker_camera_driver::SpinnakerCameraNodelet::~SpinnakerCameraNodelet
~SpinnakerCameraNodelet()
Definition: nodelet.cpp:85
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
spinnaker_camera_driver::SpinnakerCameraNodelet::connectCb
void connectCb()
Connection callback to only do work when someone is listening.
Definition: nodelet.cpp:188
publisher.h
spinnaker_camera_driver::SpinnakerCamera::start
void start()
Starts the camera loading data into its buffer.
Definition: SpinnakerCamera.cpp:300
diagnostic_updater.h
f
f
spinnaker_camera_driver::SpinnakerCameraNodelet::connect_mutex_
std::mutex connect_mutex_
Definition: nodelet.cpp:687
class_list_macros.h
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::SpinnakerCameraNodelet
Definition: nodelet.cpp:78
spinnaker_camera_driver
Definition: camera.h:45
spinnaker_camera_driver::SpinnakerCameraNodelet::diagCb
void diagCb()
Definition: nodelet.cpp:173
NODELET_WARN_ONCE
#define NODELET_WARN_ONCE(...)
spinnaker_camera_driver::SpinnakerCamera::LEVEL_RECONFIGURE_STOP
static const uint8_t LEVEL_RECONFIGURE_STOP
Definition: SpinnakerCamera.h:95
spinnaker_camera_driver::SpinnakerCameraNodelet::SpinnakerCameraNodelet
SpinnakerCameraNodelet()
Definition: nodelet.cpp:81
XmlRpc::XmlRpcValue::TypeString
TypeString
spinnaker_camera_driver::SpinnakerCamera::getWidthMax
int getWidthMax()
Definition: SpinnakerCamera.cpp:113
diagnostic_updater::DiagnosedPublisher
ROS_INFO_ONCE
#define ROS_INFO_ONCE(...)
spinnaker_camera_driver::SpinnakerCameraNodelet::updater_
diagnostic_updater::Updater updater_
Handles publishing diagnostics messages.
Definition: nodelet.cpp:689
spinnaker_camera_driver::SpinnakerCameraNodelet::roi_y_offset_
size_t roi_y_offset_
Camera Info ROI y offset.
Definition: nodelet.cpp:709
NODELET_DEBUG_ONCE
#define NODELET_DEBUG_ONCE(...)
spinnaker_camera_driver::SpinnakerCameraNodelet::roi_width_
size_t roi_width_
Camera Info ROI width.
Definition: nodelet.cpp:711
diagnostics.h
Class to support ROS Diagnostics Aggregator for Spinnaker Camera.
spinnaker_camera_driver::SpinnakerCameraNodelet::srv_
std::shared_ptr< dynamic_reconfigure::Server< spinnaker_camera_driver::SpinnakerConfig > > srv_
Definition: nodelet.cpp:669
camera_info_manager::CameraInfoManager
image_transport::CameraPublisher
spinnaker_camera_driver::SpinnakerCameraNodelet::pubThread_
std::shared_ptr< boost::thread > pubThread_
The thread that reads and publishes the images.
Definition: nodelet.cpp:696
spinnaker_camera_driver::SpinnakerCameraNodelet::readSerialAsHexFromFile
int readSerialAsHexFromFile(std::string camera_serial_path)
Reads in the camera serial from a specified file path. The format of the serial is expected to be bas...
Definition: nodelet.cpp:394
spinnaker_camera_driver::SpinnakerCameraNodelet::packet_size_
int packet_size_
GigE packet size:
Definition: nodelet.cpp:719
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
spinnaker_camera_driver::SpinnakerCameraNodelet::gainWBCallback
void gainWBCallback(const image_exposure_msgs::ExposureSequence &msg)
Definition: nodelet.cpp:647
spinnaker_camera_driver::SpinnakerCameraNodelet::it_
std::shared_ptr< image_transport::ImageTransport > it_
Definition: nodelet.cpp:674
diagnostic_updater::Updater::setHardwareID
void setHardwareID(const std::string &hwid)
XmlRpc::XmlRpcValue::getType
const Type & getType() const
image_transport.h
diagnostic_updater::Updater::update
void update()
spinnaker_camera_driver::SpinnakerCameraNodelet::diagThread_
std::shared_ptr< boost::thread > diagThread_
The thread that reads and publishes the diagnostics.
Definition: nodelet.cpp:697
spinnaker_camera_driver::SpinnakerCameraNodelet::ci_
sensor_msgs::CameraInfoPtr ci_
Camera Info message.
Definition: nodelet.cpp:694
spinnaker_camera_driver::SpinnakerCameraNodelet::paramCallback
void paramCallback(const spinnaker_camera_driver::SpinnakerConfig &config, uint32_t level)
Function that allows reconfiguration of the camera.
Definition: nodelet.cpp:125
nodelet::Nodelet
ros::Time
spinnaker_camera_driver::SpinnakerCameraNodelet::pub_
std::shared_ptr< diagnostic_updater::DiagnosedPublisher< wfov_camera_msgs::WFOVImage > > pub_
Diagnosed.
Definition: nodelet.cpp:679
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(image_proc::CropNonZeroNodelet, nodelet::Nodelet)
spinnaker_camera_driver::SpinnakerCameraNodelet::roi_x_offset_
size_t roi_x_offset_
Camera Info ROI x offset.
Definition: nodelet.cpp:708
spinnaker_camera_driver::SpinnakerCameraNodelet::cinfo_
std::shared_ptr< camera_info_manager::CameraInfoManager > cinfo_
Definition: nodelet.cpp:676
nodelet.h
spinnaker_camera_driver::SpinnakerCameraNodelet::diagPoll
void diagPoll()
Definition: nodelet.cpp:417
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
spinnaker_camera_driver::SpinnakerCameraNodelet::wb_blue_
uint16_t wb_blue_
Definition: nodelet.cpp:702
image_transport::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ros::Duration::sleep
bool sleep() const
spinnaker_camera_driver::SpinnakerCameraNodelet::onInit
void onInit()
Serves as a psuedo constructor for nodelets.
Definition: nodelet.cpp:255
spinnaker_camera_driver::SpinnakerCameraNodelet::auto_packet_size_
bool auto_packet_size_
If true, GigE packet size is automatically determined, otherwise packet_size_ is used:
Definition: nodelet.cpp:717
spinnaker_camera_driver::SpinnakerCamera::disconnect
void disconnect()
Disconnects from the camera.
Definition: SpinnakerCamera.cpp:277
SpinnakerCamera.h
Interface to Point Grey cameras.
ros::Duration
spinnaker_camera_driver::SpinnakerCameraNodelet::binning_y_
size_t binning_y_
Camera Info pixel binning along the image y axis.
Definition: nodelet.cpp:707
spinnaker_camera_driver::SpinnakerCamera::stop
void stop()
Stops the camera loading data into its buffer.
Definition: SpinnakerCamera.cpp:318
XmlRpc::XmlRpcValue
spinnaker_camera_driver::SpinnakerCameraNodelet::config_
spinnaker_camera_driver::SpinnakerConfig config_
Configuration:
Definition: nodelet.cpp:724
ros::NodeHandle
ros::Subscriber
nodelet::Nodelet::getMTNodeHandle
ros::NodeHandle & getMTNodeHandle() const
NODELET_DEBUG
#define NODELET_DEBUG(...)
ros::Time::now
static Time now()
diagnostic_updater::FrequencyStatusParam


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