38 #include <dynamic_reconfigure/server.h>
39 #include <dynamic_reconfigure/SensorLevels.h>
44 #include <sensor_msgs/CameraInfo.h>
46 #include <sensor_msgs/Image.h>
47 #include <sensor_msgs/CameraInfo.h>
49 #include <sensor_msgs/SetCameraInfo.h>
51 #include <boost/thread.hpp>
52 #include <boost/format.hpp>
53 #include <boost/date_time/posix_time/posix_time.hpp>
55 #include <prosilica_camera/ProsilicaCameraConfig.h>
193 pn.
param<std::string>(
"frame_id",
frame_id_,
"/camera_optical_frame");
241 boost::lock_guard<boost::recursive_mutex> scoped_lock(
config_mutex_);
249 camera_ = boost::make_shared<prosilica::Camera>((
unsigned long)
guid_);
273 camera_ = boost::make_shared<prosilica::Camera>((
unsigned long)
guid_);
280 throw std::runtime_error(
"Found no cameras on local subnet");
285 catch (std::exception& e)
288 std::stringstream err;
291 err <<
"Found no cameras on local subnet";
295 err <<
"Unable to open prosilica camera with guid " <<
guid_ <<
": "<<e.what();
299 err <<
"Unable to open prosilica camera with ip address " <<
ip_address_ <<
": "<<e.what();
313 boost::this_thread::sleep(itime);
322 std::stringstream list;
323 for (
unsigned int i = 0; i < cameras.size(); ++i)
325 list << cameras[i].serial <<
" - " <<cameras[i].name<<
" - Unique ID = "<<cameras[i].guid<<
" IP = "<<cameras[i].ip_address<<std::endl;
350 std::string camera_name;
354 NODELET_INFO(
"Loaded calibration for camera '%s'", camera_name.c_str());
358 intrinsics_ =
"Failed to load intrinsics from camera";
362 catch(std::exception &e)
408 catch(std::exception &e)
438 boost::lock_guard<boost::recursive_mutex> scoped_lock(
config_mutex_);
483 boost::lock_guard<boost::recursive_mutex> lock(
config_mutex_);
486 tPvFrame* frame = NULL;
490 catch(std::exception &e)
504 polled_camera::GetPolledImage::Response& rsp,
505 sensor_msgs::Image& image, sensor_msgs::CameraInfo& info)
510 rsp.status_message =
"Camera is not in software triggered mode";
525 tPvFrame* frame = NULL;
526 frame =
camera_->grab(req.timeout.toSec()*100);
529 image.header.stamp = info.header.stamp =rsp.stamp =
ros::Time::now();
530 rsp.status_message =
"Success";
536 rsp.status_message =
"Failed to process image";
540 catch(std::exception &e)
543 std::stringstream err;
544 err<<
"Failed to grab frame: "<<e.what();
545 rsp.status_message = err.str();
555 state_info_ =
"Can not sync from topic trigger unless in Software Trigger mode";
564 bool processFrame(tPvFrame* frame, sensor_msgs::Image &img, sensor_msgs::CameraInfo &cam_info)
567 if (frame==NULL || frame->Status != ePvErrSuccess)
575 tPvUint32 binning_x = 1, binning_y = 1;
576 if (
camera_->hasAttribute(
"BinningX"))
578 camera_->getAttribute(
"BinningX", binning_x);
579 camera_->getAttribute(
"BinningY", binning_y);
583 if (frame->Format == ePvFmtBayer8 && (binning_x > 1 || binning_y > 1))
584 frame->Format = ePvFmtMono8;
590 cam_info.binning_x = binning_x;
591 cam_info.binning_y = binning_y;
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) ||
603 catch(std::exception &e)
615 static const char* BAYER_ENCODINGS[] = {
"bayer_rggb8",
"bayer_gbrg8",
"bayer_grbg8",
"bayer_bggr8" };
617 std::string encoding;
619 else if (frame->Format == ePvFmtBayer8) encoding = BAYER_ENCODINGS[frame->BayerPattern];
625 NODELET_WARN(
"Received frame with unsupported pixel format %d", frame->Format);
629 if(frame->ImageSize == 0 || frame->Height == 0)
631 uint32_t step = frame->ImageSize / frame->Height;
635 bool setCameraInfo(sensor_msgs::SetCameraInfoRequest &req, sensor_msgs::SetCameraInfoResponse &rsp)
638 sensor_msgs::CameraInfo &info = req.camera_info;
644 rsp.status_message = (boost::format(
"Camera_info resolution %ix%i does not match current video "
645 "setting, camera running at resolution %ix%i.")
653 std::string cam_name =
"prosilica";
655 std::stringstream ini_stream;
658 rsp.status_message =
"Error formatting camera_info for storage.";
663 std::string ini = ini_stream.str();
667 rsp.status_message =
"Unable to write camera_info to camera memory, exceeded storage capacity.";
673 camera_->writeUserMemory(ini.c_str(), ini.size());
680 rsp.status_message = e.what();
696 if (level >= (uint32_t)dynamic_reconfigure::SensorLevels::RECONFIGURE_STOP)
700 if (config.trigger_mode ==
"streaming")
705 else if (config.trigger_mode ==
"syncin1")
710 else if (config.trigger_mode ==
"syncin2")
715 else if (config.trigger_mode ==
"fixedrate")
720 else if (config.trigger_mode ==
"software")
726 else if (config.trigger_mode ==
"polled")
731 else if (config.trigger_mode ==
"triggered")
738 NODELET_ERROR(
"Invalid trigger mode '%s' in reconfigure request", config.trigger_mode.c_str());
741 if(config.trig_timestamp_topic !=
last_config_.trig_timestamp_topic)
754 if (config.auto_exposure)
757 if (
camera_->hasAttribute(
"ExposureAutoMax"))
759 tPvUint32 us = config.exposure_auto_max*1000000. + 0.5;
760 camera_->setAttribute(
"ExposureAutoMax", us);
762 if (
camera_->hasAttribute(
"ExposureAutoTarget"))
763 camera_->setAttribute(
"ExposureAutoTarget", (tPvUint32)config.exposure_auto_target);
767 unsigned us = config.exposure*1000000. + 0.5;
769 camera_->setAttribute(
"ExposureValue", (tPvUint32)us);
773 if (config.auto_gain)
775 if (
camera_->hasAttribute(
"GainAutoMax"))
778 camera_->setAttribute(
"GainAutoMax", (tPvUint32)config.gain_auto_max);
779 camera_->setAttribute(
"GainAutoTarget", (tPvUint32)config.gain_auto_target);
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;
795 camera_->setAttribute(
"GainValue", (tPvUint32)config.gain);
799 if (config.auto_whitebalance)
801 if (
camera_->hasAttribute(
"WhitebalMode"))
805 NODELET_WARN(
"Auto white balance not available for this camera.");
806 config.auto_whitebalance =
false;
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);
819 if (
camera_->hasAttribute(
"BinningX"))
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);
824 camera_->setBinning(config.binning_x, config.binning_y);
826 else if (config.binning_x > 1 || config.binning_y > 1)
829 config.binning_x = config.binning_y = 1;
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);
839 int width = config.width ? config.width :
sensor_width_ - config.x_offset;
840 int height = config.height ? config.height :
sensor_height_ - config.y_offset;
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;
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;
854 camera_->setRoi(x_offset, y_offset, width, height);
857 img_.header.frame_id =
cam_info_.header.frame_id = config.frame_id;
865 camera_->setAttribute(
"StreamBytesPerSecond", (tPvUint32)config.stream_bytes_per_second);
871 if (level >= (uint32_t)dynamic_reconfigure::SensorLevels::RECONFIGURE_STOP)
877 catch(std::exception &e)
907 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Opening camera");
910 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Camera operating normally");
913 stat.
summaryf(diagnostic_msgs::DiagnosticStatus::ERROR,
"Can not find camera %d",
guid_ );
917 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Problem retrieving frame");
920 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Camera has encountered an error");