00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
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
00047 #include <diagnostic_updater/diagnostic_updater.h>
00048 #include <diagnostic_updater/DiagnosticStatusWrapper.h>
00049 #include <self_test/self_test.h>
00050
00051
00052 #include <dynamic_reconfigure/server.h>
00053 #include <driver_base/SensorLevels.h>
00054 #include "prosilica_camera/ProsilicaCameraConfig.h"
00055
00056
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
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_;
00083 tPvUint32 max_binning_x_, max_binning_y_;
00084
00085
00086 std::string trig_timestamp_topic_;
00087 ros::Time trig_time_;
00088
00089
00090 sensor_msgs::Image img_;
00091 sensor_msgs::CameraInfo cam_info_;
00092
00093
00094 typedef prosilica_camera::ProsilicaCameraConfig Config;
00095 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00096 ReconfigureServer reconfigure_server_;
00097
00098
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;
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
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),
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
00129
00130
00131 prosilica::init();
00132
00133 if (prosilica::numCameras() == 0)
00134 ROS_WARN("Found no cameras on local subnet");
00135
00136
00137
00138
00139 ros::NodeHandle local_nh("~");
00140 unsigned long guid = 0;
00141 std::string guid_str;
00142 if (local_nh.getParam("guid", guid_str))
00143 guid = strtol(guid_str.c_str(), NULL, 0);
00144
00145 std::string ip_str;
00146 if (local_nh.getParam("ip_address", ip_str)) {
00147 cam_.reset( new prosilica::Camera(ip_str.c_str()) );
00148
00149
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
00165 tPvUint32 dummy;
00166 PvAttrRangeUint32(cam_->handle(), "Width", &dummy, &sensor_width_);
00167 PvAttrRangeUint32(cam_->handle(), "Height", &dummy, &sensor_height_);
00168 PvAttrRangeUint32(cam_->handle(), "BinningX", &dummy, &max_binning_x_);
00169 PvAttrRangeUint32(cam_->handle(), "BinningY", &dummy, &max_binning_y_);
00170
00171
00172 loadIntrinsics();
00173
00174
00175
00176
00177
00178 self_test_.reset(new self_test::TestRunner);
00179 self_test_->add( "Info Test", this, &ProsilicaNode::infoTest );
00180 self_test_->add( "Attribute Test", this, &ProsilicaNode::attributeTest );
00181 self_test_->add( "Image Test", this, &ProsilicaNode::imageTest );
00182
00183 diagnostic_.add( "Frequency Status", this, &ProsilicaNode::freqStatus );
00184 diagnostic_.add( "Frame Statistics", this, &ProsilicaNode::frameStatistics );
00185 diagnostic_.add( "Packet Statistics", this, &ProsilicaNode::packetStatistics );
00186 diagnostic_.add( "Packet Error Status", this, &ProsilicaNode::packetErrorStatus );
00187
00188 diagnostic_timer_ = nh_.createTimer(ros::Duration(0.1), boost::bind(&ProsilicaNode::runDiagnostics, this));
00189
00190
00191 set_camera_info_srv_ = nh_.advertiseService("set_camera_info", &ProsilicaNode::setCameraInfo, this);
00192
00193
00194 reconfigure_server_.setCallback(boost::bind(&ProsilicaNode::configure, this, _1, _2));
00195 }
00196
00197 void configure(Config& config, uint32_t level)
00198 {
00199 ROS_DEBUG("Reconfigure request received");
00200
00201 if (level >= (uint32_t)driver_base::SensorLevels::RECONFIGURE_STOP)
00202 stop();
00203
00204
00205 if (config.trigger_mode == "streaming") {
00206 trigger_mode_ = prosilica::Freerun;
00208 desired_freq_ = 1;
00209 }
00210 else if (config.trigger_mode == "syncin1") {
00211 trigger_mode_ = prosilica::SyncIn1;
00212 desired_freq_ = config.trig_rate;
00213 }
00214 else if (config.trigger_mode == "syncin2") {
00215 trigger_mode_ = prosilica::SyncIn2;
00216 desired_freq_ = config.trig_rate;
00217 }
00218 #if 0
00219 else if (config.trigger_mode == "fixedrate") {
00220 ROS_DEBUG("Fixed rate not supported yet implementing software");
00221 trigger_mode_ = prosilica::Software;
00223 desired_freq_ = 0;
00224 }
00225 #endif
00226 else if (config.trigger_mode == "polled") {
00227 trigger_mode_ = prosilica::Software;
00228 desired_freq_ = 0;
00229 }
00230 else {
00231 ROS_ERROR("Invalid trigger mode '%s' in reconfigure request", config.trigger_mode.c_str());
00232 }
00233 trig_timestamp_topic_ = config.trig_timestamp_topic;
00234
00235
00236 if (config.auto_exposure)
00237 cam_->setExposure(0, prosilica::Auto);
00238 else {
00239 unsigned us = config.exposure*1000000. + 0.5;
00240 cam_->setExposure(us, prosilica::Manual);
00241 }
00242
00243
00244 if (config.auto_gain) {
00245 if (PvAttrIsAvailable(cam_->handle(), "GainMode") == ePvErrSuccess)
00246 cam_->setGain(0, prosilica::Auto);
00247 else {
00248 tPvUint32 major, minor;
00249 cam_->getAttribute("FirmwareVerMajor", major);
00250 cam_->getAttribute("FirmwareVerMinor", minor);
00251 ROS_WARN("Auto gain not available for this camera. Auto gain is available "
00252 "on firmware versions 1.36 and above. You are running version %u.%u.",
00253 (unsigned)major, (unsigned)minor);
00254 config.auto_gain = false;
00255 }
00256 }
00257 else
00258 cam_->setGain(config.gain, prosilica::Manual);
00259
00260
00261 if (config.auto_whitebalance) {
00262 if (PvAttrIsAvailable(cam_->handle(), "WhitebalMode") == ePvErrSuccess)
00263 cam_->setWhiteBalance(0, 0, prosilica::Auto);
00264 else {
00265 ROS_WARN("Auto white balance not available for this camera.");
00266 config.auto_whitebalance = false;
00267 }
00268 }
00269 else
00270 cam_->setWhiteBalance(config.whitebalance_blue, config.whitebalance_red, prosilica::Manual);
00271
00272
00273 config.binning_x = std::min(config.binning_x, (int)max_binning_x_);
00274 config.binning_y = std::min(config.binning_y, (int)max_binning_y_);
00275 int binning_x = config.binning_x, binning_y = config.binning_y;
00276 cam_->setBinning(binning_x, binning_y);
00277
00278
00279
00280 config.x_offset = std::min(config.x_offset, (int)sensor_width_ - 1);
00281 config.y_offset = std::min(config.y_offset, (int)sensor_height_ - 1);
00282 config.width = std::min(config.width, (int)sensor_width_ - config.x_offset);
00283 config.height = std::min(config.height, (int)sensor_height_ - config.y_offset);
00284
00285 int width = config.width ? config.width : sensor_width_ - config.x_offset;
00286 int height = config.height ? config.height : sensor_height_ - config.y_offset;
00287
00288
00290 int x_offset = config.x_offset / binning_x;
00291 int y_offset = config.y_offset / binning_y;
00292 unsigned int right_x = (config.x_offset + width + binning_x - 1) / binning_x;
00293 unsigned int bottom_y = (config.y_offset + height + binning_y - 1) / binning_y;
00294
00295 right_x = std::min(right_x, (unsigned)(sensor_width_ / binning_x));
00296 bottom_y = std::min(bottom_y, (unsigned)(sensor_height_ / binning_y));
00297 width = right_x - x_offset;
00298 height = bottom_y - y_offset;
00299
00300 cam_->setRoi(x_offset, y_offset, width, height);
00301
00302
00303 img_.header.frame_id = cam_info_.header.frame_id = config.frame_id;
00304
00306 if (level >= (uint32_t)driver_base::SensorLevels::RECONFIGURE_STOP)
00307 start();
00308 }
00309
00310 ~ProsilicaNode()
00311 {
00312 stop();
00313 cam_.reset();
00314 prosilica::fini();
00315 }
00316
00317 void syncInCallback (const std_msgs::HeaderConstPtr& msg)
00318 {
00320 trig_time_ = msg->stamp;
00321 }
00322
00324
00325 void start()
00326 {
00327 if (running_) return;
00328
00329 if (trigger_mode_ == prosilica::Software) {
00330 poll_srv_ = polled_camera::advertise(nh_, "request_image", &ProsilicaNode::pollCallback, this);
00331
00332
00333 }
00334 else {
00335 if ((trigger_mode_ == prosilica::SyncIn1) || (trigger_mode_ == prosilica::SyncIn2)) {
00336 if (!trig_timestamp_topic_.empty())
00337 trigger_sub_ = nh_.subscribe(trig_timestamp_topic_, 1, &ProsilicaNode::syncInCallback, this);
00338 }
00339 else {
00340 assert(trigger_mode_ == prosilica::Freerun);
00341 cam_->setFrameCallback(boost::bind(&ProsilicaNode::publishImage, this, _1));
00342 }
00343 streaming_pub_ = it_.advertiseCamera("image_raw", 1);
00344 }
00345 cam_->start(trigger_mode_, prosilica::Continuous);
00346 running_ = true;
00347 }
00348
00349 void stop()
00350 {
00351 if (!running_) return;
00352
00353 cam_->stop();
00354 poll_srv_.shutdown();
00355 trigger_sub_.shutdown();
00356 streaming_pub_.shutdown();
00357
00358 running_ = false;
00359 }
00360
00361 void pollCallback(polled_camera::GetPolledImage::Request& req,
00362 polled_camera::GetPolledImage::Response& rsp,
00363 sensor_msgs::Image& image, sensor_msgs::CameraInfo& info)
00364 {
00365 if (trigger_mode_ != prosilica::Software) {
00366 rsp.success = false;
00367 rsp.status_message = "Camera is not in software triggered mode";
00368 return;
00369 }
00370
00371 tPvFrame* frame = NULL;
00372
00373 try {
00374 cam_->setBinning(req.binning_x, req.binning_y);
00375
00376 if (req.roi.x_offset || req.roi.y_offset || req.roi.width || req.roi.height) {
00377
00378
00379 unsigned int left_x = req.roi.x_offset / req.binning_x;
00380 unsigned int top_y = req.roi.y_offset / req.binning_y;
00381 unsigned int right_x = (req.roi.x_offset + req.roi.width + req.binning_x - 1) / req.binning_x;
00382 unsigned int bottom_y = (req.roi.y_offset + req.roi.height + req.binning_y - 1) / req.binning_y;
00383 unsigned int width = right_x - left_x;
00384 unsigned int height = bottom_y - top_y;
00385 cam_->setRoi(left_x, top_y, width, height);
00386 } else {
00387 cam_->setRoiToWholeFrame();
00388 }
00389
00390
00391 unsigned long timeout = req.timeout.isZero() ? PVINFINITE : req.timeout.toNSec() / 1e6;
00392 frame = cam_->grab(timeout);
00393 }
00394 catch (prosilica::ProsilicaException &e) {
00395 if (e.error_code == ePvErrBadSequence)
00396 throw;
00397
00398 rsp.success = false;
00399 rsp.status_message = (boost::format("Prosilica exception: %s") % e.what()).str();
00400 return;
00401 }
00402
00403 if (!frame) {
00405 rsp.success = false;
00406 rsp.status_message = "Failed to capture frame, may have timed out";
00407 return;
00408 }
00409
00410 info = cam_info_;
00411 image.header.frame_id = img_.header.frame_id;
00412 if (!processFrame(frame, image, info)) {
00413 rsp.success = false;
00414 rsp.status_message = "Captured frame but failed to process it";
00415 return;
00416 }
00417 info.roi.do_rectify = req.roi.do_rectify;
00418
00419 rsp.success = true;
00420 }
00421
00422 static bool frameToImage(tPvFrame* frame, sensor_msgs::Image &image)
00423 {
00424
00425 static const char* BAYER_ENCODINGS[] = { "bayer_rggb8", "bayer_gbrg8", "bayer_grbg8", "bayer_bggr8" };
00426
00427 std::string encoding;
00428 if (frame->Format == ePvFmtMono8) encoding = sensor_msgs::image_encodings::MONO8;
00429 else if (frame->Format == ePvFmtBayer8)
00430 {
00431 #if 1
00432 encoding = BAYER_ENCODINGS[frame->BayerPattern];
00433 #else
00434 image.encoding = sensor_msgs::image_encodings::BGR8;
00435 image.height = frame->Height;
00436 image.width = frame->Width;
00437 image.step = frame->Width * 3;
00438 image.data.resize(frame->Height * (frame->Width * 3));
00439 PvUtilityColorInterpolate(frame, &image.data[2], &image.data[1], &image.data[0], 2, 0);
00440 return true;
00441 #endif
00442 }
00443 else if (frame->Format == ePvFmtRgb24) encoding = sensor_msgs::image_encodings::RGB8;
00444 else if (frame->Format == ePvFmtBgr24) encoding = sensor_msgs::image_encodings::BGR8;
00445 else if (frame->Format == ePvFmtRgba32) encoding = sensor_msgs::image_encodings::RGBA8;
00446 else if (frame->Format == ePvFmtBgra32) encoding = sensor_msgs::image_encodings::BGRA8;
00447 else {
00448 ROS_WARN("Received frame with unsupported pixel format %d", frame->Format);
00449 return false;
00450 }
00451
00452 uint32_t step = frame->ImageSize / frame->Height;
00453 return sensor_msgs::fillImage(image, encoding, frame->Height, frame->Width, step, frame->ImageBuffer);
00454 }
00455
00456 bool processFrame(tPvFrame* frame, sensor_msgs::Image &img, sensor_msgs::CameraInfo &cam_info)
00457 {
00459 if ((trigger_mode_ == prosilica::SyncIn1 || trigger_mode_ == prosilica::SyncIn2) && !trig_time_.isZero()) {
00460 img.header.stamp = cam_info.header.stamp = trig_time_;
00461 trig_time_ = ros::Time();
00462 }
00463 else {
00465 img.header.stamp = cam_info.header.stamp = ros::Time::now();
00466 }
00467
00471 tPvUint32 binning_x, binning_y;
00472 cam_->getAttribute("BinningX", binning_x);
00473 cam_->getAttribute("BinningY", binning_y);
00474
00475 if (frame->Format == ePvFmtBayer8 && (binning_x > 1 || binning_y > 1))
00476 frame->Format = ePvFmtMono8;
00477
00478 if (!frameToImage(frame, img))
00479 return false;
00480
00481
00482 cam_info.binning_x = binning_x;
00483 cam_info.binning_y = binning_y;
00484
00485 cam_info.roi.x_offset = frame->RegionX * binning_x;
00486 cam_info.roi.y_offset = frame->RegionY * binning_y;
00487 cam_info.roi.height = frame->Height * binning_y;
00488 cam_info.roi.width = frame->Width * binning_x;
00489 cam_info.roi.do_rectify = (frame->Height != sensor_height_ / binning_y) ||
00490 (frame->Width != sensor_width_ / binning_x);
00491
00492 count_++;
00493 return true;
00494 }
00495
00496 void publishImage(tPvFrame* frame)
00497 {
00498 if (processFrame(frame, img_, cam_info_))
00499 streaming_pub_.publish(img_, cam_info_);
00500 }
00501
00502 void loadIntrinsics()
00503 {
00504
00505 std::string buffer(prosilica::Camera::USER_MEMORY_SIZE, '\0');
00506 cam_->readUserMemory(&buffer[0], prosilica::Camera::USER_MEMORY_SIZE);
00507
00508
00509 std::string camera_name;
00510 if (camera_calibration_parsers::parseCalibrationIni(buffer, camera_name, cam_info_))
00511 ROS_INFO("Loaded calibration for camera '%s'", camera_name.c_str());
00512 else
00513 ROS_WARN("Failed to load intrinsics from camera");
00514 }
00515
00516 bool setCameraInfo(sensor_msgs::SetCameraInfo::Request& req,
00517 sensor_msgs::SetCameraInfo::Response& rsp)
00518 {
00519 ROS_INFO("New camera info received");
00520 sensor_msgs::CameraInfo &info = req.camera_info;
00521
00522
00523 tPvUint32 width, height, dummy;
00524 PvAttrRangeUint32(cam_->handle(), "Width", &dummy, &width);
00525 PvAttrRangeUint32(cam_->handle(), "Height", &dummy, &height);
00526 if (info.width != width || info.height != height) {
00527 rsp.success = false;
00528 rsp.status_message = (boost::format("Camera_info resolution %ix%i does not match current video "
00529 "setting, camera running at resolution %ix%i.")
00530 % info.width % info.height % width % height).str();
00531 ROS_ERROR("%s", rsp.status_message.c_str());
00532 return true;
00533 }
00534
00535 stop();
00536
00537 std::string cam_name = "prosilica";
00538 cam_name += hw_id_;
00539 std::stringstream ini_stream;
00540 if (!camera_calibration_parsers::writeCalibrationIni(ini_stream, cam_name, info)) {
00541 rsp.status_message = "Error formatting camera_info for storage.";
00542 rsp.success = false;
00543 }
00544 else {
00545 std::string ini = ini_stream.str();
00546 if (ini.size() > prosilica::Camera::USER_MEMORY_SIZE) {
00547 rsp.success = false;
00548 rsp.status_message = "Unable to write camera_info to camera memory, exceeded storage capacity.";
00549 }
00550 else {
00551 try {
00552 cam_->writeUserMemory(ini.c_str(), ini.size());
00553 cam_info_ = info;
00554 rsp.success = true;
00555 }
00556 catch (prosilica::ProsilicaException &e) {
00557 rsp.success = false;
00558 rsp.status_message = e.what();
00559 }
00560 }
00561 }
00562 if (!rsp.success)
00563 ROS_ERROR("%s", rsp.status_message.c_str());
00564
00565 start();
00566
00567 return true;
00568 }
00569
00570 void normalizeCallback(tPvFrame* frame)
00571 {
00572 unsigned long exposure;
00573 cam_->getAttribute("ExposureValue", exposure);
00574
00575
00576 if (exposure == last_exposure_value_)
00577 consecutive_stable_exposures_++;
00578 else {
00579 last_exposure_value_ = exposure;
00580 consecutive_stable_exposures_ = 0;
00581 }
00582 }
00583
00584 void normalizeExposure()
00585 {
00586 ROS_INFO("Normalizing exposure");
00588
00589 last_exposure_value_ = 0;
00590 consecutive_stable_exposures_ = 0;
00591 cam_->setFrameCallback(boost::bind(&ProsilicaNode::normalizeCallback, this, _1));
00592 cam_->start(prosilica::Freerun);
00593
00595 while (consecutive_stable_exposures_ < 3)
00596 boost::this_thread::sleep(boost::posix_time::millisec(250));
00597
00598 cam_->stop();
00599 }
00600
00602
00604
00605 void runDiagnostics()
00606 {
00607 self_test_->checkTest();
00608 diagnostic_.update();
00609 }
00610
00611 void freqStatus(diagnostic_updater::DiagnosticStatusWrapper& status)
00612 {
00613 double freq = (double)(count_)/diagnostic_.getPeriod();
00614
00615 if (freq < (.9*desired_freq_))
00616 {
00617 status.summary(2, "Desired frequency not met");
00618 }
00619 else
00620 {
00621 status.summary(0, "Desired frequency met");
00622 }
00623
00624 status.add("Images in interval", count_);
00625 status.add("Desired frequency", desired_freq_);
00626 status.add("Actual frequency", freq);
00627
00628 count_ = 0;
00629 }
00630
00631 void frameStatistics(diagnostic_updater::DiagnosticStatusWrapper& status)
00632 {
00633
00634 float frame_rate;
00635 unsigned long completed, dropped;
00636 cam_->getAttribute("StatFrameRate", frame_rate);
00637 cam_->getAttribute("StatFramesCompleted", completed);
00638 cam_->getAttribute("StatFramesDropped", dropped);
00639
00640
00641 frames_completed_acc_.add(completed - frames_completed_total_);
00642 frames_completed_total_ = completed;
00643 unsigned long completed_recent = frames_completed_acc_.sum();
00644
00645 frames_dropped_acc_.add(dropped - frames_dropped_total_);
00646 frames_dropped_total_ = dropped;
00647 unsigned long dropped_recent = frames_dropped_acc_.sum();
00648
00649 float recent_ratio = float(completed_recent) / (completed_recent + dropped_recent);
00650 float total_ratio = float(completed) / (completed + dropped);
00651
00652
00653 if (dropped_recent == 0) {
00654 status.summary(0, "No dropped frames");
00655 }
00656 else if (recent_ratio > 0.8f) {
00657 status.summary(1, "Some dropped frames");
00658 }
00659 else {
00660 status.summary(2, "Excessive proportion of dropped frames");
00661 }
00662
00663 status.add("Camera Frame Rate", frame_rate);
00664 status.add("Recent % Frames Completed", recent_ratio * 100.0f);
00665 status.add("Overall % Frames Completed", total_ratio * 100.0f);
00666 status.add("Frames Completed", completed);
00667 status.add("Frames Dropped", dropped);
00668 }
00669
00670 void packetStatistics(diagnostic_updater::DiagnosticStatusWrapper& status)
00671 {
00672
00673 unsigned long received, missed, requested, resent;
00674 cam_->getAttribute("StatPacketsReceived", received);
00675 cam_->getAttribute("StatPacketsMissed", missed);
00676 cam_->getAttribute("StatPacketsRequested", requested);
00677 cam_->getAttribute("StatPacketsResent", resent);
00678
00679
00680 packets_received_acc_.add(received - packets_received_total_);
00681 packets_received_total_ = received;
00682 unsigned long received_recent = packets_received_acc_.sum();
00683
00684 packets_missed_acc_.add(missed - packets_missed_total_);
00685 packets_missed_total_ = missed;
00686 unsigned long missed_recent = packets_missed_acc_.sum();
00687
00688 float recent_ratio = float(received_recent) / (received_recent + missed_recent);
00689 float total_ratio = float(received) / (received + missed);
00690
00691 if (missed_recent == 0) {
00692 status.summary(0, "No missed packets");
00693 }
00694 else if (recent_ratio > 0.99f) {
00695 status.summary(1, "Some missed packets");
00696 }
00697 else {
00698 status.summary(2, "Excessive proportion of missed packets");
00699 }
00700
00701
00702 unsigned long data_rate = 0;
00703 unsigned long max_data_rate = cam_->getMaxDataRate();
00704 if (max_data_rate < prosilica::Camera::GIGE_MAX_DATA_RATE)
00705 status.mergeSummary(1, "Max data rate is lower than expected for a GigE port");
00706 try {
00707 cam_->getAttribute("StreamBytesPerSecond", data_rate);
00708
00710 float multiplier = 1.0f;
00711 if (recent_ratio == 1.0f) {
00712 multiplier = 1.1f;
00713 } else if (recent_ratio < 0.99f) {
00714 multiplier = 0.9f;
00715 }
00716 if (multiplier != 1.0f) {
00717 unsigned long new_data_rate = std::min((unsigned long)(multiplier * data_rate + 0.5), max_data_rate);
00718 new_data_rate = std::max(new_data_rate, max_data_rate/1000);
00719 if (data_rate != new_data_rate) {
00720 data_rate = new_data_rate;
00721 cam_->setAttribute("StreamBytesPerSecond", data_rate);
00722 ROS_DEBUG("Changed data rate to %lu bytes per second", data_rate);
00723 }
00724 }
00725 }
00726 catch (prosilica::ProsilicaException &e) {
00727 if (e.error_code == ePvErrUnplugged)
00728 throw;
00729 ROS_ERROR("Exception occurred: '%s'\n"
00730 "Possible network issue. Attempting to reset data rate to the current maximum.",
00731 e.what());
00732 data_rate = max_data_rate;
00733 cam_->setAttribute("StreamBytesPerSecond", data_rate);
00734 }
00735
00736 status.add("Recent % Packets Received", recent_ratio * 100.0f);
00737 status.add("Overall % Packets Received", total_ratio * 100.0f);
00738 status.add("Received Packets", received);
00739 status.add("Missed Packets", missed);
00740 status.add("Requested Packets", requested);
00741 status.add("Resent Packets", resent);
00742 status.add("Data Rate (bytes/s)", data_rate);
00743 status.add("Max Data Rate (bytes/s)", max_data_rate);
00744 }
00745
00746 void packetErrorStatus(diagnostic_updater::DiagnosticStatusWrapper& status)
00747 {
00748 unsigned long erroneous;
00749 cam_->getAttribute("StatPacketsErroneous", erroneous);
00750
00751 if (erroneous == 0) {
00752 status.summary(0, "No erroneous packets");
00753 } else {
00754 status.summary(2, "Possible camera hardware failure");
00755 }
00756
00757 status.add("Erroneous Packets", erroneous);
00758 }
00759
00761
00763
00764
00765 void infoTest(diagnostic_updater::DiagnosticStatusWrapper& status)
00766 {
00767 status.name = "Info Test";
00768
00769 self_test_->setID(hw_id_);
00770
00771 std::string camera_name;
00772 try {
00773 cam_->getAttribute("CameraName", camera_name);
00774 status.summary(0, "Connected to Camera");
00775 status.add("Camera Name", camera_name);
00776 }
00777 catch (prosilica::ProsilicaException& e) {
00778 status.summary(2, e.what());
00779 }
00780 }
00781
00782
00783 void attributeTest(diagnostic_updater::DiagnosticStatusWrapper& status)
00784 {
00785 status.name = "Attribute Test";
00786
00787 tPvAttrListPtr list_ptr;
00788 unsigned long list_length;
00789
00790 if (PvAttrList(cam_->handle(), &list_ptr, &list_length) == ePvErrSuccess) {
00791 status.summary(0, "All attributes in valid range");
00792 for (unsigned int i = 0; i < list_length; ++i) {
00793 const char* attribute = list_ptr[i];
00794 tPvErr e = PvAttrIsValid(cam_->handle(), attribute);
00795 if (e != ePvErrSuccess) {
00796 status.summary(2, "One or more invalid attributes");
00797 if (e == ePvErrOutOfRange)
00798 status.add(attribute, "Out of range");
00799 else if (e == ePvErrNotFound)
00800 status.add(attribute, "Does not exist");
00801 else
00802 status.addf(attribute, "Unexpected error code %u", e);
00803 }
00804 }
00805 }
00806 else {
00807 status.summary(2, "Unable to retrieve attribute list");
00808 }
00809 }
00810
00811
00812 void imageTest(diagnostic_updater::DiagnosticStatusWrapper& status)
00813 {
00814 status.name = "Image Capture Test";
00815
00816 try {
00817 if (trigger_mode_ != prosilica::Software) {
00818 tPvUint32 start_completed, current_completed;
00819 cam_->getAttribute("StatFramesCompleted", start_completed);
00820 for (int i = 0; i < 6; ++i) {
00821 boost::this_thread::sleep(boost::posix_time::millisec(500));
00822 cam_->getAttribute("StatFramesCompleted", current_completed);
00823 if (current_completed > start_completed) {
00824 status.summary(0, "Captured a frame, see diagnostics for detailed stats");
00825 return;
00826 }
00827 }
00828
00829
00830 status.summary(2, "No frames captured over 3s in freerun mode");
00831 return;
00832 }
00833
00834
00835 cam_->setRoiToWholeFrame();
00836 tPvFrame* frame = cam_->grab(500);
00837 if (frame)
00838 {
00839 status.summary(0, "Successfully triggered a frame capture");
00840 }
00841 else
00842 {
00843 status.summary(2, "Attempted to grab a frame, but received NULL");
00844 }
00845
00846 }
00847 catch (prosilica::ProsilicaException &e) {
00848 status.summary(2, e.what());
00849 }
00850 }
00851 };
00852
00853 int main(int argc, char **argv)
00854 {
00855 ros::init(argc, argv, "prosilica_driver");
00856
00857 ros::NodeHandle nh("camera");
00858 ProsilicaNode pn(nh);
00859 ros::spin();
00860
00861 return 0;
00862 }