Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Decimation, Light Sources and Processed Raw Enabled parameters added #46

Open
wants to merge 3 commits into
base: indigo-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 9 additions & 0 deletions README.rst
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,9 @@ All parameters are listed in the default config file: ``config/default.yaml``
- **binning_x & binning_y**
Binning factor to get downsampled images. It refers here to any camera setting which combines rectangular neighborhoods of pixels into larger "super-pixels." It reduces the resolution of the output image to (width / binning_x) x (height / binning_y). The default values binning_x = binning_y = 0 are considered the same as binning_x = binning_y = 1 (no subsampling).

- **decimation_x & decimation_y**
The Decimation camera feature allows you to reduce the number of sensor pixel columns or rows that are transmitted by the camera. This procedure is also known as "subsampling". It reduces the amount of data to be transferred and may increase the camera's frame rate.

- **downsampling_factor_exposure_search**
To speed up the exposure search, the mean brightness is not calculated on the entire image, but on a subset instead. The image is downsampled until a desired window hight is reached. The window hight is calculated out of the image height divided by the downsampling_factor_exposure search

Expand Down Expand Up @@ -113,6 +116,12 @@ The following settings do **NOT** have to be set. Each camera has default values
- **exposure_auto & gain_auto**
Only relevant, if '**brightness**' is set: If the camera should try to reach and / or keep the brightness, hence adapting to changing light conditions, at least one of the following flags must be set. If both are set, the interface will use the profile that tries to keep the gain at minimum to reduce white noise. The exposure_auto flag indicates, that the desired brightness will be reached by adapting the exposure time. The gain_auto flag indicates, that the desired brightness will be reached by adapting the gain.

- **processed_raw_enable**
Only relevant, if the camera's pixel format is '**Bayer 12**'. It allows you to use the Color Transformation and Color Adjustment features when using a Bayer pixel format.

- **light_source**
It allows you to correct color shifts caused by certain light sources. The supported light_source values are: 'off', 'daylight', 'daylight6500k', 'tungsten'.

**Optional and device specific parameter**

- **gige/mtu_size**
Expand Down
25 changes: 25 additions & 0 deletions config/default.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,13 @@ camera_info_url: ""
# binning_x: 1
# binning_y: 1

# The Decimation camera feature allows you to reduce the number of sensor pixel
# columns or rows that are transmitted by the camera.
# This procedure is also known as "subsampling". It reduces the amount of data
# to be transferred and may increase the camera's frame rate.
# decimation_x: 1
# decimation_y: 1

# The desired publisher frame rate if listening to the topics.
# This parameter can only be set once at startup
# Calling the GrabImages-Action can result in a higher framerate
Expand Down Expand Up @@ -93,6 +100,24 @@ frame_rate: 5.0
# exposure_auto: true
# gain_auto: true

# The Processed Raw Enable camera feature allows you to use the Color
# Transformation and Color Adjustment features when using a Bayer pixel format.
# The camera's pixel format must be set to a Bayer pixel format, e.g., Bayer 12.
# processed_raw_enable: false

# The Light Source Preset camera feature allows you to correct color shifts
# caused by certain light sources.
# To select a light source preset, set the LightSourceSelector parameter to one
# of the following values:
# "off": No light source preset is selected
# "daylight": The camera corrects color shifts caused by daylight
# lighting that has a color temperature of about 5 000 K.
# "daylight6500K": The camera corrects color shifts caused by daylight lighting
# that has a color temperature of about 6 500 K.
# "tungsten": The camera corrects color shifts caused by tungsten lighting
# that has a color temperature of about 2 500 to 3 000 K.
# light_source: "off"

##########################################################################

# The timeout while searching the exposure which is connected to the
Expand Down
120 changes: 120 additions & 0 deletions include/pylon_camera/internal/impl/pylon_camera_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,32 @@ size_t PylonCameraImpl<CameraTraitT>::currentBinningY()
}
}

template <typename CameraTraitT>
size_t PylonCameraImpl<CameraTraitT>::currentDecimationX()
{
if (GenApi::IsAvailable(cam_->DecimationHorizontal))
{
return static_cast<size_t>(cam_->DecimationHorizontal.GetValue());
}
else
{
return 1;
}
}

template <typename CameraTraitT>
size_t PylonCameraImpl<CameraTraitT>::currentDecimationY()
{
if (GenApi::IsAvailable(cam_->DecimationVertical))
{
return static_cast<size_t>(cam_->DecimationVertical.GetValue());
}
else
{
return 1;
}
}

