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 Mellon University.
3 Its development was funded by DARPA under the LS3 program and submitted for public release on June 7th, 2012.
4 Release was granted on August, 21st 2012 with Distribution Statement "A" (Approved for Public Release, Distribution Unlimited).
5 
6 This software is released under a BSD license:
7 
8 Copyright (c) 2012, Carnegie Mellon University. All rights reserved.
9 
10 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
11 
12 Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
13 Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
14 Neither the name of the Carnegie Mellon University nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.
15 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
16 */
17 
18 
19 
31 // ROS and associated nodelet interface and PLUGINLIB declaration header
32 #include "ros/ros.h"
34 #include <nodelet/nodelet.h>
35 
36 #include "pointgrey_camera_driver/PointGreyCamera.h" // The actual standalone library for the PointGreys
37 
38 #include <image_transport/image_transport.h> // ROS library that allows sending compressed images
39 #include <camera_info_manager/camera_info_manager.h> // ROS library that publishes CameraInfo topics
40 #include <sensor_msgs/CameraInfo.h> // ROS message header for CameraInfo
41 
42 #include <wfov_camera_msgs/WFOVImage.h>
43 #include <image_exposure_msgs/ExposureSequence.h> // Message type for configuring gain and white balance.
44 
45 #include <diagnostic_updater/diagnostic_updater.h> // Headers for publishing diagnostic messages.
47 
48 #include <boost/thread.hpp> // Needed for the nodelet to launch the reading thread.
49 
50 #include <dynamic_reconfigure/server.h> // Needed for the dynamic_reconfigure gui service to run
51 
52 #include <fstream>
53 
55 {
56 
58 {
59 public:
61 
63  {
64  boost::mutex::scoped_lock scopedLock(connect_mutex_);
65 
66  if(pubThread_)
67  {
68  pubThread_->interrupt();
69  pubThread_->join();
70 
71  try
72  {
73  NODELET_DEBUG("Stopping camera capture.");
74  pg_.stop();
75  NODELET_DEBUG("Disconnecting from camera.");
76  pg_.disconnect();
77  }
78  catch(std::runtime_error& e)
79  {
80  NODELET_ERROR("%s", e.what());
81  }
82  }
83  }
84 
85 private:
93  void paramCallback(pointgrey_camera_driver::PointGreyConfig &config, uint32_t level)
94  {
95  config_ = config;
96 
97  try
98  {
99  NODELET_DEBUG("Dynamic reconfigure callback with level: %d", level);
100  pg_.setNewConfiguration(config, level);
101 
102  // Store needed parameters for the metadata message
103  gain_ = config.gain;
104  wb_blue_ = config.white_balance_blue;
105  wb_red_ = config.white_balance_red;
106 
107  // Store CameraInfo binning information
108  binning_x_ = 1;
109  binning_y_ = 1;
110  /*
111  if(config.video_mode == "640x480_mono8" || config.video_mode == "format7_mode1")
112  {
113  binning_x_ = 2;
114  binning_y_ = 2;
115  }
116  else if(config.video_mode == "format7_mode2")
117  {
118  binning_x_ = 0;
119  binning_y_ = 2;
120  }
121  else
122  {
123  binning_x_ = 0;
124  binning_y_ = 0;
125  }
126  */
127 
128  // Store CameraInfo RegionOfInterest information
129  if(config.video_mode == "format7_mode0" || config.video_mode == "format7_mode1" || config.video_mode == "format7_mode2")
130  {
131  roi_x_offset_ = config.format7_x_offset;
132  roi_y_offset_ = config.format7_y_offset;
133  roi_width_ = config.format7_roi_width;
134  roi_height_ = config.format7_roi_height;
135  do_rectify_ = true; // Set to true if an ROI is used.
136  }
137  else
138  {
139  // Zeros mean the full resolution was captured.
140  roi_x_offset_ = 0;
141  roi_y_offset_ = 0;
142  roi_height_ = 0;
143  roi_width_ = 0;
144  do_rectify_ = false; // Set to false if the whole image is captured.
145  }
146  }
147  catch(std::runtime_error& e)
148  {
149  NODELET_ERROR("Reconfigure Callback failed with error: %s", e.what());
150  }
151  }
152 
158  void connectCb()
159  {
160  NODELET_DEBUG("Connect callback!");
161  boost::mutex::scoped_lock scopedLock(connect_mutex_); // Grab the mutex. Wait until we're done initializing before letting this function through.
162  // Check if we should disconnect (there are 0 subscribers to our data)
163  if(it_pub_.getNumSubscribers() == 0 && pub_->getPublisher().getNumSubscribers() == 0)
164  {
165  if (pubThread_)
166  {
167  NODELET_DEBUG("Disconnecting.");
168  pubThread_->interrupt();
169  scopedLock.unlock();
170  pubThread_->join();
171  scopedLock.lock();
172  pubThread_.reset();
173  sub_.shutdown();
174 
175  try
176  {
177  NODELET_DEBUG("Stopping camera capture.");
178  pg_.stop();
179  }
180  catch(std::runtime_error& e)
181  {
182  NODELET_ERROR("%s", e.what());
183  }
184 
185  try
186  {
187  NODELET_DEBUG("Disconnecting from camera.");
188  pg_.disconnect();
189  }
190  catch(std::runtime_error& e)
191  {
192  NODELET_ERROR("%s", e.what());
193  }
194  }
195  }
196  else if(!pubThread_) // We need to connect
197  {
198  // Start the thread to loop through and publish messages
199  pubThread_.reset(new boost::thread(boost::bind(&pointgrey_camera_driver::PointGreyCameraNodelet::devicePoll, this)));
200  }
201  else
202  {
203  NODELET_DEBUG("Do nothing in callback.");
204  }
205  }
206 
212  void onInit()
213  {
214  // Get nodeHandles
217 
218  // Get a serial number through ros
219  int serial = 0;
220 
221  XmlRpc::XmlRpcValue serial_xmlrpc;
222  pnh.getParam("serial", serial_xmlrpc);
223  if (serial_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeInt)
224  {
225  pnh.param<int>("serial", serial, 0);
226  }
227  else if (serial_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeString)
228  {
229  std::string serial_str;
230  pnh.param<std::string>("serial", serial_str, "0");
231  std::istringstream(serial_str) >> serial;
232  }
233  else
234  {
235  NODELET_DEBUG("Serial XMLRPC type.");
236  serial = 0;
237  }
238 
239  std::string camera_serial_path;
240  pnh.param<std::string>("camera_serial_path", camera_serial_path, "");
241  NODELET_INFO("Camera serial path %s", camera_serial_path.c_str());
242  // If serial has been provided directly as a param, ignore the path
243  // to read in the serial from.
244  while (serial == 0 && !camera_serial_path.empty())
245  {
246  serial = readSerialAsHexFromFile(camera_serial_path);
247  if (serial == 0)
248  {
249  NODELET_WARN("Waiting for camera serial path to become available");
250  ros::Duration(1.0).sleep(); // Sleep for 1 second, wait for serial device path to become available
251  }
252  }
253 
254  NODELET_INFO("Using camera serial %d", serial);
255 
256  pg_.setDesiredCamera((uint32_t)serial);
257 
258  // Get GigE camera parameters:
259  pnh.param<int>("packet_size", packet_size_, 1400);
260  pnh.param<bool>("auto_packet_size", auto_packet_size_, true);
261  pnh.param<int>("packet_delay", packet_delay_, 4000);
262 
263  // Set GigE parameters:
264  pg_.setGigEParameters(auto_packet_size_, packet_size_, packet_delay_);
265 
266  // Get the location of our camera config yaml
267  std::string camera_info_url;
268  pnh.param<std::string>("camera_info_url", camera_info_url, "");
269  // Get the desired frame_id, set to 'camera' if not found
270  pnh.param<std::string>("frame_id", frame_id_, "camera");
271  // Do not call the connectCb function until after we are done initializing.
272  boost::mutex::scoped_lock scopedLock(connect_mutex_);
273 
274  // Start up the dynamic_reconfigure service, note that this needs to stick around after this function ends
275  srv_ = boost::make_shared <dynamic_reconfigure::Server<pointgrey_camera_driver::PointGreyConfig> > (pnh);
276  dynamic_reconfigure::Server<pointgrey_camera_driver::PointGreyConfig>::CallbackType f =
278  srv_->setCallback(f);
279 
280  // Start the camera info manager and attempt to load any configurations
281  std::stringstream cinfo_name;
282  cinfo_name << serial;
283  cinfo_.reset(new camera_info_manager::CameraInfoManager(nh, cinfo_name.str(), camera_info_url));
284 
285  // Publish topics using ImageTransport through camera_info_manager (gives cool things like compression)
286  it_.reset(new image_transport::ImageTransport(nh));
288  it_pub_ = it_->advertiseCamera("image_raw", 5, cb, cb);
289 
290  // Set up diagnostics
291  updater_.setHardwareID("pointgrey_camera " + cinfo_name.str());
292 
293  // Set up a diagnosed publisher
294  double desired_freq;
295  pnh.param<double>("desired_freq", desired_freq, 7.0);
296  pnh.param<double>("min_freq", min_freq_, desired_freq);
297  pnh.param<double>("max_freq", max_freq_, desired_freq);
298  double freq_tolerance; // Tolerance before stating error on publish frequency, fractional percent of desired frequencies.
299  pnh.param<double>("freq_tolerance", freq_tolerance, 0.1);
300  int window_size; // Number of samples to consider in frequency
301  pnh.param<int>("window_size", window_size, 100);
302  double min_acceptable; // The minimum publishing delay (in seconds) before warning. Negative values mean future dated messages.
303  pnh.param<double>("min_acceptable_delay", min_acceptable, 0.0);
304  double max_acceptable; // The maximum publishing delay (in seconds) before warning.
305  pnh.param<double>("max_acceptable_delay", max_acceptable, 0.2);
307  pub_.reset(new diagnostic_updater::DiagnosedPublisher<wfov_camera_msgs::WFOVImage>(nh.advertise<wfov_camera_msgs::WFOVImage>("image", 5, cb2, cb2),
308  updater_,
309  diagnostic_updater::FrequencyStatusParam(&min_freq_, &max_freq_, freq_tolerance, window_size),
310  diagnostic_updater::TimeStampStatusParam(min_acceptable, max_acceptable)));
311  }
312 
320  int readSerialAsHexFromFile(std::string camera_serial_path)
321  {
322  NODELET_DEBUG("Reading camera serial file from: %s", camera_serial_path.c_str());
323 
324  std::ifstream serial_file(camera_serial_path.c_str());
325  std::stringstream buffer;
326  int serial = 0;
327 
328  if (serial_file.is_open())
329  {
330  std::string serial_str((std::istreambuf_iterator<char>(serial_file)), std::istreambuf_iterator<char>());
331  NODELET_DEBUG("Serial file contents: %s", serial_str.c_str());
332  buffer << std::hex << serial_str;
333  buffer >> serial;
334  NODELET_DEBUG("Serial discovered %d", serial);
335 
336  return serial;
337  }
338 
339  NODELET_WARN("Unable to open serial path: %s", camera_serial_path.c_str());
340  return 0;
341  }
342 
343 
349  void devicePoll()
350  {
351  enum State
352  {
353  NONE
354  , ERROR
355  , STOPPED
356  , DISCONNECTED
357  , CONNECTED
358  , STARTED
359  };
360 
361  State state = DISCONNECTED;
362  State previous_state = NONE;
363 
364  while(!boost::this_thread::interruption_requested()) // Block until we need to stop this thread.
365  {
366  bool state_changed = state != previous_state;
367 
368  previous_state = state;
369 
370  switch(state)
371  {
372  case ERROR:
373  // Generally there's no need to stop before disconnecting after an
374  // error. Indeed, stop will usually fail.
375 #if STOP_ON_ERROR
376  // Try stopping the camera
377  {
378  boost::mutex::scoped_lock scopedLock(connect_mutex_);
379  sub_.shutdown();
380  }
381 
382  try
383  {
384  NODELET_DEBUG("Stopping camera.");
385  pg_.stop();
386  NODELET_INFO("Stopped camera.");
387 
388  state = STOPPED;
389  }
390  catch(std::runtime_error& e)
391  {
392  NODELET_ERROR_COND(state_changed,
393  "Failed to stop error: %s", e.what());
394  ros::Duration(1.0).sleep(); // sleep for one second each time
395  }
396 
397  break;
398 #endif
399  case STOPPED:
400  // Try disconnecting from the camera
401  try
402  {
403  NODELET_DEBUG("Disconnecting from camera.");
404  pg_.disconnect();
405  NODELET_INFO("Disconnected from camera.");
406 
407  state = DISCONNECTED;
408  }
409  catch(std::runtime_error& e)
410  {
411  NODELET_ERROR_COND(state_changed,
412  "Failed to disconnect with error: %s", e.what());
413  ros::Duration(1.0).sleep(); // sleep for one second each time
414  }
415 
416  break;
417  case DISCONNECTED:
418  // Try connecting to the camera
419  try
420  {
421  NODELET_DEBUG("Connecting to camera.");
422  pg_.connect();
423  NODELET_INFO("Connected to camera.");
424 
425  // Set last configuration, forcing the reconfigure level to stop
427 
428  // Set the timeout for grabbing images.
429  try
430  {
431  double timeout;
432  getMTPrivateNodeHandle().param("timeout", timeout, 1.0);
433 
434  NODELET_DEBUG("Setting timeout to: %f.", timeout);
435  pg_.setTimeout(timeout);
436  }
437  catch(std::runtime_error& e)
438  {
439  NODELET_ERROR("%s", e.what());
440  }
441 
442  // Subscribe to gain and white balance changes
443  {
444  boost::mutex::scoped_lock scopedLock(connect_mutex_);
446  }
447 
448  state = CONNECTED;
449  }
450  catch(std::runtime_error& e)
451  {
452  NODELET_ERROR_COND(state_changed,
453  "Failed to connect with error: %s", e.what());
454  ros::Duration(1.0).sleep(); // sleep for one second each time
455  }
456 
457  break;
458  case CONNECTED:
459  // Try starting the camera
460  try
461  {
462  NODELET_DEBUG("Starting camera.");
463  pg_.start();
464  NODELET_INFO("Started camera.");
465  NODELET_INFO("Attention: if nothing subscribes to the camera topic, the camera_info is not published on the correspondent topic.");
466  state = STARTED;
467  }
468  catch(std::runtime_error& e)
469  {
470  NODELET_ERROR_COND(state_changed,
471  "Failed to start with error: %s", e.what());
472  ros::Duration(1.0).sleep(); // sleep for one second each time
473  }
474 
475  break;
476  case STARTED:
477  try
478  {
479  wfov_camera_msgs::WFOVImagePtr wfov_image(new wfov_camera_msgs::WFOVImage);
480  // Get the image from the camera library
481  NODELET_DEBUG("Starting a new grab from camera.");
482  pg_.grabImage(wfov_image->image, frame_id_);
483 
484  // Set other values
485  wfov_image->header.frame_id = frame_id_;
486 
487  wfov_image->gain = gain_;
488  wfov_image->white_balance_blue = wb_blue_;
489  wfov_image->white_balance_red = wb_red_;
490 
491  wfov_image->temperature = pg_.getCameraTemperature();
492 
493  ros::Time time = ros::Time::now();
494  wfov_image->header.stamp = time;
495  wfov_image->image.header.stamp = time;
496 
497  // Set the CameraInfo message
498  ci_.reset(new sensor_msgs::CameraInfo(cinfo_->getCameraInfo()));
499  ci_->header.stamp = wfov_image->image.header.stamp;
500  ci_->header.frame_id = wfov_image->header.frame_id;
501  // The height, width, distortion model, and parameters are all filled in by camera info manager.
502  ci_->binning_x = binning_x_;
503  ci_->binning_y = binning_y_;
504  ci_->roi.x_offset = roi_x_offset_;
505  ci_->roi.y_offset = roi_y_offset_;
506  ci_->roi.height = roi_height_;
507  ci_->roi.width = roi_width_;
508  ci_->roi.do_rectify = do_rectify_;
509 
510  wfov_image->info = *ci_;
511 
512  // Publish the full message
513  pub_->publish(wfov_image);
514 
515  // Publish the message using standard image transport
516  if(it_pub_.getNumSubscribers() > 0)
517  {
518  sensor_msgs::ImagePtr image(new sensor_msgs::Image(wfov_image->image));
519  it_pub_.publish(image, ci_);
520  }
521  }
522  catch(CameraTimeoutException& e)
523  {
524  NODELET_WARN("%s", e.what());
525  }
527  {
528  NODELET_WARN("%s", e.what());
529  }
530  catch(std::runtime_error& e)
531  {
532  NODELET_ERROR("%s", e.what());
533 
534  state = ERROR;
535  }
536 
537  break;
538  default:
539  NODELET_ERROR("Unknown camera state %d!", state);
540  }
541 
542  // Update diagnostics
543  updater_.update();
544  }
545  NODELET_DEBUG("Leaving thread.");
546  }
547 
548  void gainWBCallback(const image_exposure_msgs::ExposureSequence &msg)
549  {
550  try
551  {
552  NODELET_DEBUG("Gain callback: Setting gain to %f and white balances to %u, %u", msg.gain, msg.white_balance_blue, msg.white_balance_red);
553  gain_ = msg.gain;
554  pg_.setGain(gain_);
555  wb_blue_ = msg.white_balance_blue;
556  wb_red_ = msg.white_balance_red;
558  }
559  catch(std::runtime_error& e)
560  {
561  NODELET_ERROR("gainWBCallback failed with error: %s", e.what());
562  }
563  }
564 
571 
572  boost::mutex connect_mutex_;
573 
575  double min_freq_;
576  double max_freq_;
577 
579  sensor_msgs::CameraInfoPtr ci_;
580  std::string frame_id_;
582 
583  double gain_;
584  uint16_t wb_blue_;
585  uint16_t wb_red_;
586 
587  // Parameters for cameraInfo
588  size_t binning_x_;
589  size_t binning_y_;
590  size_t roi_x_offset_;
591  size_t roi_y_offset_;
592  size_t roi_height_;
593  size_t roi_width_;
594  bool do_rectify_;
595 
596  // For GigE cameras:
603 
605  pointgrey_camera_driver::PointGreyConfig config_;
606 };
607 
609 }
static const uint8_t LEVEL_RECONFIGURE_STOP
bool auto_packet_size_
If true, GigE packet size is automatically determined, otherwise packet_size_ is used: ...
Definition: nodelet.cpp:598
float getCameraTemperature()
Gets the current operating temperature.
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
void setDesiredCamera(const uint32_t &id)
Used to set the serial number for the camera you wish to connect to.
void setBRWhiteBalance(bool auto_white_balance, uint16_t &blue, uint16_t &red)
NONE
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
uint32_t getNumSubscribers() const
Interface to Point Grey cameras.
void setHardwareID(const std::string &hwid)
bool sleep() const
ros::Subscriber sub_
Subscriber for gain and white balance changes.
Definition: nodelet.cpp:570
size_t roi_height_
Camera Info ROI height.
Definition: nodelet.cpp:592
void devicePoll()
Function for the boost::thread to grabImages and publish them.
Definition: nodelet.cpp:349
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ros::NodeHandle & getMTNodeHandle() const
size_t roi_width_
Camera Info ROI width.
Definition: nodelet.cpp:593
#define NODELET_ERROR_COND(cond,...)
image_transport::CameraPublisher it_pub_
CameraInfoManager ROS publisher.
Definition: nodelet.cpp:568
Type const & getType() const
void setGain(double &gain)
void gainWBCallback(const image_exposure_msgs::ExposureSequence &msg)
Definition: nodelet.cpp:548
boost::shared_ptr< boost::thread > pubThread_
The thread that reads and publishes the images.
Definition: nodelet.cpp:581
bool stop()
Stops the camera loading data into its buffer.
size_t binning_y_
Camera Info pixel binning along the image y axis.
Definition: nodelet.cpp:589
ros::NodeHandle & getMTPrivateNodeHandle() const
void setTimeout(const double &timeout)
Will set grabImage timeout for the camera.
PLUGINLIB_EXPORT_CLASS(image_proc::CropNonZeroNodelet, nodelet::Nodelet)
void connect()
Function that connects to a specified camera.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void paramCallback(pointgrey_camera_driver::PointGreyConfig &config, uint32_t level)
Function that allows reconfiguration of the camera.
Definition: nodelet.cpp:93
boost::shared_ptr< camera_info_manager::CameraInfoManager > cinfo_
Needed to initialize and keep the CameraInfoManager in scope.
Definition: nodelet.cpp:567
void connectCb()
Connection callback to only do work when someone is listening.
Definition: nodelet.cpp:158
PointGreyCamera pg_
Instance of the PointGreyCamera library, used to interface with the hardware.
Definition: nodelet.cpp:578
void setGigEParameters(bool auto_packet_size, unsigned int packet_size, unsigned int packet_delay)
Set parameters relative to GigE cameras.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sensor_msgs::CameraInfoPtr ci_
Camera Info message.
Definition: nodelet.cpp:579
boost::shared_ptr< diagnostic_updater::DiagnosedPublisher< wfov_camera_msgs::WFOVImage > > pub_
Diagnosed publisher, has to be a pointer because of constructor requirements.
Definition: nodelet.cpp:569
pointgrey_camera_driver::PointGreyConfig config_
Configuration:
Definition: nodelet.cpp:605
void grabImage(sensor_msgs::Image &image, const std::string &frame_id)
Loads the raw data from the cameras buffer.
bool do_rectify_
Whether or not to rectify as if part of an image. Set to false if whole image, and true if in ROI mod...
Definition: nodelet.cpp:594
diagnostic_updater::Updater updater_
Handles publishing diagnostics messages.
Definition: nodelet.cpp:574
size_t roi_x_offset_
Camera Info ROI x offset.
Definition: nodelet.cpp:590
void start()
Starts the camera loading data into its buffer.
#define NODELET_INFO(...)
size_t roi_y_offset_
Camera Info ROI y offset.
Definition: nodelet.cpp:591
bool getParam(const std::string &key, std::string &s) const
static Time now()
boost::shared_ptr< image_transport::ImageTransport > it_
Needed to initialize and keep the ImageTransport in scope.
Definition: nodelet.cpp:566
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:320
size_t binning_x_
Camera Info pixel binning along the image x axis.
Definition: nodelet.cpp:588
void disconnect()
Disconnects from the camera.
#define NODELET_DEBUG(...)
void onInit()
Serves as a psuedo constructor for nodelets.
Definition: nodelet.cpp:212
ERROR
boost::shared_ptr< dynamic_reconfigure::Server< pointgrey_camera_driver::PointGreyConfig > > srv_
Needed to initialize and keep the dynamic_reconfigure::Server in scope.
Definition: nodelet.cpp:565
std::string frame_id_
Frame id for the camera messages, defaults to &#39;camera&#39;.
Definition: nodelet.cpp:580
bool setNewConfiguration(pointgrey_camera_driver::PointGreyConfig &config, const uint32_t &level)
Function that allows reconfiguration of the camera.


pointgrey_camera_driver
Author(s): Chad Rockey
autogenerated on Thu Jun 6 2019 19:27:05