prosilica_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 *
5 * Redistribution and use in source and binary forms, with or without
6 * modification, are permitted provided that the following conditions
7 * are met:
8 *
9 * * Redistributions of source code must retain the above copyright
10 * notice, this list of conditions and the following disclaimer.
11 * * Redistributions in binary form must reproduce the above
12 * copyright notice, this list of conditions and the following
13 * disclaimer in the documentation and/or other materials provided
14 * with the distribution.
15 * * Neither the name of the Willow Garage nor the names of its
16 * contributors may be used to endorse or promote products derived
17 * from this software without specific prior written permission.
18 *
19 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
26 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30 * POSSIBILITY OF SUCH DAMAGE.
31 *********************************************************************/
32 
33 #include <string>
34 #include <ros/ros.h>
35 #include <ros/console.h>
36 #include <nodelet/nodelet.h>
38 #include <dynamic_reconfigure/server.h>
39 #include <dynamic_reconfigure/SensorLevels.h>
44 #include <sensor_msgs/CameraInfo.h>
45 
46 #include <sensor_msgs/Image.h>
47 #include <sensor_msgs/CameraInfo.h>
48 #include <sensor_msgs/fill_image.h>
49 #include <sensor_msgs/SetCameraInfo.h>
50 
51 #include <boost/thread.hpp>
52 #include <boost/format.hpp>
53 #include <boost/date_time/posix_time/posix_time.hpp>
54 
55 #include <prosilica_camera/ProsilicaCameraConfig.h>
56 #include "prosilica/prosilica.h"
57 #include "prosilica/rolling_sum.h"
58 
59 bool prosilica_inited = false;//for if the nodelet is loaded multiple times in the same manager
60 int num_cameras = 0;
61 
63 {
64 
66 {
67 
68 public:
69 
71  {
73  init_thread_.interrupt();
74  init_thread_.join();
75 
76  if(camera_)
77  {
78  camera_->stop();
79  camera_.reset(); // must destroy Camera before calling prosilica::fini
80  }
81 
85 
86  --num_cameras;
87  if(num_cameras<=0)
88  {
90  prosilica_inited = false;
91  num_cameras = 0;
92  }
93 
94  NODELET_WARN("Unloaded prosilica camera with guid %s", hw_id_.c_str());
95  }
96 
99  count_(0),
106  {
107  ++num_cameras;
108  }
109 
110 private:
111 
113  boost::thread init_thread_;
115 
120 
121  sensor_msgs::Image img_;
122  sensor_msgs::CameraInfo cam_info_;
123 
124  std::string frame_id_;
125  unsigned long guid_;
126  std::string hw_id_;
127  std::string ip_address_;
131 
132  // Dynamic reconfigure parameters
133  double update_rate_;
136 
139  int count_;
140 
141  // Dynamic Reconfigure
142  prosilica_camera::ProsilicaCameraConfig last_config_;
143  boost::recursive_mutex config_mutex_;
144  typedef dynamic_reconfigure::Server<prosilica_camera::ProsilicaCameraConfig> ReconfigureServer;
146 
147  // State updater
149  {
155  }camera_state_;
156  std::string state_info_;
157  std::string intrinsics_;
158  static const int WINDOW_SIZE = 100; // remember previous 5s
163 
165 
166 
167  virtual void onInit()
168  {
172  init_thread_ = boost::thread(boost::bind(&ProsilicaNodelet::onInitImpl, this));
173 
174  }
175 
176  void onInitImpl()
177  {
180 
182  if(!prosilica_inited)
183  {
184  NODELET_INFO("Initializing prosilica GIGE API");
185  prosilica::init();
186  prosilica_inited = true;
187  }
188 
190  count_ = 0;
191  update_rate_=30;
192  NODELET_INFO("namespace: %s", pn.getNamespace().c_str());
193  pn.param<std::string>("frame_id", frame_id_, "/camera_optical_frame");
194  NODELET_INFO("Loaded param frame_id: %s", frame_id_.c_str());
195 
196  pn.param<std::string>("guid", hw_id_, "");
197  if(hw_id_ == "")
198  {
199  guid_ = 0;
200  }
201  else
202  {
203  guid_ = boost::lexical_cast<int>(hw_id_);
204  NODELET_INFO("Loaded param guid: %lu", guid_);
205  }
206 
207  pn.param<std::string>("ip_address", ip_address_, "");
208  NODELET_INFO("Loaded ip address: %s", ip_address_.c_str());
209 
210  pn.param<double>("open_camera_retry_period", open_camera_retry_period_, 3.);
211  NODELET_INFO("Retry period: %f", open_camera_retry_period_);
212 
213  // Setup updater
215  NODELET_INFO("updated state");
216  // Setup periodic callback to get new data from the camera
217  update_timer_ = nh.createTimer(ros::Rate(update_rate_).expectedCycleTime(), &ProsilicaNodelet::updateCallback, this, false ,false);
219  NODELET_INFO("created update timer");
220  // Open camera
221  openCamera();
222 
223  // Advertise topics
224  ros::NodeHandle image_nh(nh);
225  image_transport::ImageTransport image_it(image_nh);
226  image_publisher_ = image_it.advertiseCamera("image_raw", 1);
230 
231  // Setup dynamic reconfigure server
233  ReconfigureServer::CallbackType f = boost::bind(&ProsilicaNodelet::reconfigureCallback, this, _1, _2);
234  reconfigure_server_->setCallback(f);
235  }
236 
237  void openCamera()
238  {
239  while (!camera_)
240  {
241  boost::lock_guard<boost::recursive_mutex> scoped_lock(config_mutex_);
243  try
244  {
245  if(guid_ != 0)
246  {
247  state_info_ = "Trying to load camera with guid " + hw_id_;
248  NODELET_INFO("%s", state_info_.c_str());
249  camera_ = boost::make_shared<prosilica::Camera>((unsigned long)guid_);
251  NODELET_INFO("Started Prosilica camera with guid \"%lu\"", guid_);
252 
253  }
254  else if(!ip_address_.empty())
255  {
256  state_info_ = "Trying to load camera with ipaddress: " + ip_address_;
257  NODELET_INFO("%s", state_info_.c_str());
258  camera_ = boost::make_shared<prosilica::Camera>(ip_address_.c_str());
259  guid_ = camera_->guid();
260  hw_id_ = boost::lexical_cast<std::string>(guid_);
262 
263  NODELET_INFO("Started Prosilica camera with guid \"%d\"", (int)camera_->guid());
264  }
265  else
266  {
267  updater.setHardwareID("unknown");
268  if(prosilica::numCameras()>0)
269  {
270  state_info_ = "Trying to load first camera found";
271  NODELET_INFO("%s", state_info_.c_str());
273  camera_ = boost::make_shared<prosilica::Camera>((unsigned long)guid_);
274  hw_id_ = boost::lexical_cast<std::string>(guid_);
276  NODELET_INFO("Started Prosilica camera with guid \"%d\"", (int)guid_);
277  }
278  else
279  {
280  throw std::runtime_error("Found no cameras on local subnet");
281  }
282  }
283 
284  }
285  catch (std::exception& e)
286  {
288  std::stringstream err;
289  if (prosilica::numCameras() == 0)
290  {
291  err << "Found no cameras on local subnet";
292  }
293  else if (guid_ != 0)
294  {
295  err << "Unable to open prosilica camera with guid " << guid_ <<": "<<e.what();
296  }
297  else if (ip_address_ != "")
298  {
299  err << "Unable to open prosilica camera with ip address " << ip_address_ <<": "<<e.what();
300  }
301 
302  state_info_ = err.str();
303  NODELET_WARN("%s", state_info_.c_str());
304  if(prosilica::numCameras() > 0)
305  {
306  NODELET_INFO("Available cameras:\n%s", getAvailableCameras().c_str());
307  }
308  camera_.reset();
309 
310  }
311  updater.update();
312  boost::posix_time::millisec itime = boost::posix_time::millisec( (int) (open_camera_retry_period_ * 1000));
313  boost::this_thread::sleep(itime);
314  }
315  loadIntrinsics();
316  start();
317  }
318 
319  std::string getAvailableCameras()
320  {
321  std::vector<prosilica::CameraInfo> cameras = prosilica::listCameras();
322  std::stringstream list;
323  for (unsigned int i = 0; i < cameras.size(); ++i)
324  {
325  list << cameras[i].serial << " - " <<cameras[i].name<< " - Unique ID = "<<cameras[i].guid<<" IP = "<<cameras[i].ip_address<<std::endl;
326  }
327  return list.str();
328  }
329 
331  {
332  try
333  {
334  camera_->setKillCallback(boost::bind(&ProsilicaNodelet::kill, this, _1));
335 
336  if(auto_adjust_stream_bytes_per_second_ && camera_->hasAttribute("StreamBytesPerSecond"))
337  camera_->setAttribute("StreamBytesPerSecond", (tPvUint32)(115000000/num_cameras));
338 
339  // Retrieve contents of user memory
340  std::string buffer(prosilica::Camera::USER_MEMORY_SIZE, '\0');
341  camera_->readUserMemory(&buffer[0], prosilica::Camera::USER_MEMORY_SIZE);
342 
343  PvAttrRangeUint32(camera_->handle(), "BinningX", &dummy, &max_binning_x);
344  PvAttrRangeUint32(camera_->handle(), "BinningY", &dummy, &max_binning_y);
345  PvAttrRangeUint32(camera_->handle(), "Width", &dummy, &sensor_width_);
346  PvAttrRangeUint32(camera_->handle(), "Height", &dummy, &sensor_height_);
347 
348 
349  // Parse calibration file
350  std::string camera_name;
352  {
353  intrinsics_ = "Loaded calibration";
354  NODELET_INFO("Loaded calibration for camera '%s'", camera_name.c_str());
355  }
356  else
357  {
358  intrinsics_ = "Failed to load intrinsics from camera";
359  NODELET_WARN("Failed to load intrinsics from camera");
360  }
361  }
362  catch(std::exception &e)
363  {
365  state_info_ = e.what();
366  }
367  }
368 
369  void start()
370  {
371  try
372  {
373  switch(trigger_mode_)
374  {
375  case prosilica::Software:
376  NODELET_INFO("starting camera %s in software trigger mode", hw_id_.c_str());
378  if(update_rate_ > 0)
379  {
380  update_timer_.setPeriod(ros::Rate(update_rate_).expectedCycleTime());
382  }
383  break;
384  case prosilica::Freerun:
385  NODELET_INFO("starting camera %s in freerun trigger mode", hw_id_.c_str());
386  camera_->setFrameCallback(boost::bind(&ProsilicaNodelet::publishImage, this, _1));
388  break;
390  NODELET_INFO("starting camera %s in fixedrate trigger mode", hw_id_.c_str());
391  camera_->setFrameCallback(boost::bind(&ProsilicaNodelet::publishImage, this, _1));
393  break;
394  case prosilica::SyncIn1:
395  NODELET_INFO("starting camera %s in sync1 trigger mode", hw_id_.c_str());
396  camera_->setFrameCallback(boost::bind(&ProsilicaNodelet::publishImage, this, _1));
398  break;
399  case prosilica::SyncIn2:
400  NODELET_INFO("starting camera %s in sync2 trigger mode", hw_id_.c_str());
401  camera_->setFrameCallback(boost::bind(&ProsilicaNodelet::publishImage, this, _1));
403  break;
404  default:
405  break;
406  }
407  }
408  catch(std::exception &e)
409  {
411  state_info_ = e.what();
412  }
413  }
414 
415  void stop()
416  {
418  if(!camera_)
419  return;
420  camera_->removeEvents();
421  camera_->stop();
422 
423  }
424 
425  void kill(unsigned long guid)
426  {
427  if(guid == guid_)
428  {
429  NODELET_WARN("[%s] got kill request for prosilica camera %lu",getName().c_str(), guid);
431  init_thread_.interrupt();
432  init_thread_.join();
433 
435  state_info_ = "Prosilica camera " + hw_id_ + " disconnected";
436  NODELET_ERROR("%s", state_info_.c_str());
437  updater.update();
438  boost::lock_guard<boost::recursive_mutex> scoped_lock(config_mutex_);
439  stop();
440  camera_.reset();
441  init_thread_ = boost::thread(boost::bind(&ProsilicaNodelet::openCamera, this));
442  return;
443  }
444  }
445 
446  void publishImage(tPvFrame* frame)
447  {
448  publishImage(frame, ros::Time::now());
449  }
450 
451  void publishImage(tPvFrame* frame, ros::Time time)
452  {
453  camera_state_ = OK;
454  state_info_ = "Camera operating normally";
456  {
457 
458  if (processFrame(frame, img_, cam_info_))
459  {
462  }
463  else
464  {
466  state_info_ = "Unable to process frame";
469  }
472  }
473  updater.update();
474  }
475 
476  void updateCallback(const ros::TimerEvent &event)
477  {
478  // Download the most recent data from the device
479  camera_state_ = OK;
480  state_info_ = "Camera operating normally";
482  {
483  boost::lock_guard<boost::recursive_mutex> lock(config_mutex_);
484  try
485  {
486  tPvFrame* frame = NULL;
487  frame = camera_->grab(1000);
488  publishImage(frame, event.current_real);
489  }
490  catch(std::exception &e)
491  {
493  state_info_ = e.what();
494  NODELET_ERROR("Unable to read from camera: %s", e.what());
497  updater.update();
498  return;
499  }
500  }
501  }
502 
503  void pollCallback(polled_camera::GetPolledImage::Request& req,
504  polled_camera::GetPolledImage::Response& rsp,
505  sensor_msgs::Image& image, sensor_msgs::CameraInfo& info)
506  {
508  {
509  rsp.success = false;
510  rsp.status_message = "Camera is not in software triggered mode";
511  return;
512  }
513 
514  last_config_.binning_x = req.binning_x;
515  last_config_.binning_y = req.binning_y;
516  last_config_.x_offset = req.roi.x_offset;
517  last_config_.y_offset = req.roi.y_offset;
518  last_config_.height = req.roi.height;
519  last_config_.width = req.roi.width;
520 
521  reconfigureCallback(last_config_, dynamic_reconfigure::SensorLevels::RECONFIGURE_RUNNING);
522 
523  try
524  {
525  tPvFrame* frame = NULL;
526  frame = camera_->grab(req.timeout.toSec()*100);
527  if (processFrame(frame, image, info))
528  {
529  image.header.stamp = info.header.stamp =rsp.stamp = ros::Time::now();
530  rsp.status_message = "Success";
531  rsp.success = true;
532  }
533  else
534  {
535  rsp.success = false;
536  rsp.status_message = "Failed to process image";
537  return;
538  }
539  }
540  catch(std::exception &e)
541  {
542  rsp.success = false;
543  std::stringstream err;
544  err<< "Failed to grab frame: "<<e.what();
545  rsp.status_message = err.str();
546  return;
547  }
548  }
549 
550  void syncInCallback (const std_msgs::HeaderConstPtr& msg)
551  {
553  {
555  state_info_ = "Can not sync from topic trigger unless in Software Trigger mode";
556  NODELET_ERROR_ONCE("%s", state_info_.c_str());
557  return;
558  }
559  ros::TimerEvent e;
560  e.current_real = msg->stamp;
561  updateCallback(e);
562  }
563 
564  bool processFrame(tPvFrame* frame, sensor_msgs::Image &img, sensor_msgs::CameraInfo &cam_info)
565  {
567  if (frame==NULL || frame->Status != ePvErrSuccess)
568  return false;
569 
570  try
571  {
575  tPvUint32 binning_x = 1, binning_y = 1;
576  if (camera_->hasAttribute("BinningX"))
577  {
578  camera_->getAttribute("BinningX", binning_x);
579  camera_->getAttribute("BinningY", binning_y);
580  }
581 
582  // Binning averages bayer samples, so just call it mono8 in that case
583  if (frame->Format == ePvFmtBayer8 && (binning_x > 1 || binning_y > 1))
584  frame->Format = ePvFmtMono8;
585 
586  if (!frameToImage(frame, img))
587  return false;
588 
589  // Set the operational parameters in CameraInfo (binning, ROI)
590  cam_info.binning_x = binning_x;
591  cam_info.binning_y = binning_y;
592  // ROI in CameraInfo is in unbinned coordinates, need to scale up
593  cam_info.roi.x_offset = frame->RegionX * binning_x;
594  cam_info.roi.y_offset = frame->RegionY * binning_y;
595  cam_info.roi.height = frame->Height * binning_y;
596  cam_info.roi.width = frame->Width * binning_x;
597  cam_info.roi.do_rectify = (frame->Height != sensor_height_ / binning_y) ||
598  (frame->Width != sensor_width_ / binning_x);
599 
600  if(auto_adjust_stream_bytes_per_second_ && camera_->hasAttribute("StreamBytesPerSecond"))
601  camera_->setAttribute("StreamBytesPerSecond", (tPvUint32)(115000000/num_cameras));
602  }
603  catch(std::exception &e)
604  {
605  return false;
606  }
607 
608  count_++;
609  return true;
610  }
611 
612  bool frameToImage(tPvFrame* frame, sensor_msgs::Image &image)
613  {
614  // NOTE: 16-bit and Yuv formats not supported
615  static const char* BAYER_ENCODINGS[] = { "bayer_rggb8", "bayer_gbrg8", "bayer_grbg8", "bayer_bggr8" };
616 
617  std::string encoding;
618  if (frame->Format == ePvFmtMono8) encoding = sensor_msgs::image_encodings::MONO8;
619  else if (frame->Format == ePvFmtBayer8) encoding = BAYER_ENCODINGS[frame->BayerPattern];
620  else if (frame->Format == ePvFmtRgb24) encoding = sensor_msgs::image_encodings::RGB8;
621  else if (frame->Format == ePvFmtBgr24) encoding = sensor_msgs::image_encodings::BGR8;
622  else if (frame->Format == ePvFmtRgba32) encoding = sensor_msgs::image_encodings::RGBA8;
623  else if (frame->Format == ePvFmtBgra32) encoding = sensor_msgs::image_encodings::BGRA8;
624  else {
625  NODELET_WARN("Received frame with unsupported pixel format %d", frame->Format);
626  return false;
627  }
628 
629  if(frame->ImageSize == 0 || frame->Height == 0)
630  return false;
631  uint32_t step = frame->ImageSize / frame->Height;
632  return sensor_msgs::fillImage(image, encoding, frame->Height, frame->Width, step, frame->ImageBuffer);
633  }
634 
635  bool setCameraInfo(sensor_msgs::SetCameraInfoRequest &req, sensor_msgs::SetCameraInfoResponse &rsp)
636  {
637  NODELET_INFO("New camera info received");
638  sensor_msgs::CameraInfo &info = req.camera_info;
639 
640  // Sanity check: the image dimensions should match the max resolution of the sensor.
641  if (info.width != sensor_width_ || info.height != sensor_height_)
642  {
643  rsp.success = false;
644  rsp.status_message = (boost::format("Camera_info resolution %ix%i does not match current video "
645  "setting, camera running at resolution %ix%i.")
646  % info.width % info.height % sensor_width_ % sensor_height_).str();
647  NODELET_ERROR("%s", rsp.status_message.c_str());
648  return true;
649  }
650 
651  stop();
652 
653  std::string cam_name = "prosilica";
654  cam_name += hw_id_;
655  std::stringstream ini_stream;
656  if (!camera_calibration_parsers::writeCalibrationIni(ini_stream, cam_name, info))
657  {
658  rsp.status_message = "Error formatting camera_info for storage.";
659  rsp.success = false;
660  }
661  else
662  {
663  std::string ini = ini_stream.str();
664  if (ini.size() > prosilica::Camera::USER_MEMORY_SIZE)
665  {
666  rsp.success = false;
667  rsp.status_message = "Unable to write camera_info to camera memory, exceeded storage capacity.";
668  }
669  else
670  {
671  try
672  {
673  camera_->writeUserMemory(ini.c_str(), ini.size());
674  cam_info_ = info;
675  rsp.success = true;
676  }
678  {
679  rsp.success = false;
680  rsp.status_message = e.what();
681  }
682  }
683  }
684  if (!rsp.success)
685  NODELET_ERROR("%s", rsp.status_message.c_str());
686 
687  start();
688 
689  return true;
690  }
691 
692  void reconfigureCallback(prosilica_camera::ProsilicaCameraConfig &config, uint32_t level)
693  {
694  NODELET_DEBUG("Reconfigure request received");
695 
696  if (level >= (uint32_t)dynamic_reconfigure::SensorLevels::RECONFIGURE_STOP)
697  stop();
698 
700  if (config.trigger_mode == "streaming")
701  {
703  update_rate_ = 1.; // make sure we get _something_
704  }
705  else if (config.trigger_mode == "syncin1")
706  {
708  update_rate_ = config.trig_rate;
709  }
710  else if (config.trigger_mode == "syncin2")
711  {
713  update_rate_ = config.trig_rate;
714  }
715  else if (config.trigger_mode == "fixedrate")
716  {
718  update_rate_ = config.trig_rate;
719  }
720  else if (config.trigger_mode == "software")
721  {
723  update_rate_ = config.trig_rate;
724  }
725 
726  else if (config.trigger_mode == "polled")
727  {
729  update_rate_ = 0;
730  }
731  else if (config.trigger_mode == "triggered")
732  {
734  update_rate_ = 0;
735  }
736  else
737  {
738  NODELET_ERROR("Invalid trigger mode '%s' in reconfigure request", config.trigger_mode.c_str());
739  }
740 
741  if(config.trig_timestamp_topic != last_config_.trig_timestamp_topic)
742  {
744  trig_timestamp_topic_ = config.trig_timestamp_topic;
745  }
746 
747  if(!trigger_sub_ && config.trigger_mode == "triggered")
748  {
750  }
751 
752 
753  // Exposure
754  if (config.auto_exposure)
755  {
756  camera_->setExposure(0, prosilica::Auto);
757  if (camera_->hasAttribute("ExposureAutoMax"))
758  {
759  tPvUint32 us = config.exposure_auto_max*1000000. + 0.5;
760  camera_->setAttribute("ExposureAutoMax", us);
761  }
762  if (camera_->hasAttribute("ExposureAutoTarget"))
763  camera_->setAttribute("ExposureAutoTarget", (tPvUint32)config.exposure_auto_target);
764  }
765  else
766  {
767  unsigned us = config.exposure*1000000. + 0.5;
768  camera_->setExposure(us, prosilica::Manual);
769  camera_->setAttribute("ExposureValue", (tPvUint32)us);
770  }
771 
772  // Gain
773  if (config.auto_gain)
774  {
775  if (camera_->hasAttribute("GainAutoMax"))
776  {
777  camera_->setGain(0, prosilica::Auto);
778  camera_->setAttribute("GainAutoMax", (tPvUint32)config.gain_auto_max);
779  camera_->setAttribute("GainAutoTarget", (tPvUint32)config.gain_auto_target);
780  }
781  else
782  {
783  tPvUint32 major, minor;
784  camera_->getAttribute("FirmwareVerMajor", major);
785  camera_->getAttribute("FirmwareVerMinor", minor);
786  NODELET_WARN("Auto gain not available for this camera. Auto gain is available "
787  "on firmware versions 1.36 and above. You are running version %u.%u.",
788  (unsigned)major, (unsigned)minor);
789  config.auto_gain = false;
790  }
791  }
792  else
793  {
794  camera_->setGain(config.gain, prosilica::Manual);
795  camera_->setAttribute("GainValue", (tPvUint32)config.gain);
796  }
797 
798  // White balance
799  if (config.auto_whitebalance)
800  {
801  if (camera_->hasAttribute("WhitebalMode"))
802  camera_->setWhiteBalance(0, 0, prosilica::Auto);
803  else
804  {
805  NODELET_WARN("Auto white balance not available for this camera.");
806  config.auto_whitebalance = false;
807  }
808  }
809  else
810  {
811  camera_->setWhiteBalance(config.whitebalance_blue, config.whitebalance_red, prosilica::Manual);
812  if (camera_->hasAttribute("WhitebalValueRed"))
813  camera_->setAttribute("WhitebalValueRed", (tPvUint32)config.whitebalance_red);
814  if (camera_->hasAttribute("WhitebalValueBlue"))
815  camera_->setAttribute("WhitebalValueBlue", (tPvUint32)config.whitebalance_blue);
816  }
817 
818  // Binning configuration
819  if (camera_->hasAttribute("BinningX"))
820  {
821  config.binning_x = std::min(config.binning_x, (int)max_binning_x);
822  config.binning_y = std::min(config.binning_y, (int)max_binning_y);
823 
824  camera_->setBinning(config.binning_x, config.binning_y);
825  }
826  else if (config.binning_x > 1 || config.binning_y > 1)
827  {
828  NODELET_WARN("Binning not available for this camera.");
829  config.binning_x = config.binning_y = 1;
830  }
831 
832  // Region of interest configuration
833  // Make sure ROI fits in image
834  config.x_offset = std::min(config.x_offset, (int)sensor_width_ - 1);
835  config.y_offset = std::min(config.y_offset, (int)sensor_height_ - 1);
836  config.width = std::min(config.width, (int)sensor_width_ - config.x_offset);
837  config.height = std::min(config.height, (int)sensor_height_ - config.y_offset);
838  // If width or height is 0, set it as large as possible
839  int width = config.width ? config.width : sensor_width_ - config.x_offset;
840  int height = config.height ? config.height : sensor_height_ - config.y_offset;
841 
842  // Adjust full-res ROI to binning ROI
844  int x_offset = config.x_offset / config.binning_x;
845  int y_offset = config.y_offset / config.binning_y;
846  unsigned int right_x = (config.x_offset + width + config.binning_x - 1) / config.binning_x;
847  unsigned int bottom_y = (config.y_offset + height + config.binning_y - 1) / config.binning_y;
848  // Rounding up is bad when at max resolution which is not divisible by the amount of binning
849  right_x = std::min(right_x, (unsigned)(sensor_width_ / config.binning_x));
850  bottom_y = std::min(bottom_y, (unsigned)(sensor_height_ / config.binning_y));
851  width = right_x - x_offset;
852  height = bottom_y - y_offset;
853 
854  camera_->setRoi(x_offset, y_offset, width, height);
855 
856  // TF frame
857  img_.header.frame_id = cam_info_.header.frame_id = config.frame_id;
858 
859  // Normally the node adjusts the bandwidth used by the camera during diagnostics, to use as
860  // much as possible without dropping packets. But this can create interference if two
861  // cameras are on the same switch, e.g. for stereo. So we allow the user to set the bandwidth
862  // directly.
863  auto_adjust_stream_bytes_per_second_ = config.auto_adjust_stream_bytes_per_second;
865  camera_->setAttribute("StreamBytesPerSecond", (tPvUint32)config.stream_bytes_per_second);
866  else
867  camera_->setAttribute("StreamBytesPerSecond", (tPvUint32)(115000000/num_cameras));
868 
871  if (level >= (uint32_t)dynamic_reconfigure::SensorLevels::RECONFIGURE_STOP)
872  {
873  try
874  {
875  start();
876  }
877  catch(std::exception &e)
878  {
879  NODELET_ERROR("Invalid settings: %s", e.what());
880  config = last_config_;
881  }
882  }
883 
884  last_config_ = config;
885  }
886 
888  {
889  stat.add("Serial", guid_);
890  stat.add("Info", state_info_);
891  stat.add("Intrinsics", intrinsics_);
892  stat.add("Total frames dropped", frames_dropped_total_);
893  stat.add("Total frames", frames_completed_total_);
894 
896  {
897  stat.add("Total % frames dropped", 100.*(double)frames_dropped_total_/frames_completed_total_);
898  }
899  if(frames_completed_acc_.sum()>0)
900  {
901  stat.add("Recent % frames dropped", 100.*frames_dropped_acc_.sum()/frames_completed_acc_.sum());
902  }
903 
904  switch (camera_state_)
905  {
906  case OPENING:
907  stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Opening camera");
908  break;
909  case OK:
910  stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Camera operating normally");
911  break;
912  case CAMERA_NOT_FOUND:
913  stat.summaryf(diagnostic_msgs::DiagnosticStatus::ERROR, "Can not find camera %d", guid_ );
914  stat.add("Available Cameras", getAvailableCameras());
915  break;
916  case FORMAT_ERROR:
917  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Problem retrieving frame");
918  break;
919  case ERROR:
920  stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Camera has encountered an error");
921  break;
922  default:
923  break;
924  }
925  }
926 };
927 }
928 
931 
prosilica_camera::ProsilicaNodelet::onInitImpl
void onInitImpl()
Definition: prosilica_nodelet.cpp:176
prosilica_camera::ProsilicaNodelet::frames_completed_acc_
RollingSum< unsigned long > frames_completed_acc_
Definition: prosilica_nodelet.cpp:160
fill_image.h
prosilica_camera::ProsilicaNodelet::camera_state_
enum prosilica_camera::ProsilicaNodelet::CameraState camera_state_
NODELET_ERROR
#define NODELET_ERROR(...)
prosilica.h
msg
msg
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
prosilica_camera::ProsilicaNodelet::max_binning_y
tPvUint32 max_binning_y
Definition: prosilica_nodelet.cpp:138
prosilica_camera::ProsilicaNodelet::syncInCallback
void syncInCallback(const std_msgs::HeaderConstPtr &msg)
Definition: prosilica_nodelet.cpp:550
image_transport::ImageTransport
polled_camera::PublicationServer
prosilica_camera::ProsilicaNodelet::trigger_sub_
ros::Subscriber trigger_sub_
Definition: prosilica_nodelet.cpp:119
boost::shared_ptr< prosilica::Camera >
image_transport::CameraPublisher::getNumSubscribers
uint32_t getNumSubscribers() const
diagnostic_updater::DiagnosticStatusWrapper::add
void add(const std::string &key, const bool &b)
prosilica_camera::ProsilicaNodelet::open_camera_retry_period_
double open_camera_retry_period_
Definition: prosilica_nodelet.cpp:128
diagnostic_updater::Updater::setHardwareIDf
void setHardwareIDf(const char *format,...)
prosilica::getGuid
uint64_t getGuid(size_t i)
Definition: prosilica.cpp:104
ros.h
parse_ini.h
prosilica_camera::ProsilicaNodelet::frames_dropped_total_
unsigned long frames_dropped_total_
Definition: prosilica_nodelet.cpp:159
RollingSum::sum
T sum()
Definition: rolling_sum.h:24
num_cameras
int num_cameras
Definition: prosilica_nodelet.cpp:60
prosilica_camera::ProsilicaNodelet::getCurrentState
void getCurrentState(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: prosilica_nodelet.cpp:887
prosilica_camera::ProsilicaNodelet::start
void start()
Definition: prosilica_nodelet.cpp:369
prosilica::Manual
@ Manual
Definition: prosilica.h:109
prosilica::SyncIn2
@ SyncIn2
Definition: prosilica.h:93
ros::Timer::stop
void stop()
sensor_msgs::image_encodings::RGBA8
const std::string RGBA8
diagnostic_updater::Updater
prosilica_camera::ProsilicaNodelet::trig_timestamp_topic_
std::string trig_timestamp_topic_
Definition: prosilica_nodelet.cpp:129
prosilica_camera::ProsilicaNodelet::OK
@ OK
Definition: prosilica_nodelet.cpp:154
prosilica_camera
Definition: prosilica_nodelet.cpp:62
NODELET_WARN
#define NODELET_WARN(...)
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
image_transport::CameraPublisher::publish
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
prosilica_camera::ProsilicaNodelet::camera_
boost::shared_ptr< prosilica::Camera > camera_
Definition: prosilica_nodelet.cpp:112
prosilica_camera::ProsilicaNodelet::processFrame
bool processFrame(tPvFrame *frame, sensor_msgs::Image &img, sensor_msgs::CameraInfo &cam_info)
Definition: prosilica_nodelet.cpp:564
ros::Subscriber::shutdown
void shutdown()
RollingSum::add
void add(T sample)
Definition: rolling_sum.h:17
sensor_msgs::fillImage
static bool fillImage(Image &image, const std::string &encoding_arg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, const void *data_arg)
prosilica_camera::ProsilicaNodelet::stop
void stop()
Definition: prosilica_nodelet.cpp:415
prosilica_camera::ProsilicaNodelet::auto_adjust_stream_bytes_per_second_
bool auto_adjust_stream_bytes_per_second_
Definition: prosilica_nodelet.cpp:135
prosilica_camera::ProsilicaNodelet::guid_
unsigned long guid_
Definition: prosilica_nodelet.cpp:125
sensor_msgs::image_encodings::RGB8
const std::string RGB8
prosilica_camera::ProsilicaNodelet::state_info_
std::string state_info_
Definition: prosilica_nodelet.cpp:156
image_transport::ImageTransport::advertiseCamera
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
camera_calibration_parsers::parseCalibrationIni
bool parseCalibrationIni(const std::string &buffer, std::string &camera_name, sensor_msgs::CameraInfo &cam_info)
prosilica_camera::ProsilicaNodelet::image_publisher_
image_transport::CameraPublisher image_publisher_
Definition: prosilica_nodelet.cpp:116
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
prosilica_camera::ProsilicaNodelet::packets_missed_acc_
RollingSum< unsigned long > packets_missed_acc_
Definition: prosilica_nodelet.cpp:162
prosilica_camera::ProsilicaNodelet::sensor_width_
tPvUint32 sensor_width_
Definition: prosilica_nodelet.cpp:137
publisher.h
prosilica_camera::ProsilicaNodelet::ERROR
@ ERROR
Definition: prosilica_nodelet.cpp:153
prosilica_camera::ProsilicaNodelet::ProsilicaNodelet
ProsilicaNodelet()
Definition: prosilica_nodelet.cpp:97
diagnostic_updater.h
f
f
prosilica_camera::ProsilicaNodelet::max_binning_x
tPvUint32 max_binning_x
Definition: prosilica_nodelet.cpp:138
prosilica_camera::ProsilicaNodelet::reconfigure_server_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
Definition: prosilica_nodelet.cpp:145
ros::ServiceServer
prosilica_camera::ProsilicaNodelet::publishImage
void publishImage(tPvFrame *frame, ros::Time time)
Definition: prosilica_nodelet.cpp:451
prosilica_camera::ProsilicaNodelet::update_timer_
ros::Timer update_timer_
Definition: prosilica_nodelet.cpp:114
prosilica_camera::ProsilicaNodelet
Definition: prosilica_nodelet.cpp:65
prosilica_camera::ProsilicaNodelet::FORMAT_ERROR
@ FORMAT_ERROR
Definition: prosilica_nodelet.cpp:152
class_list_macros.h
prosilica::FixedRate
@ FixedRate
Definition: prosilica.h:94
prosilica_camera::ProsilicaNodelet::pollCallback
void pollCallback(polled_camera::GetPolledImage::Request &req, polled_camera::GetPolledImage::Response &rsp, sensor_msgs::Image &image, sensor_msgs::CameraInfo &info)
Definition: prosilica_nodelet.cpp:503
console.h
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(prosilica_camera::ProsilicaNodelet, nodelet::Nodelet)
prosilica::Software
@ Software
Definition: prosilica.h:95
prosilica_camera::ProsilicaNodelet::packets_received_acc_
RollingSum< unsigned long > packets_received_acc_
Definition: prosilica_nodelet.cpp:162
prosilica_camera::ProsilicaNodelet::img_
sensor_msgs::Image img_
Definition: prosilica_nodelet.cpp:121
prosilica_camera::ProsilicaNodelet::sensor_height_
tPvUint32 sensor_height_
Definition: prosilica_nodelet.cpp:137
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
prosilica_camera::ProsilicaNodelet::cam_info_
sensor_msgs::CameraInfo cam_info_
Definition: prosilica_nodelet.cpp:122
prosilica_camera::ProsilicaNodelet::intrinsics_
std::string intrinsics_
Definition: prosilica_nodelet.cpp:157
prosilica_camera::ProsilicaNodelet::hw_id_
std::string hw_id_
Definition: prosilica_nodelet.cpp:126
prosilica_camera::ProsilicaNodelet::packets_received_total_
unsigned long packets_received_total_
Definition: prosilica_nodelet.cpp:161
prosilica_camera::ProsilicaNodelet::poll_srv_
polled_camera::PublicationServer poll_srv_
Definition: prosilica_nodelet.cpp:117
ros::Timer::setPeriod
void setPeriod(const Duration &period, bool reset=true)
prosilica_camera::ProsilicaNodelet::set_camera_info_srv_
ros::ServiceServer set_camera_info_srv_
Definition: prosilica_nodelet.cpp:118
prosilica_camera::ProsilicaNodelet::publishImage
void publishImage(tPvFrame *frame)
Definition: prosilica_nodelet.cpp:446
prosilica_camera::ProsilicaNodelet::dummy
tPvUint32 dummy
Definition: prosilica_nodelet.cpp:138
prosilica_camera::ProsilicaNodelet::packets_missed_total_
unsigned long packets_missed_total_
Definition: prosilica_nodelet.cpp:161
prosilica_camera::ProsilicaNodelet::loadIntrinsics
void loadIntrinsics()
Definition: prosilica_nodelet.cpp:330
prosilica::numCameras
size_t numCameras()
Definition: prosilica.cpp:98
prosilica::ProsilicaException
Definition: prosilica.h:63
image_transport::CameraPublisher
prosilica_camera::ProsilicaNodelet::~ProsilicaNodelet
virtual ~ProsilicaNodelet()
Definition: prosilica_nodelet.cpp:70
NODELET_ERROR_ONCE
#define NODELET_ERROR_ONCE(...)
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())
RollingSum< unsigned long >
ros::TimerEvent
prosilica_camera::ProsilicaNodelet::frames_completed_total_
unsigned long frames_completed_total_
Definition: prosilica_nodelet.cpp:159
prosilica_inited
bool prosilica_inited
Definition: prosilica_nodelet.cpp:59
ros::TimerEvent::current_real
Time current_real
prosilica_camera::ProsilicaNodelet::count_
int count_
Definition: prosilica_nodelet.cpp:139
diagnostic_updater::Updater::setHardwareID
void setHardwareID(const std::string &hwid)
prosilica::Auto
@ Auto
Definition: prosilica.h:110
prosilica::fini
void fini()
Definition: prosilica.cpp:93
polled_camera::advertise
PublicationServer advertise(ros::NodeHandle &nh, const std::string &service, const PublicationServer::DriverCallback &cb, const ros::VoidPtr &tracked_object=ros::VoidPtr())
prosilica_camera::ProsilicaNodelet::onInit
virtual void onInit()
Definition: prosilica_nodelet.cpp:167
image_transport.h
prosilica_camera::ProsilicaNodelet::ReconfigureServer
dynamic_reconfigure::Server< prosilica_camera::ProsilicaCameraConfig > ReconfigureServer
Definition: prosilica_nodelet.cpp:144
prosilica_camera::ProsilicaNodelet::OPENING
@ OPENING
Definition: prosilica_nodelet.cpp:150
prosilica_camera::ProsilicaNodelet::CAMERA_NOT_FOUND
@ CAMERA_NOT_FOUND
Definition: prosilica_nodelet.cpp:151
prosilica_camera::ProsilicaNodelet::kill
void kill(unsigned long guid)
Definition: prosilica_nodelet.cpp:425
prosilica_camera::ProsilicaNodelet::setCameraInfo
bool setCameraInfo(sensor_msgs::SetCameraInfoRequest &req, sensor_msgs::SetCameraInfoResponse &rsp)
Definition: prosilica_nodelet.cpp:635
publication_server.h
NODELET_INFO
#define NODELET_INFO(...)
prosilica_camera::ProsilicaNodelet::update_rate_
double update_rate_
Definition: prosilica_nodelet.cpp:133
prosilica_camera::ProsilicaNodelet::trigger_mode_
int trigger_mode_
Definition: prosilica_nodelet.cpp:134
diagnostic_updater::Updater::update
void update()
prosilica_camera::ProsilicaNodelet::last_config_
prosilica_camera::ProsilicaCameraConfig last_config_
Definition: prosilica_nodelet.cpp:142
nodelet::Nodelet
ros::Time
sensor_msgs::image_encodings::BGRA8
const std::string BGRA8
prosilica_camera::ProsilicaNodelet::frameToImage
bool frameToImage(tPvFrame *frame, sensor_msgs::Image &image)
Definition: prosilica_nodelet.cpp:612
prosilica_camera::ProsilicaNodelet::getAvailableCameras
std::string getAvailableCameras()
Definition: prosilica_nodelet.cpp:319
nodelet.h
sensor_msgs::image_encodings::MONO8
const std::string MONO8
prosilica::SyncIn1
@ SyncIn1
Definition: prosilica.h:92
prosilica_camera::ProsilicaNodelet::CameraState
CameraState
Definition: prosilica_nodelet.cpp:148
prosilica::Camera::USER_MEMORY_SIZE
static const size_t USER_MEMORY_SIZE
Data must have size <= USER_MEMORY_SIZE bytes.
Definition: prosilica.h:171
nodelet::Nodelet::getName
const std::string & getName() const
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
rolling_sum.h
prosilica::init
void init()
Definition: prosilica.cpp:88
diagnostic_updater::DiagnosticStatusWrapper
ros::Rate
sensor_msgs::image_encodings::BGR8
const std::string BGR8
polled_camera::PublicationServer::shutdown
void shutdown()
prosilica_camera::ProsilicaNodelet::WINDOW_SIZE
static const int WINDOW_SIZE
Definition: prosilica_nodelet.cpp:158
prosilica_camera::ProsilicaNodelet::updateCallback
void updateCallback(const ros::TimerEvent &event)
Definition: prosilica_nodelet.cpp:476
camera_calibration_parsers::writeCalibrationIni
bool writeCalibrationIni(const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
image_transport::CameraPublisher::shutdown
void shutdown()
prosilica_camera::ProsilicaNodelet::reconfigureCallback
void reconfigureCallback(prosilica_camera::ProsilicaCameraConfig &config, uint32_t level)
Definition: prosilica_nodelet.cpp:692
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
prosilica_camera::ProsilicaNodelet::init_thread_
boost::thread init_thread_
Definition: prosilica_nodelet.cpp:113
prosilica_camera::ProsilicaNodelet::config_mutex_
boost::recursive_mutex config_mutex_
Definition: prosilica_nodelet.cpp:143
ros::Timer::start
void start()
prosilica::listCameras
std::vector< CameraInfo > listCameras()
Definition: prosilica.cpp:112
diagnostic_updater::DiagnosticTaskVector::add
void add(const std::string &name, TaskFunction f)
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
prosilica_camera::ProsilicaNodelet::updater
diagnostic_updater::Updater updater
Definition: prosilica_nodelet.cpp:164
ros::Timer
diagnostic_updater::DiagnosticStatusWrapper::summaryf
void summaryf(unsigned char lvl, const char *format,...)
prosilica_camera::ProsilicaNodelet::ip_address_
std::string ip_address_
Definition: prosilica_nodelet.cpp:127
prosilica_camera::ProsilicaNodelet::openCamera
void openCamera()
Definition: prosilica_nodelet.cpp:237
prosilica::Freerun
@ Freerun
Definition: prosilica.h:91
prosilica_camera::ProsilicaNodelet::frame_id_
std::string frame_id_
Definition: prosilica_nodelet.cpp:124
prosilica::Continuous
@ Continuous
Definition: prosilica.h:101
ros::NodeHandle
ros::Subscriber
prosilica_camera::ProsilicaNodelet::trig_time_
ros::Time trig_time_
Definition: prosilica_nodelet.cpp:130
prosilica_camera::ProsilicaNodelet::frames_dropped_acc_
RollingSum< unsigned long > frames_dropped_acc_
Definition: prosilica_nodelet.cpp:160
NODELET_DEBUG
#define NODELET_DEBUG(...)
ros::Time::now
static Time now()


prosilica_camera
Author(s): Maintained by William Woodall - wwoodall@willowgarage.com, Contributions by Allison Thackston - allison.thackston@nasa.gov
autogenerated on Wed Mar 2 2022 00:45:45