template <typename CameraTraitT>
std::string PylonCameraImpl<CameraTraitT>::currentROSEncoding() const
{
Expand Down Expand Up @@ -619,6 +645,100 @@ bool PylonCameraImpl<CameraTraitT>::setBinningY(const size_t& target_binning_y,
return true;
}

template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::setDecimationX(const size_t &target_decimation_x,
size_t &reached_decimation_x)
{
try
{
if (GenApi::IsAvailable(cam_->DecimationHorizontal))
{
cam_->StopGrabbing();
size_t decimation_x_to_set = target_decimation_x;
if (decimation_x_to_set < cam_->DecimationHorizontal.GetMin())
{
ROS_WARN_STREAM("Desired horizontal decimation_x factor("
<< decimation_x_to_set << ") unreachable! Setting to lower "
<< "limit: " << cam_->DecimationHorizontal.GetMin());
decimation_x_to_set = cam_->DecimationHorizontal.GetMin();
}
else if (decimation_x_to_set > cam_->DecimationHorizontal.GetMax())
{
ROS_WARN_STREAM("Desired horizontal decimation_x factor("
<< decimation_x_to_set << ") unreachable! Setting to upper "
<< "limit: " << cam_->DecimationHorizontal.GetMax());
decimation_x_to_set = cam_->DecimationHorizontal.GetMax();
}
cam_->DecimationHorizontal.SetValue(decimation_x_to_set);
reached_decimation_x = currentDecimationX();
cam_->StartGrabbing();
img_cols_ = static_cast<size_t>(cam_->Width.GetValue());
img_size_byte_ = img_cols_ * img_rows_ * imagePixelDepth();
}
else
{
ROS_WARN_STREAM("Camera does not support decimation. Will keep the "
<< "current settings");
reached_decimation_x = currentDecimationX();
}
}
catch (const GenICam::GenericException &e)
{
ROS_ERROR_STREAM("An exception while setting target horizontal "
<< "decimation_x factor to " << target_decimation_x << " occurred: "
<< e.GetDescription());
return false;
}
return true;
}

template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::setDecimationY(const size_t &target_decimation_y,
size_t &reached_decimation_y)
{
try
{
if (GenApi::IsAvailable(cam_->DecimationVertical))
{
cam_->StopGrabbing();
size_t decimation_y_to_set = target_decimation_y;
if (decimation_y_to_set < cam_->DecimationVertical.GetMin())
{
ROS_WARN_STREAM("Desired vertical decimation_y factor("
<< decimation_y_to_set << ") unreachable! Setting to lower "
<< "limit: " << cam_->DecimationVertical.GetMin());
decimation_y_to_set = cam_->DecimationVertical.GetMin();
}
else if (decimation_y_to_set > cam_->DecimationVertical.GetMax())
{
ROS_WARN_STREAM("Desired vertical decimation_y factor("
<< decimation_y_to_set << ") unreachable! Setting to upper "
<< "limit: " << cam_->DecimationVertical.GetMax());
decimation_y_to_set = cam_->DecimationVertical.GetMax();
}
cam_->DecimationVertical.SetValue(decimation_y_to_set);
reached_decimation_y = currentDecimationY();
cam_->StartGrabbing();
img_rows_ = static_cast<size_t>(cam_->Height.GetValue());
img_size_byte_ = img_cols_ * img_rows_ * imagePixelDepth();
}
else
{
ROS_WARN_STREAM("Camera does not support decimation. Will keep the "
<< "current settings");
reached_decimation_y = currentDecimationY();
}
}
catch (const GenICam::GenericException &e)
{
ROS_ERROR_STREAM("An exception while setting target vertical "
<< "decimation_y factor to " << target_decimation_y << " occurred: "
<< e.GetDescription());
return false;
}
return true;
}

template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::setExposure(const float& target_exposure,
float& reached_exposure)
Expand Down
56 changes: 56 additions & 0 deletions include/pylon_camera/internal/impl/pylon_camera_gige.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -396,6 +396,62 @@ std::string PylonGigECamera::typeName() const
return "GigE";
}

template <>
bool PylonGigECamera::setProcessedRawEnable(bool &enabled)
{
if ( GenApi::IsAvailable(cam_->ProcessedRawEnable) ){
try
{
cam_->ProcessedRawEnable.SetValue(enabled);
}
catch (const GenICam::GenericException &e)
{
ROS_ERROR_STREAM("An exception while setting processed raw enable to "
<< (enabled ? "true" : "false" )<< " occurred:"
<< e.GetDescription());
return false;
}
return true;
}
return false;
}

