Skip to content

Commit

Permalink
better diagnostics on incomplete images
Browse files Browse the repository at this point in the history
  • Loading branch information
berndpfrommer committed Jul 21, 2024
1 parent 63df12e commit 5db11c1
Show file tree
Hide file tree
Showing 7 changed files with 68 additions and 16 deletions.
34 changes: 32 additions & 2 deletions spinnaker_camera_driver/doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -223,11 +223,11 @@ Blackfly S the parameters look like this:


Network Configuration for GigE cameras
=======================
======================================

The Spinnaker SDK abstracts away the transport layer so a GigE camera
should work the same way as USB3: you point it to the serial number and
youre set.
you're set.

There are a few GigE-specific settings in the Transport Layer Control
group that are important, in particular enabling jumbo frames from the
Expand Down Expand Up @@ -343,6 +343,36 @@ Known issues
the same address space with a composable node (see stereo launch file
for example).

Troubleshooting/Common Issues
=============================

1) Driver doesn't find camera.
This is usually due to incorrect permissions, missing udev files etc. Install the Spinnaker SDK
and get SpinView to work.

2) Driver doesn't publish images and/or warns about incomplete images for GigE cameras

.. code::
rate [Hz] in 39.76 out 0.00 drop 0% INCOMPLETE 100%
The reason for the incomplete images is usually that you are exceeding the network
bandwidth, causing packets to be dropped such that incomplete frames arrive at the host.
Check for the MTU on all network cards and switches to be 9000 (jumbo frames). Sometimes
the MTU for switches has to be set higher. Also make sure the GigE camera has jumbo frames
enabled, i.e. ``gev_scps_packet_size`` is set to 9000.

3) Driver reports dropped packages. This means the connected subscriber is not picking up fast enough.
Check CPU utilization of subscribers and the available network bandwidth between driver and subscriber.

4) Image seems laggy when viewed. This is usually not a camera driver issue, but related to ROS2 RMW
or the image viewer. Check CPU utilization on displaying host and network bandwidth.

5) Camera doesn't reach desired frame rate.
First play around in SpinView to reproduce the problem there. For GigE cameras, check network bandwidth.
Switch to Bayer images to reduce network bandwidth by a factor of three.
Check your exposure time. The frame rate cannot exceed the inverse of the exposure time.


Setting up Linux without Spinnaker SDK
======================================
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,10 @@
{ \
RCLCPP_WARN_STREAM(get_logger(), __VA_ARGS__); \
}
#define LOG_WARN_FMT(...) \
{ \
RCLCPP_WARN(get_logger(), __VA_ARGS__); \
}
#define LOG_ERROR(...) \
{ \
RCLCPP_ERROR_STREAM(get_logger(), __VA_ARGS__); \
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@ class SpinnakerWrapper

std::string getPixelFormat() const;
double getReceiveFrameRate() const;
double getIncompleteRate();
std::string getNodeMapAsString();
std::string setEnum(const std::string & nodeName, const std::string & val, std::string * retVal);
std::string setDouble(const std::string & nodeName, double val, double * retVal);
Expand Down
17 changes: 12 additions & 5 deletions spinnaker_camera_driver/src/camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,11 +165,18 @@ void Camera::printStatus()
: 0;
const rclcpp::Time t = node_->now();
const rclcpp::Duration dt = t - lastStatusTime_;
double dtns = std::max(dt.nanoseconds(), (int64_t)1);
double outRate = publishedCount_ * 1e9 / dtns;
LOG_INFO_FMT(
"rate [Hz] in %6.2f out %6.2f drop %3.0f%%", wrapper_->getReceiveFrameRate(), outRate,
dropRate * 100);
const double dtns = std::max(dt.nanoseconds(), (int64_t)1);
const double outRate = publishedCount_ * 1e9 / dtns;
const double incompleteRate = wrapper_->getIncompleteRate();
if (incompleteRate != 0) {
LOG_WARN_FMT(
"rate [Hz] in %6.2f out %6.2f drop %3.0f%% INCOMPLETE %3.0f%%",
wrapper_->getReceiveFrameRate(), outRate, dropRate * 100, incompleteRate * 100);
} else {
LOG_INFO_FMT(
"rate [Hz] in %6.2f out %6.2f drop %3.0f%%", wrapper_->getReceiveFrameRate(), outRate,
dropRate * 100);
}
lastStatusTime_ = t;
droppedCount_ = 0;
publishedCount_ = 0;
Expand Down
1 change: 1 addition & 0 deletions spinnaker_camera_driver/src/spinnaker_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ double SpinnakerWrapper::getReceiveFrameRate() const
{
return (wrapperImpl_->getReceiveFrameRate());
}
double SpinnakerWrapper::getIncompleteRate() { return (wrapperImpl_->getIncompleteRate()); }

std::string SpinnakerWrapper::getNodeMapAsString() { return (wrapperImpl_->getNodeMapAsString()); }

Expand Down
23 changes: 14 additions & 9 deletions spinnaker_camera_driver/src/spinnaker_wrapper_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,9 +151,9 @@ void SpinnakerWrapperImpl::refreshCameraList()
} // end for camList
} else {
LOG_ERROR("Unknown Interface (Display name not readable)");
} // end if-else ptrInterfaceDisplayName
} // end if ptrInterfaceType
} // end for interfaceList
}
}
}

interfaceList.Clear();
#endif
Expand Down Expand Up @@ -316,6 +316,15 @@ double SpinnakerWrapperImpl::getReceiveFrameRate() const
return (avgTimeInterval_ > 0 ? (1.0 / avgTimeInterval_) : 0);
}

double SpinnakerWrapperImpl::getIncompleteRate()
{
const double r =
numImagesTotal_ == 0 ? 0 : (numIncompleteImagesTotal_ / static_cast<double>(numImagesTotal_));
numImagesTotal_ = 0;
numIncompleteImagesTotal_ = 0;
return (r);
}

static int int_ceil(size_t x, int y)
{
// compute the integer ceil(x / y)
Expand Down Expand Up @@ -358,14 +367,10 @@ void SpinnakerWrapperImpl::OnImageEvent(Spinnaker::ImagePtr imgPtr)
std::unique_lock<std::mutex> lock(mutex_);
lastTime_ = t;
}

numImagesTotal_++;
if (imgPtr->IsIncomplete()) {
numIncompleteImages_++;
#if 0
// Retrieve and print the image status description
std::cout << "Image incomplete: "
<< Spinnaker::Image::GetImageStatusDescription(imgPtr->GetImageStatus()) << std::endl;
#endif
numIncompleteImagesTotal_++;
} else {
float expTime = 0;
float gain = 0;
Expand Down
4 changes: 4 additions & 0 deletions spinnaker_camera_driver/src/spinnaker_wrapper_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,8 @@ class SpinnakerWrapperImpl : public Spinnaker::ImageEventHandler
bool stopCamera();

double getReceiveFrameRate() const;
double getIncompleteRate();

std::string getNodeMapAsString();
// methods for setting camera params
std::string setEnum(const std::string & nodeName, const std::string & val, std::string * retVal);
Expand Down Expand Up @@ -88,6 +90,8 @@ class SpinnakerWrapperImpl : public Spinnaker::ImageEventHandler
std::mutex mutex_;
uint64_t acquisitionTimeout_{10000000000ULL};
size_t numIncompleteImages_{0};
size_t numImagesTotal_{0};
size_t numIncompleteImagesTotal_{0};
};
} // namespace spinnaker_camera_driver

Expand Down

0 comments on commit 5db11c1

Please sign in to comment.