$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 // ROS communication 00036 #include <ros/ros.h> 00037 #include <sensor_msgs/Image.h> 00038 #include <sensor_msgs/CameraInfo.h> 00039 #include <sensor_msgs/fill_image.h> 00040 #include <sensor_msgs/SetCameraInfo.h> 00041 #include <std_msgs/Header.h> 00042 #include <image_transport/image_transport.h> 00043 #include <camera_calibration_parsers/parse_ini.h> 00044 #include <polled_camera/publication_server.h> 00045 00046 // Diagnostics 00047 #include <diagnostic_updater/diagnostic_updater.h> 00048 #include <diagnostic_updater/DiagnosticStatusWrapper.h> 00049 #include <self_test/self_test.h> 00050 00051 // Dynamic reconfigure 00052 #include <dynamic_reconfigure/server.h> 00053 #include <driver_base/SensorLevels.h> 00054 #include "prosilica_camera/ProsilicaCameraConfig.h" 00055 00056 // Standard libs 00057 #include <boost/scoped_ptr.hpp> 00058 #include <boost/bind.hpp> 00059 #include <boost/lexical_cast.hpp> 00060 #include <boost/format.hpp> 00061 #include <sstream> 00062 00063 #include "prosilica/prosilica.h" 00064 #include "prosilica/rolling_sum.h" 00065 00067 class ProsilicaNode 00068 { 00069 private: 00070 ros::NodeHandle nh_; 00071 image_transport::ImageTransport it_; 00072 image_transport::CameraPublisher streaming_pub_; 00073 polled_camera::PublicationServer poll_srv_; 00074 ros::ServiceServer set_camera_info_srv_; 00075 ros::Subscriber trigger_sub_; 00076 00077 // Camera 00078 boost::scoped_ptr<prosilica::Camera> cam_; 00079 prosilica::FrameStartTriggerMode trigger_mode_; 00080 bool running_; 00081 unsigned long max_data_rate_; 00082 tPvUint32 sensor_width_, sensor_height_; // full resolution dimensions (maybe should be in lib) 00083 bool auto_adjust_stream_bytes_per_second_; 00084 00085 // Hardware triggering 00086 std::string trig_timestamp_topic_; 00087 ros::Time trig_time_; 00088 00089 // ROS messages 00090 sensor_msgs::Image img_; 00091 sensor_msgs::CameraInfo cam_info_; 00092 00093 // Dynamic reconfigure 00094 typedef prosilica_camera::ProsilicaCameraConfig Config; 00095 typedef dynamic_reconfigure::Server<Config> ReconfigureServer; 00096 ReconfigureServer reconfigure_server_; 00097 00098 // Diagnostics 00099 ros::Timer diagnostic_timer_; 00100 boost::shared_ptr<self_test::TestRunner> self_test_; 00101 diagnostic_updater::Updater diagnostic_; 00102 std::string hw_id_; 00103 int count_; 00104 double desired_freq_; 00105 static const int WINDOW_SIZE = 5; // remember previous 5s 00106 unsigned long frames_dropped_total_, frames_completed_total_; 00107 RollingSum<unsigned long> frames_dropped_acc_, frames_completed_acc_; 00108 unsigned long packets_missed_total_, packets_received_total_; 00109 RollingSum<unsigned long> packets_missed_acc_, packets_received_acc_; 00110 00111 // So we don't get burned by auto-exposure 00112 unsigned long last_exposure_value_; 00113 int consecutive_stable_exposures_; 00114 00115 public: 00116 ProsilicaNode(const ros::NodeHandle& node_handle) 00117 : nh_(node_handle), 00118 it_(nh_), 00119 cam_(NULL), running_(false), auto_adjust_stream_bytes_per_second_(false), 00120 count_(0), 00121 frames_dropped_total_(0), frames_completed_total_(0), 00122 frames_dropped_acc_(WINDOW_SIZE), 00123 frames_completed_acc_(WINDOW_SIZE), 00124 packets_missed_total_(0), packets_received_total_(0), 00125 packets_missed_acc_(WINDOW_SIZE), 00126 packets_received_acc_(WINDOW_SIZE) 00127 { 00128 // Two-stage initialization: in the constructor we open the requested camera. Most 00129 // parameters controlling capture are set and streaming started in configure(), the 00130 // callback to dynamic_reconfig. 00131 prosilica::init(); 00132 00133 if (prosilica::numCameras() == 0) 00134 ROS_WARN("Found no cameras on local subnet"); 00135 00136 // Determine which camera to use. Opening by IP address is preferred, then guid. If both 00137 // parameters are set we open by IP and verify the guid. If neither are set we default 00138 // to opening the first available camera. 00139 ros::NodeHandle local_nh("~"); 00140 unsigned long guid = 0; 00141 std::string guid_str; 00142 if (local_nh.getParam("guid", guid_str) && !guid_str.empty()) 00143 guid = strtol(guid_str.c_str(), NULL, 0); 00144 00145 std::string ip_str; 00146 if (local_nh.getParam("ip_address", ip_str) && !ip_str.empty()) { 00147 cam_.reset( new prosilica::Camera(ip_str.c_str()) ); 00148 00149 // Verify guid is the one expected 00150 unsigned long cam_guid = cam_->guid(); 00151 if (guid != 0 && guid != cam_guid) 00152 throw prosilica::ProsilicaException(ePvErrBadParameter, 00153 "guid does not match expected"); 00154 guid = cam_guid; 00155 } 00156 else { 00157 if (guid == 0) guid = prosilica::getGuid(0); 00158 cam_.reset( new prosilica::Camera(guid) ); 00159 } 00160 hw_id_ = boost::lexical_cast<std::string>(guid); 00161 ROS_INFO("Found camera, guid = %s", hw_id_.c_str()); 00162 diagnostic_.setHardwareID(hw_id_); 00163 00164 // Record some attributes of the camera 00165 tPvUint32 dummy; 00166 PvAttrRangeUint32(cam_->handle(), "Width", &dummy, &sensor_width_); 00167 PvAttrRangeUint32(cam_->handle(), "Height", &dummy, &sensor_height_); 00168 00169 // Try to load intrinsics from on-camera memory. 00170 loadIntrinsics(); 00171 00172 // Set up self tests and diagnostics. 00173 // NB: Need to wait until here to construct self_test_, otherwise an exception 00174 // above from failing to find the camera gives bizarre backtraces 00175 // (http://answers.ros.org/question/430/trouble-with-prosilica_camera-pvapi). 00176 self_test_.reset(new self_test::TestRunner); 00177 self_test_->add( "Info Test", this, &ProsilicaNode::infoTest ); 00178 self_test_->add( "Attribute Test", this, &ProsilicaNode::attributeTest ); 00179 self_test_->add( "Image Test", this, &ProsilicaNode::imageTest ); 00180 00181 diagnostic_.add( "Frequency Status", this, &ProsilicaNode::freqStatus ); 00182 diagnostic_.add( "Frame Statistics", this, &ProsilicaNode::frameStatistics ); 00183 diagnostic_.add( "Packet Statistics", this, &ProsilicaNode::packetStatistics ); 00184 diagnostic_.add( "Packet Error Status", this, &ProsilicaNode::packetErrorStatus ); 00185 00186 diagnostic_timer_ = nh_.createTimer(ros::Duration(0.1), boost::bind(&ProsilicaNode::runDiagnostics, this)); 00187 00188 // Service call for setting calibration. 00189 set_camera_info_srv_ = nh_.advertiseService("set_camera_info", &ProsilicaNode::setCameraInfo, this); 00190 00191 // Start dynamic_reconfigure 00192 reconfigure_server_.setCallback(boost::bind(&ProsilicaNode::configure, this, _1, _2)); 00193 } 00194 00195 void configure(Config& config, uint32_t level) 00196 { 00197 ROS_DEBUG("Reconfigure request received"); 00198 00199 if (level >= (uint32_t)driver_base::SensorLevels::RECONFIGURE_STOP) 00200 stop(); 00201 00202 // Trigger mode 00203 if (config.trigger_mode == "streaming") { 00204 trigger_mode_ = prosilica::Freerun; 00206 desired_freq_ = 1; // make sure we get _something_ 00207 } 00208 else if (config.trigger_mode == "syncin1") { 00209 trigger_mode_ = prosilica::SyncIn1; 00210 desired_freq_ = config.trig_rate; 00211 } 00212 else if (config.trigger_mode == "syncin2") { 00213 trigger_mode_ = prosilica::SyncIn2; 00214 desired_freq_ = config.trig_rate; 00215 } 00216 #if 0 00217 else if (config.trigger_mode == "fixedrate") { 00218 ROS_DEBUG("Fixed rate not supported yet implementing software"); 00219 trigger_mode_ = prosilica::Software; 00221 desired_freq_ = 0; 00222 } 00223 #endif 00224 else if (config.trigger_mode == "polled") { 00225 trigger_mode_ = prosilica::Software; 00226 desired_freq_ = 0; 00227 } 00228 else { 00229 ROS_ERROR("Invalid trigger mode '%s' in reconfigure request", config.trigger_mode.c_str()); 00230 } 00231 trig_timestamp_topic_ = config.trig_timestamp_topic; 00232 00233 // Exposure 00234 if (config.auto_exposure) 00235 { 00236 cam_->setExposure(0, prosilica::Auto); 00237 } 00238 else { 00239 unsigned us = config.exposure*1000000. + 0.5; 00240 cam_->setExposure(us, prosilica::Manual); 00241 } 00242 00243 // Gain 00244 if (config.auto_gain) { 00245 if (cam_->hasAttribute("GainAutoMax")) 00246 { 00247 cam_->setGain(0, prosilica::Auto); 00248 } 00249 else { 00250 tPvUint32 major, minor; 00251 cam_->getAttribute("FirmwareVerMajor", major); 00252 cam_->getAttribute("FirmwareVerMinor", minor); 00253 ROS_WARN("Auto gain not available for this camera. Auto gain is available " 00254 "on firmware versions 1.36 and above. You are running version %u.%u.", 00255 (unsigned)major, (unsigned)minor); 00256 config.auto_gain = false; 00257 } 00258 } 00259 else 00260 cam_->setGain(config.gain, prosilica::Manual); 00261 00262 // White balance 00263 if (config.auto_whitebalance) { 00264 if (cam_->hasAttribute("WhitebalMode")) 00265 cam_->setWhiteBalance(0, 0, prosilica::Auto); 00266 else { 00267 ROS_WARN("Auto white balance not available for this camera."); 00268 config.auto_whitebalance = false; 00269 } 00270 } 00271 else 00272 cam_->setWhiteBalance(config.whitebalance_blue, config.whitebalance_red, prosilica::Manual); 00273 00274 // Binning configuration 00275 if (cam_->hasAttribute("BinningX")) { 00276 tPvUint32 max_binning_x, max_binning_y, dummy; 00277 PvAttrRangeUint32(cam_->handle(), "BinningX", &dummy, &max_binning_x); 00278 PvAttrRangeUint32(cam_->handle(), "BinningY", &dummy, &max_binning_y); 00279 config.binning_x = std::min(config.binning_x, (int)max_binning_x); 00280 config.binning_y = std::min(config.binning_y, (int)max_binning_y); 00281 00282 cam_->setBinning(config.binning_x, config.binning_y); 00283 } 00284 else if (config.binning_x > 1 || config.binning_y > 1) 00285 { 00286 ROS_WARN("Binning not available for this camera."); 00287 config.binning_x = config.binning_y = 1; 00288 } 00289 00290 // Region of interest configuration 00291 // Make sure ROI fits in image 00292 config.x_offset = std::min(config.x_offset, (int)sensor_width_ - 1); 00293 config.y_offset = std::min(config.y_offset, (int)sensor_height_ - 1); 00294 config.width = std::min(config.width, (int)sensor_width_ - config.x_offset); 00295 config.height = std::min(config.height, (int)sensor_height_ - config.y_offset); 00296 // If width or height is 0, set it as large as possible 00297 int width = config.width ? config.width : sensor_width_ - config.x_offset; 00298 int height = config.height ? config.height : sensor_height_ - config.y_offset; 00299 00300 // Adjust full-res ROI to binning ROI 00302 int x_offset = config.x_offset / config.binning_x; 00303 int y_offset = config.y_offset / config.binning_y; 00304 unsigned int right_x = (config.x_offset + width + config.binning_x - 1) / config.binning_x; 00305 unsigned int bottom_y = (config.y_offset + height + config.binning_y - 1) / config.binning_y; 00306 // Rounding up is bad when at max resolution which is not divisible by the amount of binning 00307 right_x = std::min(right_x, (unsigned)(sensor_width_ / config.binning_x)); 00308 bottom_y = std::min(bottom_y, (unsigned)(sensor_height_ / config.binning_y)); 00309 width = right_x - x_offset; 00310 height = bottom_y - y_offset; 00311 00312 cam_->setRoi(x_offset, y_offset, width, height); 00313 00314 // TF frame 00315 img_.header.frame_id = cam_info_.header.frame_id = config.frame_id; 00316 00317 // Normally the node adjusts the bandwidth used by the camera during diagnostics, to use as 00318 // much as possible without dropping packets. But this can create interference if two 00319 // cameras are on the same switch, e.g. for stereo. So we allow the user to set the bandwidth 00320 // directly. 00321 auto_adjust_stream_bytes_per_second_ = config.auto_adjust_stream_bytes_per_second; 00322 if (!auto_adjust_stream_bytes_per_second_) 00323 cam_->setAttribute("StreamBytesPerSecond", (tPvUint32)config.stream_bytes_per_second); 00324 00326 if (level >= (uint32_t)driver_base::SensorLevels::RECONFIGURE_STOP) 00327 start(); 00328 } 00329 00330 ~ProsilicaNode() 00331 { 00332 stop(); 00333 cam_.reset(); // must destroy Camera before calling prosilica::fini 00334 prosilica::fini(); 00335 } 00336 00337 void syncInCallback (const std_msgs::HeaderConstPtr& msg) 00338 { 00340 trig_time_ = msg->stamp; 00341 } 00342 00344 00345 void start() 00346 { 00347 if (running_) return; 00348 00349 if (trigger_mode_ == prosilica::Software) { 00350 poll_srv_ = polled_camera::advertise(nh_, "request_image", &ProsilicaNode::pollCallback, this); 00351 // Auto-exposure tends to go wild the first few frames after startup 00352 // if (auto_expose) normalizeExposure(); 00353 } 00354 else { 00355 if ((trigger_mode_ == prosilica::SyncIn1) || (trigger_mode_ == prosilica::SyncIn2)) { 00356 if (!trig_timestamp_topic_.empty()) 00357 trigger_sub_ = nh_.subscribe(trig_timestamp_topic_, 1, &ProsilicaNode::syncInCallback, this); 00358 } 00359 else { 00360 assert(trigger_mode_ == prosilica::Freerun); 00361 } 00362 cam_->setFrameCallback(boost::bind(&ProsilicaNode::publishImage, this, _1)); 00363 streaming_pub_ = it_.advertiseCamera("image_raw", 1); 00364 } 00365 cam_->start(trigger_mode_, prosilica::Continuous); 00366 running_ = true; 00367 } 00368 00369 void stop() 00370 { 00371 if (!running_) return; 00372 00373 cam_->stop(); // Must stop camera before streaming_pub_. 00374 poll_srv_.shutdown(); 00375 trigger_sub_.shutdown(); 00376 streaming_pub_.shutdown(); 00377 00378 running_ = false; 00379 } 00380 00381 void pollCallback(polled_camera::GetPolledImage::Request& req, 00382 polled_camera::GetPolledImage::Response& rsp, 00383 sensor_msgs::Image& image, sensor_msgs::CameraInfo& info) 00384 { 00385 if (trigger_mode_ != prosilica::Software) { 00386 rsp.success = false; 00387 rsp.status_message = "Camera is not in software triggered mode"; 00388 return; 00389 } 00390 00391 tPvFrame* frame = NULL; 00392 00393 try { 00394 cam_->setBinning(req.binning_x, req.binning_y); 00395 00396 if (req.roi.x_offset || req.roi.y_offset || req.roi.width || req.roi.height) { 00397 // GigE cameras use ROI in binned coordinates, so scale the values down. 00398 // The ROI is expanded if necessary to land on binned coordinates. 00399 unsigned int left_x = req.roi.x_offset / req.binning_x; 00400 unsigned int top_y = req.roi.y_offset / req.binning_y; 00401 unsigned int right_x = (req.roi.x_offset + req.roi.width + req.binning_x - 1) / req.binning_x; 00402 unsigned int bottom_y = (req.roi.y_offset + req.roi.height + req.binning_y - 1) / req.binning_y; 00403 unsigned int width = right_x - left_x; 00404 unsigned int height = bottom_y - top_y; 00405 cam_->setRoi(left_x, top_y, width, height); 00406 } else { 00407 cam_->setRoiToWholeFrame(); 00408 } 00409 00410 // Zero duration means "no timeout" 00411 unsigned long timeout = req.timeout.isZero() ? PVINFINITE : req.timeout.toNSec() / 1e6; 00412 frame = cam_->grab(timeout); 00413 } 00414 catch (prosilica::ProsilicaException &e) { 00415 if (e.error_code == ePvErrBadSequence) 00416 throw; // not easily recoverable 00417 00418 rsp.success = false; 00419 rsp.status_message = (boost::format("Prosilica exception: %s") % e.what()).str(); 00420 return; 00421 } 00422 00423 if (!frame) { 00425 rsp.success = false; 00426 rsp.status_message = "Failed to capture frame, may have timed out"; 00427 return; 00428 } 00429 00430 info = cam_info_; 00431 image.header.frame_id = img_.header.frame_id; 00432 if (!processFrame(frame, image, info)) { 00433 rsp.success = false; 00434 rsp.status_message = "Captured frame but failed to process it"; 00435 return; 00436 } 00437 info.roi.do_rectify = req.roi.do_rectify; // do_rectify should be preserved from request 00438 00439 rsp.success = true; 00440 } 00441 00442 static bool frameToImage(tPvFrame* frame, sensor_msgs::Image &image) 00443 { 00444 // NOTE: 16-bit and Yuv formats not supported 00445 static const char* BAYER_ENCODINGS[] = { "bayer_rggb8", "bayer_gbrg8", "bayer_grbg8", "bayer_bggr8" }; 00446 00447 std::string encoding; 00448 if (frame->Format == ePvFmtMono8) encoding = sensor_msgs::image_encodings::MONO8; 00449 else if (frame->Format == ePvFmtBayer8) 00450 { 00451 #if 1 00452 encoding = BAYER_ENCODINGS[frame->BayerPattern]; 00453 #else 00454 image.encoding = sensor_msgs::image_encodings::BGR8; 00455 image.height = frame->Height; 00456 image.width = frame->Width; 00457 image.step = frame->Width * 3; 00458 image.data.resize(frame->Height * (frame->Width * 3)); 00459 PvUtilityColorInterpolate(frame, &image.data[2], &image.data[1], &image.data[0], 2, 0); 00460 return true; 00461 #endif 00462 } 00463 else if (frame->Format == ePvFmtRgb24) encoding = sensor_msgs::image_encodings::RGB8; 00464 else if (frame->Format == ePvFmtBgr24) encoding = sensor_msgs::image_encodings::BGR8; 00465 else if (frame->Format == ePvFmtRgba32) encoding = sensor_msgs::image_encodings::RGBA8; 00466 else if (frame->Format == ePvFmtBgra32) encoding = sensor_msgs::image_encodings::BGRA8; 00467 else { 00468 ROS_WARN("Received frame with unsupported pixel format %d", frame->Format); 00469 return false; 00470 } 00471 00472 uint32_t step = frame->ImageSize / frame->Height; 00473 return sensor_msgs::fillImage(image, encoding, frame->Height, frame->Width, step, frame->ImageBuffer); 00474 } 00475 00476 bool processFrame(tPvFrame* frame, sensor_msgs::Image &img, sensor_msgs::CameraInfo &cam_info) 00477 { 00479 if ((trigger_mode_ == prosilica::SyncIn1 || trigger_mode_ == prosilica::SyncIn2) && !trig_time_.isZero()) { 00480 img.header.stamp = cam_info.header.stamp = trig_time_; 00481 trig_time_ = ros::Time(); // Zero 00482 } 00483 else { 00485 img.header.stamp = cam_info.header.stamp = ros::Time::now(); 00486 } 00487 00491 tPvUint32 binning_x = 1, binning_y = 1; 00492 if (cam_->hasAttribute("BinningX")) { 00493 cam_->getAttribute("BinningX", binning_x); 00494 cam_->getAttribute("BinningY", binning_y); 00495 } 00496 // Binning averages bayer samples, so just call it mono8 in that case 00497 if (frame->Format == ePvFmtBayer8 && (binning_x > 1 || binning_y > 1)) 00498 frame->Format = ePvFmtMono8; 00499 00500 if (!frameToImage(frame, img)) 00501 return false; 00502 00503 // Set the operational parameters in CameraInfo (binning, ROI) 00504 cam_info.binning_x = binning_x; 00505 cam_info.binning_y = binning_y; 00506 // ROI in CameraInfo is in unbinned coordinates, need to scale up 00507 cam_info.roi.x_offset = frame->RegionX * binning_x; 00508 cam_info.roi.y_offset = frame->RegionY * binning_y; 00509 cam_info.roi.height = frame->Height * binning_y; 00510 cam_info.roi.width = frame->Width * binning_x; 00511 cam_info.roi.do_rectify = (frame->Height != sensor_height_ / binning_y) || 00512 (frame->Width != sensor_width_ / binning_x); 00513 00514 count_++; 00515 return true; 00516 } 00517 00518 void publishImage(tPvFrame* frame) 00519 { 00520 if (processFrame(frame, img_, cam_info_)) 00521 streaming_pub_.publish(img_, cam_info_); 00522 } 00523 00524 void loadIntrinsics() 00525 { 00526 // Retrieve contents of user memory 00527 std::string buffer(prosilica::Camera::USER_MEMORY_SIZE, '\0'); 00528 cam_->readUserMemory(&buffer[0], prosilica::Camera::USER_MEMORY_SIZE); 00529 00530 // Parse calibration file 00531 std::string camera_name; 00532 if (camera_calibration_parsers::parseCalibrationIni(buffer, camera_name, cam_info_)) 00533 ROS_INFO("Loaded calibration for camera '%s'", camera_name.c_str()); 00534 else 00535 ROS_WARN("Failed to load intrinsics from camera"); 00536 } 00537 00538 bool setCameraInfo(sensor_msgs::SetCameraInfo::Request& req, 00539 sensor_msgs::SetCameraInfo::Response& rsp) 00540 { 00541 ROS_INFO("New camera info received"); 00542 sensor_msgs::CameraInfo &info = req.camera_info; 00543 00544 // Sanity check: the image dimensions should match the max resolution of the sensor. 00545 tPvUint32 width, height, dummy; 00546 PvAttrRangeUint32(cam_->handle(), "Width", &dummy, &width); 00547 PvAttrRangeUint32(cam_->handle(), "Height", &dummy, &height); 00548 if (info.width != width || info.height != height) { 00549 rsp.success = false; 00550 rsp.status_message = (boost::format("Camera_info resolution %ix%i does not match current video " 00551 "setting, camera running at resolution %ix%i.") 00552 % info.width % info.height % width % height).str(); 00553 ROS_ERROR("%s", rsp.status_message.c_str()); 00554 return true; 00555 } 00556 00557 stop(); 00558 00559 std::string cam_name = "prosilica"; 00560 cam_name += hw_id_; 00561 std::stringstream ini_stream; 00562 if (!camera_calibration_parsers::writeCalibrationIni(ini_stream, cam_name, info)) { 00563 rsp.status_message = "Error formatting camera_info for storage."; 00564 rsp.success = false; 00565 } 00566 else { 00567 std::string ini = ini_stream.str(); 00568 if (ini.size() > prosilica::Camera::USER_MEMORY_SIZE) { 00569 rsp.success = false; 00570 rsp.status_message = "Unable to write camera_info to camera memory, exceeded storage capacity."; 00571 } 00572 else { 00573 try { 00574 cam_->writeUserMemory(ini.c_str(), ini.size()); 00575 cam_info_ = info; 00576 rsp.success = true; 00577 } 00578 catch (prosilica::ProsilicaException &e) { 00579 rsp.success = false; 00580 rsp.status_message = e.what(); 00581 } 00582 } 00583 } 00584 if (!rsp.success) 00585 ROS_ERROR("%s", rsp.status_message.c_str()); 00586 00587 start(); 00588 00589 return true; 00590 } 00591 00592 void normalizeCallback(tPvFrame* frame) 00593 { 00594 unsigned long exposure; 00595 cam_->getAttribute("ExposureValue", exposure); 00596 //ROS_WARN("Exposure value = %u", exposure); 00597 00598 if (exposure == last_exposure_value_) 00599 consecutive_stable_exposures_++; 00600 else { 00601 last_exposure_value_ = exposure; 00602 consecutive_stable_exposures_ = 0; 00603 } 00604 } 00605 00606 void normalizeExposure() 00607 { 00608 ROS_INFO("Normalizing exposure"); 00610 00611 last_exposure_value_ = 0; 00612 consecutive_stable_exposures_ = 0; 00613 cam_->setFrameCallback(boost::bind(&ProsilicaNode::normalizeCallback, this, _1)); 00614 cam_->start(prosilica::Freerun); 00615 00617 while (consecutive_stable_exposures_ < 3) 00618 boost::this_thread::sleep(boost::posix_time::millisec(250)); 00619 00620 cam_->stop(); 00621 } 00622 00624 // Diagnostics // 00626 00627 void runDiagnostics() 00628 { 00629 self_test_->checkTest(); 00630 diagnostic_.update(); 00631 } 00632 00633 void freqStatus(diagnostic_updater::DiagnosticStatusWrapper& status) 00634 { 00635 double freq = (double)(count_)/diagnostic_.getPeriod(); 00636 00637 if (freq < (.9*desired_freq_)) 00638 { 00639 status.summary(2, "Desired frequency not met"); 00640 } 00641 else 00642 { 00643 status.summary(0, "Desired frequency met"); 00644 } 00645 00646 status.add("Images in interval", count_); 00647 status.add("Desired frequency", desired_freq_); 00648 status.add("Actual frequency", freq); 00649 00650 count_ = 0; 00651 } 00652 00653 void frameStatistics(diagnostic_updater::DiagnosticStatusWrapper& status) 00654 { 00655 // Get stats from camera driver 00656 float frame_rate; 00657 unsigned long completed, dropped; 00658 cam_->getAttribute("StatFrameRate", frame_rate); 00659 cam_->getAttribute("StatFramesCompleted", completed); 00660 cam_->getAttribute("StatFramesDropped", dropped); 00661 00662 // Compute rolling totals, percentages 00663 frames_completed_acc_.add(completed - frames_completed_total_); 00664 frames_completed_total_ = completed; 00665 unsigned long completed_recent = frames_completed_acc_.sum(); 00666 00667 frames_dropped_acc_.add(dropped - frames_dropped_total_); 00668 frames_dropped_total_ = dropped; 00669 unsigned long dropped_recent = frames_dropped_acc_.sum(); 00670 00671 float recent_ratio = float(completed_recent) / (completed_recent + dropped_recent); 00672 float total_ratio = float(completed) / (completed + dropped); 00673 00674 // Set level based on recent % completed frames 00675 if (dropped_recent == 0) { 00676 status.summary(0, "No dropped frames"); 00677 } 00678 else if (recent_ratio > 0.8f) { 00679 status.summary(1, "Some dropped frames"); 00680 } 00681 else { 00682 status.summary(2, "Excessive proportion of dropped frames"); 00683 } 00684 00685 status.add("Camera Frame Rate", frame_rate); 00686 status.add("Recent % Frames Completed", recent_ratio * 100.0f); 00687 status.add("Overall % Frames Completed", total_ratio * 100.0f); 00688 status.add("Frames Completed", completed); 00689 status.add("Frames Dropped", dropped); 00690 } 00691 00692 void packetStatistics(diagnostic_updater::DiagnosticStatusWrapper& status) 00693 { 00694 // Get stats from camera driver 00695 unsigned long received, missed, requested, resent; 00696 cam_->getAttribute("StatPacketsReceived", received); 00697 cam_->getAttribute("StatPacketsMissed", missed); 00698 cam_->getAttribute("StatPacketsRequested", requested); 00699 cam_->getAttribute("StatPacketsResent", resent); 00700 00701 // Compute rolling totals, percentages 00702 packets_received_acc_.add(received - packets_received_total_); 00703 packets_received_total_ = received; 00704 unsigned long received_recent = packets_received_acc_.sum(); 00705 00706 packets_missed_acc_.add(missed - packets_missed_total_); 00707 packets_missed_total_ = missed; 00708 unsigned long missed_recent = packets_missed_acc_.sum(); 00709 00710 float recent_ratio = float(received_recent) / (received_recent + missed_recent); 00711 float total_ratio = float(received) / (received + missed); 00712 00713 if (missed_recent == 0) { 00714 status.summary(0, "No missed packets"); 00715 } 00716 else if (recent_ratio > 0.99f) { 00717 status.summary(1, "Some missed packets"); 00718 } 00719 else { 00720 status.summary(2, "Excessive proportion of missed packets"); 00721 } 00722 00723 // Adjust data rate 00724 unsigned long data_rate = 0; 00725 cam_->getAttribute("StreamBytesPerSecond", data_rate); 00726 unsigned long max_data_rate = cam_->getMaxDataRate(); 00727 00728 if (auto_adjust_stream_bytes_per_second_) 00729 { 00730 if (max_data_rate < prosilica::Camera::GIGE_MAX_DATA_RATE) 00731 status.mergeSummary(1, "Max data rate is lower than expected for a GigE port"); 00732 00733 try 00734 { 00736 float multiplier = 1.0f; 00737 if (recent_ratio == 1.0f) 00738 { 00739 multiplier = 1.1f; 00740 } 00741 else if (recent_ratio < 0.99f) 00742 { 00743 multiplier = 0.9f; 00744 } 00745 if (multiplier != 1.0f) 00746 { 00747 unsigned long new_data_rate = std::min((unsigned long)(multiplier * data_rate + 0.5), max_data_rate); 00748 new_data_rate = std::max(new_data_rate, max_data_rate/1000); 00749 if (data_rate != new_data_rate) 00750 { 00751 data_rate = new_data_rate; 00752 cam_->setAttribute("StreamBytesPerSecond", data_rate); 00753 ROS_DEBUG("Changed data rate to %lu bytes per second", data_rate); 00754 } 00755 } 00756 } 00757 catch (prosilica::ProsilicaException &e) 00758 { 00759 if (e.error_code == ePvErrUnplugged) 00760 throw; 00761 ROS_ERROR("Exception occurred: '%s'\n" 00762 "Possible network issue. Attempting to reset data rate to the current maximum.", 00763 e.what()); 00764 data_rate = max_data_rate; 00765 cam_->setAttribute("StreamBytesPerSecond", data_rate); 00766 } 00767 } 00768 00769 status.add("Recent % Packets Received", recent_ratio * 100.0f); 00770 status.add("Overall % Packets Received", total_ratio * 100.0f); 00771 status.add("Received Packets", received); 00772 status.add("Missed Packets", missed); 00773 status.add("Requested Packets", requested); 00774 status.add("Resent Packets", resent); 00775 status.add("Data Rate (bytes/s)", data_rate); 00776 status.add("Max Data Rate (bytes/s)", max_data_rate); 00777 } 00778 00779 void packetErrorStatus(diagnostic_updater::DiagnosticStatusWrapper& status) 00780 { 00781 unsigned long erroneous; 00782 cam_->getAttribute("StatPacketsErroneous", erroneous); 00783 00784 if (erroneous == 0) { 00785 status.summary(0, "No erroneous packets"); 00786 } else { 00787 status.summary(2, "Possible camera hardware failure"); 00788 } 00789 00790 status.add("Erroneous Packets", erroneous); 00791 } 00792 00794 // Self tests // 00796 00797 // Try to load camera name, etc. Should catch gross communication failure. 00798 void infoTest(diagnostic_updater::DiagnosticStatusWrapper& status) 00799 { 00800 status.name = "Info Test"; 00801 00802 self_test_->setID(hw_id_); 00803 00804 std::string camera_name; 00805 try { 00806 cam_->getAttribute("CameraName", camera_name); 00807 status.summary(0, "Connected to Camera"); 00808 status.add("Camera Name", camera_name); 00809 } 00810 catch (prosilica::ProsilicaException& e) { 00811 status.summary(2, e.what()); 00812 } 00813 } 00814 00815 // Test validity of all attribute values. 00816 void attributeTest(diagnostic_updater::DiagnosticStatusWrapper& status) 00817 { 00818 status.name = "Attribute Test"; 00819 00820 tPvAttrListPtr list_ptr; 00821 unsigned long list_length; 00822 00823 if (PvAttrList(cam_->handle(), &list_ptr, &list_length) == ePvErrSuccess) { 00824 status.summary(0, "All attributes in valid range"); 00825 for (unsigned int i = 0; i < list_length; ++i) { 00826 const char* attribute = list_ptr[i]; 00827 tPvErr e = PvAttrIsValid(cam_->handle(), attribute); 00828 if (e != ePvErrSuccess) { 00829 status.summary(2, "One or more invalid attributes"); 00830 if (e == ePvErrOutOfRange) 00831 status.add(attribute, "Out of range"); 00832 else if (e == ePvErrNotFound) 00833 status.add(attribute, "Does not exist"); 00834 else 00835 status.addf(attribute, "Unexpected error code %u", e); 00836 } 00837 } 00838 } 00839 else { 00840 status.summary(2, "Unable to retrieve attribute list"); 00841 } 00842 } 00843 00844 // Try to capture an image. 00845 void imageTest(diagnostic_updater::DiagnosticStatusWrapper& status) 00846 { 00847 status.name = "Image Capture Test"; 00848 00849 try { 00850 if (trigger_mode_ != prosilica::Software) { 00851 tPvUint32 start_completed, current_completed; 00852 cam_->getAttribute("StatFramesCompleted", start_completed); 00853 for (int i = 0; i < 6; ++i) { 00854 boost::this_thread::sleep(boost::posix_time::millisec(500)); 00855 cam_->getAttribute("StatFramesCompleted", current_completed); 00856 if (current_completed > start_completed) { 00857 status.summary(0, "Captured a frame, see diagnostics for detailed stats"); 00858 return; 00859 } 00860 } 00861 00862 // Give up after 3s 00863 status.summary(2, "No frames captured over 3s in freerun mode"); 00864 return; 00865 } 00866 00867 // In software triggered mode, try to grab a frame 00868 cam_->setRoiToWholeFrame(); 00869 tPvFrame* frame = cam_->grab(500); 00870 if (frame) 00871 { 00872 status.summary(0, "Successfully triggered a frame capture"); 00873 } 00874 else 00875 { 00876 status.summary(2, "Attempted to grab a frame, but received NULL"); 00877 } 00878 00879 } 00880 catch (prosilica::ProsilicaException &e) { 00881 status.summary(2, e.what()); 00882 } 00883 } 00884 }; 00885 00886 int main(int argc, char **argv) 00887 { 00888 ros::init(argc, argv, "prosilica_driver"); 00889 00890 ros::NodeHandle nh("camera"); 00891 ProsilicaNode pn(nh); 00892 ros::spin(); 00893 00894 return 0; 00895 }