template <>
bool PylonGigECamera::setLightSourceSelector(std::string selector)
{
if (GenApi::IsAvailable(cam_->LightSourceSelector))
{
try
{
if (selector.compare("off") == 0)
{
cam_->LightSourceSelector.SetValue(Basler_GigECamera::LightSourceSelectorEnums::LightSourceSelector_Off);
}
else if (selector.compare("daylight") == 0)
{
cam_->LightSourceSelector.SetValue(Basler_GigECamera::LightSourceSelectorEnums::LightSourceSelector_Daylight);
}
else if (selector.compare("tungsten") == 0)
{
cam_->LightSourceSelector.SetValue(Basler_GigECamera::LightSourceSelectorEnums::LightSourceSelector_Tungsten);
}
else if (selector.compare("daylight6500") == 0)
{
cam_->LightSourceSelector.SetValue(Basler_GigECamera::LightSourceSelectorEnums::LightSourceSelector_Daylight6500K);
}
}
catch (const GenICam::GenericException &e)
{
ROS_ERROR_STREAM("An exception while setting processed light source to "
<< selector << " occurred:"
<< e.GetDescription());
return false;
}
return true;
}
return false;
}

} // namespace pylon_camera

#endif // PYLON_CAMERA_INTERNAL_GIGE_H_
12 changes: 12 additions & 0 deletions include/pylon_camera/internal/impl/pylon_camera_usb.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -339,6 +339,18 @@ std::string PylonUSBCamera::typeName() const
return "USB";
}

template <>
bool PylonUSBCamera::setProcessedRawEnable(bool &enabled)
{
return false;
}

template <>
bool PylonUSBCamera::setLightSourceSelector(std::string selector)
{
return false;
}

} // namespace pylon_camera

#endif // PYLON_CAMERA_INTERNAL_USB_H_
14 changes: 14 additions & 0 deletions include/pylon_camera/internal/pylon_camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,12 @@ class PylonCameraImpl : public PylonCamera
virtual bool setBinningY(const size_t& target_binning_y,
size_t& reached_binning_y);

virtual bool setDecimationX(const size_t &target_decimation_x,
size_t &reached_decimation_x);

virtual bool setDecimationY(const size_t &target_decimation_y,
size_t &reached_decimation_y);

virtual bool setImageEncoding(const std::string& target_ros_encoding);

virtual bool setExposure(const float& target_exposure, float& reached_exposure);
Expand All @@ -93,10 +99,18 @@ class PylonCameraImpl : public PylonCamera

virtual bool setUserOutput(const int& output_id, const bool& value);

virtual bool setProcessedRawEnable(bool& enabled);

virtual bool setLightSourceSelector(std::string lightSource);

virtual size_t currentBinningX();

virtual size_t currentBinningY();

virtual size_t currentDecimationX();

virtual size_t currentDecimationY();

virtual std::vector<std::string> detectAvailableImageEncodings();

virtual std::string currentROSEncoding() const;
Expand Down
48 changes: 48 additions & 0 deletions include/pylon_camera/pylon_camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,25 @@ class PylonCamera
virtual bool setBinningY(const size_t& target_binning_y,
size_t& reached_binning_y) = 0;

/**
* Sets the target horizontal decimation_x factor
* @param target_decimation_x the target horizontal decimation_x factor.
* @param reached_decimation_x the reached horizontal decimation_x factor.
* @return false if a communication error occured or true otherwise.
*/
virtual bool setDecimationX(const size_t& target_decimation_x,
size_t& reached_decimation_x) = 0;

/**
* Sets the target vertical decimation_y factor
* @param target_decimation_y the target vertical decimation_y factor.
* @param reached_decimation_y the reached vertical decimation_y factor.
* @return false if a communication error occured or true otherwise.
*/

virtual bool setDecimationY(const size_t &target_decimation_y,
size_t &reached_decimation_y) = 0;

/**
* Detects the supported image pixel encodings of the camera an stores
* them in a vector.
Expand Down Expand Up @@ -225,6 +244,23 @@ class PylonCamera
*/
virtual bool setUserOutput(const int& output_id, const bool& value) = 0;

/**
* @brief Set the Processed Raw Enable feature
*
* @param enabled
* @return true if it could be enabled
*/
virtual bool setProcessedRawEnable(bool& enabled) = 0;

/**
* @brief Set the Light Source Selector object
*
* @param enabled
* @return true
* @return false
*/
virtual bool setLightSourceSelector(std::string enabled) = 0;

/**
* Returns the current horizontal binning_x setting.
* @return the horizontal binning_x setting.
Expand All @@ -237,6 +273,18 @@ class PylonCamera
*/
virtual size_t currentBinningY() = 0;

/**
* Returns the current horizontal decimation_x setting.
* @return the horizontal decimation_x setting.
*/
virtual size_t currentDecimationX() = 0;

/**
* Returns the current vertical decimation_y setting.
* @return the vertical decimation_y setting.
*/
virtual size_t currentDecimationY() = 0;

/**
* Get the camera image encoding according to sensor_msgs::image_encodings
* The supported encodings are 'mono8', 'bgr8', 'rgb8', 'bayer_bggr8',
Expand Down
Loading