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

Allows cameras to publish images in RGB24 format #3

Open
wants to merge 4 commits into
base: hydro-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
1 change: 1 addition & 0 deletions prosilica_camera/cfg/ProsilicaCamera.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -38,5 +38,6 @@ gen.add("exposure_auto_max", double_t, SensorLevels.RECONFIGURE_RUNNING, "The
gen.add("exposure_auto_target", int_t, SensorLevels.RECONFIGURE_RUNNING, "The auto exposure target mean value as a percentage, from 0=black to 100=white.", 50, 0, 100)
gen.add("gain_auto_max", int_t, SensorLevels.RECONFIGURE_RUNNING, "The max gain level in auto gain mode, in dB.", 24, 0, 24)
gen.add("gain_auto_target", int_t, SensorLevels.RECONFIGURE_RUNNING, "The auto gain target mean value as a percentage, from 0=black to 100=white.", 50, 0, 100)
gen.add("pixel_format", str_t, SensorLevels.RECONFIGURE_RUNNING, "The pixel format - default is Bayer8. Currently, the only other supported format is 24-bit rgb: use 'Rgb24'", "Bayer8")
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This should probably be an enumeration rather than a raw string. Take a look at how the enum for the streaming mode is implemented.


exit(gen.generate(PACKAGE, "prosilica_driver", "ProsilicaCamera"))
27 changes: 26 additions & 1 deletion prosilica_camera/src/nodes/prosilica_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,18 @@ class ProsilicaNode

// Service call for setting calibration.
set_camera_info_srv_ = nh_.advertiseService("set_camera_info", &ProsilicaNode::setCameraInfo, this);


// Set the pixel format
std::string pix_format = "";
if (local_nh.getParam("pixel_format", pix_format) && (pix_format == "Rgb24" || pix_format == "Bayer8"))
{
if (cam_->hasAttribute("PixelFormat"))
{
ROS_DEBUG_STREAM("Setting camera pixel format to " << pix_format);
cam_->setAttribute("PixelFormat", pix_format);
}
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The same block below has an else with a WARN should this not too?

}

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is unnecessary. Dynamic_reconfigure will automatically pull in parameters from the parameter server and call the configuration callback on initialization.

// Start dynamic_reconfigure
reconfigure_server_.setCallback(boost::bind(&ProsilicaNode::configure, this, _1, _2));
}
Expand Down Expand Up @@ -331,6 +342,20 @@ class ProsilicaNode
if (!auto_adjust_stream_bytes_per_second_)
cam_->setAttribute("StreamBytesPerSecond", (tPvUint32)config.stream_bytes_per_second);

// Change the pixel format
if (config.pixel_format == "Rgb24" || config.pixel_format == "Bayer8")
{
if (cam_->hasAttribute("PixelFormat"))
{
ROS_DEBUG_STREAM("Setting camera pixel format to " << config.pixel_format);
cam_->setAttribute("PixelFormat", config.pixel_format);
}
else
{
ROS_WARN("Changing pixel format is not supported by your camera");
}
}
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This should print a warning or an error if an invalid pixel format is specified. Take a look at how setting the streaming rate is handled.


/// @todo If exception thrown due to bad settings, will fail to start camera
if (level >= (uint32_t)driver_base::SensorLevels::RECONFIGURE_STOP)
start();
Expand Down